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 "coal/collision.h"
39 #include "coal/collision_utility.h"
42 
43 namespace coal {
44 
46  static CollisionFunctionMatrix table;
47  return table;
48 }
49 
50 // reorder collision results in the order the call has been made.
52  for (std::vector<Contact>::iterator it = contacts.begin();
53  it != contacts.end(); ++it) {
54  std::swap(it->o1, it->o2);
55  std::swap(it->b1, it->b2);
56  it->nearest_points[0].swap(it->nearest_points[1]);
57  it->normal *= -1;
58  }
59 }
60 
61 std::size_t collide(const CollisionObject* o1, const CollisionObject* o2,
62  const CollisionRequest& request, CollisionResult& result) {
63  return collide(o1->collisionGeometryPtr(), o1->getTransform(),
64  o2->collisionGeometryPtr(), o2->getTransform(), request,
65  result);
66 }
67 
68 std::size_t collide(const CollisionGeometry* o1, const Transform3s& tf1,
69  const CollisionGeometry* o2, const Transform3s& tf2,
70  const CollisionRequest& request, CollisionResult& result) {
71  // If security margin is set to -infinity, return that there is no collision
72  if (request.security_margin == -std::numeric_limits<CoalScalar>::infinity()) {
73  result.clear();
74  return false;
75  }
76 
77  GJKSolver solver(request);
78 
80  std::size_t res;
81  if (request.num_max_contacts == 0) {
82  COAL_THROW_PRETTY("Invalid number of max contacts (current value is 0).",
83  std::invalid_argument);
84  res = 0;
85  } else {
86  OBJECT_TYPE object_type1 = o1->getObjectType();
87  OBJECT_TYPE object_type2 = o2->getObjectType();
88  NODE_TYPE node_type1 = o1->getNodeType();
89  NODE_TYPE node_type2 = o2->getNodeType();
90 
91  if (object_type1 == OT_GEOM &&
92  (object_type2 == OT_BVH || object_type2 == OT_HFIELD)) {
93  if (!looktable.collision_matrix[node_type2][node_type1]) {
94  COAL_THROW_PRETTY("Collision function between node type "
95  << std::string(get_node_type_name(node_type1))
96  << " and node type "
97  << std::string(get_node_type_name(node_type2))
98  << " is not yet supported.",
99  std::invalid_argument);
100  res = 0;
101  } else {
102  res = looktable.collision_matrix[node_type2][node_type1](
103  o2, tf2, o1, tf1, &solver, request, result);
104  result.swapObjects();
105  result.nearest_points[0].swap(result.nearest_points[1]);
106  result.normal *= -1;
107  }
108  } else {
109  if (!looktable.collision_matrix[node_type1][node_type2]) {
110  COAL_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  }
122  // Cache narrow phase solver result. If the option in the request is selected,
123  // also store the solver result in the request for the next call.
124  result.cached_gjk_guess = solver.cached_guess;
126  request.updateGuess(result);
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  COAL_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 Transform3s& 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<CoalScalar>::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  result.nearest_points[0].swap(result.nearest_points[1]);
173  result.normal *= -1;
174  } else {
175  res = func(o1, tf1, o2, tf2, &solver, request, result);
176  }
177  // Cache narrow phase solver result. If the option in the request is selected,
178  // also store the solver result in the request for the next call.
181  request.updateGuess(result);
182 
183  return res;
184 }
185 
187  const Transform3s& tf2,
188  const CollisionRequest& request,
189  CollisionResult& result) const
190 
191 {
192  solver.set(request);
193 
194  std::size_t res;
195  if (request.enable_timings) {
196  Timer timer;
197  res = run(tf1, tf2, request, result);
198  result.timings = timer.elapsed();
199  } else
200  res = run(tf1, tf2, request, result);
201 
202  return res;
203 }
204 
205 } // namespace coal
coal::ComputeCollision::o1
const CollisionGeometry * o1
Definition: coal/collision.h:95
coal::QueryResult::cached_support_func_guess
support_func_guess_t cached_support_func_guess
stores the last support function vertex index, when relevant.
Definition: coal/collision_data.h:280
coal::CollisionFunctionMatrix
collision matrix stores the functions for collision between different types of objects and provides a...
Definition: coal/collision_func_matrix.h:50
coal::CollisionGeometry::getNodeType
virtual NODE_TYPE getNodeType() const
get the node type
Definition: coal/collision_object.h:130
collision.h
coal::ComputeCollision::run
virtual std::size_t run(const Transform3s &tf1, const Transform3s &tf2, const CollisionRequest &request, CollisionResult &result) const
Definition: src/collision.cpp:159
coal::CollisionResult::swapObjects
void swapObjects()
reposition Contact objects when fcl inverts them during their construction.
Definition: src/collision.cpp:51
coal::QueryRequest::updateGuess
COAL_COMPILER_DIAGNOSTIC_POP void updateGuess(const QueryResult &result) const
Updates the guess for the internal GJK algorithm in order to warm-start it when reusing this collisio...
Definition: coal/collision_data.h:290
coal::Timer
This class mimics the way "boost/timer/timer.hpp" operates while using the modern std::chrono library...
Definition: coal/timings.h:31
coal::getCollisionFunctionLookTable
CollisionFunctionMatrix & getCollisionFunctionLookTable()
Definition: src/collision.cpp:45
coal::CollisionObject::collisionGeometryPtr
const CollisionGeometry * collisionGeometryPtr() const
get raw pointer to collision geometry of the object instance
Definition: coal/collision_object.h:319
coal::OT_BVH
@ OT_BVH
Definition: coal/collision_object.h:54
coal::CollisionResult::contacts
std::vector< Contact > contacts
contact information
Definition: coal/collision_data.h:393
coal::CollisionObject::getTransform
const Transform3s & getTransform() const
get object's transform
Definition: coal/collision_object.h:290
gjk.tf1
tuple tf1
Definition: test/scripts/gjk.py:27
coal::CollisionRequest::security_margin
CoalScalar security_margin
Distance below which objects are considered in collision. See Collision.
Definition: coal/collision_data.h:328
coal::QueryResult::cached_gjk_guess
Vec3s cached_gjk_guess
stores the last GJK ray when relevant.
Definition: coal/collision_data.h:277
coal::NODE_TYPE
NODE_TYPE
traversal node type: bounding volume (AABB, OBB, RSS, kIOS, OBBRSS, KDOP16, KDOP18,...
Definition: coal/collision_object.h:64
coal
Main namespace.
Definition: coal/broadphase/broadphase_bruteforce.h:44
narrowphase.h
coal::QueryRequest::enable_timings
bool enable_timings
enable timings when performing collision/distance request
Definition: coal/collision_data.h:214
coal::CollisionResult::nearest_points
std::array< Vec3s, 2 > nearest_points
nearest points. A CollisionResult can have multiple contacts. The nearest points in CollisionResults ...
Definition: coal/collision_data.h:414
coal::GJKSolver
collision and distance solver based on the GJK and EPA algorithms. Originally, GJK and EPA were imple...
Definition: coal/narrowphase/narrowphase.h:57
coal::CollisionGeometry
The geometry for the object for collision or distance computation.
Definition: coal/collision_object.h:94
coal::CollisionGeometry::getObjectType
virtual OBJECT_TYPE getObjectType() const
get the type of the object
Definition: coal/collision_object.h:127
coal::QueryResult::timings
CPUTimes timings
timings for the given request
Definition: coal/collision_data.h:283
coal::Transform3s
Simple transform class used locally by InterpMotion.
Definition: coal/math/transform.h:55
res
res
coal::ComputeCollision::solver
GJKSolver solver
Definition: coal/collision.h:105
coal::CollisionResult::clear
void clear()
clear the results obtained
Definition: coal/collision_data.h:483
coal::GJKSolver::support_func_cached_guess
support_func_guess_t support_func_cached_guess
smart guess for the support function
Definition: coal/narrowphase/narrowphase.h:82
coal::GJKSolver::set
void set(const DistanceRequest &request)
setter from a DistanceRequest
Definition: coal/narrowphase/narrowphase.h:161
COAL_THROW_PRETTY
#define COAL_THROW_PRETTY(message, exception)
Definition: include/coal/fwd.hh:64
coal::CollisionFunctionMatrix::collision_matrix
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...
Definition: coal/collision_func_matrix.h:70
coal::ComputeCollision::swap_geoms
bool swap_geoms
Definition: coal/collision.h:108
coal::CollisionResult
collision result
Definition: coal/collision_data.h:390
coal::ComputeCollision::o2
const CollisionGeometry * o2
Definition: coal/collision.h:103
coal::CollisionRequest
request to the collision algorithm
Definition: coal/collision_data.h:311
coal::CollisionObject
the object for collision or distance computation, contains the geometry and the transform information
Definition: coal/collision_object.h:214
gjk.tf2
tuple tf2
Definition: test/scripts/gjk.py:36
coal::OBJECT_TYPE
OBJECT_TYPE
object type: BVH (mesh, points), basic geometry, octree
Definition: coal/collision_object.h:52
coal::OT_GEOM
@ OT_GEOM
Definition: coal/collision_object.h:55
collision_func_matrix.h
coal::ComputeCollision::ComputeCollision
ComputeCollision(const CollisionGeometry *o1, const CollisionGeometry *o2)
Default constructor from two Collision Geometries.
Definition: src/collision.cpp:131
coal::GJKSolver::cached_guess
Vec3s cached_guess
smart guess
Definition: coal/narrowphase/narrowphase.h:79
coal::get_node_type_name
const char * get_node_type_name(NODE_TYPE node_type)
Returns the name associated to a NODE_TYPE.
Definition: coal/collision_utility.h:32
coal::CollisionRequest::num_max_contacts
size_t num_max_contacts
The maximum number of contacts that can be returned.
Definition: coal/collision_data.h:313
coal::ComputeCollision::operator()
std::size_t operator()(const Transform3s &tf1, const Transform3s &tf2, const CollisionRequest &request, CollisionResult &result) const
Definition: src/collision.cpp:186
coal::Timer::elapsed
CPUTimes elapsed() const
Definition: coal/timings.h:45
coal::CollisionResult::normal
Vec3s normal
normal associated to nearest_points. Same as CollisionResult::nearest_points but for the normal.
Definition: coal/collision_data.h:405
collision_utility.h
coal::collide
COAL_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,...
Definition: src/collision.cpp:61
coal::OT_HFIELD
@ OT_HFIELD
Definition: coal/collision_object.h:57
coal::ComputeCollision::func
CollisionFunctionMatrix::CollisionFunc func
Definition: coal/collision.h:107


hpp-fcl
Author(s):
autogenerated on Sat Nov 23 2024 03:44:57