distance result
More...
#include <hpp/fcl/collision_data.h>
|
| DistanceResult (FCL_REAL min_distance_=std::numeric_limits< FCL_REAL >::max()) |
|
void | update (FCL_REAL distance, const CollisionGeometry *o1_, const CollisionGeometry *o2_, int b1_, int b2_) |
| add distance information into the result More...
|
|
void | update (FCL_REAL distance, const CollisionGeometry *o1_, const CollisionGeometry *o2_, int b1_, int b2_, const Vec3f &p1, const Vec3f &p2) |
| add distance information into the result More...
|
|
void | update (const DistanceResult &other_result) |
| add distance information into the result More...
|
|
void | clear () |
| clear the result More...
|
|
|
FCL_REAL | min_distance |
| minimum distance between two objects. if two objects are in collision, min_distance <= 0. More...
|
|
Vec3f | nearest_points [2] |
| nearest points More...
|
|
const CollisionGeometry * | o1 |
| collision object 1 More...
|
|
const CollisionGeometry * | o2 |
| collision object 2 More...
|
|
int | b1 |
| information about the nearest point in object 1 if object 1 is mesh or point cloud, it is the triangle or point id if object 1 is geometry shape, it is NONE (-1), if object 1 is octree, it is the id of the cell More...
|
|
int | b2 |
| information about the nearest point in object 2 if object 2 is mesh or point cloud, it is the triangle or point id if object 2 is geometry shape, it is NONE (-1), if object 2 is octree, it is the id of the cell More...
|
|
|
static const int | NONE = -1 |
| invalid contact primitive information More...
|
|
fcl::DistanceResult::DistanceResult |
( |
FCL_REAL |
min_distance_ = std::numeric_limits<FCL_REAL>::max() | ) |
|
|
inline |
void fcl::DistanceResult::clear |
( |
| ) |
|
|
inline |
add distance information into the result
References b1, b2, fcl::distance(), min_distance, o1, and o2.
Referenced by fcl::ShapeDistanceTraversalNode< S1, S2, NarrowPhaseSolver >::leafTesting(), fcl::MeshDistanceTraversalNode< OBBRSS >::leafTesting(), and fcl::MeshShapeDistanceTraversalNode< OBBRSS, S, NarrowPhaseSolver >::leafTesting().
void fcl::DistanceResult::update |
( |
const DistanceResult & |
other_result | ) |
|
|
inline |
int fcl::DistanceResult::b1 |
information about the nearest point in object 1 if object 1 is mesh or point cloud, it is the triangle or point id if object 1 is geometry shape, it is NONE (-1), if object 1 is octree, it is the id of the cell
Referenced by clear(), and update().
int fcl::DistanceResult::b2 |
information about the nearest point in object 2 if object 2 is mesh or point cloud, it is the triangle or point id if object 2 is geometry shape, it is NONE (-1), if object 2 is octree, it is the id of the cell
Referenced by clear(), and update().
FCL_REAL fcl::DistanceResult::min_distance |
Vec3f fcl::DistanceResult::nearest_points[2] |
const int fcl::DistanceResult::NONE = -1 |
|
static |