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... | |
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 ¤t_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) |
using tesseract_environment::CalcStateFn = typedef std::function<tesseract_common::TransformMap(const Eigen::VectorXd& state)> |
using tesseract_environment::CollisionMarginPairData = typedef tesseract_common::CollisionMarginPairData |
Definition at line 46 of file change_collision_margins_command.h.
using tesseract_environment::CollisionMarginPairOverrideType = typedef tesseract_common::CollisionMarginPairOverrideType |
Definition at line 47 of file change_collision_margins_command.h.
using tesseract_environment::Commands = typedef std::vector<std::shared_ptr<const Command> > |
using tesseract_environment::EnvironmentConstPtrAnyPoly = typedef tesseract_common::AnyWrapper<std::shared_ptr<const tesseract_environment::Environment> > |
Definition at line 594 of file environment.h.
using tesseract_environment::EnvironmentPtrAnyPoly = typedef tesseract_common::AnyWrapper<std::shared_ptr<tesseract_environment::Environment> > |
Definition at line 592 of file environment.h.
using tesseract_environment::EventCallbackFn = typedef std::function<void(const Event& event)> |
Definition at line 69 of file environment.h.
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.
|
strong |
|
strong |
Enumerator | |
---|---|
ADD | |
REMOVE | |
REPLACE |
Definition at line 45 of file modify_allowed_collisions_command.h.
|
strong |
Definition at line 40 of file environment_monitor.h.
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 | ||
) |
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.
contacts | A vector of ContactMap where each index corresponds to a segment in the trajectory. The length should be trajectory size minus one. |
manager | A continuous contact manager |
manip | The kinematic joint group |
traj | The joint values at each time step |
config | CollisionCheckConfig used to specify collision check settings |
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.
contacts | A vector of ContactMap where each index corresponds to a segment in the trajectory. The length should be trajectory size minus one. |
manager | A continuous contact manager |
state_solver | The environment state solver |
joint_names | JointNames corresponding to the values in traj (must be in same order) |
traj | The joint values at each time step |
config | CollisionCheckConfig used to specify collision check settings |
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 | ||
) |
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.
contacts | A 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. |
manager | A continuous contact manager |
manip | The kinematic joint group |
traj | The joint values at each time step |
config | CollisionCheckConfig used to specify collision check settings |
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.
contacts | A 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. |
manager | A continuous contact manager |
state_solver | The environment state solver |
joint_names | JointNames corresponding to the values in traj (must be in same order) |
traj | The joint values at each time step |
config | CollisionCheckConfig used to specify collision check settings |
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.
contact_results | The contact results to populate. It does not get cleared |
manager | A continuous contact manager |
state0 | First environment state |
state1 | Second environment state |
contact_request | Contact request passed to the manager |
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.
contact_results | The contact results to populate. It does not get cleared |
manager | A discrete contact manager |
state | First environment state |
contact_request | Contact request passed to the manager |
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.
contact_results | The contact results to populate. It does not get cleared |
manager | A discrete contact manager |
state | First environment state |
contact_request | Contact request passed to the manager |
void tesseract_environment::getActiveLinkNamesRecursive | ( | std::vector< std::string > & | active_links, |
const tesseract_scene_graph::SceneGraph & | scene_graph, | ||
const std::string & | current_link, | ||
bool | active | ||
) |
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.
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.
void tesseract_environment::load | ( | Archive & | ar, |
CommandType & | g, | ||
const unsigned int | version | ||
) |
Definition at line 47 of file command.cpp.
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 |
||
) |
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 |
||
) |
void tesseract_environment::save | ( | Archive & | ar, |
const CommandType & | g, | ||
const unsigned int | version | ||
) |
Definition at line 40 of file command.cpp.
void tesseract_environment::serialize | ( | Archive & | ar, |
CommandType & | g, | ||
const unsigned int | version | ||
) |
Definition at line 55 of file command.cpp.