moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
Bundles the CollisionGeometryData and FCL collision geometry representation into a single class. More...
#include <collision_common.h>
Public Member Functions | |
FCLGeometry () | |
FCLGeometry (fcl::CollisionGeometryd *collision_geometry, const moveit::core::LinkModel *link, int shape_index) | |
Constructor for a robot link. More... | |
FCLGeometry (fcl::CollisionGeometryd *collision_geometry, const moveit::core::AttachedBody *ab, int shape_index) | |
Constructor for an attached body. More... | |
FCLGeometry (fcl::CollisionGeometryd *collision_geometry, const World::Object *obj, int shape_index) | |
Constructor for a world object. More... | |
template<typename T > | |
void | updateCollisionGeometryData (const T *data, int shape_index, bool newType) |
Updates the collision_geometry_data_ with new data while also setting the collision_geometry_ to the new data. More... | |
Public Attributes | |
std::shared_ptr< fcl::CollisionGeometryd > | collision_geometry_ |
Pointer to FCL collision geometry. More... | |
CollisionGeometryDataPtr | collision_geometry_data_ |
Pointer to the user-defined geometry data. More... | |
Bundles the CollisionGeometryData and FCL collision geometry representation into a single class.
Definition at line 201 of file collision_common.h.
|
inline |
Definition at line 203 of file collision_common.h.
|
inline |
Constructor for a robot link.
Definition at line 208 of file collision_common.h.
|
inline |
Constructor for an attached body.
Definition at line 216 of file collision_common.h.
|
inline |
Constructor for a world object.
Definition at line 224 of file collision_common.h.
|
inline |
Updates the collision_geometry_data_ with new data while also setting the collision_geometry_ to the new data.
Definition at line 234 of file collision_common.h.
std::shared_ptr<fcl::CollisionGeometryd> collision_detection::FCLGeometry::collision_geometry_ |
Pointer to FCL collision geometry.
Definition at line 244 of file collision_common.h.
CollisionGeometryDataPtr collision_detection::FCLGeometry::collision_geometry_data_ |
Pointer to the user-defined geometry data.
Definition at line 247 of file collision_common.h.