Classes | Typedefs | Enumerations | Functions
tesseract_environment Namespace Reference

Classes

class  AddContactManagersPluginInfoCommand
 
class  AddKinematicsInformationCommand
 
class  AddLinkCommand
 
class  AddSceneGraphCommand
 
class  AddTrajectoryLinkCommand
 
class  ChangeCollisionMarginsCommand
 
class  ChangeJointAccelerationLimitsCommand
 
class  ChangeJointOriginCommand
 
class  ChangeJointPositionLimitsCommand
 
class  ChangeJointVelocityLimitsCommand
 
class  ChangeLinkCollisionEnabledCommand
 
class  ChangeLinkOriginCommand
 
class  ChangeLinkVisibilityCommand
 
class  Command
 
struct  CommandAppliedEvent
 The command applied event. More...
 
class  DefaultEnvironmentCache
 
class  Environment
 
class  EnvironmentCache
 
class  EnvironmentContactAllowedValidator
 
class  EnvironmentMonitor
 Tesseract Environment Monitor Interface Class. More...
 
class  EnvironmentMonitorInterface
 
struct  Event
 The event base class. More...
 
class  ModifyAllowedCollisionsCommand
 
class  MoveJointCommand
 
class  MoveLinkCommand
 
class  RemoveAllowedCollisionLinkCommand
 
class  RemoveJointCommand
 
class  RemoveLinkCommand
 
class  ReplaceJointCommand
 
struct  SceneStateChangedEvent
 The scene state changed event. More...
 
class  SetActiveContinuousContactManagerCommand
 
class  SetActiveDiscreteContactManagerCommand
 

Typedefs

using CalcStateFn = std::function< tesseract_common::TransformMap(const Eigen::VectorXd &state)>
 
using CollisionMarginPairData = tesseract_common::CollisionMarginPairData
 
using CollisionMarginPairOverrideType = tesseract_common::CollisionMarginPairOverrideType
 
using Commands = std::vector< std::shared_ptr< const Command > >
 
using EnvironmentConstPtrAnyPoly = tesseract_common::AnyWrapper< std::shared_ptr< const tesseract_environment::Environment > >
 
using EnvironmentPtrAnyPoly = tesseract_common::AnyWrapper< std::shared_ptr< tesseract_environment::Environment > >
 
using EventCallbackFn = std::function< void(const Event &event)>
 
using FindTCPOffsetCallbackFn = std::function< Eigen::Isometry3d(const tesseract_common::ManipulatorInfo &)>
 Function signature for adding additional callbacks for looking up TCP information. More...
 

Enumerations

enum  CommandType {
  CommandType::UNINITIALIZED = -1, CommandType::ADD_LINK = 0, CommandType::MOVE_LINK = 1, CommandType::MOVE_JOINT = 2,
  CommandType::REMOVE_LINK = 3, CommandType::REMOVE_JOINT = 4, CommandType::CHANGE_LINK_ORIGIN = 5, CommandType::CHANGE_JOINT_ORIGIN = 6,
  CommandType::CHANGE_LINK_COLLISION_ENABLED = 7, CommandType::CHANGE_LINK_VISIBILITY = 8, CommandType::MODIFY_ALLOWED_COLLISIONS = 9, CommandType::REMOVE_ALLOWED_COLLISION_LINK = 10,
  CommandType::ADD_SCENE_GRAPH = 11, CommandType::CHANGE_JOINT_POSITION_LIMITS = 12, CommandType::CHANGE_JOINT_VELOCITY_LIMITS = 13, CommandType::CHANGE_JOINT_ACCELERATION_LIMITS = 14,
  CommandType::ADD_KINEMATICS_INFORMATION = 15, CommandType::REPLACE_JOINT = 16, CommandType::CHANGE_COLLISION_MARGINS = 17, CommandType::ADD_CONTACT_MANAGERS_PLUGIN_INFO = 18,
  CommandType::SET_ACTIVE_DISCRETE_CONTACT_MANAGER = 19, CommandType::SET_ACTIVE_CONTINUOUS_CONTACT_MANAGER = 20, CommandType::ADD_TRAJECTORY_LINK = 21
}
 
enum  Events { Events::COMMAND_APPLIED = 0, Events::SCENE_STATE_CHANGED = 1 }
 
enum  ModifyAllowedCollisionsType { ModifyAllowedCollisionsType::ADD, ModifyAllowedCollisionsType::REMOVE, ModifyAllowedCollisionsType::REPLACE }
 
enum  MonitoredEnvironmentMode : int { MonitoredEnvironmentMode::DEFAULT = 0, MonitoredEnvironmentMode::SYNCHRONIZED = 1 }
 

Functions

bool checkTrajectory (std::vector< tesseract_collision::ContactResultMap > &contacts, tesseract_collision::ContinuousContactManager &manager, const CalcStateFn &state_fn, const std::vector< std::string > &joint_names, const tesseract_common::TrajArray &traj, const tesseract_collision::CollisionCheckConfig &config)
 
bool checkTrajectory (std::vector< tesseract_collision::ContactResultMap > &contacts, tesseract_collision::ContinuousContactManager &manager, const tesseract_kinematics::JointGroup &manip, const tesseract_common::TrajArray &traj, const tesseract_collision::CollisionCheckConfig &config)
 Should perform a continuous collision check over the trajectory and stop on first collision. More...
 
bool checkTrajectory (std::vector< tesseract_collision::ContactResultMap > &contacts, tesseract_collision::ContinuousContactManager &manager, const tesseract_scene_graph::StateSolver &state_solver, const std::vector< std::string > &joint_names, const tesseract_common::TrajArray &traj, const tesseract_collision::CollisionCheckConfig &config)
 Should perform a continuous collision check over the trajectory and stop on first collision. More...
 
bool checkTrajectory (std::vector< tesseract_collision::ContactResultMap > &contacts, tesseract_collision::DiscreteContactManager &manager, const CalcStateFn &state_fn, const std::vector< std::string > &joint_names, const tesseract_common::TrajArray &traj, const tesseract_collision::CollisionCheckConfig &config)
 
bool checkTrajectory (std::vector< tesseract_collision::ContactResultMap > &contacts, tesseract_collision::DiscreteContactManager &manager, const tesseract_kinematics::JointGroup &manip, const tesseract_common::TrajArray &traj, const tesseract_collision::CollisionCheckConfig &config)
 Should perform a discrete collision check over the trajectory and stop on first collision. More...
 
bool checkTrajectory (std::vector< tesseract_collision::ContactResultMap > &contacts, tesseract_collision::DiscreteContactManager &manager, const tesseract_scene_graph::StateSolver &state_solver, const std::vector< std::string > &joint_names, const tesseract_common::TrajArray &traj, const tesseract_collision::CollisionCheckConfig &config)
 Should perform a discrete collision check over the trajectory and stop on first collision. More...
 
void checkTrajectorySegment (tesseract_collision::ContactResultMap &contact_results, tesseract_collision::ContinuousContactManager &manager, const tesseract_common::TransformMap &state0, const tesseract_common::TransformMap &state1, const tesseract_collision::ContactRequest &contact_request)
 Should perform a continuous collision check between two states only passing along the contact_request to the manager. More...
 
void checkTrajectoryState (tesseract_collision::ContactResultMap &contact_results, tesseract_collision::ContinuousContactManager &manager, const tesseract_common::TransformMap &state, const tesseract_collision::ContactRequest &contact_request)
 Should perform a discrete collision check a state first configuring manager with config. More...
 
void checkTrajectoryState (tesseract_collision::ContactResultMap &contact_results, tesseract_collision::DiscreteContactManager &manager, const tesseract_common::TransformMap &state, const tesseract_collision::ContactRequest &contact_request)
 Should perform a discrete collision check a state only passing contact_request to the manager. More...
 
void getActiveLinkNamesRecursive (std::vector< std::string > &active_links, const tesseract_scene_graph::SceneGraph &scene_graph, const std::string &current_link, bool active)
 Get the active Link Names Recursively. More...
 
void getCollisionObject (std::vector< std::shared_ptr< const tesseract_geometry::Geometry >> &shapes, tesseract_common::VectorIsometry3d &shape_poses, const tesseract_scene_graph::Link &link)
 
std::vector< std::shared_ptr< const Command > > getInitCommands (const tesseract_scene_graph::SceneGraph &scene_graph, const std::shared_ptr< const tesseract_srdf::SRDFModel > &srdf_model=nullptr)
 
template<class Archive >
void load (Archive &ar, CommandType &g, const unsigned int version)
 
void printContinuousDebugInfo (const std::vector< std::string > &joint_names, const Eigen::VectorXd &swp0, const Eigen::VectorXd &swp1, tesseract_common::TrajArray::Index step_idx, tesseract_common::TrajArray::Index step_size, tesseract_common::TrajArray::Index sub_step_idx=-1)
 
void printDiscreteDebugInfo (const std::vector< std::string > &joint_names, const Eigen::VectorXd &swp, tesseract_common::TrajArray::Index step_idx, tesseract_common::TrajArray::Index step_size, tesseract_common::TrajArray::Index sub_step_idx=-1)
 
template<class Archive >
void save (Archive &ar, const CommandType &g, const unsigned int version)
 
template<class Archive >
void serialize (Archive &ar, CommandType &g, const unsigned int version)
 

Typedef Documentation

◆ CalcStateFn

Definition at line 157 of file utils.cpp.

◆ CollisionMarginPairData

Definition at line 46 of file change_collision_margins_command.h.

◆ CollisionMarginPairOverrideType

Definition at line 47 of file change_collision_margins_command.h.

◆ Commands

using tesseract_environment::Commands = typedef std::vector<std::shared_ptr<const Command> >

Definition at line 110 of file command.h.

◆ EnvironmentConstPtrAnyPoly

Definition at line 594 of file environment.h.

◆ EnvironmentPtrAnyPoly

Definition at line 592 of file environment.h.

◆ EventCallbackFn

using tesseract_environment::EventCallbackFn = typedef std::function<void(const Event& event)>

Definition at line 69 of file environment.h.

◆ FindTCPOffsetCallbackFn

using tesseract_environment::FindTCPOffsetCallbackFn = typedef std::function<Eigen::Isometry3d(const tesseract_common::ManipulatorInfo&)>

Function signature for adding additional callbacks for looking up TCP information.

The function should throw and exception if not located

Definition at line 67 of file environment.h.

Enumeration Type Documentation

◆ CommandType

Enumerator
UNINITIALIZED 
ADD_LINK 
MOVE_LINK 
MOVE_JOINT 
REMOVE_LINK 
REMOVE_JOINT 
CHANGE_LINK_ORIGIN 
CHANGE_JOINT_ORIGIN 
CHANGE_LINK_COLLISION_ENABLED 
CHANGE_LINK_VISIBILITY 
MODIFY_ALLOWED_COLLISIONS 
REMOVE_ALLOWED_COLLISION_LINK 
ADD_SCENE_GRAPH 
CHANGE_JOINT_POSITION_LIMITS 
CHANGE_JOINT_VELOCITY_LIMITS 
CHANGE_JOINT_ACCELERATION_LIMITS 
ADD_KINEMATICS_INFORMATION 
REPLACE_JOINT 
CHANGE_COLLISION_MARGINS 
ADD_CONTACT_MANAGERS_PLUGIN_INFO 
SET_ACTIVE_DISCRETE_CONTACT_MANAGER 
SET_ACTIVE_CONTINUOUS_CONTACT_MANAGER 
ADD_TRAJECTORY_LINK 

Definition at line 47 of file command.h.

◆ Events

Enumerator
COMMAND_APPLIED 
SCENE_STATE_CHANGED 

Definition at line 41 of file events.h.

◆ ModifyAllowedCollisionsType

Enumerator
ADD 
REMOVE 
REPLACE 

Definition at line 45 of file modify_allowed_collisions_command.h.

◆ MonitoredEnvironmentMode

Enumerator
DEFAULT 

The default behavior when monitoring another environment is the following.

Case1: If the revision is greater than, it will call a service of the monitored environment to get the changes and apply them. Case2: If the revision is less than, it will reinitialize the environment and request the remaining changes and apply them.

SYNCHRONIZED 

The synchronized behavior when monitoring another environment is the following.

Warning
Currently this works best if there is only one monitor which is synchronized because currently if two environment monitors are synchronized, it currently does not have a way to reason about which ones should get applied. Need to research approach for this type of system.

Case1: If the revision is greater than, it will call a service of the monitored environment to get the changes and apply them. Case2: If the revision is less than, it will call a service of the monitored environment to apply the new changes.

Definition at line 40 of file environment_monitor.h.

Function Documentation

◆ checkTrajectory() [1/6]

bool tesseract_environment::checkTrajectory ( std::vector< tesseract_collision::ContactResultMap > &  contacts,
tesseract_collision::ContinuousContactManager manager,
const CalcStateFn state_fn,
const std::vector< std::string > &  joint_names,
const tesseract_common::TrajArray traj,
const tesseract_collision::CollisionCheckConfig config 
)

Making this thread_local does not help because it is not called enough during planning

Definition at line 159 of file utils.cpp.

◆ checkTrajectory() [2/6]

bool tesseract_environment::checkTrajectory ( std::vector< tesseract_collision::ContactResultMap > &  contacts,
tesseract_collision::ContinuousContactManager manager,
const tesseract_kinematics::JointGroup manip,
const tesseract_common::TrajArray traj,
const tesseract_collision::CollisionCheckConfig config 
)

Should perform a continuous collision check over the trajectory and stop on first collision.

Parameters
contactsA vector of ContactMap where each index corresponds to a segment in the trajectory. The length should be trajectory size minus one.
managerA continuous contact manager
manipThe kinematic joint group
trajThe joint values at each time step
configCollisionCheckConfig used to specify collision check settings
Returns
True if collision was found, otherwise false.

Definition at line 451 of file utils.cpp.

◆ checkTrajectory() [3/6]

bool tesseract_environment::checkTrajectory ( std::vector< tesseract_collision::ContactResultMap > &  contacts,
tesseract_collision::ContinuousContactManager manager,
const tesseract_scene_graph::StateSolver state_solver,
const std::vector< std::string > &  joint_names,
const tesseract_common::TrajArray traj,
const tesseract_collision::CollisionCheckConfig config 
)

Should perform a continuous collision check over the trajectory and stop on first collision.

Parameters
contactsA vector of ContactMap where each index corresponds to a segment in the trajectory. The length should be trajectory size minus one.
managerA continuous contact manager
state_solverThe environment state solver
joint_namesJointNames corresponding to the values in traj (must be in same order)
trajThe joint values at each time step
configCollisionCheckConfig used to specify collision check settings
Returns
True if collision was found, otherwise false.

Definition at line 437 of file utils.cpp.

◆ checkTrajectory() [4/6]

bool tesseract_environment::checkTrajectory ( std::vector< tesseract_collision::ContactResultMap > &  contacts,
tesseract_collision::DiscreteContactManager manager,
const CalcStateFn state_fn,
const std::vector< std::string > &  joint_names,
const tesseract_common::TrajArray traj,
const tesseract_collision::CollisionCheckConfig config 
)

Making this thread_local does not help because it is not called enough during planning

Definition at line 463 of file utils.cpp.

◆ checkTrajectory() [5/6]

bool tesseract_environment::checkTrajectory ( std::vector< tesseract_collision::ContactResultMap > &  contacts,
tesseract_collision::DiscreteContactManager manager,
const tesseract_kinematics::JointGroup manip,
const tesseract_common::TrajArray traj,
const tesseract_collision::CollisionCheckConfig config 
)

Should perform a discrete collision check over the trajectory and stop on first collision.

Parameters
contactsA vector of ContactMap where each index corresponds to a segment in the trajectory, except the last which is the end state. The length should be the same size as the input trajectory.
managerA continuous contact manager
manipThe kinematic joint group
trajThe joint values at each time step
configCollisionCheckConfig used to specify collision check settings
Returns
True if collision was found, otherwise false.

Definition at line 873 of file utils.cpp.

◆ checkTrajectory() [6/6]

bool tesseract_environment::checkTrajectory ( std::vector< tesseract_collision::ContactResultMap > &  contacts,
tesseract_collision::DiscreteContactManager manager,
const tesseract_scene_graph::StateSolver state_solver,
const std::vector< std::string > &  joint_names,
const tesseract_common::TrajArray traj,
const tesseract_collision::CollisionCheckConfig config 
)

Should perform a discrete collision check over the trajectory and stop on first collision.

Parameters
contactsA vector of ContactMap where each index corresponds to a segment in the trajectory, except the last which is the end state. The length should be the same size as the input trajectory.
managerA continuous contact manager
state_solverThe environment state solver
joint_namesJointNames corresponding to the values in traj (must be in same order)
trajThe joint values at each time step
configCollisionCheckConfig used to specify collision check settings
Returns
True if collision was found, otherwise false.

Definition at line 859 of file utils.cpp.

◆ checkTrajectorySegment()

void tesseract_environment::checkTrajectorySegment ( tesseract_collision::ContactResultMap contact_results,
tesseract_collision::ContinuousContactManager manager,
const tesseract_common::TransformMap state0,
const tesseract_common::TransformMap state1,
const tesseract_collision::ContactRequest contact_request 
)

Should perform a continuous collision check between two states only passing along the contact_request to the manager.

Parameters
contact_resultsThe contact results to populate. It does not get cleared
managerA continuous contact manager
state0First environment state
state1Second environment state
contact_requestContact request passed to the manager

Definition at line 77 of file utils.cpp.

◆ checkTrajectoryState() [1/2]

void tesseract_environment::checkTrajectoryState ( tesseract_collision::ContactResultMap contact_results,
tesseract_collision::ContinuousContactManager manager,
const tesseract_common::TransformMap state,
const tesseract_collision::ContactRequest contact_request 
)

Should perform a discrete collision check a state first configuring manager with config.

Parameters
contact_resultsThe contact results to populate. It does not get cleared
managerA discrete contact manager
stateFirst environment state
contact_requestContact request passed to the manager

Definition at line 100 of file utils.cpp.

◆ checkTrajectoryState() [2/2]

void tesseract_environment::checkTrajectoryState ( tesseract_collision::ContactResultMap contact_results,
tesseract_collision::DiscreteContactManager manager,
const tesseract_common::TransformMap state,
const tesseract_collision::ContactRequest contact_request 
)

Should perform a discrete collision check a state only passing contact_request to the manager.

Parameters
contact_resultsThe contact results to populate. It does not get cleared
managerA discrete contact manager
stateFirst environment state
contact_requestContact request passed to the manager

Definition at line 89 of file utils.cpp.

◆ getActiveLinkNamesRecursive()

void tesseract_environment::getActiveLinkNamesRecursive ( std::vector< std::string > &  active_links,
const tesseract_scene_graph::SceneGraph scene_graph,
const std::string &  current_link,
bool  active 
)

Get the active Link Names Recursively.

   This currently only works for graphs that are trees. Need to create a generic method using boost::visitor
   TODO: Need to update using graph->getLinkChildren
Parameters
active_links
scene_graph
current_link
active

Definition at line 54 of file utils.cpp.

◆ getCollisionObject()

void tesseract_environment::getCollisionObject ( std::vector< std::shared_ptr< const tesseract_geometry::Geometry >> &  shapes,
tesseract_common::VectorIsometry3d shape_poses,
const tesseract_scene_graph::Link link 
)

Definition at line 107 of file environment.cpp.

◆ getInitCommands()

std::vector<std::shared_ptr<const Command> > tesseract_environment::getInitCommands ( const tesseract_scene_graph::SceneGraph scene_graph,
const std::shared_ptr< const tesseract_srdf::SRDFModel > &  srdf_model = nullptr 
)

Definition at line 119 of file environment.cpp.

◆ load()

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

Definition at line 47 of file command.cpp.

◆ printContinuousDebugInfo()

void tesseract_environment::printContinuousDebugInfo ( const std::vector< std::string > &  joint_names,
const Eigen::VectorXd swp0,
const Eigen::VectorXd swp1,
tesseract_common::TrajArray::Index  step_idx,
tesseract_common::TrajArray::Index  step_size,
tesseract_common::TrajArray::Index  sub_step_idx = -1 
)

Definition at line 111 of file utils.cpp.

◆ printDiscreteDebugInfo()

void tesseract_environment::printDiscreteDebugInfo ( const std::vector< std::string > &  joint_names,
const Eigen::VectorXd swp,
tesseract_common::TrajArray::Index  step_idx,
tesseract_common::TrajArray::Index  step_size,
tesseract_common::TrajArray::Index  sub_step_idx = -1 
)

Definition at line 135 of file utils.cpp.

◆ save()

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

Definition at line 40 of file command.cpp.

◆ serialize()

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

Definition at line 55 of file command.cpp.



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