moveit2
The MoveIt Motion Planning Framework for ROS 2.
collision_octomap_filter.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2012, Willow Garage, Inc.
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 Willow Garage 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 
35 /* Author: Adam Leeper */
36 
39 #include <octomap/math/Vector3.h>
40 #include <octomap/math/Utils.h>
41 #include <octomap/octomap.h>
42 #include <geometric_shapes/shapes.h>
43 #include <rclcpp/logger.hpp>
44 #include <rclcpp/logging.hpp>
45 #include <memory>
46 #include <moveit/utils/logger.hpp>
47 
48 namespace
49 {
50 rclcpp::Logger getLogger()
51 {
52  return moveit::getLogger("collision_detection_octomap_filter");
53 }
54 } // namespace
55 
56 // forward declarations
57 bool getMetaballSurfaceProperties(const octomap::point3d_list& cloud, double spacing, double iso_value,
58  double r_multiple, const octomath::Vector3& contact_point, octomath::Vector3& normal,
59  double& depth, bool estimate_depth);
60 
61 bool findSurface(const octomap::point3d_list& cloud, double spacing, double iso_value, double r_multiple,
62  const octomath::Vector3& seed, octomath::Vector3& surface_point, octomath::Vector3& normal);
63 
64 bool sampleCloud(const octomap::point3d_list& cloud, double spacing, double r_multiple,
65  const octomath::Vector3& position, double& intensity, octomath::Vector3& gradient);
66 
67 int collision_detection::refineContactNormals(const World::ObjectConstPtr& object, CollisionResult& res,
68  double cell_bbx_search_distance, double allowed_angle_divergence,
69  bool estimate_depth, double iso_value, double metaball_radius_multiple)
70 {
71  if (!object)
72  {
73  RCLCPP_ERROR(getLogger(), "No valid Object passed in, cannot refine Normals!");
74  return 0;
75  }
76  if (res.contact_count < 1)
77  {
78  RCLCPP_WARN(getLogger(), "There do not appear to be any contacts, so there is nothing to refine!");
79  return 0;
80  }
81 
82  int modified = 0;
83 
84  // iterate through contacts
85  for (auto& contact : res.contacts)
86  {
87  const std::string contact1 = contact.first.first;
88  const std::string contact2 = contact.first.second;
89  std::string octomap_name = "";
90  std::vector<collision_detection::Contact>& contact_vector = contact.second;
91 
92  if (contact1.find("octomap") != std::string::npos)
93  {
94  octomap_name = contact1;
95  }
96  else if (contact2.find("octomap") != std::string::npos)
97  {
98  octomap_name = contact2;
99  }
100  else
101  {
102  continue;
103  }
104 
105  if (!object->shapes_.empty())
106  {
107  const shapes::ShapeConstPtr& shape = object->shapes_[0];
108  const std::shared_ptr<const shapes::OcTree> shape_octree = std::dynamic_pointer_cast<const shapes::OcTree>(shape);
109  if (shape_octree)
110  {
111  double cell_size = 0;
112  std::shared_ptr<const octomap::OcTree> octree = shape_octree->octree;
113  cell_size = octree->getResolution();
114  for (auto& contact_info : contact_vector)
115  {
116  const Eigen::Vector3d& point = contact_info.pos;
117  const Eigen::Vector3d& normal = contact_info.normal;
118 
119  const octomath::Vector3 contact_point(point[0], point[1], point[2]);
120  const octomath::Vector3 contact_normal(normal[0], normal[1], normal[2]);
121  const octomath::Vector3 diagonal = octomath::Vector3(1, 1, 1);
122  const octomath::Vector3 bbx_min = contact_point - diagonal * cell_size * cell_bbx_search_distance;
123  const octomath::Vector3 bbx_max = contact_point + diagonal * cell_size * cell_bbx_search_distance;
124  octomap::point3d_list node_centers;
125  octomap::OcTreeBaseImpl<octomap::OcTreeNode, octomap::AbstractOccupancyOcTree>::leaf_bbx_iterator it =
126  octree->begin_leafs_bbx(bbx_min, bbx_max);
127  octomap::OcTreeBaseImpl<octomap::OcTreeNode, octomap::AbstractOccupancyOcTree>::leaf_bbx_iterator leafs_end =
128  octree->end_leafs_bbx();
129  int count = 0;
130  for (; it != leafs_end; ++it)
131  {
132  const octomap::point3d pt = it.getCoordinate();
133  // double prob = it->getOccupancy();
134  if (octree->isNodeOccupied(*it)) // magic number!
135  {
136  count++;
137  node_centers.push_back(pt);
138  // RCLCPP_INFO(getLogger(), "Adding point %d with prob %.3f at [%.3f, %.3f, %.3f]",
139  // count, prob, pt.x(), pt.y(), pt.z());
140  }
141  }
142  // RCLCPP_INFO(getLogger(), "Contact point at [%.3f, %.3f, %.3f], cell size %.3f, occupied cells
143  // %d",
144  // contact_point.x(), contact_point.y(), contact_point.z(), cell_size, count);
145 
146  // octree->getOccupiedLeafsBBX(node_centers, bbx_min, bbx_max);
147  // RCLCPP_ERROR(getLogger(), "bad stuff in collision_octomap_filter.cpp; need to port octomap
148  // call for groovy");
149 
150  octomath::Vector3 n;
151  double depth;
152  if (getMetaballSurfaceProperties(node_centers, cell_size, iso_value, metaball_radius_multiple, contact_point,
153  n, depth, estimate_depth))
154  {
155  // only modify normal if the refinement predicts a "very different" result.
156  const double divergence = contact_normal.angleTo(n);
157  if (divergence > allowed_angle_divergence)
158  {
159  modified++;
160  // RCLCPP_INFO(getLogger(), "Normals differ by %.3f, changing: [%.3f, %.3f, %.3f] -> [%.3f,
161  // %.3f, %.3f]",
162  // divergence, contact_normal.x(), contact_normal.y(), contact_normal.z(),
163  // n.x(), n.y(), n.z());
164  contact_info.normal = Eigen::Vector3d(n.x(), n.y(), n.z());
165  }
166 
167  if (estimate_depth)
168  contact_info.depth = depth;
169  }
170  }
171  }
172  }
173  }
174  return modified;
175 }
176 
177 bool getMetaballSurfaceProperties(const octomap::point3d_list& cloud, double spacing, double iso_value,
178  double r_multiple, const octomath::Vector3& contact_point, octomath::Vector3& normal,
179  double& depth, bool estimate_depth)
180 {
181  if (estimate_depth)
182  {
183  octomath::Vector3 surface_point;
184  if (findSurface(cloud, spacing, iso_value, r_multiple, contact_point, surface_point, normal))
185  {
186  depth = normal.dot(surface_point - contact_point); // do we prefer this, or magnitude of surface - contact?
187  return true;
188  }
189  else
190  {
191  return false;
192  }
193  }
194  else // just get normals, no depth
195  {
196  octomath::Vector3 gradient;
197  double intensity = 0;
198  if (sampleCloud(cloud, spacing, r_multiple, contact_point, intensity, gradient))
199  {
200  normal = gradient.normalized();
201  return true;
202  }
203  else
204  {
205  return false;
206  }
207  }
208 }
209 
210 // --------------------------------------------------------------------------
211 // This algorithm is from Salisbury & Tarr's 1997 paper. It will find the
212 // closest point on the surface starting from a seed point that is close by
213 // following the direction of the field gradient.
214 bool findSurface(const octomap::point3d_list& cloud, double spacing, double iso_value, double r_multiple,
215  const octomath::Vector3& seed, octomath::Vector3& surface_point, octomath::Vector3& normal)
216 {
217  octomath::Vector3 p = seed, dp, gs;
218  const int iterations = 10;
219  const double epsilon = 1e-10;
220  double intensity = 0;
221  for (int i = 0; i < iterations; ++i)
222  {
223  if (!sampleCloud(cloud, spacing, r_multiple, p, intensity, gs))
224  return false;
225  const double s = iso_value - intensity;
226  dp = (gs * -s) * (1.0 / std::max(gs.dot(gs), epsilon));
227  p = p + dp;
228  if (dp.dot(dp) < epsilon)
229  {
230  surface_point = p;
231  normal = gs.normalized();
232  return true;
233  }
234  }
235  return false;
236  // return p;
237 }
238 
239 bool sampleCloud(const octomap::point3d_list& cloud, double spacing, double r_multiple,
240  const octomath::Vector3& position, double& intensity, octomath::Vector3& gradient)
241 {
242  intensity = 0.f;
243  gradient = octomath::Vector3(0, 0, 0);
244 
245  const double r = r_multiple * spacing; // TODO magic number!
246  // double T = 0.5; // TODO magic number!
247 
248  const int nn = cloud.size();
249  if (nn == 0)
250  {
251  return false;
252  }
253 
254  // variables for Wyvill
255  double a = 0, b = 0, c = 0, r2 = 0, r4 = 0, r6 = 0, a1 = 0, b1 = 0, c1 = 0, a2 = 0, b2 = 0, c2 = 0;
256  const bool wyvill = true;
257 
258  for (const octomath::Vector3& v : cloud)
259  {
260  if (wyvill)
261  {
262  r2 = r * r;
263  r4 = r2 * r2;
264  r6 = r4 * r2;
265  a = -4.0 / 9.0;
266  b = 17.0 / 9.0;
267  c = -22.0 / 9.0;
268  a1 = a / r6;
269  b1 = b / r4;
270  c1 = c / r2;
271  a2 = 6 * a1;
272  b2 = 4 * b1;
273  c2 = 2 * c1;
274  }
275  else
276  {
277  RCLCPP_ERROR(getLogger(), "This should not be called!");
278  }
279 
280  double f_val = 0;
281  octomath::Vector3 f_grad(0, 0, 0);
282 
283  octomath::Vector3 pos = position - v;
284  const double r = pos.norm();
285  pos = pos * (1.0 / r);
286  if (r > r) // must skip points outside valid bounds.
287  {
288  continue;
289  }
290  const double r2 = r * r;
291  const double r3 = r * r2;
292  const double r4 = r2 * r2;
293  const double r5 = r3 * r2;
294  const double r6 = r3 * r3;
295 
296  if (wyvill)
297  {
298  f_val = (a1 * r6 + b1 * r4 + c1 * r2 + 1);
299  f_grad = pos * (a2 * r5 + b2 * r3 + c2 * r);
300  }
301  else
302  {
303  RCLCPP_ERROR(getLogger(), "This should not be called!");
304  const double r_scaled = r / r;
305  // TODO still need to address the scaling...
306  f_val = pow((1 - r_scaled), 4) * (4 * r_scaled + 1);
307  f_grad = pos * (-4.0 / r * pow(1.0 - r_scaled, 3) * (4.0 * r_scaled + 1.0) + 4.0 / r * pow(1 - r_scaled, 4));
308  }
309 
310  // TODO: The whole library should be overhauled to follow the "gradient points out"
311  // convention of implicit functions.
312  intensity += f_val;
313  gradient += f_grad;
314  }
315  // implicit surface gradient convention points out, so we flip it.
316  gradient *= -1.0;
317  return true; // it worked
318 }
bool getMetaballSurfaceProperties(const octomap::point3d_list &cloud, double spacing, double iso_value, double r_multiple, const octomath::Vector3 &contact_point, octomath::Vector3 &normal, double &depth, bool estimate_depth)
bool findSurface(const octomap::point3d_list &cloud, double spacing, double iso_value, double r_multiple, const octomath::Vector3 &seed, octomath::Vector3 &surface_point, octomath::Vector3 &normal)
bool sampleCloud(const octomap::point3d_list &cloud, double spacing, double r_multiple, const octomath::Vector3 &position, double &intensity, octomath::Vector3 &gradient)
int refineContactNormals(const World::ObjectConstPtr &object, CollisionResult &res, double cell_bbx_search_distance=1.0, double allowed_angle_divergence=0.0, bool estimate_depth=false, double iso_value=0.5, double metaball_radius_multiple=1.5)
Re-proceses contact normals for an octomap by estimating a metaball iso-surface using the centers of ...
Vec3fX< details::Vec3Data< double > > Vector3d
Definition: fcl_compat.h:89
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.
Definition: logger.cpp:79
Representation of a collision checking result.
std::size_t contact_count
Number of contacts returned.