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

#include <collision_distance_field_types.h>

Public Member Functions

EIGEN_MAKE_ALIGNED_OPERATOR_NEW PosedBodyPointDecompositionVector ()
 
EigenSTL::vector_Vector3d getCollisionPoints () const
 
void addToVector (PosedBodyPointDecompositionPtr &bd)
 
unsigned int getSize () const
 
PosedBodyPointDecompositionConstPtr getPosedBodyDecomposition (unsigned int i) const
 
void updatePose (unsigned int ind, const Eigen::Isometry3d &pose)
 

Static Protected Attributes

static const rclcpp::Logger LOGGER = collision_detection::LOGGER
 

Detailed Description

Definition at line 444 of file collision_distance_field_types.h.

Constructor & Destructor Documentation

◆ PosedBodyPointDecompositionVector()

EIGEN_MAKE_ALIGNED_OPERATOR_NEW collision_detection::PosedBodyPointDecompositionVector::PosedBodyPointDecompositionVector ( )
inline

Definition at line 449 of file collision_distance_field_types.h.

Member Function Documentation

◆ addToVector()

void collision_detection::PosedBodyPointDecompositionVector::addToVector ( PosedBodyPointDecompositionPtr &  bd)
inline

Definition at line 463 of file collision_distance_field_types.h.

◆ getCollisionPoints()

EigenSTL::vector_Vector3d collision_detection::PosedBodyPointDecompositionVector::getCollisionPoints ( ) const
inline

Definition at line 453 of file collision_distance_field_types.h.

◆ getPosedBodyDecomposition()

PosedBodyPointDecompositionConstPtr collision_detection::PosedBodyPointDecompositionVector::getPosedBodyDecomposition ( unsigned int  i) const
inline

Definition at line 473 of file collision_distance_field_types.h.

◆ getSize()

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

Definition at line 468 of file collision_distance_field_types.h.

◆ updatePose()

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

Definition at line 483 of file collision_distance_field_types.h.

Member Data Documentation

◆ LOGGER

const rclcpp::Logger collision_detection::PosedBodyPointDecompositionVector::LOGGER = collision_detection::LOGGER
staticprotected

Definition at line 497 of file collision_distance_field_types.h.


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