#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_Affine3d &poses, double resolution, double padding) | |
unsigned int | getBodiesCount () |
const bodies::Body * | getBody (unsigned int i) const |
const EigenSTL::vector_Vector3d & | getCollisionPoints () const |
const std::vector< CollisionSphere > & | getCollisionSpheres () const |
const bodies::BoundingSphere & | getRelativeBoundingSphere () const |
Eigen::Affine3d | getRelativeCylinderPose () const |
const std::vector< double > & | getSphereRadii () const |
void | replaceCollisionSpheres (const std::vector< CollisionSphere > &new_collision_spheres, const Eigen::Affine3d &new_relative_cylinder_pose) |
~BodyDecomposition () | |
Public Attributes | |
Eigen::Affine3d | relative_cylinder_pose_ |
Protected Member Functions | |
void | init (const std::vector< shapes::ShapeConstPtr > &shapes, const EigenSTL::vector_Affine3d &poses, double resolution, double padding) |
Protected Attributes | |
bodies::BodyVector | bodies_ |
std::vector< CollisionSphere > | collision_spheres_ |
bodies::BoundingSphere | relative_bounding_sphere_ |
EigenSTL::vector_Vector3d | relative_collision_points_ |
std::vector< double > | sphere_radii_ |
Friends | |
class | BodyDecompositionVector |
Definition at line 222 of file collision_distance_field_types.h.
collision_detection::BodyDecomposition::BodyDecomposition | ( | const shapes::ShapeConstPtr & | shape, |
double | resolution, | ||
double | padding = 0.01 |
||
) |
Definition at line 260 of file collision_distance_field_types.cpp.
collision_detection::BodyDecomposition::BodyDecomposition | ( | const std::vector< shapes::ShapeConstPtr > & | shapes, |
const EigenSTL::vector_Affine3d & | poses, | ||
double | resolution, | ||
double | padding | ||
) |
Definition at line 270 of file collision_distance_field_types.cpp.
collision_detection::BodyDecomposition::~BodyDecomposition | ( | ) |
Definition at line 323 of file collision_distance_field_types.cpp.
|
inline |
Definition at line 267 of file collision_distance_field_types.h.
|
inline |
Definition at line 262 of file collision_distance_field_types.h.
|
inline |
Definition at line 257 of file collision_distance_field_types.h.
|
inline |
Definition at line 247 of file collision_distance_field_types.h.
|
inline |
Definition at line 277 of file collision_distance_field_types.h.
|
inline |
Definition at line 272 of file collision_distance_field_types.h.
|
inline |
Definition at line 252 of file collision_distance_field_types.h.
|
protected |
Definition at line 277 of file collision_distance_field_types.cpp.
|
inline |
Definition at line 238 of file collision_distance_field_types.h.
|
friend |
Definition at line 224 of file collision_distance_field_types.h.
|
protected |
Definition at line 287 of file collision_distance_field_types.h.
|
protected |
Definition at line 291 of file collision_distance_field_types.h.
|
protected |
Definition at line 289 of file collision_distance_field_types.h.
|
protected |
Definition at line 292 of file collision_distance_field_types.h.
Eigen::Affine3d collision_detection::BodyDecomposition::relative_cylinder_pose_ |
Definition at line 236 of file collision_distance_field_types.h.
|
protected |
Definition at line 290 of file collision_distance_field_types.h.