1 /*
2  * Software License Agreement (BSD License)
3  *
4  *  Copyright (c) 2011-2014, Willow Garage, Inc.
5  *  Copyright (c) 2014-2016, Open Source Robotics Foundation
6  *  All rights reserved.
7  *
8  *  Redistribution and use in source and binary forms, with or without
9  *  modification, are permitted provided that the following conditions
10  *  are met:
11  *
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  *   * Neither the name of Open Source Robotics Foundation nor the names of its
19  *     contributors may be used to endorse or promote products derived
20  *     from this software without specific prior written permission.
21  *
22  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  *  POSSIBILITY OF SUCH DAMAGE.
34  */
35 
36 /** @author Jia Pan */
37 
38 #ifndef FCL_DISTANCEREQUEST_H
39 #define FCL_DISTANCEREQUEST_H
40 
41 #include "fcl/common/types.h"
42 #include "fcl/narrowphase/gjk_solver_type.h"
43 
44 namespace fcl
45 {
46 
47 template <typename S>
48 struct DistanceResult;
49 
50 /// @brief request to the distance computation
51 template <typename S>
52 struct FCL_EXPORT DistanceRequest
53 {
54   /// @brief whether to return the nearest points
55   bool enable_nearest_points;
56 
57   /// @brief Whether to compute exact negative distance.
58   ///
59   /// Basically, the distance computation routine computes only the exact
60   /// positive distance when the two objects are not in collision. If the
61   /// objects are in collision, the result distance is implementation defined
62   /// (mostly -1).
63   ///
64   ///       [ Current Implementation Status ]
65   /// -----------------+--------------+--------------
66   ///   GJKSolverType  |  GST_LIBCCD  |  GST_INDEP
67   /// -----------------+--------------+--------------
68   /// primitive shapes | SD_1, NP     | SD_2, NP_X
69   /// mesh and octree  | SD_2, NP_X   | SD_2, NP_X
70   /// -----------------+--------------+--------------
71   /// SD_1: Signed distance is computed using convexity based methods (GJK, MPA)
72   /// SD_2: Positive distance is computed using convexity based mothods (GJK,
73   ///       MPA), but negative distance is computed by a workaround using
74   ///       penetration computation.
75   /// NP  : The pair of nearest points are guaranteed to be on the surface of
76   ///       objects.
77   /// NP_X: The pair of nearest points are NOT guaranteed to be on the surface
78   ///       of objects.
79   ///
80   /// If this flag is set to true, FCL will perform additional collision
81   /// checking when the two objects are in collision in order to get the exact
82   /// negative distance, which is the negated penetration depth. If there are
83   /// multiple contact for the two objects, then the maximum penetration depth
84   /// is used.
85   ///
86   /// If this flag is set to false, the result minimum distance is
87   /// implementation defined (mostly -1).
88   ///
89   /// The default is false.
90   ///
91   /// @sa DistanceResult::min_distance
92   bool enable_signed_distance;
93 
94   /// @brief error threshold for approximate distance
95   S rel_err; // relative error, between 0 and 1
96   S abs_err; // absoluate error
97 
98   /// @brief the threshold used in GJK algorithm to stop distance iteration
99   S distance_tolerance;
100 
101   /// @brief narrow phase solver type
102   GJKSolverType gjk_solver_type;
103 
104   explicit DistanceRequest(
105       bool enable_nearest_points_ = false,
106       bool enable_signed_distance = false,
107       S rel_err_ = 0.0,
108       S abs_err_ = 0.0,
109       S distance_tolerance = 1e-6,
110       GJKSolverType gjk_solver_type_ = GST_LIBCCD);
111 
112   bool isSatisfied(const DistanceResult<S>& result) const;
113 };
114 
115 using DistanceRequestf = DistanceRequest<float>;
116 using DistanceRequestd = DistanceRequest<double>;
117 
118 } // namespace fcl
119 
120 #include "fcl/narrowphase/distance_request-inl.h"
121 
122 #endif
123