default_broadphase_callbacks.cpp
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 
38 #include <algorithm>
39 
40 namespace hpp {
41 namespace fcl {
42 
44  void* data) {
45  assert(data != nullptr);
46  auto* collision_data = static_cast<CollisionData*>(data);
47  const CollisionRequest& request = collision_data->request;
48  CollisionResult& result = collision_data->result;
49 
50  if (collision_data->done) return true;
51 
52  collide(o1, o2, request, result);
53 
54  if (result.isCollision() &&
55  result.numContacts() >= request.num_max_contacts) {
56  collision_data->done = true;
57  }
58 
59  return collision_data->done;
60 }
61 
63  CollisionObject* o2) {
64  return defaultCollisionFunction(o1, o2, &data);
65 }
66 
68  void* data, FCL_REAL& dist) {
69  assert(data != nullptr);
70  auto* cdata = static_cast<DistanceData*>(data);
71  const DistanceRequest& request = cdata->request;
72  DistanceResult& result = cdata->result;
73 
74  if (cdata->done) {
75  dist = result.min_distance;
76  return true;
77  }
78 
79  distance(o1, o2, request, result);
80 
81  dist = result.min_distance;
82 
83  if (dist <= 0) return true; // in collision or in touch
84 
85  return cdata->done;
86 }
87 
89  FCL_REAL& dist) {
90  return defaultDistanceFunction(o1, o2, &data, dist);
91 }
92 
94  : max_size(max_size) {
95  collision_pairs.resize(max_size);
96 }
97 
99  CollisionObject* o2) {
100  collision_pairs.push_back(std::make_pair(o1, o2));
101  return false;
102 }
103 
105  return collision_pairs.size();
106 }
107 
108 const std::vector<CollisionCallBackCollect::CollisionPair>&
110  return collision_pairs;
111 }
112 
114 
116  return std::find(collision_pairs.begin(), collision_pairs.end(), pair) !=
117  collision_pairs.end();
118 }
119 
120 } // namespace fcl
121 } // namespace hpp
size_t num_max_contacts
The maximum number of contacts will return.
request to the distance computation
Collision data stores the collision request and the result given by collision algorithm.
bool distance(CollisionObject *o1, CollisionObject *o2, FCL_REAL &dist)
Distance evaluation between two objects in collision. This callback will cause the broadphase evaluat...
Main namespace.
size_t numCollisionPairs() const
Returns the number of registered collision pairs.
size_t numContacts() const
number of contacts found
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
FCL_REAL min_distance
minimum distance between two objects. if two objects are in collision, min_distance <= 0...
bool collide(CollisionObject *o1, CollisionObject *o2)
Collision evaluation between two objects in collision. This callback will cause the broadphase evalua...
bool collide(CollisionObject *o1, CollisionObject *o2)
Collision evaluation between two objects in collision. This callback will cause the broadphase evalua...
const std::vector< CollisionPair > & getCollisionPairs() const
Returns a const reference to the active collision_pairs to check.
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.
bool exist(const CollisionPair &pair) const
Check wether a collision pair exists.
std::pair< CollisionObject *, CollisionObject * > CollisionPair
bool isCollision() const
return binary collision result
CollisionCallBackCollect(const size_t max_size)
Default constructor.
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.
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