default_broadphase_callbacks.h
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2020, Toyota Research Institute
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of the copyright holder nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  */
34 
37 #ifndef FCL_BROADPHASE_DEFAULTBROADPHASECALLBACKS_H
38 #define FCL_BROADPHASE_DEFAULTBROADPHASECALLBACKS_H
39 
49 
50 namespace fcl {
51 
56 template <typename S>
60 
62  bool done{false};
63 };
64 
87 template <typename S>
89  void* data) {
90  assert(data != nullptr);
91  auto* collision_data = static_cast<DefaultCollisionData<S>*>(data);
92  const CollisionRequest<S>& request = collision_data->request;
93  CollisionResult<S>& result = collision_data->result;
94 
95  if(collision_data->done) return true;
96 
97  collide(o1, o2, request, result);
98 
99  if (!request.enable_cost && result.isCollision() &&
100  result.numContacts() >= request.num_max_contacts) {
101  collision_data->done = true;
102  }
103 
104  return collision_data->done;
105 }
106 
107 
112 template <typename S>
116 
118  bool done{false};
119 };
120 
121 
144 template <typename S>
147  void* data) {
148  assert(data != nullptr);
149  auto* cdata = static_cast<DefaultContinuousCollisionData<S>*>(data);
150 
151  if (cdata->done) return true;
152 
153  const ContinuousCollisionRequest<S>& request = cdata->request;
154  ContinuousCollisionResult<S>& result = cdata->result;
155  collide(o1, o2, request, result);
156 
157  return cdata->done;
158 }
159 
164 template <typename S>
168 
170  bool done{false};
171 };
172 
195 template <typename S>
197  void* data, S& dist) {
198  assert(data != nullptr);
199  auto* cdata = static_cast<DefaultDistanceData<S>*>(data);
200  const DistanceRequest<S>& request = cdata->request;
201  DistanceResult<S>& result = cdata->result;
202 
203  if (cdata->done) {
204  dist = result.min_distance;
205  return true;
206  }
207 
208  distance(o1, o2, request, result);
209 
210  dist = result.min_distance;
211 
212  if (dist <= 0) return true; // in collision or in touch
213 
214  return cdata->done;
215 }
216 
217 } // namespace fcl
218 
219 #endif // FCL_BROADPHASE_DEFAULTBROADPHASECALLBACKS_H
size_t numContacts() const
number of contacts found
S min_distance
Minimum distance between two objects.
Main namespace.
collision result
bool DefaultDistanceFunction(CollisionObject< S > *o1, CollisionObject< S > *o2, void *data, S &dist)
Provides a simple callback for the distance query in the BroadPhaseCollisionManager. It assumes the data parameter is non-null and points to an instance of DefaultDistanceData. It simply invokes the distance() method on the culled pair of geometries and stores the results in the data&#39;s DistanceResult instance.
distance result
bool done
If true, requests that the broadphase evaluation stop.
S distance(const Eigen::MatrixBase< DerivedA > &R0, const Eigen::MatrixBase< DerivedB > &T0, const kIOS< S > &b1, const kIOS< S > &b2, Vector3< S > *P, Vector3< S > *Q)
Approximate distance between two kIOS bounding volumes.
Definition: kIOS-inl.h:266
the object for continuous collision or distance computation, contains the geometry and the motion inf...
bool DefaultContinuousCollisionFunction(ContinuousCollisionObject< S > *o1, ContinuousCollisionObject< S > *o2, void *data)
Provides a simple callback for the continuous collision query in the BroadPhaseCollisionManager. It assumes the data parameter is non-null and points to an instance of DefaultContinuousCollisionData. It simply invokes the collide() method on the culled pair of geometries and stores the results in the data&#39;s ContinuousCollisionResult instance.
template FCL_EXPORT std::size_t collide(const CollisionObject< double > *o1, const CollisionObject< double > *o2, const CollisionRequest< double > &request, CollisionResult< double > &result)
Parameters for performing collision request.
Distance data for use with the DefaultDistanceFunction. It stores the distance request and the result...
the object for collision or distance computation, contains the geometry and the transform information...
Collision data for use with the DefaultCollisionFunction. It stores the collision request and the res...
Collision data for use with the DefaultContinuousCollisionFunction. It stores the collision request a...
bool DefaultCollisionFunction(CollisionObject< S > *o1, CollisionObject< S > *o2, void *data)
Provides a simple callback for the collision query in the BroadPhaseCollisionManager. It assumes the data parameter is non-null and points to an instance of DefaultCollisionData. It simply invokes the collide() method on the culled pair of geometries and stores the results in the data&#39;s CollisionResult instance.
bool isCollision() const
return binary collision result
request to the distance computation


fcl_catkin
Author(s):
autogenerated on Thu Mar 23 2023 03:00:18