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

#include <collision_distance_field_types.h>

Public Member Functions

EIGEN_MAKE_ALIGNED_OPERATOR_NEW PosedBodySphereDecomposition (const BodyDecompositionConstPtr &body_decomposition)
 
const std::vector< CollisionSphere > & getCollisionSpheres () const
 
const EigenSTL::vector_Vector3d & getSphereCenters () const
 
const EigenSTL::vector_Vector3d & getCollisionPoints () const
 
const std::vector< double > & getSphereRadii () const
 
const Eigen::Vector3d & getBoundingSphereCenter () const
 
double getBoundingSphereRadius () const
 
void updatePose (const Eigen::Isometry3d &linkTransform)
 

Protected Attributes

BodyDecompositionConstPtr body_decomposition_
 
Eigen::Vector3d posed_bounding_sphere_center_
 
EigenSTL::vector_Vector3d posed_collision_points_
 
EigenSTL::vector_Vector3d sphere_centers_
 

Detailed Description

Definition at line 300 of file collision_distance_field_types.h.

Constructor & Destructor Documentation

◆ PosedBodySphereDecomposition()

collision_detection::PosedBodySphereDecomposition::PosedBodySphereDecomposition ( const BodyDecompositionConstPtr &  body_decomposition)

Definition at line 374 of file collision_distance_field_types.cpp.

Here is the call graph for this function:

Member Function Documentation

◆ getBoundingSphereCenter()

const Eigen::Vector3d& collision_detection::PosedBodySphereDecomposition::getBoundingSphereCenter ( ) const
inline

Definition at line 326 of file collision_distance_field_types.h.

◆ getBoundingSphereRadius()

double collision_detection::PosedBodySphereDecomposition::getBoundingSphereRadius ( ) const
inline

Definition at line 331 of file collision_distance_field_types.h.

◆ getCollisionPoints()

const EigenSTL::vector_Vector3d& collision_detection::PosedBodySphereDecomposition::getCollisionPoints ( ) const
inline

Definition at line 317 of file collision_distance_field_types.h.

◆ getCollisionSpheres()

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

Definition at line 307 of file collision_distance_field_types.h.

◆ getSphereCenters()

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

Definition at line 312 of file collision_distance_field_types.h.

◆ getSphereRadii()

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

Definition at line 322 of file collision_distance_field_types.h.

◆ updatePose()

void collision_detection::PosedBodySphereDecomposition::updatePose ( const Eigen::Isometry3d &  linkTransform)

Definition at line 382 of file collision_distance_field_types.cpp.

Here is the caller graph for this function:

Member Data Documentation

◆ body_decomposition_

BodyDecompositionConstPtr collision_detection::PosedBodySphereDecomposition::body_decomposition_
protected

Definition at line 341 of file collision_distance_field_types.h.

◆ posed_bounding_sphere_center_

Eigen::Vector3d collision_detection::PosedBodySphereDecomposition::posed_bounding_sphere_center_
protected

Definition at line 342 of file collision_distance_field_types.h.

◆ posed_collision_points_

EigenSTL::vector_Vector3d collision_detection::PosedBodySphereDecomposition::posed_collision_points_
protected

Definition at line 343 of file collision_distance_field_types.h.

◆ sphere_centers_

EigenSTL::vector_Vector3d collision_detection::PosedBodySphereDecomposition::sphere_centers_
protected

Definition at line 344 of file collision_distance_field_types.h.


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