Tesseract
Motion Planning Environment
Loading...
Searching...
No Matches
utils.h
Go to the documentation of this file.
1
26#ifndef TESSERACT_ENVIRONMENT_CORE_UTILS_H
27#define TESSERACT_ENVIRONMENT_CORE_UTILS_H
28
35
37{
49void getActiveLinkNamesRecursive(std::vector<std::string>& active_links,
51 const std::string& current_link,
52 bool active);
53
67
81 const tesseract_collision::ContactRequest& contact_request);
82
94
105 const tesseract_collision::ContactRequest& contact_request);
106
118bool checkTrajectory(std::vector<tesseract_collision::ContactResultMap>& contacts,
120 const tesseract_scene_graph::StateSolver& state_solver,
121 const std::vector<std::string>& joint_names,
122 const tesseract_common::TrajArray& traj,
124
135bool checkTrajectory(std::vector<tesseract_collision::ContactResultMap>& contacts,
138 const tesseract_common::TrajArray& traj,
140
152bool checkTrajectory(std::vector<tesseract_collision::ContactResultMap>& contacts,
154 const tesseract_scene_graph::StateSolver& state_solver,
155 const std::vector<std::string>& joint_names,
156 const tesseract_common::TrajArray& traj,
158
169bool checkTrajectory(std::vector<tesseract_collision::ContactResultMap>& contacts,
172 const tesseract_common::TrajArray& traj,
174
175} // namespace tesseract_environment
176#endif // TESSERACT_ENVIRONMENT_CORE_UTILS_H
This structure hold contact results for link pairs.
Definition: types.h:154
Definition: continuous_contact_manager.h:41
Definition: discrete_contact_manager.h:41
A Joint Group is defined by a list of joint_names.
Definition: joint_group.h:43
Definition: graph.h:125
Definition: state_solver.h:46
tesseract_collision::CollisionCheckConfig config(5, request, tesseract_collision::CollisionEvaluatorType::LVS_DISCRETE, 0.5)
Definition: tesseract_common_serialization_unit.cpp:154
This is the continuous contact manager base class.
This is the discrete contact manager base class.
A basic scene graph using boost.
auto scene_graph
Definition: ikfast_kinematics_7dof_unit.cpp:51
Eigen::Matrix< double, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor > TrajArray
Definition: types.h:69
AlignedMap< std::string, Eigen::Isometry3d > TransformMap
Definition: types.h:66
Definition: command.h:39
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.
Definition: utils.cpp:138
void checkTrajectoryState(tesseract_collision::ContactResultMap &contact_results, tesseract_collision::DiscreteContactManager &manager, const tesseract_common::TransformMap &state, const tesseract_collision::CollisionCheckConfig &config)
Should perform a discrete collision check a state first configuring manager with config.
Definition: utils.cpp:103
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.
Definition: utils.cpp:43
void checkTrajectorySegment(tesseract_collision::ContactResultMap &contact_results, tesseract_collision::ContinuousContactManager &manager, const tesseract_common::TransformMap &state0, const tesseract_common::TransformMap &state1, const tesseract_collision::CollisionCheckConfig &config)
Should perform a continuous collision check between two states configuring the manager with the confi...
Definition: utils.cpp:66
This holds a state of the scene.
This is a high level structure containing common information that collision checking utilities need....
Definition: types.h:418
The ContactRequest struct.
Definition: types.h:294
Tesseracts Collision Common Types.
joint_state joint_names
Definition: tesseract_common_serialization_unit.cpp:75
std::vector< std::string > active_links
Definition: tesseract_environment_collision.cpp:112
DiscreteContactManager::Ptr manager
Definition: tesseract_environment_collision.cpp:109
tesseract_collision::ContactResultMap contacts
Definition: tesseract_environment_utils.cpp:132