moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
Public Member Functions | Public Attributes | List of all members
collision_detection::FCLGeometry Struct Reference

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.
 
 FCLGeometry (fcl::CollisionGeometryd *collision_geometry, const moveit::core::AttachedBody *ab, int shape_index)
 Constructor for an attached body.
 
 FCLGeometry (fcl::CollisionGeometryd *collision_geometry, const World::Object *obj, int shape_index)
 Constructor for a world object.
 
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.
 

Public Attributes

std::shared_ptr< fcl::CollisionGeometrydcollision_geometry_
 Pointer to FCL collision geometry.
 
CollisionGeometryDataPtr collision_geometry_data_
 Pointer to the user-defined geometry data.
 

Detailed Description

Bundles the CollisionGeometryData and FCL collision geometry representation into a single class.

Definition at line 201 of file collision_common.h.

Constructor & Destructor Documentation

◆ FCLGeometry() [1/4]

collision_detection::FCLGeometry::FCLGeometry ( )
inline

Definition at line 203 of file collision_common.h.

◆ FCLGeometry() [2/4]

collision_detection::FCLGeometry::FCLGeometry ( fcl::CollisionGeometryd collision_geometry,
const moveit::core::LinkModel link,
int  shape_index 
)
inline

Constructor for a robot link.

Definition at line 208 of file collision_common.h.

◆ FCLGeometry() [3/4]

collision_detection::FCLGeometry::FCLGeometry ( fcl::CollisionGeometryd collision_geometry,
const moveit::core::AttachedBody ab,
int  shape_index 
)
inline

Constructor for an attached body.

Definition at line 216 of file collision_common.h.

◆ FCLGeometry() [4/4]

collision_detection::FCLGeometry::FCLGeometry ( fcl::CollisionGeometryd collision_geometry,
const World::Object obj,
int  shape_index 
)
inline

Constructor for a world object.

Definition at line 224 of file collision_common.h.

Member Function Documentation

◆ updateCollisionGeometryData()

template<typename T >
void collision_detection::FCLGeometry::updateCollisionGeometryData ( const T *  data,
int  shape_index,
bool  newType 
)
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.

Member Data Documentation

◆ collision_geometry_

std::shared_ptr<fcl::CollisionGeometryd> collision_detection::FCLGeometry::collision_geometry_

Pointer to FCL collision geometry.

Definition at line 246 of file collision_common.h.

◆ collision_geometry_data_

CollisionGeometryDataPtr collision_detection::FCLGeometry::collision_geometry_data_

Pointer to the user-defined geometry data.

Definition at line 249 of file collision_common.h.


The documentation for this struct was generated from the following file: