Tesseract
Motion Planning Environment
|
#include <environment.h>
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 | |
Environment & | operator= (const Environment &)=delete |
Environment (Environment &&)=delete | |
Environment & | operator= (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< FindTCPOffsetCallbackFn > | getFindTCPOffsetCallbacks () 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, EventCallbackFn > | getEventCallbacks () 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< FindTCPOffsetCallbackFn > | find_tcp_cb_ {} |
A vector of user defined callbacks for locating tool center point. More... | |
std::map< std::size_t, EventCallbackFn > | event_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::UPtr > | 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 >, tesseract_kinematics::KinematicGroup::UPtr > | kinematic_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... | |
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 |
using tesseract_environment::Environment::ConstPtr = std::shared_ptr<const Environment> |
using tesseract_environment::Environment::ConstUPtr = std::unique_ptr<const Environment> |
using tesseract_environment::Environment::Ptr = std::shared_ptr<Environment> |
using tesseract_environment::Environment::UPtr = std::unique_ptr<Environment> |
|
default |
Default constructor.
|
virtualdefault |
|
delete |
|
delete |
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.
hash | The 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. |
fn | User defined callback function which gets called for different event triggers |
void tesseract_environment::Environment::addFindTCPOffsetCallback | ( | const FindTCPOffsetCallbackFn & | fn | ) |
This allows for user defined callbacks for looking up TCP information.
fn | User defined callback function for locating TCP information |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
bool tesseract_environment::Environment::applyCommand | ( | Command::ConstPtr | command | ) |
bool tesseract_environment::Environment::applyCommands | ( | const Commands & | commands | ) |
Applies the commands to the environment.
commands | Commands to be applied to the environment |
|
private |
Apply Command Helper which does not lock.
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
void tesseract_environment::Environment::clear | ( | ) |
clear content and uninitialized
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
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
void tesseract_environment::Environment::clearEventCallbacks | ( | ) |
clear all event callbacks
Environment::UPtr tesseract_environment::Environment::clone | ( | ) | const |
Clone the environment.
|
protected |
This will update the contact managers transforms
|
protected |
This will notify the state solver that the environment has changed
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
manip_info | The manipulator info |
std::vector< std::string > tesseract_environment::Environment::getActiveJointNames | ( | ) | const |
Get a vector of active joint names in the environment.
std::vector< std::string > tesseract_environment::Environment::getActiveLinkNames | ( | ) | const |
Get a vector of active link names in the environment.
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.
joint_names | A list of joint names |
tesseract_common::AllowedCollisionMatrix::ConstPtr tesseract_environment::Environment::getAllowedCollisionMatrix | ( | ) | const |
Get the allowed collision matrix.
tesseract_common::CollisionMarginData tesseract_environment::Environment::getCollisionMarginData | ( | ) | const |
Get the environment collision margin data.
|
staticprivate |
Commands tesseract_environment::Environment::getCommandHistory | ( | ) | const |
Get Environment command history post initialization.
tesseract_common::ContactManagersPluginInfo tesseract_environment::Environment::getContactManagersPluginInfo | ( | ) | const |
Get the contact managers plugin information.
tesseract_collision::ContinuousContactManager::UPtr tesseract_environment::Environment::getContinuousContactManager | ( | ) | const |
Get a copy of the environments active continuous contact manager.
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.
|
private |
Eigen::VectorXd tesseract_environment::Environment::getCurrentJointValues | ( | ) | const |
Get the current state of the environment.
Order should be the same as getActiveJointNames()
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
std::chrono::system_clock::time_point tesseract_environment::Environment::getCurrentStateTimestamp | ( | ) | const |
Last update time to current state. Updated only when current state is updated.
tesseract_collision::DiscreteContactManager::UPtr tesseract_environment::Environment::getDiscreteContactManager | ( | ) | const |
Get a copy of the environments active discrete contact manager.
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.
|
private |
std::map< std::size_t, EventCallbackFn > tesseract_environment::Environment::getEventCallbacks | ( | ) | const |
Get the current event callbacks stored in the environment.
std::vector< FindTCPOffsetCallbackFn > tesseract_environment::Environment::getFindTCPOffsetCallbacks | ( | ) | const |
This get the current find tcp callbacks stored in the environment.
std::vector< std::string > tesseract_environment::Environment::getGroupJointNames | ( | const std::string & | group_name | ) | const |
Get a groups joint names.
group_name | The group name |
tesseract_srdf::GroupNames tesseract_environment::Environment::getGroupNames | ( | ) | const |
Get the available group names.
|
staticprivate |
tesseract_scene_graph::Joint::ConstPtr tesseract_environment::Environment::getJoint | ( | const std::string & | name | ) | const |
Get joint by name.
name | The name of the joint |
tesseract_kinematics::JointGroup::UPtr tesseract_environment::Environment::getJointGroup | ( | const std::string & | group_name | ) | const |
Get a joint group by name.
group_name | The group name |
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.
name | The name to assign to the joint group |
joint_names | The joint names that make up the group |
tesseract_scene_graph::JointLimits::ConstPtr tesseract_environment::Environment::getJointLimits | ( | const std::string & | joint_name | ) | const |
Gets the limits associated with a joint.
joint_name | Name of the joint to be updated |
std::vector< std::string > tesseract_environment::Environment::getJointNames | ( | ) | const |
Get a vector of joint names in the environment.
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
group_name | The group name |
ik_solver_name | The IK solver name |
tesseract_srdf::KinematicsInformation tesseract_environment::Environment::getKinematicsInformation | ( | ) | const |
Get the kinematics information.
tesseract_scene_graph::Link::ConstPtr tesseract_environment::Environment::getLink | ( | const std::string & | name | ) | const |
Get a link in the environment.
name | The name of the link |
bool tesseract_environment::Environment::getLinkCollisionEnabled | ( | const std::string & | name | ) | const |
Get whether a link should be considered during collision checking.
std::vector< std::string > tesseract_environment::Environment::getLinkNames | ( | ) | const |
Get a vector of link names in the environment.
Eigen::Isometry3d tesseract_environment::Environment::getLinkTransform | ( | const std::string & | link_name | ) | const |
Get the transform corresponding to the link.
tesseract_common::VectorIsometry3d tesseract_environment::Environment::getLinkTransforms | ( | ) | const |
Get all of the links transforms.
Order should be the same as getLinkNames()
bool tesseract_environment::Environment::getLinkVisibility | ( | const std::string & | name | ) | const |
Get a given links visibility setting.
const std::string & tesseract_environment::Environment::getName | ( | ) | const |
Get the name of the environment.
This may be empty, if so check urdf name
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.
from_link_name | The link name the transform should be relative to |
to_link_name | The link name to get transform |
tesseract_common::ResourceLocator::ConstPtr tesseract_environment::Environment::getResourceLocator | ( | ) | const |
Get the resource locator assigned.
This can be a nullptr
int tesseract_environment::Environment::getRevision | ( | ) | const |
Get the current revision number.
std::string tesseract_environment::Environment::getRootLinkName | ( | ) | const |
Get the root link name.
tesseract_scene_graph::SceneGraph::ConstPtr tesseract_environment::Environment::getSceneGraph | ( | ) | const |
Get the Scene Graph.
tesseract_scene_graph::SceneState tesseract_environment::Environment::getState | ( | ) | const |
Get the current state of the environment.
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.
joints | A map of joint names to joint values to change. |
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_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.
std::vector< std::string > tesseract_environment::Environment::getStaticLinkNames | ( | ) | const |
Get a vector of static link names in the environment.
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.
joint_names | A list of joint names |
std::chrono::system_clock::time_point tesseract_environment::Environment::getTimestamp | ( | ) | const |
Last update time. Updated when any change to the environment occurs.
bool tesseract_environment::Environment::init | ( | const Commands & | commands | ) |
Initialize the Environment.
The template class provided should be a derived class from StateSolver.
scene_graph | The scene graph to initialize the environment. |
bool tesseract_environment::Environment::init | ( | const std::string & | urdf_string, |
const std::string & | srdf_string, | ||
const tesseract_common::ResourceLocator::ConstPtr & | locator | ||
) |
bool tesseract_environment::Environment::init | ( | const std::string & | urdf_string, |
const tesseract_common::ResourceLocator::ConstPtr & | locator | ||
) |
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 | ||
) |
bool tesseract_environment::Environment::init | ( | const tesseract_common::fs::path & | urdf_path, |
const tesseract_common::ResourceLocator::ConstPtr & | locator | ||
) |
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.
scene_graph | The scene graph to initialize the environment. |
|
private |
bool tesseract_environment::Environment::isInitialized | ( | ) | const |
check if the environment is initialized
|
private |
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
bool tesseract_environment::Environment::operator!= | ( | const Environment & | rhs | ) | const |
|
delete |
|
delete |
bool tesseract_environment::Environment::operator== | ( | const Environment & | rhs | ) | const |
These operators are to facilitate checking serialization but may have value elsewhere.
rhs | The environment to compare |
void tesseract_environment::Environment::removeEventCallback | ( | std::size_t | hash | ) |
Remove event callbacks.
hash | the id associated with the callback to be removed |
|
private |
bool tesseract_environment::Environment::reset | ( | ) |
reset to initialized state
If the environment has not been initialized then this returns false
|
private |
|
private |
bool tesseract_environment::Environment::setActiveContinuousContactManager | ( | const std::string & | name | ) |
Set the active continuous contact manager.
name | The name used to register the contact manager |
|
private |
bool tesseract_environment::Environment::setActiveDiscreteContactManager | ( | const std::string & | name | ) |
Set the active discrete contact manager.
name | The name used to register the contact manager |
|
private |
void tesseract_environment::Environment::setName | ( | const std::string & | name | ) |
Give the environment a name.
void tesseract_environment::Environment::setResourceLocator | ( | tesseract_common::ResourceLocator::ConstPtr | locator | ) |
Set resource locator for environment.
locator | The resource locator |
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
void tesseract_environment::Environment::setState | ( | const std::vector< std::string > & | joint_names, |
const Eigen::Ref< const Eigen::VectorXd > & | joint_values | ||
) |
|
protected |
Passes a current state changed event to the callbacks.
|
protected |
Passes a environment changed event to the callbacks.
|
friend |
|
protected |
The collision margin data.
|
protected |
The history of commands applied to the environment after initialization.
|
protected |
The contact managers factory.
|
protected |
The contact manager information.
|
mutableprotected |
The continuous contact manager object.
|
mutableprotected |
|
protected |
Current state of the environment.
|
protected |
Current state timestamp.
|
mutableprotected |
The discrete contact manager object.
|
mutableprotected |
|
protected |
A map of user defined event callback functions.
This should not be cloned or serialized
|
protected |
A vector of user defined callbacks for locating tool center point.
|
mutableprotected |
A cache of group joint names to provide faster access.
This will cleared when environment changes
|
mutableprotected |
|
protected |
This is the revision number after initialization used when reset is called.
|
protected |
Identifies if the object has been initialized.
|
protected |
The function used to determine if two objects are allowed in collision.
|
mutableprotected |
A cache of joint groups to provide faster access.
This will cleared when environment changes
|
mutableprotected |
|
mutableprotected |
A cache of kinematic groups to provide faster access.
This will cleared when environment changes
|
mutableprotected |
|
protected |
The kinematics factory.
|
protected |
The kinematics information.
|
mutableprotected |
The environment can be accessed from multiple threads, need use mutex throughout.
|
protected |
Used when initialized by URDF_STRING, URDF_STRING_SRDF_STRING, URDF_PATH, and URDF_PATH_SRDF_PATH.
|
protected |
This increments when the scene graph is modified.
|
protected |
Tesseract Scene Graph.
|
protected |
Tesseract Scene Graph Const.
|
protected |
Tesseract State Solver.
|
protected |
Environment timestamp.