Tesseract
Motion Planning Environment
Loading...
Searching...
No Matches
Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | Private Member Functions | Static Private Member Functions | Friends | List of all members
tesseract_environment::Environment Class Reference

#include <environment.h>

Collaboration diagram for tesseract_environment::Environment:
Collaboration graph
[legend]

Public Types

using Ptr = std::shared_ptr< Environment >
 
using ConstPtr = std::shared_ptr< const Environment >
 
using UPtr = std::unique_ptr< Environment >
 
using ConstUPtr = std::unique_ptr< const Environment >
 

Public Member Functions

 Environment ()=default
 Default constructor. More...
 
virtual ~Environment ()=default
 
 Environment (const Environment &)=delete
 
Environmentoperator= (const Environment &)=delete
 
 Environment (Environment &&)=delete
 
Environmentoperator= (Environment &&)=delete
 
bool init (const Commands &commands)
 Initialize the Environment. More...
 
bool init (const tesseract_scene_graph::SceneGraph &scene_graph, const tesseract_srdf::SRDFModel::ConstPtr &srdf_model=nullptr)
 Initialize the Environment. More...
 
bool init (const std::string &urdf_string, const tesseract_common::ResourceLocator::ConstPtr &locator)
 
bool init (const std::string &urdf_string, const std::string &srdf_string, const tesseract_common::ResourceLocator::ConstPtr &locator)
 
bool init (const tesseract_common::fs::path &urdf_path, const tesseract_common::ResourceLocator::ConstPtr &locator)
 
bool init (const tesseract_common::fs::path &urdf_path, const tesseract_common::fs::path &srdf_path, const tesseract_common::ResourceLocator::ConstPtr &locator)
 
Environment::UPtr clone () const
 Clone the environment. More...
 
bool reset ()
 reset to initialized state More...
 
void clear ()
 clear content and uninitialized More...
 
bool isInitialized () const
 check if the environment is initialized More...
 
int getRevision () const
 Get the current revision number. More...
 
Commands getCommandHistory () const
 Get Environment command history post initialization. More...
 
bool applyCommands (const Commands &commands)
 Applies the commands to the environment. More...
 
bool applyCommand (Command::ConstPtr command)
 Apply command to the environment. More...
 
tesseract_scene_graph::SceneGraph::ConstPtr getSceneGraph () const
 Get the Scene Graph. More...
 
std::vector< std::string > getGroupJointNames (const std::string &group_name) const
 Get a groups joint names. More...
 
tesseract_kinematics::JointGroup::UPtr getJointGroup (const std::string &group_name) const
 Get a joint group by name. More...
 
tesseract_kinematics::JointGroup::UPtr getJointGroup (const std::string &name, const std::vector< std::string > &joint_names) const
 Get a joint group given a vector of joint names. More...
 
tesseract_kinematics::KinematicGroup::UPtr getKinematicGroup (const std::string &group_name, std::string ik_solver_name="") const
 Get a kinematic group given group name and solver name. More...
 
Eigen::Isometry3d findTCPOffset (const tesseract_common::ManipulatorInfo &manip_info) const
 Find tool center point provided in the manipulator info. More...
 
void addFindTCPOffsetCallback (const FindTCPOffsetCallbackFn &fn)
 This allows for user defined callbacks for looking up TCP information. More...
 
std::vector< FindTCPOffsetCallbackFngetFindTCPOffsetCallbacks () const
 This get the current find tcp callbacks stored in the environment. More...
 
void addEventCallback (std::size_t hash, const EventCallbackFn &fn)
 Add an event callback function. More...
 
void removeEventCallback (std::size_t hash)
 Remove event callbacks. More...
 
void clearEventCallbacks ()
 clear all event callbacks More...
 
std::map< std::size_t, EventCallbackFngetEventCallbacks () const
 Get the current event callbacks stored in the environment. More...
 
void setResourceLocator (tesseract_common::ResourceLocator::ConstPtr locator)
 Set resource locator for environment. More...
 
tesseract_common::ResourceLocator::ConstPtr getResourceLocator () const
 Get the resource locator assigned. More...
 
void setName (const std::string &name)
 Give the environment a name. More...
 
const std::string & getName () const
 Get the name of the environment. More...
 
void setState (const std::unordered_map< std::string, double > &joints)
 Set the current state of the environment. More...
 
void setState (const std::vector< std::string > &joint_names, const Eigen::Ref< const Eigen::VectorXd > &joint_values)
 
tesseract_scene_graph::SceneState getState (const std::unordered_map< std::string, double > &joints) const
 Get the state of the environment for a given set or subset of joint values. More...
 
tesseract_scene_graph::SceneState getState (const std::vector< std::string > &joint_names, const Eigen::Ref< const Eigen::VectorXd > &joint_values) const
 
tesseract_scene_graph::SceneState getState () const
 Get the current state of the environment. More...
 
std::chrono::system_clock::time_point getTimestamp () const
 Last update time. Updated when any change to the environment occurs. More...
 
std::chrono::system_clock::time_point getCurrentStateTimestamp () const
 Last update time to current state. Updated only when current state is updated. More...
 
tesseract_scene_graph::Link::ConstPtr getLink (const std::string &name) const
 Get a link in the environment. More...
 
tesseract_scene_graph::Joint::ConstPtr getJoint (const std::string &name) const
 Get joint by name. More...
 
tesseract_scene_graph::JointLimits::ConstPtr getJointLimits (const std::string &joint_name) const
 Gets the limits associated with a joint. More...
 
bool getLinkCollisionEnabled (const std::string &name) const
 Get whether a link should be considered during collision checking. More...
 
bool getLinkVisibility (const std::string &name) const
 Get a given links visibility setting. More...
 
tesseract_common::AllowedCollisionMatrix::ConstPtr getAllowedCollisionMatrix () const
 Get the allowed collision matrix. More...
 
std::vector< std::string > getJointNames () const
 Get a vector of joint names in the environment. More...
 
std::vector< std::string > getActiveJointNames () const
 Get a vector of active joint names in the environment. More...
 
Eigen::VectorXd getCurrentJointValues () const
 Get the current state of the environment. More...
 
Eigen::VectorXd getCurrentJointValues (const std::vector< std::string > &joint_names) const
 Get the current joint values for a vector of joints. More...
 
std::string getRootLinkName () const
 Get the root link name. More...
 
std::vector< std::string > getLinkNames () const
 Get a vector of link names in the environment. More...
 
std::vector< std::string > getActiveLinkNames () const
 Get a vector of active link names in the environment. More...
 
std::vector< std::string > getActiveLinkNames (const std::vector< std::string > &joint_names) const
 Get a vector of active link names affected by the provided joints in the environment. More...
 
std::vector< std::string > getStaticLinkNames () const
 Get a vector of static link names in the environment. More...
 
std::vector< std::string > getStaticLinkNames (const std::vector< std::string > &joint_names) const
 Get a vector of static link names not affected by the provided joints in the environment. More...
 
tesseract_common::VectorIsometry3d getLinkTransforms () const
 Get all of the links transforms. More...
 
Eigen::Isometry3d getLinkTransform (const std::string &link_name) const
 Get the transform corresponding to the link. More...
 
Eigen::Isometry3d getRelativeLinkTransform (const std::string &from_link_name, const std::string &to_link_name) const
 Get transform between two links using the current state. More...
 
tesseract_scene_graph::StateSolver::UPtr getStateSolver () const
 Returns a clone of the environments state solver. More...
 
tesseract_srdf::KinematicsInformation getKinematicsInformation () const
 Get the kinematics information. More...
 
tesseract_srdf::GroupNames getGroupNames () const
 Get the available group names. More...
 
tesseract_common::ContactManagersPluginInfo getContactManagersPluginInfo () const
 Get the contact managers plugin information. More...
 
bool setActiveDiscreteContactManager (const std::string &name)
 Set the active discrete contact manager. More...
 
tesseract_collision::DiscreteContactManager::UPtr getDiscreteContactManager () const
 Get a copy of the environments active discrete contact manager. More...
 
void clearCachedDiscreteContactManager () const
 Set the cached internal copy of the environments active discrete contact manager not nullptr. More...
 
tesseract_collision::DiscreteContactManager::UPtr getDiscreteContactManager (const std::string &name) const
 Get a copy of the environments available discrete contact manager by name. More...
 
bool setActiveContinuousContactManager (const std::string &name)
 Set the active continuous contact manager. More...
 
tesseract_collision::ContinuousContactManager::UPtr getContinuousContactManager () const
 Get a copy of the environments active continuous contact manager. More...
 
void clearCachedContinuousContactManager () const
 Set the cached internal copy of the environments active continuous contact manager not nullptr. More...
 
tesseract_collision::ContinuousContactManager::UPtr getContinuousContactManager (const std::string &name) const
 Get a copy of the environments available continuous contact manager by name. More...
 
tesseract_common::CollisionMarginData getCollisionMarginData () const
 Get the environment collision margin data. More...
 
std::shared_lock< std::shared_mutex > lockRead () const
 Lock the environment when wanting to make multiple reads. More...
 
bool operator== (const Environment &rhs) const
 These operators are to facilitate checking serialization but may have value elsewhere. More...
 
bool operator!= (const Environment &rhs) const
 

Protected Member Functions

void currentStateChanged ()
 
void environmentChanged ()
 
void triggerCurrentStateChangedCallbacks ()
 Passes a current state changed event to the callbacks. More...
 
void triggerEnvironmentChangedCallbacks ()
 Passes a environment changed event to the callbacks. More...
 

Protected Attributes

bool initialized_ { false }
 Identifies if the object has been initialized. More...
 
int revision_ { 0 }
 This increments when the scene graph is modified. More...
 
int init_revision_ { 0 }
 This is the revision number after initialization used when reset is called. More...
 
Commands commands_ {}
 The history of commands applied to the environment after initialization. More...
 
tesseract_scene_graph::SceneGraph::Ptr scene_graph_ { nullptr }
 Tesseract Scene Graph. More...
 
tesseract_scene_graph::SceneGraph::ConstPtr scene_graph_const_ { nullptr }
 Tesseract Scene Graph Const. More...
 
tesseract_srdf::KinematicsInformation kinematics_information_
 The kinematics information. More...
 
tesseract_kinematics::KinematicsPluginFactory kinematics_factory_
 The kinematics factory. More...
 
tesseract_scene_graph::SceneState current_state_
 Current state of the environment. More...
 
std::chrono::system_clock::time_point timestamp_ { std::chrono::system_clock::now() }
 Environment timestamp. More...
 
std::chrono::system_clock::time_point current_state_timestamp_ { std::chrono::system_clock::now() }
 Current state timestamp. More...
 
tesseract_scene_graph::MutableStateSolver::UPtr state_solver_ { nullptr }
 Tesseract State Solver. More...
 
tesseract_collision::IsContactAllowedFn is_contact_allowed_fn_
 The function used to determine if two objects are allowed in collision. More...
 
std::vector< FindTCPOffsetCallbackFnfind_tcp_cb_ {}
 A vector of user defined callbacks for locating tool center point. More...
 
std::map< std::size_t, EventCallbackFnevent_cb_ {}
 A map of user defined event callback functions. More...
 
tesseract_common::ResourceLocator::ConstPtr resource_locator_ { nullptr }
 Used when initialized by URDF_STRING, URDF_STRING_SRDF_STRING, URDF_PATH, and URDF_PATH_SRDF_PATH. More...
 
tesseract_common::ContactManagersPluginInfo contact_managers_plugin_info_
 The contact manager information. More...
 
tesseract_collision::ContactManagersPluginFactory contact_managers_factory_
 The contact managers factory. More...
 
tesseract_collision::CollisionMarginData collision_margin_data_
 The collision margin data. More...
 
tesseract_collision::DiscreteContactManager::UPtr discrete_manager_ { nullptr }
 The discrete contact manager object. More...
 
std::shared_mutex discrete_manager_mutex_
 
tesseract_collision::ContinuousContactManager::UPtr continuous_manager_ { nullptr }
 The continuous contact manager object. More...
 
std::shared_mutex continuous_manager_mutex_
 
std::unordered_map< std::string, std::vector< std::string > > group_joint_names_cache_ {}
 A cache of group joint names to provide faster access. More...
 
std::shared_mutex group_joint_names_cache_mutex_
 
std::unordered_map< std::string, tesseract_kinematics::JointGroup::UPtrjoint_group_cache_ {}
 A cache of joint groups to provide faster access. More...
 
std::shared_mutex joint_group_cache_mutex_
 
std::map< std::pair< std::string, std::string >, tesseract_kinematics::KinematicGroup::UPtrkinematic_group_cache_ {}
 A cache of kinematic groups to provide faster access. More...
 
std::shared_mutex kinematic_group_cache_mutex_
 
std::shared_mutex mutex_
 The environment can be accessed from multiple threads, need use mutex throughout. More...
 

Private Member Functions

bool removeLinkHelper (const std::string &name)
 
bool setActiveDiscreteContactManagerHelper (const std::string &name)
 
bool setActiveContinuousContactManagerHelper (const std::string &name)
 
tesseract_collision::DiscreteContactManager::UPtr getDiscreteContactManagerHelper (const std::string &name) const
 
tesseract_collision::ContinuousContactManager::UPtr getContinuousContactManagerHelper (const std::string &name) const
 
bool initHelper (const Commands &commands)
 
bool applyCommandsHelper (const Commands &commands)
 Apply Command Helper which does not lock. More...
 
bool applyAddCommand (AddLinkCommand::ConstPtr cmd)
 
bool applyMoveLinkCommand (const MoveLinkCommand::ConstPtr &cmd)
 
bool applyMoveJointCommand (const MoveJointCommand::ConstPtr &cmd)
 
bool applyRemoveLinkCommand (const RemoveLinkCommand::ConstPtr &cmd)
 
bool applyRemoveJointCommand (const RemoveJointCommand::ConstPtr &cmd)
 
bool applyReplaceJointCommand (const ReplaceJointCommand::ConstPtr &cmd)
 
bool applyChangeLinkOriginCommand (const ChangeLinkOriginCommand::ConstPtr &cmd)
 
bool applyChangeJointOriginCommand (const ChangeJointOriginCommand::ConstPtr &cmd)
 
bool applyChangeLinkCollisionEnabledCommand (const ChangeLinkCollisionEnabledCommand::ConstPtr &cmd)
 
bool applyChangeLinkVisibilityCommand (const ChangeLinkVisibilityCommand::ConstPtr &cmd)
 
bool applyModifyAllowedCollisionsCommand (const ModifyAllowedCollisionsCommand::ConstPtr &cmd)
 
bool applyRemoveAllowedCollisionLinkCommand (const RemoveAllowedCollisionLinkCommand::ConstPtr &cmd)
 
bool applyAddSceneGraphCommand (AddSceneGraphCommand::ConstPtr cmd)
 
bool applyChangeJointPositionLimitsCommand (const ChangeJointPositionLimitsCommand::ConstPtr &cmd)
 
bool applyChangeJointVelocityLimitsCommand (const ChangeJointVelocityLimitsCommand::ConstPtr &cmd)
 
bool applyChangeJointAccelerationLimitsCommand (const ChangeJointAccelerationLimitsCommand::ConstPtr &cmd)
 
bool applyAddKinematicsInformationCommand (const AddKinematicsInformationCommand::ConstPtr &cmd)
 
bool applyChangeCollisionMarginsCommand (const ChangeCollisionMarginsCommand::ConstPtr &cmd)
 
bool applyAddContactManagersPluginInfoCommand (const AddContactManagersPluginInfoCommand::ConstPtr &cmd)
 
bool applySetActiveContinuousContactManagerCommand (const SetActiveContinuousContactManagerCommand::ConstPtr &cmd)
 
bool applySetActiveDiscreteContactManagerCommand (const SetActiveDiscreteContactManagerCommand::ConstPtr &cmd)
 
template<class Archive >
void save (Archive &ar, const unsigned int version) const
 
template<class Archive >
void load (Archive &ar, const unsigned int version)
 
template<class Archive >
void serialize (Archive &ar, const unsigned int version)
 

Static Private Member Functions

static void getCollisionObject (tesseract_collision::CollisionShapesConst &shapes, tesseract_common::VectorIsometry3d &shape_poses, const tesseract_scene_graph::Link &link)
 
static Commands getInitCommands (const tesseract_scene_graph::SceneGraph &scene_graph, const tesseract_srdf::SRDFModel::ConstPtr &srdf_model=nullptr)
 

Friends

class boost::serialization::access
 

Member Typedef Documentation

◆ ConstPtr

◆ ConstUPtr

◆ Ptr

◆ UPtr

Constructor & Destructor Documentation

◆ Environment() [1/3]

tesseract_environment::Environment::Environment ( )
default

Default constructor.

◆ ~Environment()

virtual tesseract_environment::Environment::~Environment ( )
virtualdefault

◆ Environment() [2/3]

tesseract_environment::Environment::Environment ( const Environment )
delete

◆ Environment() [3/3]

tesseract_environment::Environment::Environment ( Environment &&  )
delete

Member Function Documentation

◆ addEventCallback()

void tesseract_environment::Environment::addEventCallback ( std::size_t  hash,
const EventCallbackFn fn 
)

Add an event callback function.

When these get called they are protected by a unique lock internally so if the callback is a long event it can impact performance.

Note
These do not get cloned or serialized
Parameters
hashThe id associated with the callback to allow removal. It is recommended to use std::hash<Object*>{}(this) to associate the callback with the class it associated with.
fnUser defined callback function which gets called for different event triggers

◆ addFindTCPOffsetCallback()

void tesseract_environment::Environment::addFindTCPOffsetCallback ( const FindTCPOffsetCallbackFn fn)

This allows for user defined callbacks for looking up TCP information.

Parameters
fnUser defined callback function for locating TCP information

◆ applyAddCommand()

bool tesseract_environment::Environment::applyAddCommand ( AddLinkCommand::ConstPtr  cmd)
private

◆ applyAddContactManagersPluginInfoCommand()

bool tesseract_environment::Environment::applyAddContactManagersPluginInfoCommand ( const AddContactManagersPluginInfoCommand::ConstPtr cmd)
private

◆ applyAddKinematicsInformationCommand()

bool tesseract_environment::Environment::applyAddKinematicsInformationCommand ( const AddKinematicsInformationCommand::ConstPtr cmd)
private

◆ applyAddSceneGraphCommand()

bool tesseract_environment::Environment::applyAddSceneGraphCommand ( AddSceneGraphCommand::ConstPtr  cmd)
private

◆ applyChangeCollisionMarginsCommand()

bool tesseract_environment::Environment::applyChangeCollisionMarginsCommand ( const ChangeCollisionMarginsCommand::ConstPtr cmd)
private

◆ applyChangeJointAccelerationLimitsCommand()

bool tesseract_environment::Environment::applyChangeJointAccelerationLimitsCommand ( const ChangeJointAccelerationLimitsCommand::ConstPtr cmd)
private

◆ applyChangeJointOriginCommand()

bool tesseract_environment::Environment::applyChangeJointOriginCommand ( const ChangeJointOriginCommand::ConstPtr cmd)
private

◆ applyChangeJointPositionLimitsCommand()

bool tesseract_environment::Environment::applyChangeJointPositionLimitsCommand ( const ChangeJointPositionLimitsCommand::ConstPtr cmd)
private

◆ applyChangeJointVelocityLimitsCommand()

bool tesseract_environment::Environment::applyChangeJointVelocityLimitsCommand ( const ChangeJointVelocityLimitsCommand::ConstPtr cmd)
private

◆ applyChangeLinkCollisionEnabledCommand()

bool tesseract_environment::Environment::applyChangeLinkCollisionEnabledCommand ( const ChangeLinkCollisionEnabledCommand::ConstPtr cmd)
private

◆ applyChangeLinkOriginCommand()

bool tesseract_environment::Environment::applyChangeLinkOriginCommand ( const ChangeLinkOriginCommand::ConstPtr cmd)
private

◆ applyChangeLinkVisibilityCommand()

bool tesseract_environment::Environment::applyChangeLinkVisibilityCommand ( const ChangeLinkVisibilityCommand::ConstPtr cmd)
private

◆ applyCommand()

bool tesseract_environment::Environment::applyCommand ( Command::ConstPtr  command)

Apply command to the environment.

Parameters
commandCommand to be applied to the environment
Returns
true if successful. If returned false, then the command have not been applied. Some type of Command are not checked for success

◆ applyCommands()

bool tesseract_environment::Environment::applyCommands ( const Commands commands)

Applies the commands to the environment.

Parameters
commandsCommands to be applied to the environment
Returns
true if successful. If returned false, then only a partial set of commands have been applied. Call getCommandHistory to check. Some commands are not checked for success

◆ applyCommandsHelper()

bool tesseract_environment::Environment::applyCommandsHelper ( const Commands commands)
private

Apply Command Helper which does not lock.

◆ applyModifyAllowedCollisionsCommand()

bool tesseract_environment::Environment::applyModifyAllowedCollisionsCommand ( const ModifyAllowedCollisionsCommand::ConstPtr cmd)
private

◆ applyMoveJointCommand()

bool tesseract_environment::Environment::applyMoveJointCommand ( const MoveJointCommand::ConstPtr cmd)
private

◆ applyMoveLinkCommand()

bool tesseract_environment::Environment::applyMoveLinkCommand ( const MoveLinkCommand::ConstPtr cmd)
private

◆ applyRemoveAllowedCollisionLinkCommand()

bool tesseract_environment::Environment::applyRemoveAllowedCollisionLinkCommand ( const RemoveAllowedCollisionLinkCommand::ConstPtr cmd)
private

◆ applyRemoveJointCommand()

bool tesseract_environment::Environment::applyRemoveJointCommand ( const RemoveJointCommand::ConstPtr cmd)
private

◆ applyRemoveLinkCommand()

bool tesseract_environment::Environment::applyRemoveLinkCommand ( const RemoveLinkCommand::ConstPtr cmd)
private

◆ applyReplaceJointCommand()

bool tesseract_environment::Environment::applyReplaceJointCommand ( const ReplaceJointCommand::ConstPtr cmd)
private

◆ applySetActiveContinuousContactManagerCommand()

bool tesseract_environment::Environment::applySetActiveContinuousContactManagerCommand ( const SetActiveContinuousContactManagerCommand::ConstPtr cmd)
private

◆ applySetActiveDiscreteContactManagerCommand()

bool tesseract_environment::Environment::applySetActiveDiscreteContactManagerCommand ( const SetActiveDiscreteContactManagerCommand::ConstPtr cmd)
private

◆ clear()

void tesseract_environment::Environment::clear ( )

clear content and uninitialized

◆ clearCachedContinuousContactManager()

void tesseract_environment::Environment::clearCachedContinuousContactManager ( ) const

Set the cached internal copy of the environments active continuous contact manager not nullptr.

This can be useful to save space in the event the environment is being saved

◆ clearCachedDiscreteContactManager()

void tesseract_environment::Environment::clearCachedDiscreteContactManager ( ) const

Set the cached internal copy of the environments active discrete contact manager not nullptr.

This can be useful to save space in the event the environment is being saved

◆ clearEventCallbacks()

void tesseract_environment::Environment::clearEventCallbacks ( )

clear all event callbacks

◆ clone()

Environment::UPtr tesseract_environment::Environment::clone ( ) const

Clone the environment.

Returns
A clone of the environment

◆ currentStateChanged()

void tesseract_environment::Environment::currentStateChanged ( )
protected

This will update the contact managers transforms

◆ environmentChanged()

void tesseract_environment::Environment::environmentChanged ( )
protected

This will notify the state solver that the environment has changed

◆ findTCPOffset()

Eigen::Isometry3d tesseract_environment::Environment::findTCPOffset ( const tesseract_common::ManipulatorInfo manip_info) const

Find tool center point provided in the manipulator info.

If manipulator information tcp is defined as a string it does the following

  • First check if manipulator info is empty or already an Isometry3d, if so return identity
  • Next if not, it checks if the tcp offset name is a link in the environment if so throw an exception.
  • Next if not found, it looks up the tcp name in the SRDF kinematics information
  • Next if not found, it leverages the user defined callbacks to try an locate the tcp information.
  • Next throw an exception, because no tcp information was located.
Parameters
manip_infoThe manipulator info
Returns
The tool center point

◆ getActiveJointNames()

std::vector< std::string > tesseract_environment::Environment::getActiveJointNames ( ) const

Get a vector of active joint names in the environment.

Returns
A vector of active joint names

◆ getActiveLinkNames() [1/2]

std::vector< std::string > tesseract_environment::Environment::getActiveLinkNames ( ) const

Get a vector of active link names in the environment.

Returns
A vector of active link names

◆ getActiveLinkNames() [2/2]

std::vector< std::string > tesseract_environment::Environment::getActiveLinkNames ( const std::vector< std::string > &  joint_names) const

Get a vector of active link names affected by the provided joints in the environment.

Parameters
joint_namesA list of joint names
Returns
A vector of active link names

◆ getAllowedCollisionMatrix()

tesseract_common::AllowedCollisionMatrix::ConstPtr tesseract_environment::Environment::getAllowedCollisionMatrix ( ) const

Get the allowed collision matrix.

Returns
AllowedCollisionMatrixConstPtr

◆ getCollisionMarginData()

tesseract_common::CollisionMarginData tesseract_environment::Environment::getCollisionMarginData ( ) const

Get the environment collision margin data.

◆ getCollisionObject()

void tesseract_environment::Environment::getCollisionObject ( tesseract_collision::CollisionShapesConst shapes,
tesseract_common::VectorIsometry3d shape_poses,
const tesseract_scene_graph::Link link 
)
staticprivate

◆ getCommandHistory()

Commands tesseract_environment::Environment::getCommandHistory ( ) const

Get Environment command history post initialization.

Returns
List of commands

◆ getContactManagersPluginInfo()

tesseract_common::ContactManagersPluginInfo tesseract_environment::Environment::getContactManagersPluginInfo ( ) const

Get the contact managers plugin information.

Returns
The contact managers plugin information

◆ getContinuousContactManager() [1/2]

tesseract_collision::ContinuousContactManager::UPtr tesseract_environment::Environment::getContinuousContactManager ( ) const

Get a copy of the environments active continuous contact manager.

◆ getContinuousContactManager() [2/2]

tesseract_collision::ContinuousContactManager::UPtr tesseract_environment::Environment::getContinuousContactManager ( const std::string &  name) const

Get a copy of the environments available continuous contact manager by name.

◆ getContinuousContactManagerHelper()

tesseract_collision::ContinuousContactManager::UPtr tesseract_environment::Environment::getContinuousContactManagerHelper ( const std::string &  name) const
private

◆ getCurrentJointValues() [1/2]

Eigen::VectorXd tesseract_environment::Environment::getCurrentJointValues ( ) const

Get the current state of the environment.

Order should be the same as getActiveJointNames()

Returns
A vector of joint values

◆ getCurrentJointValues() [2/2]

Eigen::VectorXd tesseract_environment::Environment::getCurrentJointValues ( const std::vector< std::string > &  joint_names) const

Get the current joint values for a vector of joints.

Order should be the same as the input vector

Returns
A vector of joint values

◆ getCurrentStateTimestamp()

std::chrono::system_clock::time_point tesseract_environment::Environment::getCurrentStateTimestamp ( ) const

Last update time to current state. Updated only when current state is updated.

◆ getDiscreteContactManager() [1/2]

tesseract_collision::DiscreteContactManager::UPtr tesseract_environment::Environment::getDiscreteContactManager ( ) const

Get a copy of the environments active discrete contact manager.

◆ getDiscreteContactManager() [2/2]

tesseract_collision::DiscreteContactManager::UPtr tesseract_environment::Environment::getDiscreteContactManager ( const std::string &  name) const

Get a copy of the environments available discrete contact manager by name.

◆ getDiscreteContactManagerHelper()

tesseract_collision::DiscreteContactManager::UPtr tesseract_environment::Environment::getDiscreteContactManagerHelper ( const std::string &  name) const
private

◆ getEventCallbacks()

std::map< std::size_t, EventCallbackFn > tesseract_environment::Environment::getEventCallbacks ( ) const

Get the current event callbacks stored in the environment.

Returns
A map of callback functions

◆ getFindTCPOffsetCallbacks()

std::vector< FindTCPOffsetCallbackFn > tesseract_environment::Environment::getFindTCPOffsetCallbacks ( ) const

This get the current find tcp callbacks stored in the environment.

Returns
A vector of callback functions

◆ getGroupJointNames()

std::vector< std::string > tesseract_environment::Environment::getGroupJointNames ( const std::string &  group_name) const

Get a groups joint names.

Parameters
group_nameThe group name
Returns
A vector of joint names

◆ getGroupNames()

tesseract_srdf::GroupNames tesseract_environment::Environment::getGroupNames ( ) const

Get the available group names.

Returns
The group names

◆ getInitCommands()

Commands tesseract_environment::Environment::getInitCommands ( const tesseract_scene_graph::SceneGraph scene_graph,
const tesseract_srdf::SRDFModel::ConstPtr srdf_model = nullptr 
)
staticprivate

◆ getJoint()

tesseract_scene_graph::Joint::ConstPtr tesseract_environment::Environment::getJoint ( const std::string &  name) const

Get joint by name.

Parameters
nameThe name of the joint
Returns
Joint Const Pointer

◆ getJointGroup() [1/2]

tesseract_kinematics::JointGroup::UPtr tesseract_environment::Environment::getJointGroup ( const std::string &  group_name) const

Get a joint group by name.

Parameters
group_nameThe group name
Returns
A joint group

◆ getJointGroup() [2/2]

tesseract_kinematics::JointGroup::UPtr tesseract_environment::Environment::getJointGroup ( const std::string &  name,
const std::vector< std::string > &  joint_names 
) const

Get a joint group given a vector of joint names.

Parameters
nameThe name to assign to the joint group
joint_namesThe joint names that make up the group
Returns
A joint group

◆ getJointLimits()

tesseract_scene_graph::JointLimits::ConstPtr tesseract_environment::Environment::getJointLimits ( const std::string &  joint_name) const

Gets the limits associated with a joint.

Parameters
joint_nameName of the joint to be updated
Returns
The joint limits set for the given joint

◆ getJointNames()

std::vector< std::string > tesseract_environment::Environment::getJointNames ( ) const

Get a vector of joint names in the environment.

Returns
A vector of joint names

◆ getKinematicGroup()

tesseract_kinematics::KinematicGroup::UPtr tesseract_environment::Environment::getKinematicGroup ( const std::string &  group_name,
std::string  ik_solver_name = "" 
) const

Get a kinematic group given group name and solver name.

If ik_solver_name is empty it will choose the first ik solver for the group

Parameters
group_nameThe group name
ik_solver_nameThe IK solver name
Returns
A kinematics group

◆ getKinematicsInformation()

tesseract_srdf::KinematicsInformation tesseract_environment::Environment::getKinematicsInformation ( ) const

Get the kinematics information.

Returns
The kinematics information

◆ getLink()

tesseract_scene_graph::Link::ConstPtr tesseract_environment::Environment::getLink ( const std::string &  name) const

Get a link in the environment.

Parameters
nameThe name of the link
Returns
Return nullptr if link name does not exists, otherwise a pointer to the link

◆ getLinkCollisionEnabled()

bool tesseract_environment::Environment::getLinkCollisionEnabled ( const std::string &  name) const

Get whether a link should be considered during collision checking.

Returns
True if should be considered during collision checking, otherwise false

◆ getLinkNames()

std::vector< std::string > tesseract_environment::Environment::getLinkNames ( ) const

Get a vector of link names in the environment.

Returns
A vector of link names

◆ getLinkTransform()

Eigen::Isometry3d tesseract_environment::Environment::getLinkTransform ( const std::string &  link_name) const

Get the transform corresponding to the link.

Returns
Transform and is identity when no transform is available.

◆ getLinkTransforms()

tesseract_common::VectorIsometry3d tesseract_environment::Environment::getLinkTransforms ( ) const

Get all of the links transforms.

Order should be the same as getLinkNames()

Returns
Get a vector of transforms for all links in the environment.

◆ getLinkVisibility()

bool tesseract_environment::Environment::getLinkVisibility ( const std::string &  name) const

Get a given links visibility setting.

Returns
True if should be visible, otherwise false

◆ getName()

const std::string & tesseract_environment::Environment::getName ( ) const

Get the name of the environment.

This may be empty, if so check urdf name

◆ getRelativeLinkTransform()

Eigen::Isometry3d tesseract_environment::Environment::getRelativeLinkTransform ( const std::string &  from_link_name,
const std::string &  to_link_name 
) const

Get transform between two links using the current state.

Parameters
from_link_nameThe link name the transform should be relative to
to_link_nameThe link name to get transform
Returns
The relative transform = inv(Transform(from_link_name)) * Transform(to_link_name)

◆ getResourceLocator()

tesseract_common::ResourceLocator::ConstPtr tesseract_environment::Environment::getResourceLocator ( ) const

Get the resource locator assigned.

This can be a nullptr

Returns
The resource locator assigned to the environment

◆ getRevision()

int tesseract_environment::Environment::getRevision ( ) const

Get the current revision number.

Returns
Revision number

◆ getRootLinkName()

std::string tesseract_environment::Environment::getRootLinkName ( ) const

Get the root link name.

Returns
String

◆ getSceneGraph()

tesseract_scene_graph::SceneGraph::ConstPtr tesseract_environment::Environment::getSceneGraph ( ) const

Get the Scene Graph.

Returns
SceneGraphConstPtr

◆ getState() [1/3]

tesseract_scene_graph::SceneState tesseract_environment::Environment::getState ( ) const

Get the current state of the environment.

◆ getState() [2/3]

tesseract_scene_graph::SceneState tesseract_environment::Environment::getState ( const std::unordered_map< std::string, double > &  joints) const

Get the state of the environment for a given set or subset of joint values.

This does not change the internal state of the environment.

Parameters
jointsA map of joint names to joint values to change.
Returns
A the state of the environment

◆ getState() [3/3]

tesseract_scene_graph::SceneState tesseract_environment::Environment::getState ( const std::vector< std::string > &  joint_names,
const Eigen::Ref< const Eigen::VectorXd > &  joint_values 
) const

◆ getStateSolver()

tesseract_scene_graph::StateSolver::UPtr tesseract_environment::Environment::getStateSolver ( ) const

Returns a clone of the environments state solver.

The Environment::getState contains mutex's which is may not be needed in all motion planners. This allows the user to get snap shot of the environment to calculate the state.

Returns
A clone of the environments state solver

◆ getStaticLinkNames() [1/2]

std::vector< std::string > tesseract_environment::Environment::getStaticLinkNames ( ) const

Get a vector of static link names in the environment.

Returns
A vector of static link names

◆ getStaticLinkNames() [2/2]

std::vector< std::string > tesseract_environment::Environment::getStaticLinkNames ( const std::vector< std::string > &  joint_names) const

Get a vector of static link names not affected by the provided joints in the environment.

Parameters
joint_namesA list of joint names
Returns
A vector of static link names

◆ getTimestamp()

std::chrono::system_clock::time_point tesseract_environment::Environment::getTimestamp ( ) const

Last update time. Updated when any change to the environment occurs.

◆ init() [1/6]

bool tesseract_environment::Environment::init ( const Commands commands)

Initialize the Environment.

The template class provided should be a derived class from StateSolver.

Parameters
scene_graphThe scene graph to initialize the environment.
Returns
True if successful, otherwise false

◆ init() [2/6]

bool tesseract_environment::Environment::init ( const std::string &  urdf_string,
const std::string &  srdf_string,
const tesseract_common::ResourceLocator::ConstPtr locator 
)

◆ init() [3/6]

bool tesseract_environment::Environment::init ( const std::string &  urdf_string,
const tesseract_common::ResourceLocator::ConstPtr locator 
)

◆ init() [4/6]

bool tesseract_environment::Environment::init ( const tesseract_common::fs::path &  urdf_path,
const tesseract_common::fs::path &  srdf_path,
const tesseract_common::ResourceLocator::ConstPtr locator 
)

◆ init() [5/6]

bool tesseract_environment::Environment::init ( const tesseract_common::fs::path &  urdf_path,
const tesseract_common::ResourceLocator::ConstPtr locator 
)

◆ init() [6/6]

bool tesseract_environment::Environment::init ( const tesseract_scene_graph::SceneGraph scene_graph,
const tesseract_srdf::SRDFModel::ConstPtr srdf_model = nullptr 
)

Initialize the Environment.

The template class provided should be a derived class from StateSolver.

Parameters
scene_graphThe scene graph to initialize the environment.
Returns
True if successful, otherwise false

◆ initHelper()

bool tesseract_environment::Environment::initHelper ( const Commands commands)
private

◆ isInitialized()

bool tesseract_environment::Environment::isInitialized ( ) const

check if the environment is initialized

◆ load()

template<class Archive >
void tesseract_environment::Environment::load ( Archive &  ar,
const unsigned int  version 
)
private

◆ lockRead()

std::shared_lock< std::shared_mutex > tesseract_environment::Environment::lockRead ( ) const

Lock the environment when wanting to make multiple reads.

This is useful when making multiple read function calls and don't want the data to get updated between function calls when there a multiple threads updating a single environment

◆ operator!=()

bool tesseract_environment::Environment::operator!= ( const Environment rhs) const

◆ operator=() [1/2]

Environment & tesseract_environment::Environment::operator= ( const Environment )
delete

◆ operator=() [2/2]

Environment & tesseract_environment::Environment::operator= ( Environment &&  )
delete

◆ operator==()

bool tesseract_environment::Environment::operator== ( const Environment rhs) const

These operators are to facilitate checking serialization but may have value elsewhere.

Parameters
rhsThe environment to compare
Returns
True if they are equal otherwise false
Todo:
uncomment after serialized

◆ removeEventCallback()

void tesseract_environment::Environment::removeEventCallback ( std::size_t  hash)

Remove event callbacks.

Parameters
hashthe id associated with the callback to be removed

◆ removeLinkHelper()

bool tesseract_environment::Environment::removeLinkHelper ( const std::string &  name)
private

◆ reset()

bool tesseract_environment::Environment::reset ( )

reset to initialized state

If the environment has not been initialized then this returns false

Returns
True if environment was successfully reset, otherwise false.

◆ save()

template<class Archive >
void tesseract_environment::Environment::save ( Archive &  ar,
const unsigned int  version 
) const
private

◆ serialize()

template<class Archive >
void tesseract_environment::Environment::serialize ( Archive &  ar,
const unsigned int  version 
)
private

◆ setActiveContinuousContactManager()

bool tesseract_environment::Environment::setActiveContinuousContactManager ( const std::string &  name)

Set the active continuous contact manager.

Parameters
nameThe name used to register the contact manager
Returns
True of name exists in ContinuousContactManagerFactory

◆ setActiveContinuousContactManagerHelper()

bool tesseract_environment::Environment::setActiveContinuousContactManagerHelper ( const std::string &  name)
private

◆ setActiveDiscreteContactManager()

bool tesseract_environment::Environment::setActiveDiscreteContactManager ( const std::string &  name)

Set the active discrete contact manager.

Parameters
nameThe name used to register the contact manager
Returns
True of name exists in DiscreteContactManagerFactory

◆ setActiveDiscreteContactManagerHelper()

bool tesseract_environment::Environment::setActiveDiscreteContactManagerHelper ( const std::string &  name)
private

◆ setName()

void tesseract_environment::Environment::setName ( const std::string &  name)

Give the environment a name.

◆ setResourceLocator()

void tesseract_environment::Environment::setResourceLocator ( tesseract_common::ResourceLocator::ConstPtr  locator)

Set resource locator for environment.

Parameters
locatorThe resource locator

◆ setState() [1/2]

void tesseract_environment::Environment::setState ( const std::unordered_map< std::string, double > &  joints)

Set the current state of the environment.

After updating the current state these function must call currentStateChanged() which will update the contact managers transforms

◆ setState() [2/2]

void tesseract_environment::Environment::setState ( const std::vector< std::string > &  joint_names,
const Eigen::Ref< const Eigen::VectorXd > &  joint_values 
)

◆ triggerCurrentStateChangedCallbacks()

void tesseract_environment::Environment::triggerCurrentStateChangedCallbacks ( )
protected

Passes a current state changed event to the callbacks.

Note
This does not take a lock

◆ triggerEnvironmentChangedCallbacks()

void tesseract_environment::Environment::triggerEnvironmentChangedCallbacks ( )
protected

Passes a environment changed event to the callbacks.

Note
This does not take a lock

Friends And Related Function Documentation

◆ boost::serialization::access

friend class boost::serialization::access
friend

Member Data Documentation

◆ collision_margin_data_

tesseract_collision::CollisionMarginData tesseract_environment::Environment::collision_margin_data_
protected

The collision margin data.

Note
This is intentionally not serialized it will auto updated

◆ commands_

Commands tesseract_environment::Environment::commands_ {}
protected

The history of commands applied to the environment after initialization.

◆ contact_managers_factory_

tesseract_collision::ContactManagersPluginFactory tesseract_environment::Environment::contact_managers_factory_
protected

The contact managers factory.

Note
This is intentionally not serialized it will auto updated

◆ contact_managers_plugin_info_

tesseract_common::ContactManagersPluginInfo tesseract_environment::Environment::contact_managers_plugin_info_
protected

The contact manager information.

Note
This is intentionally not serialized it will auto updated

◆ continuous_manager_

tesseract_collision::ContinuousContactManager::UPtr tesseract_environment::Environment::continuous_manager_ { nullptr }
mutableprotected

The continuous contact manager object.

Note
This is intentionally not serialized it will auto updated

◆ continuous_manager_mutex_

std::shared_mutex tesseract_environment::Environment::continuous_manager_mutex_
mutableprotected

◆ current_state_

tesseract_scene_graph::SceneState tesseract_environment::Environment::current_state_
protected

Current state of the environment.

◆ current_state_timestamp_

std::chrono::system_clock::time_point tesseract_environment::Environment::current_state_timestamp_ { std::chrono::system_clock::now() }
protected

Current state timestamp.

◆ discrete_manager_

tesseract_collision::DiscreteContactManager::UPtr tesseract_environment::Environment::discrete_manager_ { nullptr }
mutableprotected

The discrete contact manager object.

Note
This is intentionally not serialized it will auto updated

◆ discrete_manager_mutex_

std::shared_mutex tesseract_environment::Environment::discrete_manager_mutex_
mutableprotected

◆ event_cb_

std::map<std::size_t, EventCallbackFn> tesseract_environment::Environment::event_cb_ {}
protected

A map of user defined event callback functions.

This should not be cloned or serialized

◆ find_tcp_cb_

std::vector<FindTCPOffsetCallbackFn> tesseract_environment::Environment::find_tcp_cb_ {}
protected

A vector of user defined callbacks for locating tool center point.

Todo:
This needs to be switched to class so it may be serialized

◆ group_joint_names_cache_

std::unordered_map<std::string, std::vector<std::string> > tesseract_environment::Environment::group_joint_names_cache_ {}
mutableprotected

A cache of group joint names to provide faster access.

This will cleared when environment changes

Note
This is intentionally not serialized it will auto updated

◆ group_joint_names_cache_mutex_

std::shared_mutex tesseract_environment::Environment::group_joint_names_cache_mutex_
mutableprotected

◆ init_revision_

int tesseract_environment::Environment::init_revision_ { 0 }
protected

This is the revision number after initialization used when reset is called.

◆ initialized_

bool tesseract_environment::Environment::initialized_ { false }
protected

Identifies if the object has been initialized.

Note
This is intentionally not serialized it will auto updated

◆ is_contact_allowed_fn_

tesseract_collision::IsContactAllowedFn tesseract_environment::Environment::is_contact_allowed_fn_
protected

The function used to determine if two objects are allowed in collision.

Todo:
This needs to be switched to class so it may be serialized

◆ joint_group_cache_

std::unordered_map<std::string, tesseract_kinematics::JointGroup::UPtr> tesseract_environment::Environment::joint_group_cache_ {}
mutableprotected

A cache of joint groups to provide faster access.

This will cleared when environment changes

Note
This is intentionally not serialized it will auto updated

◆ joint_group_cache_mutex_

std::shared_mutex tesseract_environment::Environment::joint_group_cache_mutex_
mutableprotected

◆ kinematic_group_cache_

std::map<std::pair<std::string, std::string>, tesseract_kinematics::KinematicGroup::UPtr> tesseract_environment::Environment::kinematic_group_cache_ {}
mutableprotected

A cache of kinematic groups to provide faster access.

This will cleared when environment changes

Note
This is intentionally not serialized it will auto updated

◆ kinematic_group_cache_mutex_

std::shared_mutex tesseract_environment::Environment::kinematic_group_cache_mutex_
mutableprotected

◆ kinematics_factory_

tesseract_kinematics::KinematicsPluginFactory tesseract_environment::Environment::kinematics_factory_
protected

The kinematics factory.

Note
This is intentionally not serialized it will auto updated

◆ kinematics_information_

tesseract_srdf::KinematicsInformation tesseract_environment::Environment::kinematics_information_
protected

The kinematics information.

Note
This is intentionally not serialized it will auto updated

◆ mutex_

std::shared_mutex tesseract_environment::Environment::mutex_
mutableprotected

The environment can be accessed from multiple threads, need use mutex throughout.

◆ resource_locator_

tesseract_common::ResourceLocator::ConstPtr tesseract_environment::Environment::resource_locator_ { nullptr }
protected

Used when initialized by URDF_STRING, URDF_STRING_SRDF_STRING, URDF_PATH, and URDF_PATH_SRDF_PATH.

◆ revision_

int tesseract_environment::Environment::revision_ { 0 }
protected

This increments when the scene graph is modified.

Note
This is intentionally not serialized it will auto updated

◆ scene_graph_

tesseract_scene_graph::SceneGraph::Ptr tesseract_environment::Environment::scene_graph_ { nullptr }
protected

Tesseract Scene Graph.

Note
This is intentionally not serialized it will auto updated

◆ scene_graph_const_

tesseract_scene_graph::SceneGraph::ConstPtr tesseract_environment::Environment::scene_graph_const_ { nullptr }
protected

Tesseract Scene Graph Const.

Note
This is intentionally not serialized it will auto updated

◆ state_solver_

tesseract_scene_graph::MutableStateSolver::UPtr tesseract_environment::Environment::state_solver_ { nullptr }
protected

Tesseract State Solver.

Note
This is intentionally not serialized it will auto updated

◆ timestamp_

std::chrono::system_clock::time_point tesseract_environment::Environment::timestamp_ { std::chrono::system_clock::now() }
protected

Environment timestamp.


The documentation for this class was generated from the following files: