moveit2
The MoveIt Motion Planning Framework for ROS 2.
Public Member Functions | List of all members
collision_detection::PosedBodySphereDecompositionVector Class Reference

#include <collision_distance_field_types.h>

Public Member Functions

EIGEN_MAKE_ALIGNED_OPERATOR_NEW PosedBodySphereDecompositionVector ()
 
const std::vector< CollisionSphere > & getCollisionSpheres () const
 
const EigenSTL::vector_Vector3d & getSphereCenters () const
 
const std::vector< double > & getSphereRadii () const
 
void addToVector (PosedBodySphereDecompositionPtr &bd)
 
unsigned int getSize () const
 
PosedBodySphereDecompositionConstPtr getPosedBodySphereDecomposition (unsigned int i) const
 
void updatePose (unsigned int ind, const Eigen::Isometry3d &pose)
 

Detailed Description

Definition at line 370 of file collision_distance_field_types.h.

Constructor & Destructor Documentation

◆ PosedBodySphereDecompositionVector()

EIGEN_MAKE_ALIGNED_OPERATOR_NEW collision_detection::PosedBodySphereDecompositionVector::PosedBodySphereDecompositionVector ( )
inline

Definition at line 375 of file collision_distance_field_types.h.

Member Function Documentation

◆ addToVector()

void collision_detection::PosedBodySphereDecompositionVector::addToVector ( PosedBodySphereDecompositionPtr &  bd)
inline

Definition at line 394 of file collision_distance_field_types.h.

◆ getCollisionSpheres()

const std::vector<CollisionSphere>& collision_detection::PosedBodySphereDecompositionVector::getCollisionSpheres ( ) const
inline

Definition at line 379 of file collision_distance_field_types.h.

◆ getPosedBodySphereDecomposition()

PosedBodySphereDecompositionConstPtr collision_detection::PosedBodySphereDecompositionVector::getPosedBodySphereDecomposition ( unsigned int  i) const
inline

Definition at line 410 of file collision_distance_field_types.h.

◆ getSize()

unsigned int collision_detection::PosedBodySphereDecompositionVector::getSize ( ) const
inline

Definition at line 405 of file collision_distance_field_types.h.

◆ getSphereCenters()

const EigenSTL::vector_Vector3d& collision_detection::PosedBodySphereDecompositionVector::getSphereCenters ( ) const
inline

Definition at line 384 of file collision_distance_field_types.h.

◆ getSphereRadii()

const std::vector<double>& collision_detection::PosedBodySphereDecompositionVector::getSphereRadii ( ) const
inline

Definition at line 389 of file collision_distance_field_types.h.

◆ updatePose()

void collision_detection::PosedBodySphereDecompositionVector::updatePose ( unsigned int  ind,
const Eigen::Isometry3d &  pose 
)
inline

Definition at line 420 of file collision_distance_field_types.h.


The documentation for this class was generated from the following files: