#include <collision_distance_field_types.h>
◆ PosedBodyPointDecomposition() [1/3]
collision_detection::PosedBodyPointDecomposition::PosedBodyPointDecomposition |
( |
const BodyDecompositionConstPtr & |
body_decomposition | ) |
|
◆ PosedBodyPointDecomposition() [2/3]
collision_detection::PosedBodyPointDecomposition::PosedBodyPointDecomposition |
( |
const BodyDecompositionConstPtr & |
body_decomposition, |
|
|
const Eigen::Isometry3d & |
pose |
|
) |
| |
◆ PosedBodyPointDecomposition() [3/3]
collision_detection::PosedBodyPointDecomposition::PosedBodyPointDecomposition |
( |
const std::shared_ptr< const octomap::OcTree > & |
octree | ) |
|
◆ getCollisionPoints()
const EigenSTL::vector_Vector3d & collision_detection::PosedBodyPointDecomposition::getCollisionPoints |
( |
| ) |
const |
|
inline |
◆ updatePose()
void collision_detection::PosedBodyPointDecomposition::updatePose |
( |
const Eigen::Isometry3d & |
linkTransform | ) |
|
◆ body_decomposition_
BodyDecompositionConstPtr collision_detection::PosedBodyPointDecomposition::body_decomposition_ |
|
protected |
◆ posed_collision_points_
EigenSTL::vector_Vector3d collision_detection::PosedBodyPointDecomposition::posed_collision_points_ |
|
protected |
The documentation for this class was generated from the following files: