#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::AllowedCollisionMatrix > | getAllowedCollisionMatrix () 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::ContinuousContactManager > | getContinuousContactManager () const |
Get a copy of the environments active continuous contact manager. More... | |
std::unique_ptr< tesseract_collision::ContinuousContactManager > | getContinuousContactManager (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::DiscreteContactManager > | getDiscreteContactManager () const |
Get a copy of the environments active discrete contact manager. More... | |
std::unique_ptr< tesseract_collision::DiscreteContactManager > | getDiscreteContactManager (const std::string &name) const |
Get a copy of the environments available discrete contact manager by name. More... | |
std::map< std::size_t, EventCallbackFn > | getEventCallbacks () const |
Get the current event callbacks stored in the environment. More... | |
std::vector< FindTCPOffsetCallbackFn > | getFindTCPOffsetCallbacks () 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::Joint > | getJoint (const std::string &name) const |
Get joint by name. More... | |
std::shared_ptr< const tesseract_kinematics::JointGroup > | getJointGroup (const std::string &group_name) const |
Get a joint group by name. More... | |
std::shared_ptr< const tesseract_kinematics::JointGroup > | getJointGroup (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::JointLimits > | getJointLimits (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::KinematicGroup > | getKinematicGroup (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::Link > | getLink (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::ResourceLocator > | getResourceLocator () 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::SceneGraph > | getSceneGraph () 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::StateSolver > | getStateSolver () 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 |
Environment & | operator= (const Environment &)=delete |
Environment & | operator= (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< Implementation > | impl_ |
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 |
Definition at line 71 of file environment.h.
using tesseract_environment::Environment::ConstPtr = std::shared_ptr<const Environment> |
Definition at line 79 of file environment.h.
using tesseract_environment::Environment::ConstUPtr = std::unique_ptr<const Environment> |
Definition at line 81 of file environment.h.
using tesseract_environment::Environment::Ptr = std::shared_ptr<Environment> |
Definition at line 78 of file environment.h.
using tesseract_environment::Environment::UPtr = std::unique_ptr<Environment> |
Definition at line 80 of file environment.h.
tesseract_environment::Environment::Environment | ( | ) |
Default constructor.
Definition at line 2152 of file environment.cpp.
|
virtualdefault |
|
delete |
|
delete |
|
explicit |
This should only be used by the clone method.
Definition at line 2153 of file environment.cpp.
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 |
Definition at line 2416 of file environment.cpp.
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 |
Definition at line 2404 of file environment.cpp.
bool tesseract_environment::Environment::applyCommand | ( | std::shared_ptr< const Command > | command | ) |
Apply command to the environment.
command | Command to be applied to the environment |
Definition at line 2364 of file environment.cpp.
bool tesseract_environment::Environment::applyCommands | ( | const std::vector< std::shared_ptr< const Command >> & | commands | ) |
Applies the commands to the environment.
commands | Commands to be applied to the environment |
Definition at line 2351 of file environment.cpp.
void tesseract_environment::Environment::clear | ( | ) |
clear content and uninitialized
Definition at line 2321 of file environment.cpp.
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.
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.
void tesseract_environment::Environment::clearEventCallbacks | ( | ) |
clear all event callbacks
Definition at line 2428 of file environment.cpp.
Environment::UPtr tesseract_environment::Environment::clone | ( | ) | const |
Clone the environment.
Definition at line 2762 of file environment.cpp.
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 |
Definition at line 2398 of file environment.cpp.
std::vector< std::string > tesseract_environment::Environment::getActiveJointNames | ( | ) | const |
Get a vector of active joint names in the environment.
Definition at line 2577 of file environment.cpp.
std::vector< std::string > tesseract_environment::Environment::getActiveLinkNames | ( | ) | const |
Get a vector of active link names in the environment.
Definition at line 2626 of file environment.cpp.
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 |
Definition at line 2632 of file environment.cpp.
std::shared_ptr< const tesseract_common::AllowedCollisionMatrix > tesseract_environment::Environment::getAllowedCollisionMatrix | ( | ) | const |
Get the allowed collision matrix.
Definition at line 2565 of file environment.cpp.
tesseract_common::CollisionMarginData tesseract_environment::Environment::getCollisionMarginData | ( | ) | const |
Get the environment collision margin data.
Definition at line 2743 of file environment.cpp.
std::vector< std::shared_ptr< const Command > > tesseract_environment::Environment::getCommandHistory | ( | ) | const |
Get Environment command history post initialization.
Definition at line 2345 of file environment.cpp.
tesseract_common::ContactManagersPluginInfo tesseract_environment::Environment::getContactManagersPluginInfo | ( | ) | const |
Get the contact managers plugin information.
Definition at line 2687 of file environment.cpp.
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.
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.
tesseract_common::TransformMap tesseract_environment::Environment::getCurrentFloatingJointValues | ( | ) | const |
Get the current floating joint values.
Definition at line 2601 of file environment.cpp.
tesseract_common::TransformMap tesseract_environment::Environment::getCurrentFloatingJointValues | ( | const std::vector< std::string > & | joint_names | ) | const |
Get the current floating joint values.
Definition at line 2608 of file environment.cpp.
Eigen::VectorXd tesseract_environment::Environment::getCurrentJointValues | ( | ) | const |
Get the current state of the environment.
Order should be the same as getActiveJointNames()
Definition at line 2589 of file environment.cpp.
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
Definition at line 2595 of file environment.cpp.
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.
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.
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.
std::map< std::size_t, EventCallbackFn > tesseract_environment::Environment::getEventCallbacks | ( | ) | const |
Get the current event callbacks stored in the environment.
Definition at line 2434 of file environment.cpp.
std::vector< FindTCPOffsetCallbackFn > tesseract_environment::Environment::getFindTCPOffsetCallbacks | ( | ) | const |
This get the current find tcp callbacks stored in the environment.
Definition at line 2410 of file environment.cpp.
std::vector< std::string > tesseract_environment::Environment::getGroupJointNames | ( | const std::string & | group_name | ) | const |
Get a groups joint names.
group_name | The group name |
Definition at line 2371 of file environment.cpp.
std::set< std::string > tesseract_environment::Environment::getGroupNames | ( | ) | const |
Get the available group names.
Definition at line 2681 of file environment.cpp.
int tesseract_environment::Environment::getInitRevision | ( | ) | const |
Get the initialization revision number.
Definition at line 2339 of file environment.cpp.
std::shared_ptr< const tesseract_scene_graph::Joint > tesseract_environment::Environment::getJoint | ( | const std::string & | name | ) | const |
Get joint by name.
name | The name of the joint |
Definition at line 2583 of file environment.cpp.
std::shared_ptr< const tesseract_kinematics::JointGroup > tesseract_environment::Environment::getJointGroup | ( | const std::string & | group_name | ) | const |
Get a joint group by name.
group_name | The group name |
Definition at line 2377 of file environment.cpp.
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.
name | The name to assign to the joint group |
joint_names | The joint names that make up the group |
Definition at line 2384 of file environment.cpp.
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.
joint_name | Name of the joint to be updated |
Definition at line 2547 of file environment.cpp.
std::vector< std::string > tesseract_environment::Environment::getJointNames | ( | ) | const |
Get a vector of joint names in the environment.
Definition at line 2571 of file environment.cpp.
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
group_name | The group name |
ik_solver_name | The IK solver name |
Definition at line 2391 of file environment.cpp.
tesseract_srdf::KinematicsInformation tesseract_environment::Environment::getKinematicsInformation | ( | ) | const |
Get the kinematics information.
Definition at line 2675 of file environment.cpp.
std::shared_ptr< const tesseract_scene_graph::Link > tesseract_environment::Environment::getLink | ( | const std::string & | name | ) | const |
Get a link in the environment.
name | The name of the link |
Definition at line 2539 of file environment.cpp.
bool tesseract_environment::Environment::getLinkCollisionEnabled | ( | const std::string & | name | ) | const |
Get whether a link should be considered during collision checking.
Definition at line 2553 of file environment.cpp.
std::vector< std::string > tesseract_environment::Environment::getLinkNames | ( | ) | const |
Get a vector of link names in the environment.
Definition at line 2620 of file environment.cpp.
Eigen::Isometry3d tesseract_environment::Environment::getLinkTransform | ( | const std::string & | link_name | ) | const |
Get the transform corresponding to the link.
Definition at line 2656 of file environment.cpp.
tesseract_common::VectorIsometry3d tesseract_environment::Environment::getLinkTransforms | ( | ) | const |
Get all of the links transforms.
Order should be the same as getLinkNames()
Definition at line 2650 of file environment.cpp.
bool tesseract_environment::Environment::getLinkVisibility | ( | const std::string & | name | ) | const |
Get a given links visibility setting.
Definition at line 2559 of file environment.cpp.
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.
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 |
Definition at line 2662 of file environment.cpp.
std::shared_ptr< const tesseract_common::ResourceLocator > tesseract_environment::Environment::getResourceLocator | ( | ) | const |
Get the resource locator assigned.
This can be a nullptr
Definition at line 2446 of file environment.cpp.
int tesseract_environment::Environment::getRevision | ( | ) | const |
Get the current revision number.
Definition at line 2333 of file environment.cpp.
std::string tesseract_environment::Environment::getRootLinkName | ( | ) | const |
std::shared_ptr< const tesseract_scene_graph::SceneGraph > tesseract_environment::Environment::getSceneGraph | ( | ) | const |
tesseract_scene_graph::SceneState tesseract_environment::Environment::getState | ( | ) | const |
Get the current state of the environment.
Definition at line 2521 of file environment.cpp.
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.
joints | A map of joint names to joint values to change. |
Definition at line 2500 of file environment.cpp.
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.
tesseract_scene_graph::SceneState tesseract_environment::Environment::getState | ( | const tesseract_common::TransformMap & | floating_joints | ) | const |
Get the state given floating joint values.
floating_joint_values | The floating joint values to leverage |
Definition at line 2515 of file environment.cpp.
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.
Definition at line 2669 of file environment.cpp.
std::vector< std::string > tesseract_environment::Environment::getStaticLinkNames | ( | ) | const |
Get a vector of static link names in the environment.
Definition at line 2638 of file environment.cpp.
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 |
Definition at line 2644 of file environment.cpp.
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.
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.
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.
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.
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.
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.
scene_graph | The scene graph to initialize the environment. |
Definition at line 2156 of file environment.cpp.
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.
scene_graph | The scene graph to initialize the environment. |
Definition at line 2171 of file environment.cpp.
bool tesseract_environment::Environment::isInitialized | ( | ) | const |
check if the environment is initialized
Definition at line 2327 of file environment.cpp.
|
private |
Definition at line 2776 of file environment.cpp.
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.
bool tesseract_environment::Environment::operator!= | ( | const Environment & | rhs | ) | const |
Definition at line 2760 of file environment.cpp.
|
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 |
Definition at line 2754 of file environment.cpp.
void tesseract_environment::Environment::removeEventCallback | ( | std::size_t | hash | ) |
Remove event callbacks.
hash | the id associated with the callback to be removed |
Definition at line 2422 of file environment.cpp.
bool tesseract_environment::Environment::reset | ( | ) |
reset to initialized state
If the environment has not been initialized then this returns false
Definition at line 2306 of file environment.cpp.
|
private |
Definition at line 2769 of file environment.cpp.
|
private |
Definition at line 2783 of file environment.cpp.
bool tesseract_environment::Environment::setActiveContinuousContactManager | ( | const std::string & | name | ) |
Set the active continuous contact manager.
name | The name used to register the contact manager |
Definition at line 2706 of file environment.cpp.
bool tesseract_environment::Environment::setActiveDiscreteContactManager | ( | const std::string & | name | ) |
Set the active discrete contact manager.
name | The name used to register the contact manager |
Definition at line 2693 of file environment.cpp.
void tesseract_environment::Environment::setName | ( | const std::string & | name | ) |
Give the environment a name.
Definition at line 2452 of file environment.cpp.
void tesseract_environment::Environment::setResourceLocator | ( | std::shared_ptr< const tesseract_common::ResourceLocator > | locator | ) |
Set resource locator for environment.
locator | The resource locator |
Definition at line 2440 of file environment.cpp.
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.
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.
void tesseract_environment::Environment::setState | ( | const tesseract_common::TransformMap & | floating_joints | ) |
Set the current state of the floating joint values.
floating_joint_values | The floating joint values to set |
Definition at line 2489 of file environment.cpp.
|
friend |
Definition at line 576 of file environment.h.
|
friend |
Definition at line 577 of file environment.h.
|
private |
Definition at line 573 of file environment.h.
|
mutableprivate |
The environment can be accessed from multiple threads, need use mutex throughout.
Definition at line 570 of file environment.h.