Classes | Public Types | Public Member Functions | Private Member Functions | Private Attributes | Friends | List of all members
tesseract_environment::Environment Class Reference

#include <environment.h>

Classes

struct  Implementation
 

Public Types

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

Public Member Functions

void addEventCallback (std::size_t hash, const EventCallbackFn &fn)
 Add an event callback function. More...
 
void addFindTCPOffsetCallback (const FindTCPOffsetCallbackFn &fn)
 This allows for user defined callbacks for looking up TCP information. More...
 
bool applyCommand (std::shared_ptr< const Command > command)
 Apply command to the environment. More...
 
bool applyCommands (const std::vector< std::shared_ptr< const Command >> &commands)
 Applies the commands to the environment. More...
 
void clear ()
 clear content and uninitialized More...
 
void clearCachedContinuousContactManager () const
 Set the cached internal copy of the environments active continuous contact manager not nullptr. More...
 
void clearCachedDiscreteContactManager () const
 Set the cached internal copy of the environments active discrete contact manager not nullptr. More...
 
void clearEventCallbacks ()
 clear all event callbacks More...
 
Environment::UPtr clone () const
 Clone the environment. More...
 
 Environment ()
 Default constructor. More...
 
 Environment (const Environment &)=delete
 
 Environment (Environment &&)=delete
 
 Environment (std::unique_ptr< Implementation > impl)
 This should only be used by the clone method. More...
 
Eigen::Isometry3d findTCPOffset (const tesseract_common::ManipulatorInfo &manip_info) const
 Find tool center point provided in the manipulator info. More...
 
std::vector< std::string > getActiveJointNames () const
 Get a vector of active joint 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::shared_ptr< const tesseract_common::AllowedCollisionMatrixgetAllowedCollisionMatrix () const
 Get the allowed collision matrix. More...
 
tesseract_common::CollisionMarginData getCollisionMarginData () const
 Get the environment collision margin data. More...
 
std::vector< std::shared_ptr< const Command > > getCommandHistory () const
 Get Environment command history post initialization. More...
 
tesseract_common::ContactManagersPluginInfo getContactManagersPluginInfo () const
 Get the contact managers plugin information. More...
 
std::unique_ptr< tesseract_collision::ContinuousContactManagergetContinuousContactManager () const
 Get a copy of the environments active continuous contact manager. More...
 
std::unique_ptr< tesseract_collision::ContinuousContactManagergetContinuousContactManager (const std::string &name) const
 Get a copy of the environments available continuous contact manager by name. More...
 
tesseract_common::TransformMap getCurrentFloatingJointValues () const
 Get the current floating joint values. More...
 
tesseract_common::TransformMap getCurrentFloatingJointValues (const std::vector< std::string > &joint_names) const
 Get the current floating joint values. 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::chrono::system_clock::time_point getCurrentStateTimestamp () const
 Last update time to current state. Updated only when current state is updated. More...
 
std::unique_ptr< tesseract_collision::DiscreteContactManagergetDiscreteContactManager () const
 Get a copy of the environments active discrete contact manager. More...
 
std::unique_ptr< tesseract_collision::DiscreteContactManagergetDiscreteContactManager (const std::string &name) const
 Get a copy of the environments available discrete contact manager by name. More...
 
std::map< std::size_t, EventCallbackFngetEventCallbacks () const
 Get the current event callbacks stored in the environment. More...
 
std::vector< FindTCPOffsetCallbackFngetFindTCPOffsetCallbacks () const
 This get the current find tcp callbacks stored in the environment. More...
 
std::vector< std::string > getGroupJointNames (const std::string &group_name) const
 Get a groups joint names. More...
 
std::set< std::string > getGroupNames () const
 Get the available group names. More...
 
int getInitRevision () const
 Get the initialization revision number. More...
 
std::shared_ptr< const tesseract_scene_graph::JointgetJoint (const std::string &name) const
 Get joint by name. More...
 
std::shared_ptr< const tesseract_kinematics::JointGroupgetJointGroup (const std::string &group_name) const
 Get a joint group by name. More...
 
std::shared_ptr< const tesseract_kinematics::JointGroupgetJointGroup (const std::string &name, const std::vector< std::string > &joint_names) const
 Get a joint group given a vector of joint names. More...
 
std::shared_ptr< const tesseract_scene_graph::JointLimitsgetJointLimits (const std::string &joint_name) const
 Gets the limits associated with a joint. More...
 
std::vector< std::string > getJointNames () const
 Get a vector of joint names in the environment. More...
 
std::shared_ptr< const tesseract_kinematics::KinematicGroupgetKinematicGroup (const std::string &group_name, const std::string &ik_solver_name="") const
 Get a kinematic group given group name and solver name. More...
 
tesseract_srdf::KinematicsInformation getKinematicsInformation () const
 Get the kinematics information. More...
 
std::shared_ptr< const tesseract_scene_graph::LinkgetLink (const std::string &name) const
 Get a link in the environment. More...
 
bool getLinkCollisionEnabled (const std::string &name) const
 Get whether a link should be considered during collision checking. More...
 
std::vector< std::string > getLinkNames () const
 Get a vector of link names in the environment. More...
 
Eigen::Isometry3d getLinkTransform (const std::string &link_name) const
 Get the transform corresponding to the link. More...
 
tesseract_common::VectorIsometry3d getLinkTransforms () const
 Get all of the links transforms. More...
 
bool getLinkVisibility (const std::string &name) const
 Get a given links visibility setting. More...
 
const std::string & getName () const
 Get the name of the environment. 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...
 
std::shared_ptr< const tesseract_common::ResourceLocatorgetResourceLocator () const
 Get the resource locator assigned. More...
 
int getRevision () const
 Get the current revision number. More...
 
std::string getRootLinkName () const
 Get the root link name. More...
 
std::shared_ptr< const tesseract_scene_graph::SceneGraphgetSceneGraph () const
 Get the Scene Graph. More...
 
tesseract_scene_graph::SceneState getState () const
 Get the current state of the environment. More...
 
tesseract_scene_graph::SceneState getState (const std::unordered_map< std::string, double > &joints, const tesseract_common::TransformMap &floating_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_common::TransformMap &floating_joints={}) const
 
tesseract_scene_graph::SceneState getState (const tesseract_common::TransformMap &floating_joints) const
 Get the state given floating joint values. More...
 
std::unique_ptr< tesseract_scene_graph::StateSolvergetStateSolver () const
 Returns a clone of the environments state solver. 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...
 
std::chrono::system_clock::time_point getTimestamp () const
 Last update time. Updated when any change to the environment occurs. More...
 
bool init (const std::filesystem::path &urdf_path, const std::filesystem::path &srdf_path, const std::shared_ptr< const tesseract_common::ResourceLocator > &locator)
 
bool init (const std::filesystem::path &urdf_path, const std::shared_ptr< const tesseract_common::ResourceLocator > &locator)
 
bool init (const std::string &urdf_string, const std::shared_ptr< const tesseract_common::ResourceLocator > &locator)
 
bool init (const std::string &urdf_string, const std::string &srdf_string, const std::shared_ptr< const tesseract_common::ResourceLocator > &locator)
 
bool init (const std::vector< std::shared_ptr< const Command >> &commands)
 Initialize the Environment. More...
 
bool init (const tesseract_scene_graph::SceneGraph &scene_graph, const std::shared_ptr< const tesseract_srdf::SRDFModel > &srdf_model=nullptr)
 Initialize the Environment. More...
 
bool isInitialized () const
 check if the environment is initialized 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
 
Environmentoperator= (const Environment &)=delete
 
Environmentoperator= (Environment &&)=delete
 
bool operator== (const Environment &rhs) const
 These operators are to facilitate checking serialization but may have value elsewhere. More...
 
void removeEventCallback (std::size_t hash)
 Remove event callbacks. More...
 
bool reset ()
 reset to initialized state More...
 
bool setActiveContinuousContactManager (const std::string &name)
 Set the active continuous contact manager. More...
 
bool setActiveDiscreteContactManager (const std::string &name)
 Set the active discrete contact manager. More...
 
void setName (const std::string &name)
 Give the environment a name. More...
 
void setResourceLocator (std::shared_ptr< const tesseract_common::ResourceLocator > locator)
 Set resource locator for environment. More...
 
void setState (const std::unordered_map< std::string, double > &joints, const tesseract_common::TransformMap &floating_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, const tesseract_common::TransformMap &floating_joints={})
 
void setState (const tesseract_common::TransformMap &floating_joints)
 Set the current state of the floating joint values. More...
 
virtual ~Environment ()
 

Private Member Functions

template<class Archive >
void load (Archive &ar, const unsigned int version)
 
template<class Archive >
void save (Archive &ar, const unsigned int version) const
 
template<class Archive >
void serialize (Archive &ar, const unsigned int version)
 

Private Attributes

std::unique_ptr< Implementationimpl_
 
std::shared_mutex mutex_
 The environment can be accessed from multiple threads, need use mutex throughout. More...
 

Friends

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

Detailed Description

Definition at line 71 of file environment.h.

Member Typedef Documentation

◆ ConstPtr

Definition at line 79 of file environment.h.

◆ ConstUPtr

Definition at line 81 of file environment.h.

◆ Ptr

Definition at line 78 of file environment.h.

◆ UPtr

Definition at line 80 of file environment.h.

Constructor & Destructor Documentation

◆ Environment() [1/4]

tesseract_environment::Environment::Environment ( )

Default constructor.

Definition at line 2152 of file environment.cpp.

◆ ~Environment()

tesseract_environment::Environment::~Environment ( )
virtualdefault

◆ Environment() [2/4]

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

◆ Environment() [3/4]

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

◆ Environment() [4/4]

tesseract_environment::Environment::Environment ( std::unique_ptr< Implementation impl)
explicit

This should only be used by the clone method.

Definition at line 2153 of file environment.cpp.

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

Definition at line 2416 of file environment.cpp.

◆ 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

Definition at line 2404 of file environment.cpp.

◆ applyCommand()

bool tesseract_environment::Environment::applyCommand ( std::shared_ptr< const Command 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

Definition at line 2364 of file environment.cpp.

◆ applyCommands()

bool tesseract_environment::Environment::applyCommands ( const std::vector< std::shared_ptr< const Command >> &  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

Definition at line 2351 of file environment.cpp.

◆ clear()

void tesseract_environment::Environment::clear ( )

clear content and uninitialized

Definition at line 2321 of file environment.cpp.

◆ 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

Definition at line 2737 of file environment.cpp.

◆ 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

Definition at line 2725 of file environment.cpp.

◆ clearEventCallbacks()

void tesseract_environment::Environment::clearEventCallbacks ( )

clear all event callbacks

Definition at line 2428 of file environment.cpp.

◆ clone()

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

Clone the environment.

Returns
A clone of the environment

Definition at line 2762 of file environment.cpp.

◆ 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

Definition at line 2398 of file environment.cpp.

◆ 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

Definition at line 2577 of file environment.cpp.

◆ 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

Definition at line 2626 of file environment.cpp.

◆ 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

Definition at line 2632 of file environment.cpp.

◆ getAllowedCollisionMatrix()

std::shared_ptr< const tesseract_common::AllowedCollisionMatrix > tesseract_environment::Environment::getAllowedCollisionMatrix ( ) const

Get the allowed collision matrix.

Returns
AllowedCollisionMatrixConstPtr

Definition at line 2565 of file environment.cpp.

◆ getCollisionMarginData()

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

Get the environment collision margin data.

Definition at line 2743 of file environment.cpp.

◆ getCommandHistory()

std::vector< std::shared_ptr< const Command > > tesseract_environment::Environment::getCommandHistory ( ) const

Get Environment command history post initialization.

Returns
List of commands

Definition at line 2345 of file environment.cpp.

◆ getContactManagersPluginInfo()

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

Get the contact managers plugin information.

Returns
The contact managers plugin information

Definition at line 2687 of file environment.cpp.

◆ getContinuousContactManager() [1/2]

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

Get a copy of the environments active continuous contact manager.

Definition at line 2731 of file environment.cpp.

◆ getContinuousContactManager() [2/2]

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

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

Definition at line 2713 of file environment.cpp.

◆ getCurrentFloatingJointValues() [1/2]

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

Get the current floating joint values.

Returns
The joint origin transform for the floating joint

Definition at line 2601 of file environment.cpp.

◆ getCurrentFloatingJointValues() [2/2]

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

Get the current floating joint values.

Returns
The joint origin transform for the floating joint

Definition at line 2608 of file environment.cpp.

◆ 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

Definition at line 2589 of file environment.cpp.

◆ 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

Definition at line 2595 of file environment.cpp.

◆ 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.

Definition at line 2533 of file environment.cpp.

◆ getDiscreteContactManager() [1/2]

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

Get a copy of the environments active discrete contact manager.

Definition at line 2719 of file environment.cpp.

◆ getDiscreteContactManager() [2/2]

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

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

Definition at line 2700 of file environment.cpp.

◆ 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

Definition at line 2434 of file environment.cpp.

◆ 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

Definition at line 2410 of file environment.cpp.

◆ 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

Definition at line 2371 of file environment.cpp.

◆ getGroupNames()

std::set< std::string > tesseract_environment::Environment::getGroupNames ( ) const

Get the available group names.

Returns
The group names

Definition at line 2681 of file environment.cpp.

◆ getInitRevision()

int tesseract_environment::Environment::getInitRevision ( ) const

Get the initialization revision number.

Returns
Initialization revision number

Definition at line 2339 of file environment.cpp.

◆ getJoint()

std::shared_ptr< const tesseract_scene_graph::Joint > tesseract_environment::Environment::getJoint ( const std::string &  name) const

Get joint by name.

Parameters
nameThe name of the joint
Returns
Joint Const Pointer

Definition at line 2583 of file environment.cpp.

◆ getJointGroup() [1/2]

std::shared_ptr< const tesseract_kinematics::JointGroup > 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

Definition at line 2377 of file environment.cpp.

◆ getJointGroup() [2/2]

std::shared_ptr< const tesseract_kinematics::JointGroup > 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

Definition at line 2384 of file environment.cpp.

◆ getJointLimits()

std::shared_ptr< const tesseract_scene_graph::JointLimits > 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

Definition at line 2547 of file environment.cpp.

◆ 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

Definition at line 2571 of file environment.cpp.

◆ getKinematicGroup()

std::shared_ptr< const tesseract_kinematics::KinematicGroup > tesseract_environment::Environment::getKinematicGroup ( const std::string &  group_name,
const 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

Definition at line 2391 of file environment.cpp.

◆ getKinematicsInformation()

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

Get the kinematics information.

Returns
The kinematics information

Definition at line 2675 of file environment.cpp.

◆ getLink()

std::shared_ptr< const tesseract_scene_graph::Link > 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

Definition at line 2539 of file environment.cpp.

◆ 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

Definition at line 2553 of file environment.cpp.

◆ 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

Definition at line 2620 of file environment.cpp.

◆ 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.

Definition at line 2656 of file environment.cpp.

◆ 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.

Definition at line 2650 of file environment.cpp.

◆ 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

Definition at line 2559 of file environment.cpp.

◆ getName()

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

Get the name of the environment.

This may be empty, if so check urdf name

Definition at line 2458 of file environment.cpp.

◆ 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)

Definition at line 2662 of file environment.cpp.

◆ getResourceLocator()

std::shared_ptr< const tesseract_common::ResourceLocator > tesseract_environment::Environment::getResourceLocator ( ) const

Get the resource locator assigned.

This can be a nullptr

Returns
The resource locator assigned to the environment

Definition at line 2446 of file environment.cpp.

◆ getRevision()

int tesseract_environment::Environment::getRevision ( ) const

Get the current revision number.

Returns
Revision number

Definition at line 2333 of file environment.cpp.

◆ getRootLinkName()

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

Get the root link name.

Returns
String

Definition at line 2614 of file environment.cpp.

◆ getSceneGraph()

std::shared_ptr< const tesseract_scene_graph::SceneGraph > tesseract_environment::Environment::getSceneGraph ( ) const

Get the Scene Graph.

Returns
SceneGraphConstPtr

Definition at line 2366 of file environment.cpp.

◆ getState() [1/4]

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

Get the current state of the environment.

Definition at line 2521 of file environment.cpp.

◆ getState() [2/4]

tesseract_scene_graph::SceneState tesseract_environment::Environment::getState ( const std::unordered_map< std::string, double > &  joints,
const tesseract_common::TransformMap floating_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

Definition at line 2500 of file environment.cpp.

◆ getState() [3/4]

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

Definition at line 2507 of file environment.cpp.

◆ getState() [4/4]

tesseract_scene_graph::SceneState tesseract_environment::Environment::getState ( const tesseract_common::TransformMap floating_joints) const

Get the state given floating joint values.

Parameters
floating_joint_valuesThe floating joint values to leverage
Returns
A the state of the environment

Definition at line 2515 of file environment.cpp.

◆ getStateSolver()

std::unique_ptr< tesseract_scene_graph::StateSolver > 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

Definition at line 2669 of file environment.cpp.

◆ 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

Definition at line 2638 of file environment.cpp.

◆ 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

Definition at line 2644 of file environment.cpp.

◆ getTimestamp()

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

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

Definition at line 2527 of file environment.cpp.

◆ init() [1/6]

bool tesseract_environment::Environment::init ( const std::filesystem::path &  urdf_path,
const std::filesystem::path &  srdf_path,
const std::shared_ptr< const tesseract_common::ResourceLocator > &  locator 
)

Definition at line 2267 of file environment.cpp.

◆ init() [2/6]

bool tesseract_environment::Environment::init ( const std::filesystem::path &  urdf_path,
const std::shared_ptr< const tesseract_common::ResourceLocator > &  locator 
)

Definition at line 2242 of file environment.cpp.

◆ init() [3/6]

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

Definition at line 2178 of file environment.cpp.

◆ init() [4/6]

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

Definition at line 2203 of file environment.cpp.

◆ init() [5/6]

bool tesseract_environment::Environment::init ( const std::vector< std::shared_ptr< const Command >> &  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

Definition at line 2156 of file environment.cpp.

◆ init() [6/6]

bool tesseract_environment::Environment::init ( const tesseract_scene_graph::SceneGraph scene_graph,
const std::shared_ptr< const tesseract_srdf::SRDFModel > &  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

Definition at line 2171 of file environment.cpp.

◆ isInitialized()

bool tesseract_environment::Environment::isInitialized ( ) const

check if the environment is initialized

Definition at line 2327 of file environment.cpp.

◆ load()

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

Definition at line 2776 of file environment.cpp.

◆ 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

Definition at line 2749 of file environment.cpp.

◆ operator!=()

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

Definition at line 2760 of file environment.cpp.

◆ 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

Definition at line 2754 of file environment.cpp.

◆ removeEventCallback()

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

Remove event callbacks.

Parameters
hashthe id associated with the callback to be removed

Definition at line 2422 of file environment.cpp.

◆ 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.

Definition at line 2306 of file environment.cpp.

◆ save()

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

Definition at line 2769 of file environment.cpp.

◆ serialize()

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

Definition at line 2783 of file environment.cpp.

◆ 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

Definition at line 2706 of file environment.cpp.

◆ 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

Definition at line 2693 of file environment.cpp.

◆ setName()

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

Give the environment a name.

Definition at line 2452 of file environment.cpp.

◆ setResourceLocator()

void tesseract_environment::Environment::setResourceLocator ( std::shared_ptr< const tesseract_common::ResourceLocator locator)

Set resource locator for environment.

Parameters
locatorThe resource locator

Definition at line 2440 of file environment.cpp.

◆ setState() [1/3]

void tesseract_environment::Environment::setState ( const std::unordered_map< std::string, double > &  joints,
const tesseract_common::TransformMap floating_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

Definition at line 2464 of file environment.cpp.

◆ setState() [2/3]

void tesseract_environment::Environment::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 2476 of file environment.cpp.

◆ setState() [3/3]

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

Set the current state of the floating joint values.

Parameters
floating_joint_valuesThe floating joint values to set

Definition at line 2489 of file environment.cpp.

Friends And Related Function Documentation

◆ boost::serialization::access

friend class boost::serialization::access
friend

Definition at line 576 of file environment.h.

◆ tesseract_common::Serialization

friend struct tesseract_common::Serialization
friend

Definition at line 577 of file environment.h.

Member Data Documentation

◆ impl_

std::unique_ptr<Implementation> tesseract_environment::Environment::impl_
private

Definition at line 573 of file environment.h.

◆ mutex_

std::shared_mutex tesseract_environment::Environment::mutex_
mutableprivate

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

Definition at line 570 of file environment.h.


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


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