DART  6.10.1
DistanceResult.hpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2011-2021, The DART development contributors
3  * All rights reserved.
4  *
5  * The list of contributors can be found at:
6  * https://github.com/dartsim/dart/blob/master/LICENSE
7  *
8  * This file is provided under the following "BSD-style" License:
9  * Redistribution and use in source and binary forms, with or
10  * without modification, are permitted provided that the following
11  * conditions are met:
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND
19  * CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES,
20  * INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
21  * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
22  * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
23  * CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
24  * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
25  * LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF
26  * USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
27  * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
28  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
29  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
30  * POSSIBILITY OF SUCH DAMAGE.
31  */
32 
33 #ifndef DART_COLLISION_DISTANCE_RESULT_HPP_
34 #define DART_COLLISION_DISTANCE_RESULT_HPP_
35 
36 #include <Eigen/Dense>
37 
38 namespace dart {
39 
40 namespace dynamics {
41 class ShapeFrame;
42 } // namespace dynamics
43 
44 namespace collision {
45 
47 {
63  double minDistance;
64 
74 
79 
84 
93  Eigen::Vector3d nearestPoint1;
94 
103  Eigen::Vector3d nearestPoint2;
104 
106  DistanceResult();
107 
109  void clear();
110 
113  bool found() const;
114 
117  bool isMinDistanceClamped() const;
118 };
119 
120 } // namespace collision
121 } // namespace dart
122 
123 #endif // DART_COLLISION_DISTANCE_RESULT_HPP_
Definition: ShapeFrame.hpp:192
Definition: BulletCollisionDetector.cpp:65
Definition: DistanceResult.hpp:47
double unclampedMinDistance
Unclamped minimum distance that is the first distance equal to or less than DistanceOption::distanceL...
Definition: DistanceResult.hpp:73
double minDistance
Minimum singed distance between the checked Shape pairs.
Definition: DistanceResult.hpp:63
Eigen::Vector3d nearestPoint2
The nearest point on DistanceResult::shapeFrame2 expressed the world coordinates.
Definition: DistanceResult.hpp:103
bool isMinDistanceClamped() const
Get true if the minimum distance was not clamped (minDistance == unclampedMinDistance).
Definition: DistanceResult.cpp:76
const dynamics::ShapeFrame * shapeFrame2
Second ShapeFrame of the minDistance.
Definition: DistanceResult.hpp:83
bool found() const
Get true if the result is valid (at least one shape pair was checked and the result values are good t...
Definition: DistanceResult.cpp:67
DistanceResult()
Constructor.
Definition: DistanceResult.cpp:42
void clear()
Clear the result.
Definition: DistanceResult.cpp:54
Eigen::Vector3d nearestPoint1
The nearest point on DistanceResult::shapeFrame1 expressed in the world coordinates.
Definition: DistanceResult.hpp:93
const dynamics::ShapeFrame * shapeFrame1
First ShapeFrame of the minDistance.
Definition: DistanceResult.hpp:78