src/collision.cpp
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2011-2014, Willow Garage, Inc.
5  * Copyright (c) 2014-2015, 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 
38 #include <hpp/fcl/collision.h>
42 
43 #include <iostream>
44 
45 namespace hpp {
46 namespace fcl {
47 
49  static CollisionFunctionMatrix table;
50  return table;
51 }
52 
53 // reorder collision results in the order the call has been made.
55  for (std::vector<Contact>::iterator it = contacts.begin();
56  it != contacts.end(); ++it) {
57  std::swap(it->o1, it->o2);
58  std::swap(it->b1, it->b2);
59  it->normal *= -1;
60  }
61 }
62 
63 std::size_t collide(const CollisionObject* o1, const CollisionObject* o2,
64  const CollisionRequest& request, CollisionResult& result) {
65  return collide(o1->collisionGeometry().get(), o1->getTransform(),
66  o2->collisionGeometry().get(), o2->getTransform(), request,
67  result);
68 }
69 
70 std::size_t collide(const CollisionGeometry* o1, const Transform3f& tf1,
71  const CollisionGeometry* o2, const Transform3f& tf2,
72  const CollisionRequest& request, CollisionResult& result) {
73  // If securit margin is set to -infinity, return that there is no collision
74  if (request.security_margin == -std::numeric_limits<FCL_REAL>::infinity()) {
75  result.clear();
76  return false;
77  }
78 
79  GJKSolver solver(request);
80 
82  std::size_t res;
83  if (request.num_max_contacts == 0) {
84  HPP_FCL_THROW_PRETTY("Invalid number of max contacts (current value is 0).",
85  std::invalid_argument);
86  res = 0;
87  } else {
88  OBJECT_TYPE object_type1 = o1->getObjectType();
89  OBJECT_TYPE object_type2 = o2->getObjectType();
90  NODE_TYPE node_type1 = o1->getNodeType();
91  NODE_TYPE node_type2 = o2->getNodeType();
92 
93  if (object_type1 == OT_GEOM &&
94  (object_type2 == OT_BVH || object_type2 == OT_HFIELD)) {
95  if (!looktable.collision_matrix[node_type2][node_type1]) {
96  HPP_FCL_THROW_PRETTY("Collision function between node type "
97  << std::string(get_node_type_name(node_type1))
98  << " and node type "
99  << std::string(get_node_type_name(node_type2))
100  << " is not yet supported.",
101  std::invalid_argument);
102  res = 0;
103  } else {
104  res = looktable.collision_matrix[node_type2][node_type1](
105  o2, tf2, o1, tf1, &solver, request, result);
106  result.swapObjects();
107  }
108  } else {
109  if (!looktable.collision_matrix[node_type1][node_type2]) {
110  HPP_FCL_THROW_PRETTY("Collision function between node type "
111  << std::string(get_node_type_name(node_type1))
112  << " and node type "
113  << std::string(get_node_type_name(node_type2))
114  << " is not yet supported.",
115  std::invalid_argument);
116  res = 0;
117  } else
118  res = looktable.collision_matrix[node_type1][node_type2](
119  o1, tf1, o2, tf2, &solver, request, result);
120  }
121  }
123  solver.enable_cached_guess) {
124  result.cached_gjk_guess = solver.cached_guess;
126  }
127 
128  return res;
129 }
130 
132  const CollisionGeometry* o2)
133  : o1(o1), o2(o2) {
135 
136  OBJECT_TYPE object_type1 = o1->getObjectType();
137  NODE_TYPE node_type1 = o1->getNodeType();
138  OBJECT_TYPE object_type2 = o2->getObjectType();
139  NODE_TYPE node_type2 = o2->getNodeType();
140 
141  swap_geoms = object_type1 == OT_GEOM &&
142  (object_type2 == OT_BVH || object_type2 == OT_HFIELD);
143 
144  if ((swap_geoms && !looktable.collision_matrix[node_type2][node_type1]) ||
145  (!swap_geoms && !looktable.collision_matrix[node_type1][node_type2])) {
146  HPP_FCL_THROW_PRETTY("Collision function between node type "
147  << std::string(get_node_type_name(node_type1))
148  << " and node type "
149  << std::string(get_node_type_name(node_type2))
150  << " is not yet supported.",
151  std::invalid_argument);
152  }
153  if (swap_geoms)
154  func = looktable.collision_matrix[node_type2][node_type1];
155  else
156  func = looktable.collision_matrix[node_type1][node_type2];
157 }
158 
160  const Transform3f& tf2,
161  const CollisionRequest& request,
162  CollisionResult& result) const {
163  // If security margin is set to -infinity, return that there is no collision
164  if (request.security_margin == -std::numeric_limits<FCL_REAL>::infinity()) {
165  result.clear();
166  return false;
167  }
168  std::size_t res;
169  if (swap_geoms) {
170  res = func(o2, tf2, o1, tf1, &solver, request, result);
171  result.swapObjects();
172  } else {
173  res = func(o1, tf1, o2, tf2, &solver, request, result);
174  }
175  return res;
176 }
177 
179  const Transform3f& tf2,
180  const CollisionRequest& request,
181  CollisionResult& result) const
182 
183 {
184  solver.set(request);
185 
186  std::size_t res;
187  if (request.enable_timings) {
188  Timer timer;
189  res = run(tf1, tf2, request, result);
190  result.timings = timer.elapsed();
191  } else
192  res = run(tf1, tf2, request, result);
193 
198  }
199 
200  return res;
201 }
202 
203 } // namespace fcl
204 } // namespace hpp
size_t num_max_contacts
The maximum number of contacts will return.
Simple transform class used locally by InterpMotion.
Definition: transform.h:54
support_func_guess_t cached_support_func_guess
stores the last support function vertex index, when relevant.
const char * get_node_type_name(NODE_TYPE node_type)
Returns the name associated to a NODE_TYPE.
OBJECT_TYPE
object type: BVH (mesh, points), basic geometry, octree
CPUTimes elapsed() const
Definition: timings.h:46
Main namespace.
std::vector< Contact > contacts
contact information
CollisionFunc collision_matrix[NODE_COUNT][NODE_COUNT]
each item in the collision matrix is a function to handle collision between objects of type1 and type...
bool enable_cached_guess
Whether smart guess can be provided Use gjk_initial_guess instead.
Definition: narrowphase.h:496
tuple tf2
const CollisionGeometry * o1
Definition: collision.h:129
const Transform3f & getTransform() const
get object&#39;s transform
CollisionFunctionMatrix & getCollisionFunctionLookTable()
virtual NODE_TYPE getNodeType() const
get the node type
request to the collision algorithm
void clear()
clear the results obtained
void set(const DistanceRequest &request)
setter from a DistanceRequest
Definition: narrowphase.h:389
virtual OBJECT_TYPE getObjectType() const
get the type of the object
This class mimics the way "boost/timer/timer.hpp" operates while using the modern std::chrono library...
Definition: timings.h:32
CPUTimes timings
timings for the given request
bool enable_timings
enable timings when performing collision/distance request
const shared_ptr< const CollisionGeometry > collisionGeometry() const
get geometry from the object instance
Vec3f cached_guess
smart guess
Definition: narrowphase.h:499
NODE_TYPE
traversal node type: bounding volume (AABB, OBB, RSS, kIOS, OBBRSS, KDOP16, KDOP18, kDOP24), basic shape (box, sphere, ellipsoid, capsule, cone, cylinder, convex, plane, triangle), and octree
res
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::size_t operator()(const Transform3f &tf1, const Transform3f &tf2, const CollisionRequest &request, CollisionResult &result) const
CollisionFunctionMatrix::CollisionFunc func
Definition: collision.h:141
ComputeCollision(const CollisionGeometry *o1, const CollisionGeometry *o2)
Default constructor from two Collision Geometries.
Vec3f cached_gjk_guess
stores the last GJK ray when relevant.
const CollisionGeometry * o2
Definition: collision.h:137
collision and distance solver based on GJK algorithm implemented in fcl (rewritten the code from the ...
Definition: narrowphase.h:54
the object for collision or distance computation, contains the geometry and the transform information...
The geometry for the object for collision or distance computation.
support_func_guess_t support_func_cached_guess
smart guess for the support function
Definition: narrowphase.h:514
virtual std::size_t run(const Transform3f &tf1, const Transform3f &tf2, const CollisionRequest &request, CollisionResult &result) const
void swapObjects()
reposition Contact objects when fcl inverts them during their construction.
GJKInitialGuess gjk_initial_guess
which warm start to use for GJK
Definition: narrowphase.h:502
tuple tf1
collision matrix stores the functions for collision between different types of objects and provides a...
#define HPP_FCL_THROW_PRETTY(message, exception)
FCL_REAL security_margin
Distance below which objects are considered in collision. See Collision.


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