Public Member Functions | Public Attributes | Friends | List of all members
tesseract_environment::Environment::Implementation Struct Reference

Public Member Functions

bool applyAddCommand (const std::shared_ptr< const AddLinkCommand > &cmd)
 
bool applyAddContactManagersPluginInfoCommand (const std::shared_ptr< const AddContactManagersPluginInfoCommand > &cmd)
 
bool applyAddKinematicsInformationCommand (const std::shared_ptr< const AddKinematicsInformationCommand > &cmd)
 
bool applyAddLinkCommandHelper (const std::shared_ptr< const tesseract_scene_graph::Link > &link, const std::shared_ptr< const tesseract_scene_graph::Joint > &joint, bool replace_allowed)
 
bool applyAddSceneGraphCommand (std::shared_ptr< const AddSceneGraphCommand > cmd)
 
bool applyAddTrajectoryLinkCommand (const std::shared_ptr< const AddTrajectoryLinkCommand > &cmd)
 
bool applyChangeCollisionMarginsCommand (const std::shared_ptr< const ChangeCollisionMarginsCommand > &cmd)
 
bool applyChangeJointAccelerationLimitsCommand (const std::shared_ptr< const ChangeJointAccelerationLimitsCommand > &cmd)
 
bool applyChangeJointOriginCommand (const std::shared_ptr< const ChangeJointOriginCommand > &cmd)
 
bool applyChangeJointPositionLimitsCommand (const std::shared_ptr< const ChangeJointPositionLimitsCommand > &cmd)
 
bool applyChangeJointVelocityLimitsCommand (const std::shared_ptr< const ChangeJointVelocityLimitsCommand > &cmd)
 
bool applyChangeLinkCollisionEnabledCommand (const std::shared_ptr< const ChangeLinkCollisionEnabledCommand > &cmd)
 
bool applyChangeLinkOriginCommand (const std::shared_ptr< const ChangeLinkOriginCommand > &cmd)
 
bool applyChangeLinkVisibilityCommand (const std::shared_ptr< const ChangeLinkVisibilityCommand > &cmd)
 
bool applyCommandsHelper (const std::vector< std::shared_ptr< const Command >> &commands)
 Apply Command Helper which does not lock. More...
 
bool applyModifyAllowedCollisionsCommand (const std::shared_ptr< const ModifyAllowedCollisionsCommand > &cmd)
 
bool applyMoveJointCommand (const std::shared_ptr< const MoveJointCommand > &cmd)
 
bool applyMoveLinkCommand (const std::shared_ptr< const MoveLinkCommand > &cmd)
 
bool applyRemoveAllowedCollisionLinkCommand (const std::shared_ptr< const RemoveAllowedCollisionLinkCommand > &cmd)
 
bool applyRemoveJointCommand (const std::shared_ptr< const RemoveJointCommand > &cmd)
 
bool applyRemoveLinkCommand (const std::shared_ptr< const RemoveLinkCommand > &cmd)
 
bool applyReplaceJointCommand (const std::shared_ptr< const ReplaceJointCommand > &cmd)
 
bool applySetActiveContinuousContactManagerCommand (const std::shared_ptr< const SetActiveContinuousContactManagerCommand > &cmd)
 
bool applySetActiveDiscreteContactManagerCommand (const std::shared_ptr< const SetActiveDiscreteContactManagerCommand > &cmd)
 
void clear ()
 
void clearCachedContinuousContactManager () const
 
void clearCachedDiscreteContactManager () const
 
std::unique_ptr< Implementationclone () const
 
void currentStateChanged ()
 
void environmentChanged ()
 
Eigen::Isometry3d findTCPOffset (const tesseract_common::ManipulatorInfo &manip_info) const
 
std::unique_ptr< tesseract_collision::ContinuousContactManagergetContinuousContactManager () const
 
std::unique_ptr< tesseract_collision::ContinuousContactManagergetContinuousContactManager (const std::string &name) const
 
std::unique_ptr< tesseract_collision::ContinuousContactManagergetContinuousContactManagerHelper (const std::string &name) const
 
tesseract_common::TransformMap getCurrentFloatingJointValues () const
 
tesseract_common::TransformMap getCurrentFloatingJointValues (const std::vector< std::string > &joint_names) const
 
Eigen::VectorXd getCurrentJointValues () const
 
Eigen::VectorXd getCurrentJointValues (const std::vector< std::string > &joint_names) const
 
std::unique_ptr< tesseract_collision::DiscreteContactManagergetDiscreteContactManager () const
 
std::unique_ptr< tesseract_collision::DiscreteContactManagergetDiscreteContactManager (const std::string &name) const
 
std::unique_ptr< tesseract_collision::DiscreteContactManagergetDiscreteContactManagerHelper (const std::string &name) const
 
std::vector< std::string > getGroupJointNames (const std::string &group_name) const
 
std::shared_ptr< const tesseract_kinematics::JointGroupgetJointGroup (const std::string &group_name) const
 
std::shared_ptr< const tesseract_kinematics::JointGroupgetJointGroup (const std::string &name, const std::vector< std::string > &joint_names) const
 
std::shared_ptr< const tesseract_kinematics::KinematicGroupgetKinematicGroup (const std::string &group_name, std::string ik_solver_name) const
 
std::vector< std::string > getStaticLinkNames (const std::vector< std::string > &joint_names) const
 
bool initHelper (const std::vector< std::shared_ptr< const Command >> &commands)
 
template<class Archive >
void load (Archive &ar, const unsigned int)
 
bool operator== (const Implementation &rhs) const
 
bool removeLinkHelper (const std::string &name)
 
bool reset ()
 
template<class Archive >
void save (Archive &ar, const unsigned int) const
 
template<class Archive >
void serialize (Archive &ar, const unsigned int version)
 
bool setActiveContinuousContactManager (const std::string &name)
 
bool setActiveContinuousContactManagerHelper (const std::string &name)
 
bool setActiveDiscreteContactManager (const std::string &name)
 
bool setActiveDiscreteContactManagerHelper (const std::string &name)
 
void setState (const std::unordered_map< std::string, double > &joints, const tesseract_common::TransformMap &floating_joints={})
 
void setState (const std::vector< std::string > &joint_names, const Eigen::Ref< const Eigen::VectorXd > &joint_values, const tesseract_common::TransformMap &floating_joints={})
 
void setState (const tesseract_common::TransformMap &floating_joints)
 
void triggerCallbacks ()
 Trigger both Current State and Environment changed callback. More...
 
void triggerCurrentStateChangedCallbacks ()
 Passes a current state changed event to the callbacks. More...
 
void triggerEnvironmentChangedCallbacks ()
 Passes a environment changed event to the callbacks. More...
 
 ~Implementation ()=default
 

Public Attributes

tesseract_common::CollisionMarginData collision_margin_data
 The collision margin data. More...
 
std::vector< std::shared_ptr< const Command > > commands {}
 The history of commands applied to the environment after initialization. More...
 
tesseract_common::ContactAllowedValidator::ConstPtr contact_allowed_validator
 The validator used to determine if two objects are allowed in collision. More...
 
tesseract_collision::ContactManagersPluginFactory contact_managers_factory
 The contact managers factory. More...
 
tesseract_common::ContactManagersPluginInfo contact_managers_plugin_info
 The contact manager information. More...
 
std::unique_ptr< tesseract_collision::ContinuousContactManagercontinuous_manager { nullptr }
 The continuous contact manager object. More...
 
std::shared_mutex continuous_manager_mutex
 
tesseract_scene_graph::SceneState current_state
 Current state of the environment. More...
 
std::chrono::system_clock::time_point current_state_timestamp { std::chrono::system_clock::now() }
 Current state timestamp. More...
 
std::unique_ptr< tesseract_collision::DiscreteContactManagerdiscrete_manager { nullptr }
 The discrete contact manager object. More...
 
std::shared_mutex discrete_manager_mutex
 
std::map< std::size_t, EventCallbackFnevent_cb {}
 A map of user defined event callback functions. More...
 
std::vector< FindTCPOffsetCallbackFnfind_tcp_cb {}
 A vector of user defined callbacks for locating tool center point. More...
 
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
 
int init_revision { 0 }
 This is the revision number after initialization used when reset is called. More...
 
bool initialized { false }
 Identifies if the object has been initialized. More...
 
std::unordered_map< std::string, std::shared_ptr< const tesseract_kinematics::JointGroup > > joint_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 >, std::shared_ptr< const tesseract_kinematics::KinematicGroup > > kinematic_group_cache {}
 A cache of kinematic groups to provide faster access. More...
 
std::shared_mutex kinematic_group_cache_mutex
 
tesseract_kinematics::KinematicsPluginFactory kinematics_factory
 The kinematics factory. More...
 
tesseract_srdf::KinematicsInformation kinematics_information
 The kinematics information. More...
 
std::shared_ptr< const tesseract_common::ResourceLocatorresource_locator { nullptr }
 Used when initialized by URDF_STRING, URDF_STRING_SRDF_STRING, URDF_PATH, and URDF_PATH_SRDF_PATH. More...
 
int revision { 0 }
 This increments when the scene graph is modified. More...
 
std::shared_ptr< tesseract_scene_graph::SceneGraphscene_graph { nullptr }
 Tesseract Scene Graph. More...
 
std::unique_ptr< tesseract_scene_graph::MutableStateSolverstate_solver { nullptr }
 Tesseract State Solver. More...
 
std::chrono::system_clock::time_point timestamp { std::chrono::system_clock::now() }
 Environment timestamp. More...
 

Friends

class boost::serialization::access
 
struct tesseract_common::Serialization
 

Detailed Description

Definition at line 164 of file environment.cpp.

Constructor & Destructor Documentation

◆ ~Implementation()

tesseract_environment::Environment::Implementation::~Implementation ( )
default

Member Function Documentation

◆ applyAddCommand()

bool tesseract_environment::Environment::Implementation::applyAddCommand ( const std::shared_ptr< const AddLinkCommand > &  cmd)

Definition at line 1354 of file environment.cpp.

◆ applyAddContactManagersPluginInfoCommand()

bool tesseract_environment::Environment::Implementation::applyAddContactManagersPluginInfoCommand ( const std::shared_ptr< const AddContactManagersPluginInfoCommand > &  cmd)

Definition at line 2046 of file environment.cpp.

◆ applyAddKinematicsInformationCommand()

bool tesseract_environment::Environment::Implementation::applyAddKinematicsInformationCommand ( const std::shared_ptr< const AddKinematicsInformationCommand > &  cmd)

Definition at line 2007 of file environment.cpp.

◆ applyAddLinkCommandHelper()

bool tesseract_environment::Environment::Implementation::applyAddLinkCommandHelper ( const std::shared_ptr< const tesseract_scene_graph::Link > &  link,
const std::shared_ptr< const tesseract_scene_graph::Joint > &  joint,
bool  replace_allowed 
)

Definition at line 1476 of file environment.cpp.

◆ applyAddSceneGraphCommand()

bool tesseract_environment::Environment::Implementation::applyAddSceneGraphCommand ( std::shared_ptr< const AddSceneGraphCommand cmd)

Definition at line 1844 of file environment.cpp.

◆ applyAddTrajectoryLinkCommand()

bool tesseract_environment::Environment::Implementation::applyAddTrajectoryLinkCommand ( const std::shared_ptr< const AddTrajectoryLinkCommand > &  cmd)

Definition at line 1370 of file environment.cpp.

◆ applyChangeCollisionMarginsCommand()

bool tesseract_environment::Environment::Implementation::applyChangeCollisionMarginsCommand ( const std::shared_ptr< const ChangeCollisionMarginsCommand > &  cmd)

Definition at line 2126 of file environment.cpp.

◆ applyChangeJointAccelerationLimitsCommand()

bool tesseract_environment::Environment::Implementation::applyChangeJointAccelerationLimitsCommand ( const std::shared_ptr< const ChangeJointAccelerationLimitsCommand > &  cmd)

Definition at line 1978 of file environment.cpp.

◆ applyChangeJointOriginCommand()

bool tesseract_environment::Environment::Implementation::applyChangeJointOriginCommand ( const std::shared_ptr< const ChangeJointOriginCommand > &  cmd)

Definition at line 1740 of file environment.cpp.

◆ applyChangeJointPositionLimitsCommand()

bool tesseract_environment::Environment::Implementation::applyChangeJointPositionLimitsCommand ( const std::shared_ptr< const ChangeJointPositionLimitsCommand > &  cmd)

Definition at line 1919 of file environment.cpp.

◆ applyChangeJointVelocityLimitsCommand()

bool tesseract_environment::Environment::Implementation::applyChangeJointVelocityLimitsCommand ( const std::shared_ptr< const ChangeJointVelocityLimitsCommand > &  cmd)

Definition at line 1949 of file environment.cpp.

◆ applyChangeLinkCollisionEnabledCommand()

bool tesseract_environment::Environment::Implementation::applyChangeLinkCollisionEnabledCommand ( const std::shared_ptr< const ChangeLinkCollisionEnabledCommand > &  cmd)

Definition at line 1754 of file environment.cpp.

◆ applyChangeLinkOriginCommand()

bool tesseract_environment::Environment::Implementation::applyChangeLinkOriginCommand ( const std::shared_ptr< const ChangeLinkOriginCommand > &  cmd)

Definition at line 1734 of file environment.cpp.

◆ applyChangeLinkVisibilityCommand()

bool tesseract_environment::Environment::Implementation::applyChangeLinkVisibilityCommand ( const std::shared_ptr< const ChangeLinkVisibilityCommand > &  cmd)

Definition at line 1786 of file environment.cpp.

◆ applyCommandsHelper()

bool tesseract_environment::Environment::Implementation::applyCommandsHelper ( const std::vector< std::shared_ptr< const Command >> &  commands)

Apply Command Helper which does not lock.

Definition at line 1182 of file environment.cpp.

◆ applyModifyAllowedCollisionsCommand()

bool tesseract_environment::Environment::Implementation::applyModifyAllowedCollisionsCommand ( const std::shared_ptr< const ModifyAllowedCollisionsCommand > &  cmd)

Definition at line 1799 of file environment.cpp.

◆ applyMoveJointCommand()

bool tesseract_environment::Environment::Implementation::applyMoveJointCommand ( const std::shared_ptr< const MoveJointCommand > &  cmd)

Definition at line 1646 of file environment.cpp.

◆ applyMoveLinkCommand()

bool tesseract_environment::Environment::Implementation::applyMoveLinkCommand ( const std::shared_ptr< const MoveLinkCommand > &  cmd)

Definition at line 1632 of file environment.cpp.

◆ applyRemoveAllowedCollisionLinkCommand()

bool tesseract_environment::Environment::Implementation::applyRemoveAllowedCollisionLinkCommand ( const std::shared_ptr< const RemoveAllowedCollisionLinkCommand > &  cmd)

Definition at line 1833 of file environment.cpp.

◆ applyRemoveJointCommand()

bool tesseract_environment::Environment::Implementation::applyRemoveJointCommand ( const std::shared_ptr< const RemoveJointCommand > &  cmd)

Definition at line 1674 of file environment.cpp.

◆ applyRemoveLinkCommand()

bool tesseract_environment::Environment::Implementation::applyRemoveLinkCommand ( const std::shared_ptr< const RemoveLinkCommand > &  cmd)

Definition at line 1660 of file environment.cpp.

◆ applyReplaceJointCommand()

bool tesseract_environment::Environment::Implementation::applyReplaceJointCommand ( const std::shared_ptr< const ReplaceJointCommand > &  cmd)

Definition at line 1696 of file environment.cpp.

◆ applySetActiveContinuousContactManagerCommand()

bool tesseract_environment::Environment::Implementation::applySetActiveContinuousContactManagerCommand ( const std::shared_ptr< const SetActiveContinuousContactManagerCommand > &  cmd)

Definition at line 2104 of file environment.cpp.

◆ applySetActiveDiscreteContactManagerCommand()

bool tesseract_environment::Environment::Implementation::applySetActiveDiscreteContactManagerCommand ( const std::shared_ptr< const SetActiveDiscreteContactManagerCommand > &  cmd)

Definition at line 2115 of file environment.cpp.

◆ clear()

void tesseract_environment::Environment::Implementation::clear ( )

Definition at line 665 of file environment.cpp.

◆ clearCachedContinuousContactManager()

void tesseract_environment::Environment::Implementation::clearCachedContinuousContactManager ( ) const

Definition at line 988 of file environment.cpp.

◆ clearCachedDiscreteContactManager()

void tesseract_environment::Environment::Implementation::clearCachedDiscreteContactManager ( ) const

Definition at line 982 of file environment.cpp.

◆ clone()

std::unique_ptr< Environment::Implementation > tesseract_environment::Environment::Implementation::clone ( ) const

Definition at line 496 of file environment.cpp.

◆ currentStateChanged()

void tesseract_environment::Environment::Implementation::currentStateChanged ( )

This will update the contact managers transforms

Definition at line 722 of file environment.cpp.

◆ environmentChanged()

void tesseract_environment::Environment::Implementation::environmentChanged ( )

This will notify the state solver that the environment has changed

Definition at line 753 of file environment.cpp.

◆ findTCPOffset()

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

Definition at line 903 of file environment.cpp.

◆ getContinuousContactManager() [1/2]

std::unique_ptr< tesseract_collision::ContinuousContactManager > tesseract_environment::Environment::Implementation::getContinuousContactManager ( ) const

Definition at line 960 of file environment.cpp.

◆ getContinuousContactManager() [2/2]

std::unique_ptr< tesseract_collision::ContinuousContactManager > tesseract_environment::Environment::Implementation::getContinuousContactManager ( const std::string &  name) const

Definition at line 1137 of file environment.cpp.

◆ getContinuousContactManagerHelper()

std::unique_ptr< tesseract_collision::ContinuousContactManager > tesseract_environment::Environment::Implementation::getContinuousContactManagerHelper ( const std::string &  name) const

Definition at line 1072 of file environment.cpp.

◆ getCurrentFloatingJointValues() [1/2]

tesseract_common::TransformMap tesseract_environment::Environment::Implementation::getCurrentFloatingJointValues ( ) const

Definition at line 630 of file environment.cpp.

◆ getCurrentFloatingJointValues() [2/2]

tesseract_common::TransformMap tesseract_environment::Environment::Implementation::getCurrentFloatingJointValues ( const std::vector< std::string > &  joint_names) const

Definition at line 636 of file environment.cpp.

◆ getCurrentJointValues() [1/2]

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

Definition at line 609 of file environment.cpp.

◆ getCurrentJointValues() [2/2]

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

Definition at line 620 of file environment.cpp.

◆ getDiscreteContactManager() [1/2]

std::unique_ptr< tesseract_collision::DiscreteContactManager > tesseract_environment::Environment::Implementation::getDiscreteContactManager ( ) const

Definition at line 937 of file environment.cpp.

◆ getDiscreteContactManager() [2/2]

std::unique_ptr< tesseract_collision::DiscreteContactManager > tesseract_environment::Environment::Implementation::getDiscreteContactManager ( const std::string &  name) const

Definition at line 1118 of file environment.cpp.

◆ getDiscreteContactManagerHelper()

std::unique_ptr< tesseract_collision::DiscreteContactManager > tesseract_environment::Environment::Implementation::getDiscreteContactManagerHelper ( const std::string &  name) const

Definition at line 1040 of file environment.cpp.

◆ getGroupJointNames()

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

Definition at line 804 of file environment.cpp.

◆ getJointGroup() [1/2]

std::shared_ptr< const tesseract_kinematics::JointGroup > tesseract_environment::Environment::Implementation::getJointGroup ( const std::string &  group_name) const

Definition at line 844 of file environment.cpp.

◆ getJointGroup() [2/2]

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

Definition at line 860 of file environment.cpp.

◆ getKinematicGroup()

std::shared_ptr< const tesseract_kinematics::KinematicGroup > tesseract_environment::Environment::Implementation::getKinematicGroup ( const std::string &  group_name,
std::string  ik_solver_name 
) const

Definition at line 866 of file environment.cpp.

◆ getStaticLinkNames()

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

Definition at line 646 of file environment.cpp.

◆ initHelper()

bool tesseract_environment::Environment::Implementation::initHelper ( const std::vector< std::shared_ptr< const Command >> &  commands)

Definition at line 555 of file environment.cpp.

◆ load()

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

Definition at line 434 of file environment.cpp.

◆ operator==()

bool tesseract_environment::Environment::Implementation::operator== ( const Implementation rhs) const
Todo:
uncomment after serialized

Definition at line 465 of file environment.cpp.

◆ removeLinkHelper()

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

Definition at line 1149 of file environment.cpp.

◆ reset()

bool tesseract_environment::Environment::Implementation::reset ( )

Definition at line 709 of file environment.cpp.

◆ save()

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

Definition at line 418 of file environment.cpp.

◆ serialize()

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

Definition at line 459 of file environment.cpp.

◆ setActiveContinuousContactManager()

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

Definition at line 1130 of file environment.cpp.

◆ setActiveContinuousContactManagerHelper()

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

Definition at line 1016 of file environment.cpp.

◆ setActiveDiscreteContactManager()

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

Definition at line 1111 of file environment.cpp.

◆ setActiveDiscreteContactManagerHelper()

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

Definition at line 994 of file environment.cpp.

◆ setState() [1/3]

void tesseract_environment::Environment::Implementation::setState ( const std::unordered_map< std::string, double > &  joints,
const tesseract_common::TransformMap floating_joints = {} 
)

Definition at line 588 of file environment.cpp.

◆ setState() [2/3]

void tesseract_environment::Environment::Implementation::setState ( const std::vector< std::string > &  joint_names,
const Eigen::Ref< const Eigen::VectorXd > &  joint_values,
const tesseract_common::TransformMap floating_joints = {} 
)

Definition at line 595 of file environment.cpp.

◆ setState() [3/3]

void tesseract_environment::Environment::Implementation::setState ( const tesseract_common::TransformMap floating_joints)

Definition at line 603 of file environment.cpp.

◆ triggerCallbacks()

void tesseract_environment::Environment::Implementation::triggerCallbacks ( )

Trigger both Current State and Environment changed callback.

Definition at line 798 of file environment.cpp.

◆ triggerCurrentStateChangedCallbacks()

void tesseract_environment::Environment::Implementation::triggerCurrentStateChangedCallbacks ( )

Passes a current state changed event to the callbacks.

Definition at line 778 of file environment.cpp.

◆ triggerEnvironmentChangedCallbacks()

void tesseract_environment::Environment::Implementation::triggerEnvironmentChangedCallbacks ( )

Passes a environment changed event to the callbacks.

Definition at line 788 of file environment.cpp.

Friends And Related Function Documentation

◆ boost::serialization::access

friend class boost::serialization::access
friend

Definition at line 415 of file environment.cpp.

◆ tesseract_common::Serialization

friend struct tesseract_common::Serialization
friend

Definition at line 416 of file environment.cpp.

Member Data Documentation

◆ collision_margin_data

tesseract_common::CollisionMarginData tesseract_environment::Environment::Implementation::collision_margin_data

The collision margin data.

Note
This is intentionally not serialized it will auto updated

Definition at line 231 of file environment.cpp.

◆ commands

std::vector<std::shared_ptr<const Command> > tesseract_environment::Environment::Implementation::commands {}

The history of commands applied to the environment after initialization.

Definition at line 184 of file environment.cpp.

◆ contact_allowed_validator

tesseract_common::ContactAllowedValidator::ConstPtr tesseract_environment::Environment::Implementation::contact_allowed_validator

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

Definition at line 210 of file environment.cpp.

◆ contact_managers_factory

tesseract_collision::ContactManagersPluginFactory tesseract_environment::Environment::Implementation::contact_managers_factory

The contact managers factory.

Note
This is intentionally not serialized it will auto updated

Definition at line 255 of file environment.cpp.

◆ contact_managers_plugin_info

tesseract_common::ContactManagersPluginInfo tesseract_environment::Environment::Implementation::contact_managers_plugin_info

The contact manager information.

Note
This is intentionally not serialized it will auto updated

Definition at line 249 of file environment.cpp.

◆ continuous_manager

std::unique_ptr<tesseract_collision::ContinuousContactManager> tesseract_environment::Environment::Implementation::continuous_manager { nullptr }
mutable

The continuous contact manager object.

Note
This is intentionally not serialized it will auto updated

Definition at line 268 of file environment.cpp.

◆ continuous_manager_mutex

std::shared_mutex tesseract_environment::Environment::Implementation::continuous_manager_mutex
mutable

Definition at line 269 of file environment.cpp.

◆ current_state

tesseract_scene_graph::SceneState tesseract_environment::Environment::Implementation::current_state

Current state of the environment.

Definition at line 193 of file environment.cpp.

◆ current_state_timestamp

std::chrono::system_clock::time_point tesseract_environment::Environment::Implementation::current_state_timestamp { std::chrono::system_clock::now() }

Current state timestamp.

Definition at line 199 of file environment.cpp.

◆ discrete_manager

std::unique_ptr<tesseract_collision::DiscreteContactManager> tesseract_environment::Environment::Implementation::discrete_manager { nullptr }
mutable

The discrete contact manager object.

Note
This is intentionally not serialized it will auto updated

Definition at line 261 of file environment.cpp.

◆ discrete_manager_mutex

std::shared_mutex tesseract_environment::Environment::Implementation::discrete_manager_mutex
mutable

Definition at line 262 of file environment.cpp.

◆ event_cb

std::map<std::size_t, EventCallbackFn> tesseract_environment::Environment::Implementation::event_cb {}

A map of user defined event callback functions.

This should not be cloned or serialized

Definition at line 222 of file environment.cpp.

◆ find_tcp_cb

std::vector<FindTCPOffsetCallbackFn> tesseract_environment::Environment::Implementation::find_tcp_cb {}

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

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

Definition at line 216 of file environment.cpp.

◆ group_joint_names_cache

std::unordered_map<std::string, std::vector<std::string> > tesseract_environment::Environment::Implementation::group_joint_names_cache {}
mutable

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

Definition at line 276 of file environment.cpp.

◆ group_joint_names_cache_mutex

std::shared_mutex tesseract_environment::Environment::Implementation::group_joint_names_cache_mutex
mutable

Definition at line 277 of file environment.cpp.

◆ init_revision

int tesseract_environment::Environment::Implementation::init_revision { 0 }

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

Definition at line 181 of file environment.cpp.

◆ initialized

bool tesseract_environment::Environment::Implementation::initialized { false }

Identifies if the object has been initialized.

Note
This is intentionally not serialized it will auto updated

Definition at line 172 of file environment.cpp.

◆ joint_group_cache

std::unordered_map<std::string, std::shared_ptr<const tesseract_kinematics::JointGroup> > tesseract_environment::Environment::Implementation::joint_group_cache {}
mutable

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

Definition at line 284 of file environment.cpp.

◆ joint_group_cache_mutex

std::shared_mutex tesseract_environment::Environment::Implementation::joint_group_cache_mutex
mutable

Definition at line 285 of file environment.cpp.

◆ kinematic_group_cache

std::map<std::pair<std::string, std::string>, std::shared_ptr<const tesseract_kinematics::KinematicGroup> > tesseract_environment::Environment::Implementation::kinematic_group_cache {}
mutable

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

Definition at line 293 of file environment.cpp.

◆ kinematic_group_cache_mutex

std::shared_mutex tesseract_environment::Environment::Implementation::kinematic_group_cache_mutex
mutable

Definition at line 294 of file environment.cpp.

◆ kinematics_factory

tesseract_kinematics::KinematicsPluginFactory tesseract_environment::Environment::Implementation::kinematics_factory

The kinematics factory.

Note
This is intentionally not serialized it will auto updated

Definition at line 243 of file environment.cpp.

◆ kinematics_information

tesseract_srdf::KinematicsInformation tesseract_environment::Environment::Implementation::kinematics_information

The kinematics information.

Note
This is intentionally not serialized it will auto updated

Definition at line 237 of file environment.cpp.

◆ resource_locator

std::shared_ptr<const tesseract_common::ResourceLocator> tesseract_environment::Environment::Implementation::resource_locator { nullptr }

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

Definition at line 225 of file environment.cpp.

◆ revision

int tesseract_environment::Environment::Implementation::revision { 0 }

This increments when the scene graph is modified.

Note
This is intentionally not serialized it will auto updated

Definition at line 178 of file environment.cpp.

◆ scene_graph

std::shared_ptr<tesseract_scene_graph::SceneGraph> tesseract_environment::Environment::Implementation::scene_graph { nullptr }

Tesseract Scene Graph.

Note
This is intentionally not serialized it will auto updated

Definition at line 190 of file environment.cpp.

◆ state_solver

std::unique_ptr<tesseract_scene_graph::MutableStateSolver> tesseract_environment::Environment::Implementation::state_solver { nullptr }

Tesseract State Solver.

Note
This is intentionally not serialized it will auto updated

Definition at line 205 of file environment.cpp.

◆ timestamp

std::chrono::system_clock::time_point tesseract_environment::Environment::Implementation::timestamp { std::chrono::system_clock::now() }

Environment timestamp.

Definition at line 196 of file environment.cpp.


The documentation for this struct was generated from the following file:


tesseract_environment
Author(s): Levi Armstrong
autogenerated on Sun May 18 2025 03:02:21