Data structure which is passed to the collision callback function of the collision manager. More...
#include <collision_common.h>
Public Member Functions | |
CollisionData () | |
CollisionData (const CollisionRequest *req, CollisionResult *res, const AllowedCollisionMatrix *acm) | |
void | enableGroup (const moveit::core::RobotModelConstPtr &robot_model) |
Compute active_components_only_ based on the joint group specified in req_. More... | |
~CollisionData () | |
Public Attributes | |
const AllowedCollisionMatrix * | acm_ |
The user-specified collision matrix (may be NULL). More... | |
const std::set< const moveit::core::LinkModel * > * | active_components_only_ |
If the collision request includes a group name, this set contains the pointers to the link models that are considered for collision. More... | |
bool | done_ |
Flag indicating whether collision checking is complete. More... | |
const CollisionRequest * | req_ |
The collision request passed by the user. More... | |
CollisionResult * | res_ |
The user-specified response location. More... | |
Data structure which is passed to the collision callback function of the collision manager.
Definition at line 173 of file fcl/include/moveit/collision_detection_fcl/collision_common.h.
|
inline |
Definition at line 175 of file fcl/include/moveit/collision_detection_fcl/collision_common.h.
|
inline |
Definition at line 179 of file fcl/include/moveit/collision_detection_fcl/collision_common.h.
|
inline |
Definition at line 184 of file fcl/include/moveit/collision_detection_fcl/collision_common.h.
void collision_detection::CollisionData::enableGroup | ( | const moveit::core::RobotModelConstPtr & | robot_model | ) |
Compute active_components_only_ based on the joint group specified in req_.
Definition at line 970 of file fcl/src/collision_common.cpp.
const AllowedCollisionMatrix* collision_detection::CollisionData::acm_ |
The user-specified collision matrix (may be NULL).
Definition at line 204 of file fcl/include/moveit/collision_detection_fcl/collision_common.h.
const std::set<const moveit::core::LinkModel*>* collision_detection::CollisionData::active_components_only_ |
If the collision request includes a group name, this set contains the pointers to the link models that are considered for collision.
If the pointer is NULL, all collisions are considered.
Definition at line 198 of file fcl/include/moveit/collision_detection_fcl/collision_common.h.
bool collision_detection::CollisionData::done_ |
Flag indicating whether collision checking is complete.
Definition at line 207 of file fcl/include/moveit/collision_detection_fcl/collision_common.h.
const CollisionRequest* collision_detection::CollisionData::req_ |
The collision request passed by the user.
Definition at line 192 of file fcl/include/moveit/collision_detection_fcl/collision_common.h.
CollisionResult* collision_detection::CollisionData::res_ |
The user-specified response location.
Definition at line 201 of file fcl/include/moveit/collision_detection_fcl/collision_common.h.