src/distance.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/distance.h"
39 #include "coal/collision_utility.h"
42 
43 #include <iostream>
44 
45 namespace coal {
46 
48  static DistanceFunctionMatrix table;
49  return table;
50 }
51 
53  const DistanceRequest& request, DistanceResult& result) {
54  return distance(o1->collisionGeometryPtr(), o1->getTransform(),
55  o2->collisionGeometryPtr(), o2->getTransform(), request,
56  result);
57 }
58 
60  const CollisionGeometry* o2, const Transform3s& tf2,
61  const DistanceRequest& request, DistanceResult& result) {
62  GJKSolver solver(request);
63 
65 
66  OBJECT_TYPE object_type1 = o1->getObjectType();
67  NODE_TYPE node_type1 = o1->getNodeType();
68  OBJECT_TYPE object_type2 = o2->getObjectType();
69  NODE_TYPE node_type2 = o2->getNodeType();
70 
71  CoalScalar res = (std::numeric_limits<CoalScalar>::max)();
72 
73  if (object_type1 == OT_GEOM &&
74  (object_type2 == OT_BVH || object_type2 == OT_HFIELD)) {
75  if (!looktable.distance_matrix[node_type2][node_type1]) {
76  COAL_THROW_PRETTY("Distance function between node type "
77  << std::string(get_node_type_name(node_type1))
78  << " and node type "
79  << std::string(get_node_type_name(node_type2))
80  << " is not yet supported.",
81  std::invalid_argument);
82  } else {
83  res = looktable.distance_matrix[node_type2][node_type1](
84  o2, tf2, o1, tf1, &solver, request, result);
85  std::swap(result.o1, result.o2);
86  result.nearest_points[0].swap(result.nearest_points[1]);
87  result.normal *= -1;
88  }
89  } else {
90  if (!looktable.distance_matrix[node_type1][node_type2]) {
91  COAL_THROW_PRETTY("Distance function between node type "
92  << std::string(get_node_type_name(node_type1))
93  << " and node type "
94  << std::string(get_node_type_name(node_type2))
95  << " is not yet supported.",
96  std::invalid_argument);
97  } else {
98  res = looktable.distance_matrix[node_type1][node_type2](
99  o1, tf1, o2, tf2, &solver, request, result);
100  }
101  }
102  // Cache narrow phase solver result. If the option in the request is selected,
103  // also store the solver result in the request for the next call.
104  result.cached_gjk_guess = solver.cached_guess;
106  request.updateGuess(result);
107  return res;
108 }
109 
111  const CollisionGeometry* o2)
112  : o1(o1), o2(o2) {
114 
115  OBJECT_TYPE object_type1 = o1->getObjectType();
116  NODE_TYPE node_type1 = o1->getNodeType();
117  OBJECT_TYPE object_type2 = o2->getObjectType();
118  NODE_TYPE node_type2 = o2->getNodeType();
119 
120  swap_geoms = object_type1 == OT_GEOM &&
121  (object_type2 == OT_BVH || object_type2 == OT_HFIELD);
122 
123  if ((swap_geoms && !looktable.distance_matrix[node_type2][node_type1]) ||
124  (!swap_geoms && !looktable.distance_matrix[node_type1][node_type2])) {
125  COAL_THROW_PRETTY("Distance function between node type "
126  << std::string(get_node_type_name(node_type1))
127  << " and node type "
128  << std::string(get_node_type_name(node_type2))
129  << " is not yet supported.",
130  std::invalid_argument);
131  }
132  if (swap_geoms)
133  func = looktable.distance_matrix[node_type2][node_type1];
134  else
135  func = looktable.distance_matrix[node_type1][node_type2];
136 }
137 
139  const DistanceRequest& request,
140  DistanceResult& result) const {
141  CoalScalar res;
142 
143  if (swap_geoms) {
144  res = func(o2, tf2, o1, tf1, &solver, request, result);
145  std::swap(result.o1, result.o2);
146  result.nearest_points[0].swap(result.nearest_points[1]);
147  result.normal *= -1;
148  } else {
149  res = func(o1, tf1, o2, tf2, &solver, request, result);
150  }
151  // Cache narrow phase solver result. If the option in the request is selected,
152  // also store the solver result in the request for the next call.
155  request.updateGuess(result);
156  return res;
157 }
158 
160  const Transform3s& tf2,
161  const DistanceRequest& request,
162  DistanceResult& result) const {
163  solver.set(request);
164 
165  CoalScalar res;
166  if (request.enable_timings) {
167  Timer timer;
168  res = run(tf1, tf2, request, result);
169  result.timings = timer.elapsed();
170  } else
171  res = run(tf1, tf2, request, result);
172  return res;
173 }
174 
175 } // namespace coal
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::CollisionGeometry::getNodeType
virtual NODE_TYPE getNodeType() const
get the node type
Definition: coal/collision_object.h:130
distance_func_matrix.h
coal::DistanceResult::o1
const CollisionGeometry * o1
collision object 1
Definition: coal/collision_data.h:1068
coal::ComputeDistance::ComputeDistance
ComputeDistance(const CollisionGeometry *o1, const CollisionGeometry *o2)
Definition: src/distance.cpp:110
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::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::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::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::DistanceResult::normal
Vec3s normal
normal.
Definition: coal/collision_data.h:1061
coal::QueryRequest::enable_timings
bool enable_timings
enable timings when performing collision/distance request
Definition: coal/collision_data.h:214
coal::ComputeDistance::func
DistanceFunctionMatrix::DistanceFunc func
Definition: coal/distance.h:102
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::distance
COAL_DLLAPI CoalScalar distance(const Matrix3s &R0, const Vec3s &T0, const kIOS &b1, const kIOS &b2, Vec3s *P=NULL, Vec3s *Q=NULL)
Approximate distance between two kIOS bounding volumes.
Definition: kIOS.cpp:180
coal::CollisionGeometry
The geometry for the object for collision or distance computation.
Definition: coal/collision_object.h:94
coal::DistanceResult::o2
const CollisionGeometry * o2
collision object 2
Definition: coal/collision_data.h:1071
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
coal::ComputeDistance::o2
const CollisionGeometry * o2
Definition: coal/distance.h:98
coal::ComputeDistance::operator()
CoalScalar operator()(const Transform3s &tf1, const Transform3s &tf2, const DistanceRequest &request, DistanceResult &result) const
Definition: src/distance.cpp:159
res
res
coal::DistanceRequest
request to the distance computation
Definition: coal/collision_data.h:985
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
distance.h
coal::DistanceResult
distance result
Definition: coal/collision_data.h:1051
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::ComputeDistance::o1
const CollisionGeometry * o1
Definition: coal/distance.h:90
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
coal::ComputeDistance::swap_geoms
bool swap_geoms
Definition: coal/distance.h:103
coal::DistanceFunctionMatrix::distance_matrix
DistanceFunc distance_matrix[NODE_COUNT][NODE_COUNT]
each item in the distance matrix is a function to handle distance between objects of type1 and type2
Definition: coal/distance_func_matrix.h:67
coal::ComputeDistance::run
virtual CoalScalar run(const Transform3s &tf1, const Transform3s &tf2, const DistanceRequest &request, DistanceResult &result) const
Definition: src/distance.cpp:138
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::getDistanceFunctionLookTable
DistanceFunctionMatrix & getDistanceFunctionLookTable()
Definition: src/distance.cpp:47
coal::Timer::elapsed
CPUTimes elapsed() const
Definition: coal/timings.h:45
coal::DistanceFunctionMatrix
distance matrix stores the functions for distance between different types of objects and provides a u...
Definition: coal/distance_func_matrix.h:49
coal::ComputeDistance::solver
GJKSolver solver
Definition: coal/distance.h:100
collision_utility.h
coal::OT_HFIELD
@ OT_HFIELD
Definition: coal/collision_object.h:57
coal::CoalScalar
double CoalScalar
Definition: coal/data_types.h:76
coal::DistanceResult::nearest_points
std::array< Vec3s, 2 > nearest_points
nearest points. See CollisionResult::nearest_points.
Definition: coal/collision_data.h:1065


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