Public Member Functions | Public Attributes | Protected Member Functions | Protected Attributes | Friends | List of all members
collision_detection::BodyDecomposition Class Reference

#include <collision_distance_field_types.h>

Public Member Functions

EIGEN_MAKE_ALIGNED_OPERATOR_NEW BodyDecomposition (const shapes::ShapeConstPtr &shape, double resolution, double padding=0.01)
 
 BodyDecomposition (const std::vector< shapes::ShapeConstPtr > &shapes, const EigenSTL::vector_Isometry3d &poses, double resolution, double padding)
 
unsigned int getBodiesCount ()
 
const bodies::BodygetBody (unsigned int i) const
 
const EigenSTL::vector_Vector3dgetCollisionPoints () const
 
const std::vector< CollisionSphere > & getCollisionSpheres () const
 
const bodies::BoundingSpheregetRelativeBoundingSphere () const
 
Eigen::Isometry3d getRelativeCylinderPose () const
 
const std::vector< double > & getSphereRadii () const
 
void replaceCollisionSpheres (const std::vector< CollisionSphere > &new_collision_spheres, const Eigen::Isometry3d &new_relative_cylinder_pose)
 
 ~BodyDecomposition ()
 

Public Attributes

Eigen::Isometry3d relative_cylinder_pose_
 

Protected Member Functions

void init (const std::vector< shapes::ShapeConstPtr > &shapes, const EigenSTL::vector_Isometry3d &poses, double resolution, double padding)
 

Protected Attributes

bodies::BodyVector bodies_
 
std::vector< CollisionSpherecollision_spheres_
 
bodies::BoundingSphere relative_bounding_sphere_
 
EigenSTL::vector_Vector3d relative_collision_points_
 
std::vector< double > sphere_radii_
 

Friends

class BodyDecompositionVector
 

Detailed Description

Definition at line 252 of file collision_distance_field_types.h.

Constructor & Destructor Documentation

◆ BodyDecomposition() [1/2]

collision_detection::BodyDecomposition::BodyDecomposition ( const shapes::ShapeConstPtr shape,
double  resolution,
double  padding = 0.01 
)

◆ BodyDecomposition() [2/2]

collision_detection::BodyDecomposition::BodyDecomposition ( const std::vector< shapes::ShapeConstPtr > &  shapes,
const EigenSTL::vector_Isometry3d poses,
double  resolution,
double  padding 
)

Definition at line 283 of file collision_distance_field_types.cpp.

◆ ~BodyDecomposition()

collision_detection::BodyDecomposition::~BodyDecomposition ( )

Definition at line 336 of file collision_distance_field_types.cpp.

Member Function Documentation

◆ getBodiesCount()

unsigned int collision_detection::BodyDecomposition::getBodiesCount ( )
inline

Definition at line 297 of file collision_distance_field_types.h.

◆ getBody()

const bodies::Body* collision_detection::BodyDecomposition::getBody ( unsigned int  i) const
inline

Definition at line 292 of file collision_distance_field_types.h.

◆ getCollisionPoints()

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

Definition at line 287 of file collision_distance_field_types.h.

◆ getCollisionSpheres()

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

Definition at line 277 of file collision_distance_field_types.h.

◆ getRelativeBoundingSphere()

const bodies::BoundingSphere& collision_detection::BodyDecomposition::getRelativeBoundingSphere ( ) const
inline

Definition at line 307 of file collision_distance_field_types.h.

◆ getRelativeCylinderPose()

Eigen::Isometry3d collision_detection::BodyDecomposition::getRelativeCylinderPose ( ) const
inline

Definition at line 302 of file collision_distance_field_types.h.

◆ getSphereRadii()

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

Definition at line 282 of file collision_distance_field_types.h.

◆ init()

void collision_detection::BodyDecomposition::init ( const std::vector< shapes::ShapeConstPtr > &  shapes,
const EigenSTL::vector_Isometry3d poses,
double  resolution,
double  padding 
)
protected

Definition at line 290 of file collision_distance_field_types.cpp.

◆ replaceCollisionSpheres()

void collision_detection::BodyDecomposition::replaceCollisionSpheres ( const std::vector< CollisionSphere > &  new_collision_spheres,
const Eigen::Isometry3d &  new_relative_cylinder_pose 
)
inline

Definition at line 268 of file collision_distance_field_types.h.

Friends And Related Function Documentation

◆ BodyDecompositionVector

friend class BodyDecompositionVector
friend

Definition at line 254 of file collision_distance_field_types.h.

Member Data Documentation

◆ bodies_

bodies::BodyVector collision_detection::BodyDecomposition::bodies_
protected

Definition at line 317 of file collision_distance_field_types.h.

◆ collision_spheres_

std::vector<CollisionSphere> collision_detection::BodyDecomposition::collision_spheres_
protected

Definition at line 321 of file collision_distance_field_types.h.

◆ relative_bounding_sphere_

bodies::BoundingSphere collision_detection::BodyDecomposition::relative_bounding_sphere_
protected

Definition at line 319 of file collision_distance_field_types.h.

◆ relative_collision_points_

EigenSTL::vector_Vector3d collision_detection::BodyDecomposition::relative_collision_points_
protected

Definition at line 322 of file collision_distance_field_types.h.

◆ relative_cylinder_pose_

Eigen::Isometry3d collision_detection::BodyDecomposition::relative_cylinder_pose_

Definition at line 266 of file collision_distance_field_types.h.

◆ sphere_radii_

std::vector<double> collision_detection::BodyDecomposition::sphere_radii_
protected

Definition at line 320 of file collision_distance_field_types.h.


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


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Thu Apr 18 2024 02:23:41