DART
6.7.3
|
#include <DistanceResult.hpp>
Public Member Functions | |
DistanceResult () | |
Constructor. More... | |
void | clear () |
Clear the result. More... | |
bool | found () const |
Get true if the result is valid (at least one shape pair was checked and the result values are good to use). More... | |
bool | isMinDistanceClamped () const |
Get true if the minimum distance was not clamped (minDistance == unclampedMinDistance). More... | |
Public Attributes | |
double | minDistance |
Minimum singed distance between the checked Shape pairs. More... | |
double | unclampedMinDistance |
Unclamped minimum distance that is the first distance equal to or less than DistanceOption::distanceLowerBound. More... | |
const dynamics::ShapeFrame * | shapeFrame1 |
First ShapeFrame of the minDistance. More... | |
const dynamics::ShapeFrame * | shapeFrame2 |
Second ShapeFrame of the minDistance. More... | |
Eigen::Vector3d | nearestPoint1 |
The nearest point on DistanceResult::shapeFrame1 expressed in the world coordinates. More... | |
Eigen::Vector3d | nearestPoint2 |
The nearest point on DistanceResult::shapeFrame2 expressed the world coordinates. More... | |
dart::collision::DistanceResult::DistanceResult | ( | ) |
Constructor.
void dart::collision::DistanceResult::clear | ( | ) |
Clear the result.
bool dart::collision::DistanceResult::found | ( | ) | const |
Get true if the result is valid (at least one shape pair was checked and the result values are good to use).
bool dart::collision::DistanceResult::isMinDistanceClamped | ( | ) | const |
Get true if the minimum distance was not clamped (minDistance == unclampedMinDistance).
double dart::collision::DistanceResult::minDistance |
Minimum singed distance between the checked Shape pairs.
If no shape pair was checked (the collision group was empty or all pairs were excluded by the filter) then this value will be remained the default value 0.0. You can check if a valid distance was found using DistanceResult::found() that returns true when it's found.
The result minimum distance is clamped by DistanceOption::distanceLowerBound (min. distance >= distance lower bound). You can still get the unclamped distance from DistanceResult::unclampedMinDistance.
If the minimum distance is negative value, that means the distance is the negative penetration depth measured from the shapes that are in collision.
Eigen::Vector3d dart::collision::DistanceResult::nearestPoint1 |
The nearest point on DistanceResult::shapeFrame1 expressed in the world coordinates.
The point is calculated only when DistanceOption::enableNearestPoints is true.
The distance between the two nearest points is equal to unclampedMinDistance rather than minDistance.
Eigen::Vector3d dart::collision::DistanceResult::nearestPoint2 |
The nearest point on DistanceResult::shapeFrame2 expressed the world coordinates.
The point is calculated only when DistanceOption::enableNearestPoints is true.
The distance between the two nearest points is equal to unclampedMinDistance rather than minDistance.
const dynamics::ShapeFrame* dart::collision::DistanceResult::shapeFrame1 |
First ShapeFrame of the minDistance.
If no shape pair was checked then shapeFrame1 will be nullptr.
const dynamics::ShapeFrame* dart::collision::DistanceResult::shapeFrame2 |
Second ShapeFrame of the minDistance.
If no shape pair was checked then shapeFrame2 will be nullptr.
double dart::collision::DistanceResult::unclampedMinDistance |
Unclamped minimum distance that is the first distance equal to or less than DistanceOption::distanceLowerBound.