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  * Copyright (c) 2022, INRIA
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 the copyright holder 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 
39 #ifndef HPP_FCL_BROADPHASE_DEFAULT_BROADPHASE_CALLBACKS_H
40 #define HPP_FCL_BROADPHASE_DEFAULT_BROADPHASE_CALLBACKS_H
41 
43 #include "hpp/fcl/collision.h"
44 #include "hpp/fcl/distance.h"
45 // #include "hpp/fcl/narrowphase/continuous_collision.h"
46 // #include "hpp/fcl/narrowphase/continuous_collision_request.h"
47 // #include "hpp/fcl/narrowphase/continuous_collision_result.h"
48 // #include "hpp/fcl/narrowphase/distance_request.h"
49 // #include "hpp/fcl/narrowphase/distance_result.h"
50 
51 namespace hpp {
52 namespace fcl {
53 
56 struct CollisionData {
57  CollisionData() { done = false; }
58 
61 
64 
66  bool done;
67 };
68 
71 struct DistanceData {
72  DistanceData() { done = false; }
73 
76 
79 
81  bool done;
82 };
83 
107  void* data);
108 
113 // struct DefaultContinuousCollisionData {
114 // ContinuousCollisionRequest request;
115 // ContinuousCollisionResult result;
116 //
117 // /// If `true`, requests that the broadphase evaluation stop.
118 // bool done{false};
119 // };
120 
143 // bool DefaultContinuousCollisionFunction(ContinuousCollisionObject* o1,
144 // ContinuousCollisionObject* o2,
145 // void* data) {
146 // assert(data != nullptr);
147 // auto* cdata = static_cast<DefaultContinuousCollisionData*>(data);
148 //
149 // if (cdata->done) return true;
150 //
151 // const ContinuousCollisionRequest& request = cdata->request;
152 // ContinuousCollisionResult& result = cdata->result;
153 // collide(o1, o2, request, result);
154 //
155 // return cdata->done;
156 // }
157 
181  void* data, FCL_REAL& dist);
182 
186  bool collide(CollisionObject* o1, CollisionObject* o2);
187 
189 
191 };
192 
196  bool distance(CollisionObject* o1, CollisionObject* o2, FCL_REAL& dist);
197 
199 
201 };
202 
205  typedef std::pair<CollisionObject*, CollisionObject*> CollisionPair;
206 
208  CollisionCallBackCollect(const size_t max_size);
209 
210  bool collide(CollisionObject* o1, CollisionObject* o2);
211 
213  size_t numCollisionPairs() const;
214 
216  const std::vector<CollisionPair>& getCollisionPairs() const;
217 
219  void init();
220 
222  bool exist(const CollisionPair& pair) const;
223 
225 
226  protected:
227  std::vector<CollisionPair> collision_pairs;
228  size_t max_size;
229 };
230 
231 } // namespace fcl
232 
233 } // namespace hpp
234 
235 #endif // HPP_FCL_BROADPHASE_DEFAULT_BROADPHASE_CALLBACKS_H
request to the distance computation
Collision data stores the collision request and the result given by collision algorithm.
CollisionRequest request
Collision request.
bool done
Whether the distance iteration can stop.
Main namespace.
Base callback class for collision queries. This class can be supersed by child classes to provide des...
DistanceResult result
Distance result.
request to the collision algorithm
HPP_FCL_DLLAPI FCL_REAL distance(const Matrix3f &R0, const Vec3f &T0, const kIOS &b1, const kIOS &b2, Vec3f *P=NULL, Vec3f *Q=NULL)
Approximate distance between two kIOS bounding volumes.
Definition: kIOS.cpp:181
double FCL_REAL
Definition: data_types.h:65
DistanceRequest request
Distance request.
Collision callback to collect collision pairs potentially in contacts.
Default collision callback to check collision between collision objects.
CollisionResult result
Collision result.
bool defaultDistanceFunction(CollisionObject *o1, CollisionObject *o2, void *data, FCL_REAL &dist)
Collision data for use with the DefaultContinuousCollisionFunction. It stores the collision request a...
HPP_FCL_DLLAPI std::size_t collide(const CollisionObject *o1, const CollisionObject *o2, const CollisionRequest &request, CollisionResult &result)
Main collision interface: given two collision objects, and the requirements for contacts, including num of max contacts, whether perform exhaustive collision (i.e., returning returning all the contact points), whether return detailed contact information (i.e., normal, contact point, depth; otherwise only contact primitive id is returned), this function performs the collision between them. Return value is the number of contacts generated between the two objects.
std::pair< CollisionObject *, CollisionObject * > CollisionPair
Default distance callback to check collision between collision objects.
bool done
Whether the collision iteration can stop.
the object for collision or distance computation, contains the geometry and the transform information...
bool defaultCollisionFunction(CollisionObject *o1, CollisionObject *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 CollisionData. It simply invokes the collide() method on the culled pair of geometries and stores the results in the data&#39;s CollisionResult instance.
Base callback class for distance queries. This class can be supersed by child classes to provide desi...
Distance data stores the distance request and the result given by distance algorithm.


hpp-fcl
Author(s):
autogenerated on Fri Jun 2 2023 02:39:00