moveit2
The MoveIt Motion Planning Framework for ROS 2.
test_distance_field.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2009, 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: Mrinal Kalakrishnan, Ken Anderson */
36 
37 #include <gtest/gtest.h>
38 
42 #include <geometric_shapes/body_operations.h>
43 #include <tf2_eigen/tf2_eigen.hpp>
44 #include <octomap/octomap.h>
45 #include <memory>
46 
47 using namespace distance_field;
48 
49 static const double WIDTH = 1.0;
50 static const double HEIGHT = 1.0;
51 static const double DEPTH = 1.0;
52 static const double RESOLUTION = 0.1;
53 static const double ORIGIN_X = 0.0;
54 static const double ORIGIN_Y = 0.0;
55 static const double ORIGIN_Z = 0.0;
56 static const double MAX_DIST = 0.3;
57 
58 static const Eigen::Vector3d POINT1(0.1, 0.0, 0.0);
59 static const Eigen::Vector3d POINT2(0.0, 0.1, 0.2);
60 static const Eigen::Vector3d POINT3(0.4, 0.0, 0.0);
61 
62 int dist_sq(int x, int y, int z)
63 {
64  return x * x + y * y + z * z;
65 }
66 
67 void print(PropagationDistanceField& pdf, int numX, int numY, int numZ)
68 {
69  for (int z = 0; z < numZ; ++z)
70  {
71  for (int y = 0; y < numY; ++y)
72  {
73  for (int x = 0; x < numX; ++x)
74  {
75  std::cout << pdf.getCell(x, y, z).distance_square_ << " ";
76  }
77  std::cout << '\n';
78  }
79  std::cout << '\n';
80  }
81  for (int z = 0; z < numZ; ++z)
82  {
83  for (int y = 0; y < numY; ++y)
84  {
85  for (int x = 0; x < numX; ++x)
86  {
87  if (pdf.getCell(x, y, z).distance_square_ == 0)
88  {
89  // RCLCPP_INFO("distance_field", "Obstacle cell %d %d %d", x, y, z);
90  }
91  }
92  }
93  }
94 }
95 
96 void printNeg(PropagationDistanceField& pdf, int numX, int numY, int numZ)
97 {
98  for (int z = 0; z < numZ; ++z)
99  {
100  for (int y = 0; y < numY; ++y)
101  {
102  for (int x = 0; x < numX; ++x)
103  {
104  std::cout << pdf.getCell(x, y, z).negative_distance_square_ << " ";
105  }
106  std::cout << '\n';
107  }
108  std::cout << '\n';
109  }
110 }
111 
112 void printPointCoords(const Eigen::Vector3i& p)
113 {
114  if (p.x() < 0)
115  std::cout << '-';
116  else
117  std::cout << p.x();
118 
119  if (p.y() < 0)
120  std::cout << '-';
121  else
122  std::cout << p.y();
123 
124  if (p.z() < 0)
125  std::cout << '-';
126  else
127  std::cout << p.z();
128 
129  std::cout << " ";
130 }
131 
132 void printBoth(PropagationDistanceField& pdf, int numX, int numY, int numZ)
133 {
134  std::cout << "Positive distance square ... negative distance square\n";
135  for (int z = 0; z < numZ; ++z)
136  {
137  std::cout << "Z=" << z << '\n';
138  for (int y = 0; y < numY; ++y)
139  {
140  for (int x = 0; x < numX; ++x)
141  {
142  std::cout << pdf.getCell(x, y, z).distance_square_ << " ";
143  }
144  std::cout << " ";
145  for (int x = 0; x < numX; ++x)
146  {
147  std::cout << pdf.getCell(x, y, z).negative_distance_square_ << " ";
148  }
149  std::cout << " ";
150  for (int x = 0; x < numX; ++x)
151  {
153  }
154  std::cout << " ";
155  for (int x = 0; x < numX; ++x)
156  {
158  }
159  std::cout << '\n';
160  }
161  std::cout << '\n';
162  }
163 }
164 
166 {
167  if (df1.getXNumCells() != df2.getXNumCells())
168  return false;
169  if (df1.getYNumCells() != df2.getYNumCells())
170  return false;
171  if (df1.getZNumCells() != df2.getZNumCells())
172  return false;
173  for (int z = 0; z < df1.getZNumCells(); ++z)
174  {
175  for (int x = 0; x < df1.getXNumCells(); ++x)
176  {
177  for (int y = 0; y < df1.getYNumCells(); ++y)
178  {
179  if (df1.getCell(x, y, z).distance_square_ != df2.getCell(x, y, z).distance_square_)
180  {
181  printf("Cell %d %d %d distances not equal %d %d\n", x, y, z, df1.getCell(x, y, z).distance_square_,
182  df2.getCell(x, y, z).distance_square_);
183  return false;
184  }
186  {
187  printf("Cell %d %d %d neg distances not equal %d %d\n", x, y, z,
189  return false;
190  }
191  }
192  }
193  }
194  return true;
195 }
196 
197 bool checkOctomapVersusDistanceField(const PropagationDistanceField& df, const octomap::OcTree& octree)
198 {
199  // just one way for now
200  for (int z = 0; z < df.getZNumCells(); ++z)
201  {
202  for (int x = 0; x < df.getXNumCells(); ++x)
203  {
204  for (int y = 0; y < df.getYNumCells(); ++y)
205  {
206  if (df.getCell(x, y, z).distance_square_ == 0)
207  {
208  // making sure that octomap also shows it as occupied
209  double qx, qy, qz;
210  df.gridToWorld(x, y, z, qx, qy, qz);
211  octomap::point3d query(qx, qy, qz);
212  octomap::OcTreeNode* result = octree.search(query);
213  if (!result)
214  {
215  for (float boundary_x = query.x() - df.getResolution();
216  boundary_x <= query.x() + df.getResolution() && !result; boundary_x += df.getResolution())
217  {
218  for (float boundary_y = query.y() - df.getResolution();
219  boundary_y <= query.y() + df.getResolution() && !result; boundary_y += df.getResolution())
220  {
221  for (float boundary_z = query.z() - df.getResolution(); boundary_z <= query.z() + df.getResolution();
222  boundary_z += df.getResolution())
223  {
224  octomap::point3d query_boundary(boundary_x, boundary_y, boundary_z);
225  result = octree.search(query_boundary);
226  if (result)
227  {
228  break;
229  }
230  }
231  }
232  }
233  if (!result)
234  {
235  std::cout << "No point at potential boundary query " << query.x() << " " << query.y() << " " << query.z()
236  << '\n';
237  return false;
238  }
239  }
240  if (!octree.isNodeOccupied(result))
241  {
242  std::cout << "Disagreement at " << qx << " " << qy << " " << qz << '\n';
243  return false;
244  }
245  }
246  }
247  }
248  }
249  return true;
250 }
251 
253 {
254  unsigned int count = 0;
255  for (int z = 0; z < df.getZNumCells(); ++z)
256  {
257  for (int x = 0; x < df.getXNumCells(); ++x)
258  {
259  for (int y = 0; y < df.getYNumCells(); ++y)
260  {
261  if (df.getCell(x, y, z).distance_square_ == 0)
262  {
263  count++;
264  }
265  }
266  }
267  }
268  return count;
269 }
270 
271 unsigned int countLeafNodes(const octomap::OcTree& octree)
272 {
273  unsigned int count = 0;
274  for (octomap::OcTree::leaf_iterator it = octree.begin_leafs(), end = octree.end_leafs(); it != end; ++it)
275  {
276  if (octree.isNodeOccupied(*it))
277  {
278  std::cout << "Leaf node " << it.getX() << " " << it.getY() << " " << it.getZ() << '\n';
279  count++;
280  }
281  }
282  return count;
283 }
284 
285 // points should contain all occupied points
286 void check_distance_field(const PropagationDistanceField& df, const EigenSTL::vector_Vector3d& points, int numX,
287  int numY, int numZ, bool do_negs)
288 {
289  EigenSTL::vector_Vector3i points_ind(points.size());
290  for (unsigned int i = 0; i < points.size(); ++i)
291  {
292  Eigen::Vector3i loc;
293  df.worldToGrid(points[i].x(), points[i].y(), points[i].z(), loc.x(), loc.y(), loc.z());
294  points_ind[i] = loc;
295  }
296 
297  for (int x = 0; x < numX; ++x)
298  {
299  for (int y = 0; y < numY; ++y)
300  {
301  for (int z = 0; z < numZ; ++z)
302  {
303  double dsq = df.getCell(x, y, z).distance_square_;
304  double ndsq = df.getCell(x, y, z).negative_distance_square_;
305  if (dsq == 0)
306  {
307  bool found = false;
308  for (Eigen::Vector3i& point : points_ind)
309  {
310  if (point.x() == x && point.y() == y && point.z() == z)
311  {
312  found = true;
313  break;
314  }
315  }
316  if (do_negs)
317  {
318  ASSERT_GT(ndsq, 0) << "Obstacle point " << x << " " << y << " " << z << " has zero negative value";
319  }
320  ASSERT_TRUE(found) << "Obstacle point " << x << " " << y << " " << z << " not found";
321  }
322  }
323  }
324  }
325 }
326 
327 TEST(TestPropagationDistanceField, TestAddRemovePoints)
328 {
329  PropagationDistanceField df(WIDTH, HEIGHT, DEPTH, RESOLUTION, ORIGIN_X, ORIGIN_Y, ORIGIN_Z, MAX_DIST);
330 
331  // Check size
332  int num_x = df.getXNumCells();
333  int num_y = df.getYNumCells();
334  int num_z = df.getZNumCells();
335 
336  EXPECT_EQ(num_x, static_cast<int>(WIDTH / RESOLUTION + 0.5));
337  EXPECT_EQ(num_y, static_cast<int>(HEIGHT / RESOLUTION + 0.5));
338  EXPECT_EQ(num_z, static_cast<int>(DEPTH / RESOLUTION + 0.5));
339 
340  // getting a bad point
341  double tgx, tgy, tgz;
342  bool in_bounds;
343  EXPECT_NEAR(df.getDistance(1000.0, 1000.0, 1000.0), MAX_DIST, .0001);
344  EXPECT_NEAR(df.getDistanceGradient(1000.0, 1000.0, 1000.0, tgx, tgy, tgz, in_bounds), MAX_DIST, .0001);
345  EXPECT_FALSE(in_bounds);
346 
347  // Add points to the grid
348  EigenSTL::vector_Vector3d points;
349  points.push_back(POINT1);
350  points.push_back(POINT2);
351  // RCLCPP_INFO("distance_field", "Adding %zu points", points.size());
352  df.addPointsToField(points);
353  // print(df, numX, numY, numZ);
354 
355  // Update - iterative
356  points.clear();
357  points.push_back(POINT2);
358  points.push_back(POINT3);
359  EigenSTL::vector_Vector3d old_points;
360  old_points.push_back(POINT1);
361  df.updatePointsInField(old_points, points);
362  // std::cout << "One removal, one addition" << '\n';
363  // print(df, numX, numY, numZ);
364  // printNeg(df, numX, numY, numZ);
365  check_distance_field(df, points, num_x, num_y, num_z, false);
366 
367  // Remove
368  points.clear();
369  points.push_back(POINT2);
370  df.removePointsFromField(points);
371  points.clear();
372  points.push_back(POINT3);
373  check_distance_field(df, points, num_x, num_y, num_z, false);
374 
375  // now testing gradient calls
376  df.reset();
377  points.clear();
378  points.push_back(POINT1);
379  df.addPointsToField(points);
380  bool first = true;
381  for (int z = 1; z < df.getZNumCells() - 1; ++z)
382  {
383  for (int x = 1; x < df.getXNumCells() - 1; ++x)
384  {
385  for (int y = 1; y < df.getYNumCells() - 1; ++y)
386  {
387  double dist = df.getDistance(x, y, z);
388  double wx, wy, wz;
389  df.gridToWorld(x, y, z, wx, wy, wz);
390  Eigen::Vector3d grad(0.0, 0.0, 0.0);
391  bool grad_in_bounds;
392  double dist_grad = df.getDistanceGradient(wx, wy, wz, grad.x(), grad.y(), grad.z(), grad_in_bounds);
393  ASSERT_TRUE(grad_in_bounds) << x << " " << y << " " << z;
394  ASSERT_NEAR(dist, dist_grad, .0001);
395  if (dist > 0 && dist < MAX_DIST)
396  {
397  double xscale = grad.x() / grad.norm();
398  double yscale = grad.y() / grad.norm();
399  double zscale = grad.z() / grad.norm();
400 
401  double comp_x = wx - xscale * dist;
402  double comp_y = wy - yscale * dist;
403  double comp_z = wz - zscale * dist;
404  if (first)
405  {
406  first = false;
407  std::cout << "Dist " << dist << '\n';
408  std::cout << "Cell " << x << " " << y << " " << z << " " << wx << " " << wy << " " << wz << '\n';
409  std::cout << "Scale " << xscale << " " << yscale << " " << zscale << '\n';
410  std::cout << "Grad " << grad.x() << " " << grad.y() << " " << grad.z() << " comp " << comp_x << " "
411  << comp_y << " " << comp_z << '\n';
412  }
413  ASSERT_NEAR(comp_x, POINT1.x(), RESOLUTION)
414  << dist << x << " " << y << " " << z << " " << grad.x() << " " << grad.y() << " " << grad.z() << " "
415  << xscale << " " << yscale << " " << zscale << '\n';
416  ASSERT_NEAR(comp_y, POINT1.y(), RESOLUTION)
417  << x << " " << y << " " << z << " " << grad.x() << " " << grad.y() << " " << grad.z() << " " << xscale
418  << " " << yscale << " " << zscale << '\n';
419  ASSERT_NEAR(comp_z, POINT1.z(), RESOLUTION)
420  << x << " " << y << " " << z << " " << grad.x() << " " << grad.y() << " " << grad.z() << " " << xscale
421  << " " << yscale << " " << zscale << '\n';
422  }
423  }
424  }
425  }
426  ASSERT_FALSE(first);
427 }
428 
429 TEST(TestSignedPropagationDistanceField, TestSignedAddRemovePoints)
430 {
431  PropagationDistanceField df(WIDTH, HEIGHT, DEPTH, RESOLUTION, ORIGIN_X, ORIGIN_Y, ORIGIN_Z, MAX_DIST, true);
432 
433  // Check size
434  int num_x = df.getXNumCells();
435  int num_y = df.getYNumCells();
436  int num_z = df.getZNumCells();
437 
438  EXPECT_EQ(num_x, static_cast<int>(WIDTH / RESOLUTION + 0.5));
439  EXPECT_EQ(num_y, static_cast<int>(HEIGHT / RESOLUTION + 0.5));
440  EXPECT_EQ(num_z, static_cast<int>(DEPTH / RESOLUTION + 0.5));
441 
442  // Error checking
443  // print(df, numX, numY, numZ);
444 
445  // TODO - check initial values
446  // EXPECT_EQ( df.getCell(0,0,0).distance_square_, max_dist_sq_in_voxels );
447 
448  // Add points to the grid
449  double lwx, lwy, lwz;
450  double hwx, hwy, hwz;
451  df.gridToWorld(1, 1, 1, lwx, lwy, lwz);
452  df.gridToWorld(8, 8, 8, hwx, hwy, hwz);
453 
454  EigenSTL::vector_Vector3d points;
455  for (double x = lwx; x <= hwx; x += .1)
456  {
457  for (double y = lwy; y <= hwy; y += .1)
458  {
459  for (double z = lwz; z <= hwz; z += .1)
460  {
461  points.push_back(Eigen::Vector3d(x, y, z));
462  }
463  }
464  }
465 
466  df.reset();
467  // RCLCPP_INFO("distance_field", "Adding %zu points", points.size());
468  df.addPointsToField(points);
469  // print(df, numX, numY, numZ);
470  // printNeg(df, numX, numY, numZ);
471 
472  double cx, cy, cz;
473  df.gridToWorld(5, 5, 5, cx, cy, cz);
474 
475  Eigen::Vector3d center_point(cx, cy, cz);
476 
477  EigenSTL::vector_Vector3d rem_points;
478  rem_points.push_back(center_point);
479  df.removePointsFromField(rem_points);
480  // std::cout << "Pos "<< '\n';
481  // print(df, numX, numY, numZ);
482  // std::cout << "Neg "<< '\n';
483  // printNeg(df, numX, numY, numZ);
484 
485  // testing equality with initial add of points without the center point
486  PropagationDistanceField test_df(WIDTH, HEIGHT, DEPTH, RESOLUTION, ORIGIN_X, ORIGIN_Y, ORIGIN_Z, MAX_DIST, true);
487  EigenSTL::vector_Vector3d test_points;
488  for (const Eigen::Vector3d& point : points)
489  {
490  if (point.x() != center_point.x() || point.y() != center_point.y() || point.z() != center_point.z())
491  {
492  test_points.push_back(point);
493  }
494  }
495  test_df.addPointsToField(test_points);
496  ASSERT_TRUE(areDistanceFieldsDistancesEqual(df, test_df));
497 
498  PropagationDistanceField gradient_df(WIDTH, HEIGHT, DEPTH, RESOLUTION, ORIGIN_X, ORIGIN_Y, ORIGIN_Z, MAX_DIST, true);
499 
500  shapes::Sphere sphere(.25);
501 
502  geometry_msgs::msg::Pose p;
503  p.orientation.w = 1.0;
504  p.position.x = .5;
505  p.position.y = .5;
506  p.position.z = .5;
507 
508  Eigen::Isometry3d p_eigen;
509  tf2::fromMsg(p, p_eigen);
510 
511  gradient_df.addShapeToField(&sphere, p_eigen);
512  // printBoth(gradient_df, numX, numY, numZ);
513  EXPECT_GT(gradient_df.getCell(5, 5, 5).negative_distance_square_, 1);
514  // all negative cells should have gradients that point towards cells with distance 1
515  for (int z = 1; z < df.getZNumCells() - 1; ++z)
516  {
517  for (int x = 1; x < df.getXNumCells() - 1; ++x)
518  {
519  for (int y = 1; y < df.getYNumCells() - 1; ++y)
520  {
521  double dist = gradient_df.getDistance(x, y, z);
522  double ncell_dist;
523  Eigen::Vector3i ncell_pos;
524  const PropDistanceFieldVoxel* ncell = gradient_df.getNearestCell(x, y, z, ncell_dist, ncell_pos);
525 
526  EXPECT_EQ(ncell_dist, dist);
527 
528  if (ncell == nullptr)
529  {
530  if (ncell_dist > 0)
531  {
532  EXPECT_GE(ncell_dist, gradient_df.getUninitializedDistance())
533  << "dist=" << dist << " xyz=" << x << " " << y << " " << z << " ncell=" << ncell_pos.x() << " "
534  << ncell_pos.y() << " " << ncell_pos.z() << '\n';
535  }
536  else if (ncell_dist < 0)
537  {
538  EXPECT_LE(ncell_dist, -gradient_df.getUninitializedDistance())
539  << "dist=" << dist << " xyz=" << x << " " << y << " " << z << " ncell=" << ncell_pos.x() << " "
540  << ncell_pos.y() << " " << ncell_pos.z() << '\n';
541  }
542  }
543 
544  if (gradient_df.getCell(x, y, z).negative_distance_square_ > 0)
545  {
546  ASSERT_LT(dist, 0) << "Pos " << gradient_df.getCell(x, y, z).distance_square_ << " "
547  << gradient_df.getCell(x, y, z).negative_distance_square_;
548  double wx, wy, wz;
549  df.gridToWorld(x, y, z, wx, wy, wz);
550  Eigen::Vector3d grad(0.0, 0.0, 0.0);
551  bool grad_in_bounds;
552  double dist_grad = gradient_df.getDistanceGradient(wx, wy, wz, grad.x(), grad.y(), grad.z(), grad_in_bounds);
553  ASSERT_TRUE(grad_in_bounds) << x << " " << y << " " << z;
554  ASSERT_NEAR(dist, dist_grad, .0001);
555 
556  if (!ncell)
557  continue;
558 
559  EXPECT_GE(gradient_df.getCell(ncell_pos.x(), ncell_pos.y(), ncell_pos.z()).distance_square_, 1)
560  << "dist=" << dist << " xyz=" << x << " " << y << " " << z << " grad=" << grad.x() << " " << grad.y()
561  << " " << grad.z() << " ncell=" << ncell_pos.x() << " " << ncell_pos.y() << " " << ncell_pos.z() << '\n';
562 
563  double grad_size_sq = grad.squaredNorm();
564  if (grad_size_sq < std::numeric_limits<double>::epsilon())
565  continue;
566 
567  double oo_grad_size = 1.0 / sqrt(grad_size_sq);
568  double xscale = grad.x() * oo_grad_size;
569  double yscale = grad.y() * oo_grad_size;
570  double zscale = grad.z() * oo_grad_size;
571 
572  double comp_x = wx - xscale * dist;
573  double comp_y = wy - yscale * dist;
574  double comp_z = wz - zscale * dist;
575 
576  int cell_x, cell_y, cell_z;
577  bool cell_in_bounds = gradient_df.worldToGrid(comp_x, comp_y, comp_z, cell_x, cell_y, cell_z);
578 
579  ASSERT_EQ(cell_in_bounds, true);
580  const PropDistanceFieldVoxel* cell = &gradient_df.getCell(cell_x, cell_y, cell_z);
581 
582 #if 0
583  EXPECT_EQ(ncell_pos.x(), cell_x);
584  EXPECT_EQ(ncell_pos.y(), cell_y);
585  EXPECT_EQ(ncell_pos.z(), cell_z);
586  EXPECT_EQ(ncell, cell);
587 #endif
588  EXPECT_GE(cell->distance_square_, 1)
589  << dist << " " << x << " " << y << " " << z << " " << grad.x() << " " << grad.y() << " " << grad.z()
590  << " " << xscale << " " << yscale << " " << zscale << " cell " << comp_x << " " << comp_y << " " << comp_z
591  << '\n';
592  }
593  }
594  }
595  }
596 }
597 
598 TEST(TestSignedPropagationDistanceField, TestShape)
599 {
600  PropagationDistanceField df(WIDTH, HEIGHT, DEPTH, RESOLUTION, ORIGIN_X, ORIGIN_Y, ORIGIN_Z, MAX_DIST, true);
601 
602  int num_x = df.getXNumCells();
603  int num_y = df.getYNumCells();
604  int num_z = df.getZNumCells();
605 
606  shapes::Sphere sphere(.25);
607 
608  Eigen::Isometry3d p = Eigen::Translation3d(0.5, 0.5, 0.5) * Eigen::Quaterniond(0.0, 0.0, 0.0, 1.0);
609  Eigen::Isometry3d np = Eigen::Translation3d(0.7, 0.7, 0.7) * Eigen::Quaterniond(0.0, 0.0, 0.0, 1.0);
610 
611  df.addShapeToField(&sphere, p);
612 
613  bodies::Body* body = bodies::createBodyFromShape(&sphere);
614  body->setPose(p);
615  EigenSTL::vector_Vector3d point_vec;
616  findInternalPointsConvex(*body, RESOLUTION, point_vec);
617  delete body;
618  check_distance_field(df, point_vec, num_x, num_y, num_z, true);
619 
620  // std::cout << "Shape pos "<< '\n';
621  // print(df, numX, numY, numZ);
622  // std::cout << "Shape neg "<< '\n';
623  // printNeg(df, numX, numY, numZ);
624 
625  df.addShapeToField(&sphere, np);
626 
627  body = bodies::createBodyFromShape(&sphere);
628  body->setPose(np);
629 
630  EigenSTL::vector_Vector3d point_vec_2;
631  findInternalPointsConvex(*body, RESOLUTION, point_vec_2);
632  delete body;
633  EigenSTL::vector_Vector3d point_vec_union = point_vec_2;
634  point_vec_union.insert(point_vec_union.end(), point_vec.begin(), point_vec.end());
635  check_distance_field(df, point_vec_union, num_x, num_y, num_z, true);
636 
637  // should get rid of old pose
638  df.moveShapeInField(&sphere, p, np);
639 
640  check_distance_field(df, point_vec_2, num_x, num_y, num_z, true);
641 
642  // should be equivalent to just adding second shape
643  PropagationDistanceField test_df(WIDTH, HEIGHT, DEPTH, RESOLUTION, ORIGIN_X, ORIGIN_Y, ORIGIN_Z, MAX_DIST, true);
644  test_df.addShapeToField(&sphere, np);
645  ASSERT_TRUE(areDistanceFieldsDistancesEqual(df, test_df));
646 }
647 
648 static const double PERF_WIDTH = 3.0;
649 static const double PERF_HEIGHT = 3.0;
650 static const double PERF_DEPTH = 4.0;
651 static const double PERF_RESOLUTION = 0.02;
652 static const double PERF_ORIGIN_X = 0.0;
653 static const double PERF_ORIGIN_Y = 0.0;
654 static const double PERF_ORIGIN_Z = 0.0;
655 static const double PERF_MAX_DIST = .25;
656 static const unsigned int UNIFORM_DISTANCE = 10;
657 
658 TEST(TestSignedPropagationDistanceField, TestPerformance)
659 {
660  std::cout << "Creating distance field with "
661  << (PERF_WIDTH / PERF_RESOLUTION) * (PERF_HEIGHT / PERF_RESOLUTION) * (PERF_DEPTH / PERF_RESOLUTION)
662  << " entries" << '\n';
663 
664  auto dt = std::chrono::system_clock::now();
665  PropagationDistanceField df(PERF_WIDTH, PERF_HEIGHT, PERF_DEPTH, PERF_RESOLUTION, PERF_ORIGIN_X, PERF_ORIGIN_Y,
666  PERF_ORIGIN_Z, PERF_MAX_DIST, false);
667  std::cout
668  << "Creating unsigned took "
669  << std::chrono::duration_cast<std::chrono::milliseconds>(std::chrono::system_clock::now() - dt).count() / 1000.0
670  << " secs" << '\n';
671 
672  dt = std::chrono::system_clock::now();
673  PropagationDistanceField sdf(PERF_WIDTH, PERF_HEIGHT, PERF_DEPTH, PERF_RESOLUTION, PERF_ORIGIN_X, PERF_ORIGIN_Y,
674  PERF_ORIGIN_Z, PERF_MAX_DIST, true);
675 
676  std::cout
677  << "Creating signed took "
678  << std::chrono::duration_cast<std::chrono::milliseconds>(std::chrono::system_clock::now() - dt).count() / 1000.0
679  << " secs" << '\n';
680 
681  shapes::Box big_table(2.0, 2.0, .5);
682 
683  Eigen::Isometry3d p = Eigen::Translation3d(PERF_WIDTH / 2.0, PERF_DEPTH / 2.0, PERF_HEIGHT / 2.0) *
684  Eigen::Quaterniond(0.0, 0.0, 0.0, 1.0);
685  Eigen::Isometry3d np = Eigen::Translation3d(PERF_WIDTH / 2.0 + .01, PERF_DEPTH / 2.0, PERF_HEIGHT / 2.0) *
686  Eigen::Quaterniond(0.0, 0.0, 0.0, 1.0);
687 
688  unsigned int big_num_points = ceil(2.0 / PERF_RESOLUTION) * ceil(2.0 / PERF_RESOLUTION) * ceil(.5 / PERF_RESOLUTION);
689 
690  std::cout << "Adding " << big_num_points << " points" << '\n';
691 
692  dt = std::chrono::system_clock::now();
693  df.addShapeToField(&big_table, p);
694  std::cout
695  << "Adding to unsigned took "
696  << std::chrono::duration_cast<std::chrono::milliseconds>(std::chrono::system_clock::now() - dt).count() / 1000.0
697  << " secs"
698  << " avg "
699  << (std::chrono::duration_cast<std::chrono::milliseconds>(std::chrono::system_clock::now() - dt).count() /
700  1000.0) /
701  (big_num_points * 1.0)
702  << '\n';
703 
704  dt = std::chrono::system_clock::now();
705  df.addShapeToField(&big_table, p);
706  std::cout
707  << "Re-adding to unsigned took "
708  << std::chrono::duration_cast<std::chrono::milliseconds>(std::chrono::system_clock::now() - dt).count() / 1000.0
709  << " secs" << '\n';
710 
711  dt = std::chrono::system_clock::now();
712  sdf.addShapeToField(&big_table, p);
713  std::cout
714  << "Adding to signed took "
715  << std::chrono::duration_cast<std::chrono::milliseconds>(std::chrono::system_clock::now() - dt).count() / 1000.0
716  << " secs"
717  << " avg "
718  << (std::chrono::duration_cast<std::chrono::milliseconds>(std::chrono::system_clock::now() - dt).count() /
719  1000.0) /
720  (big_num_points * 1.0)
721  << '\n';
722 
723  dt = std::chrono::system_clock::now();
724  df.moveShapeInField(&big_table, p, np);
725  std::cout
726  << "Moving in unsigned took "
727  << std::chrono::duration_cast<std::chrono::milliseconds>(std::chrono::system_clock::now() - dt).count() / 1000.0
728  << " secs" << '\n';
729 
730  dt = std::chrono::system_clock::now();
731  sdf.moveShapeInField(&big_table, p, np);
732  std::cout
733  << "Moving in signed took "
734  << std::chrono::duration_cast<std::chrono::milliseconds>(std::chrono::system_clock::now() - dt).count() / 1000.0
735  << " secs" << '\n';
736 
737  dt = std::chrono::system_clock::now();
738  df.removeShapeFromField(&big_table, np);
739  std::cout
740  << "Removing from unsigned took "
741  << std::chrono::duration_cast<std::chrono::milliseconds>(std::chrono::system_clock::now() - dt).count() / 1000.0
742  << " secs" << '\n';
743 
744  dt = std::chrono::system_clock::now();
745  sdf.removeShapeFromField(&big_table, np);
746  std::cout
747  << "Removing from signed took "
748  << std::chrono::duration_cast<std::chrono::milliseconds>(std::chrono::system_clock::now() - dt).count() / 1000.0
749  << " secs" << '\n';
750 
751  dt = std::chrono::system_clock::now();
752  df.reset();
753 
754  shapes::Box small_table(.25, .25, .05);
755 
756  unsigned int small_num_points = (13) * (13) * (3);
757 
758  std::cout << "Adding " << small_num_points << " points" << '\n';
759 
760  dt = std::chrono::system_clock::now();
761  df.addShapeToField(&small_table, p);
762  std::cout
763  << "Adding to unsigned took "
764  << std::chrono::duration_cast<std::chrono::milliseconds>(std::chrono::system_clock::now() - dt).count() / 1000.0
765  << " secs"
766  << " avg " << (std::chrono::system_clock::now() - dt).count() / (small_num_points * 1.0) << '\n';
767 
768  dt = std::chrono::system_clock::now();
769  sdf.addShapeToField(&small_table, p);
770  std::cout
771  << "Adding to signed took "
772  << std::chrono::duration_cast<std::chrono::milliseconds>(std::chrono::system_clock::now() - dt).count() / 1000.0
773  << " secs"
774  << " avg " << (std::chrono::system_clock::now() - dt).count() / (small_num_points * 1.0) << '\n';
775 
776  dt = std::chrono::system_clock::now();
777  df.moveShapeInField(&small_table, p, np);
778  std::cout
779  << "Moving in unsigned took "
780  << std::chrono::duration_cast<std::chrono::milliseconds>(std::chrono::system_clock::now() - dt).count() / 1000.0
781  << " secs" << '\n';
782 
783  dt = std::chrono::system_clock::now();
784  sdf.moveShapeInField(&small_table, p, np);
785  std::cout
786  << "Moving in signed took "
787  << std::chrono::duration_cast<std::chrono::milliseconds>(std::chrono::system_clock::now() - dt).count() / 1000.0
788  << " secs" << '\n';
789 
790  // uniformly spaced points - a worst case scenario
791  PropagationDistanceField worstdfu(PERF_WIDTH, PERF_HEIGHT, PERF_DEPTH, PERF_RESOLUTION, PERF_ORIGIN_X, PERF_ORIGIN_Y,
792  PERF_ORIGIN_Z, PERF_MAX_DIST, false);
793 
794  PropagationDistanceField worstdfs(PERF_WIDTH, PERF_HEIGHT, PERF_DEPTH, PERF_RESOLUTION, PERF_ORIGIN_X, PERF_ORIGIN_Y,
795  PERF_ORIGIN_Z, PERF_MAX_DIST, true);
796 
797  EigenSTL::vector_Vector3d bad_vec;
798  unsigned int count = 0;
799  for (unsigned int z = UNIFORM_DISTANCE; z < worstdfu.getZNumCells() - UNIFORM_DISTANCE; z += UNIFORM_DISTANCE)
800  {
801  for (unsigned int x = UNIFORM_DISTANCE; x < worstdfu.getXNumCells() - UNIFORM_DISTANCE; x += UNIFORM_DISTANCE)
802  {
803  for (unsigned int y = UNIFORM_DISTANCE; y < worstdfu.getYNumCells() - UNIFORM_DISTANCE; y += UNIFORM_DISTANCE)
804  {
805  count++;
806  Eigen::Vector3d loc;
807  bool valid = worstdfu.gridToWorld(x, y, z, loc.x(), loc.y(), loc.z());
808 
809  if (!valid)
810  {
811  // RCLCPP_WARN("distance_field", "Something wrong");
812  continue;
813  }
814  bad_vec.push_back(loc);
815  }
816  }
817  }
818 
819  dt = std::chrono::system_clock::now();
820  worstdfu.addPointsToField(bad_vec);
821  std::chrono::duration<double> wd = std::chrono::system_clock::now() - dt;
822  printf("Time for unsigned adding %u uniform points is %g average %g\n", (unsigned int)bad_vec.size(), wd.count(),
823  wd.count() / (bad_vec.size() * 1.0));
824  dt = std::chrono::system_clock::now();
825  worstdfs.addPointsToField(bad_vec);
826  wd = std::chrono::system_clock::now() - dt;
827  printf("Time for signed adding %u uniform points is %g average %g\n", (unsigned int)bad_vec.size(), wd.count(),
828  wd.count() / (bad_vec.size() * 1.0));
829 }
830 
831 TEST(TestSignedPropagationDistanceField, TestOcTree)
832 {
833  PropagationDistanceField df(PERF_WIDTH, PERF_HEIGHT, PERF_DEPTH, PERF_RESOLUTION, PERF_ORIGIN_X, PERF_ORIGIN_Y,
834  PERF_ORIGIN_Z, PERF_MAX_DIST, false);
835 
836  octomap::OcTree tree(.02);
837 
838  unsigned int count = 0;
839  for (float x = 1.01; x < 1.5; x += .02)
840  {
841  for (float y = 1.01; y < 1.5; y += .02)
842  {
843  for (float z = 1.01; z < 1.5; z += .02, ++count)
844  {
845  octomap::point3d point(x, y, z);
846  tree.updateNode(point, true);
847  }
848  }
849  }
850 
851  // more points at the border of the distance field
852  for (float x = 2.51; x < 3.5; x += .02)
853  {
854  for (float y = 1.01; y < 3.5; y += .02)
855  {
856  for (float z = 1.01; z < 3.5; z += .02, ++count)
857  {
858  octomap::point3d point(x, y, z);
859  tree.updateNode(point, true);
860  }
861  }
862  }
863 
864  std::cout << "OcTree nodes " << count << '\n';
865  df.addOcTreeToField(&tree);
866 
867  EXPECT_TRUE(checkOctomapVersusDistanceField(df, tree));
868 
869  // more cells
870  for (float x = .01; x < .50; x += .02)
871  {
872  for (float y = .01; y < .50; y += .02)
873  {
874  for (float z = .01; z < .50; z += .02, ++count)
875  {
876  octomap::point3d point(x, y, z);
877  tree.updateNode(point, true);
878  }
879  }
880  }
881  df.addOcTreeToField(&tree);
882  EXPECT_TRUE(checkOctomapVersusDistanceField(df, tree));
883 
884  PropagationDistanceField df_oct(tree, octomap::point3d(0.5, 0.5, 0.5), octomap::point3d(5.0, 5.0, 5.0), PERF_MAX_DIST,
885  false);
886 
887  EXPECT_TRUE(checkOctomapVersusDistanceField(df_oct, tree));
888 
889  // now try different resolutions
890  octomap::OcTree tree_lowres(.05);
891  octomap::point3d point1(.5, .5, .5);
892  octomap::point3d point2(.7, .5, .5);
893  octomap::point3d point3(1.0, .5, .5);
894  tree_lowres.updateNode(point1, true);
895  tree_lowres.updateNode(point2, true);
896  tree_lowres.updateNode(point3, true);
897  ASSERT_EQ(countLeafNodes(tree_lowres), 3u);
898 
899  PropagationDistanceField df_highres(PERF_WIDTH, PERF_HEIGHT, PERF_DEPTH, PERF_RESOLUTION, PERF_ORIGIN_X,
900  PERF_ORIGIN_Y, PERF_ORIGIN_Z, PERF_MAX_DIST, false);
901 
902  df_highres.addOcTreeToField(&tree_lowres);
903  EXPECT_EQ(countOccupiedCells(df_highres), 3u * (4u * 4u * 4u));
904  std::cout << "Occupied cells " << countOccupiedCells(df_highres) << '\n';
905 
906  // testing adding shape that happens to be octree
907  auto tree_shape = std::make_shared<octomap::OcTree>(.05);
908  octomap::point3d tpoint1(1.0, .5, 1.0);
909  octomap::point3d tpoint2(1.7, .5, .5);
910  octomap::point3d tpoint3(1.8, .5, .5);
911  tree_shape->updateNode(tpoint1, true);
912  tree_shape->updateNode(tpoint2, true);
913  tree_shape->updateNode(tpoint3, true);
914 
915  auto shape_oc = std::make_shared<shapes::OcTree>(tree_shape);
916 
917  PropagationDistanceField df_test_shape_1(PERF_WIDTH, PERF_HEIGHT, PERF_DEPTH, PERF_RESOLUTION, PERF_ORIGIN_X,
918  PERF_ORIGIN_Y, PERF_ORIGIN_Z, PERF_MAX_DIST, false);
919 
920  PropagationDistanceField df_test_shape_2(PERF_WIDTH, PERF_HEIGHT, PERF_DEPTH, PERF_RESOLUTION, PERF_ORIGIN_X,
921  PERF_ORIGIN_Y, PERF_ORIGIN_Z, PERF_MAX_DIST, false);
922 
923  df_test_shape_1.addOcTreeToField(tree_shape.get());
924  df_test_shape_2.addShapeToField(shape_oc.get(), Eigen::Isometry3d());
925  EXPECT_TRUE(areDistanceFieldsDistancesEqual(df_test_shape_1, df_test_shape_2));
926 }
927 
928 TEST(TestSignedPropagationDistanceField, TestReadWrite)
929 {
930  PropagationDistanceField small_df(WIDTH, HEIGHT, DEPTH, RESOLUTION, ORIGIN_X, ORIGIN_Y, ORIGIN_Z, MAX_DIST);
931 
932  EigenSTL::vector_Vector3d points;
933  points.push_back(POINT1);
934  points.push_back(POINT2);
935  points.push_back(POINT3);
936  small_df.addPointsToField(points);
937 
938  std::ofstream sf("test_small.df", std::ios::out);
939 
940  small_df.writeToStream(sf);
941  // must close to make sure that the buffer is written
942  sf.close();
943 
944  std::ifstream si("test_small.df", std::ios::in | std::ios::binary);
945  PropagationDistanceField small_df2(si, PERF_MAX_DIST, false);
946  ASSERT_TRUE(areDistanceFieldsDistancesEqual(small_df, small_df2));
947 
948  PropagationDistanceField df(PERF_WIDTH, PERF_HEIGHT, PERF_DEPTH, PERF_RESOLUTION, PERF_ORIGIN_X, PERF_ORIGIN_Y,
949  PERF_ORIGIN_Z, PERF_MAX_DIST, false);
950 
951  shapes::Sphere sphere(.5);
952 
953  Eigen::Isometry3d p = Eigen::Translation3d(0.5, 0.5, 0.5) * Eigen::Quaterniond(0.0, 0.0, 0.0, 1.0);
954 
955  df.addShapeToField(&sphere, p);
956 
957  std::ofstream f("test_big.df", std::ios::out);
958 
959  df.writeToStream(f);
960  f.close();
961 
962  std::ifstream i("test_big.df", std::ios::in);
963  PropagationDistanceField df2(i, PERF_MAX_DIST, false);
964  EXPECT_TRUE(areDistanceFieldsDistancesEqual(df, df2));
965 
966  // we shouldn't segfault if we start with an old ifstream
967  PropagationDistanceField dfx(i, PERF_MAX_DIST, false);
968 
969  std::ifstream i2("test_big.df", std::ios::in);
970  auto wt = std::chrono::system_clock::now();
971  PropagationDistanceField df3(i2, PERF_MAX_DIST + .02, false);
972  std::cout << "Reconstruction for big file took " << (std::chrono::system_clock::now() - wt).count() << '\n';
973  EXPECT_FALSE(areDistanceFieldsDistancesEqual(df, df3));
974 }
975 
976 int main(int argc, char** argv)
977 {
978  testing::InitGoogleTest(&argc, argv);
979  return RUN_ALL_TESTS();
980 }
void moveShapeInField(const shapes::Shape *shape, const Eigen::Isometry3d &old_pose, const Eigen::Isometry3d &new_pose)
Moves the shape in the distance field from the old pose to the new pose, removing points that are no ...
void removeShapeFromField(const shapes::Shape *shape, const Eigen::Isometry3d &pose)
All points corresponding to the shape are removed from the distance field.
double getDistanceGradient(double x, double y, double z, double &gradient_x, double &gradient_y, double &gradient_z, bool &in_bounds) const
Gets not only the distance to the nearest cell but the gradient direction. The gradient is computed a...
void addOcTreeToField(const octomap::OcTree *octree)
Adds an octree to the distance field. Cells that are occupied in the octree that lie within the voxel...
double getResolution() const
Gets the resolution of the distance field in meters.
void addShapeToField(const shapes::Shape *shape, const Eigen::Isometry3d &pose)
Adds the set of points corresponding to the shape at the given pose as obstacle points into the dista...
A DistanceField implementation that uses a vector propagation method. Distances propagate outward fro...
void addPointsToField(const EigenSTL::vector_Vector3d &points) override
Add a set of obstacle points to the distance field, updating distance values accordingly....
void reset() override
Resets the entire distance field to max_distance for positive values and zero for negative values.
int getXNumCells() const override
Gets the number of cells along the X axis.
int getZNumCells() const override
Gets the number of cells along the Z axis.
bool worldToGrid(double world_x, double world_y, double world_z, int &x, int &y, int &z) const override
Converts from a world location to a set of integer indices. Should return false if the world location...
void removePointsFromField(const EigenSTL::vector_Vector3d &points) override
Remove a set of obstacle points from the distance field, updating distance values accordingly.
double getUninitializedDistance() const override
Gets a distance value for an invalid cell.
double getDistance(double x, double y, double z) const override
Get the distance value associated with the cell indicated by the world coordinate....
int getYNumCells() const override
Gets the number of cells along the Y axis.
const PropDistanceFieldVoxel & getCell(int x, int y, int z) const
Gets full cell data given an index.
void updatePointsInField(const EigenSTL::vector_Vector3d &old_points, const EigenSTL::vector_Vector3d &new_points) override
This function will remove any obstacle points that are in the old point set but not the new point set...
bool writeToStream(std::ostream &stream) const override
Writes the contents of the distance field to the supplied stream.
const PropDistanceFieldVoxel * getNearestCell(int x, int y, int z, double &dist, Eigen::Vector3i &pos) const
Gets nearest surface cell and returns distance to it.
bool gridToWorld(int x, int y, int z, double &world_x, double &world_y, double &world_z) const override
Converts from an set of integer indices to a world location given the origin and resolution parameter...
std::vector< Eigen::Vector3i, Eigen::aligned_allocator< Eigen::Vector3i > > vector_Vector3i
Namespace for holding classes that generate distance fields.
void findInternalPointsConvex(const bodies::Body &body, double resolution, EigenSTL::vector_Vector3d &points)
Find all points on a regular grid that are internal to the body, assuming the body is a convex shape....
Vec3fX< details::Vec3Data< double > > Vector3d
Definition: fcl_compat.h:89
p
Definition: pick.py:62
x
Definition: pick.py:64
y
Definition: pick.py:65
z
Definition: pick.py:66
Structure that holds voxel information for the DistanceField. Will be used in VoxelGrid.
Eigen::Vector3i closest_point_
Closest occupied cell.
Eigen::Vector3i closest_negative_point_
Closest unoccupied cell.
int negative_distance_square_
Distance in cells to the nearest unoccupied cell, squared.
int distance_square_
Distance in cells to the closest obstacle, squared.
unsigned int countLeafNodes(const octomap::OcTree &octree)
void print(PropagationDistanceField &pdf, int numX, int numY, int numZ)
void check_distance_field(const PropagationDistanceField &df, const EigenSTL::vector_Vector3d &points, int numX, int numY, int numZ, bool do_negs)
int main(int argc, char **argv)
void printPointCoords(const Eigen::Vector3i &p)
bool areDistanceFieldsDistancesEqual(const PropagationDistanceField &df1, const PropagationDistanceField &df2)
void printBoth(PropagationDistanceField &pdf, int numX, int numY, int numZ)
int dist_sq(int x, int y, int z)
bool checkOctomapVersusDistanceField(const PropagationDistanceField &df, const octomap::OcTree &octree)
void printNeg(PropagationDistanceField &pdf, int numX, int numY, int numZ)
TEST(TestPropagationDistanceField, TestAddRemovePoints)
unsigned int countOccupiedCells(const PropagationDistanceField &df)