moveit2
The MoveIt Motion Planning Framework for ROS 2.
distance_field.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: Mrinal Kalakrishnan, Ken Anderson, E. Gil Jones */
36 
39 #include <geometric_shapes/body_operations.h>
40 #include <rclcpp/logger.hpp>
41 #include <rclcpp/logging.hpp>
42 #include <rclcpp/time.hpp>
43 #include <tf2_eigen/tf2_eigen.hpp>
44 #include <octomap/octomap.h>
45 #include <octomap/OcTree.h>
46 #include <moveit/utils/logger.hpp>
47 
48 namespace distance_field
49 {
50 namespace
51 {
52 rclcpp::Logger getLogger()
53 {
54  return moveit::getLogger("distance_field");
55 }
56 } // namespace
57 
58 DistanceField::DistanceField(double size_x, double size_y, double size_z, double resolution, double origin_x,
59  double origin_y, double origin_z)
60  : size_x_(size_x)
61  , size_y_(size_y)
62  , size_z_(size_z)
63  , origin_x_(origin_x)
64  , origin_y_(origin_y)
65  , origin_z_(origin_z)
66  , resolution_(resolution)
67  , inv_twice_resolution_(1.0 / (2.0 * resolution_))
68 {
69 }
70 
72 
73 double DistanceField::getDistanceGradient(double x, double y, double z, double& gradient_x, double& gradient_y,
74  double& gradient_z, bool& in_bounds) const
75 {
76  int gx, gy, gz;
77 
78  worldToGrid(x, y, z, gx, gy, gz);
79 
80  // if out of bounds, return max_distance, and 0 gradient
81  // we need extra padding of 1 to get gradients
82  if (gx < 1 || gy < 1 || gz < 1 || gx >= getXNumCells() - 1 || gy >= getYNumCells() - 1 || gz >= getZNumCells() - 1)
83  {
84  gradient_x = 0.0;
85  gradient_y = 0.0;
86  gradient_z = 0.0;
87  in_bounds = false;
88  return getUninitializedDistance();
89  }
90 
91  gradient_x = (getDistance(gx + 1, gy, gz) - getDistance(gx - 1, gy, gz)) * inv_twice_resolution_;
92  gradient_y = (getDistance(gx, gy + 1, gz) - getDistance(gx, gy - 1, gz)) * inv_twice_resolution_;
93  gradient_z = (getDistance(gx, gy, gz + 1) - getDistance(gx, gy, gz - 1)) * inv_twice_resolution_;
94 
95  in_bounds = true;
96  return getDistance(gx, gy, gz);
97 }
98 
99 void DistanceField::getIsoSurfaceMarkers(double min_distance, double max_distance, const std::string& frame_id,
100  const rclcpp::Time& stamp, visualization_msgs::msg::Marker& inf_marker) const
101 {
102  inf_marker.points.clear();
103  inf_marker.header.frame_id = frame_id;
104  inf_marker.header.stamp = stamp;
105  inf_marker.ns = "distance_field";
106  inf_marker.id = 1;
107  inf_marker.type = visualization_msgs::msg::Marker::CUBE_LIST;
108  inf_marker.action = visualization_msgs::msg::Marker::MODIFY;
109  inf_marker.scale.x = resolution_;
110  inf_marker.scale.y = resolution_;
111  inf_marker.scale.z = resolution_;
112  inf_marker.color.r = 1.0;
113  inf_marker.color.g = 0.0;
114  inf_marker.color.b = 0.0;
115  inf_marker.color.a = 0.1;
116  // inf_marker.lifetime = ros::Duration(30.0);
117 
118  inf_marker.points.reserve(100000);
119  for (int x = 0; x < getXNumCells(); ++x)
120  {
121  for (int y = 0; y < getYNumCells(); ++y)
122  {
123  for (int z = 0; z < getZNumCells(); ++z)
124  {
125  double dist = getDistance(x, y, z);
126 
127  if (dist >= min_distance && dist <= max_distance)
128  {
129  int last = inf_marker.points.size();
130  inf_marker.points.resize(last + 1);
131  double nx, ny, nz;
132  gridToWorld(x, y, z, nx, ny, nz);
133  Eigen::Translation3d vec(nx, ny, nz);
134  inf_marker.points[last].x = vec.x();
135  inf_marker.points[last].y = vec.y();
136  inf_marker.points[last].z = vec.z();
137  }
138  }
139  }
140  }
141 }
142 
143 void DistanceField::getGradientMarkers(double min_distance, double max_distance, const std::string& frame_id,
144  const rclcpp::Time& stamp,
145  visualization_msgs::msg::MarkerArray& marker_array) const
146 {
147  Eigen::Vector3d unit_x(1, 0, 0);
148  Eigen::Vector3d unit_y(0, 1, 0);
149  Eigen::Vector3d unit_z(0, 0, 1);
150 
151  int id = 0;
152 
153  for (int x = 0; x < getXNumCells(); ++x)
154  {
155  for (int y = 0; y < getYNumCells(); ++y)
156  {
157  for (int z = 0; z < getZNumCells(); ++z)
158  {
159  double world_x, world_y, world_z;
160  gridToWorld(x, y, z, world_x, world_y, world_z);
161 
162  double gradient_x, gradient_y, gradient_z;
163  bool in_bounds;
164  double distance = getDistanceGradient(world_x, world_y, world_z, gradient_x, gradient_y, gradient_z, in_bounds);
165  Eigen::Vector3d gradient(gradient_x, gradient_y, gradient_z);
166 
167  if (in_bounds && distance >= min_distance && distance <= max_distance && gradient.norm() > 0)
168  {
169  visualization_msgs::msg::Marker marker;
170 
171  marker.header.frame_id = frame_id;
172  marker.header.stamp = stamp;
173 
174  marker.ns = "distance_field_gradient";
175  marker.id = id++;
176  marker.type = visualization_msgs::msg::Marker::ARROW;
177  marker.action = visualization_msgs::msg::Marker::ADD;
178 
179  marker.pose.position.x = world_x;
180  marker.pose.position.y = world_y;
181  marker.pose.position.z = world_z;
182 
183  // Eigen::Vector3d axis = gradient.cross(unitX).norm() > 0 ? gradient.cross(unitX) : unitY;
184  // double angle = -gradient.angle(unitX);
185  // Eigen::AngleAxisd rotation(angle, axis);
186 
187  // marker.pose.orientation.x = rotation.linear().x();
188  // marker.pose.orientation.y = rotation.linear().y();
189  // marker.pose.orientation.z = rotation.linear().z();
190  // marker.pose.orientation.w = rotation.linear().w();
191 
192  marker.scale.x = getResolution();
193  marker.scale.y = getResolution();
194  marker.scale.z = getResolution();
195 
196  marker.color.r = 0.0;
197  marker.color.g = 0.0;
198  marker.color.b = 1.0;
199  marker.color.a = 1.0;
200 
201  marker_array.markers.push_back(marker);
202  }
203  }
204  }
205  }
206 }
207 
208 bool DistanceField::getShapePoints(const shapes::Shape* shape, const Eigen::Isometry3d& pose,
209  EigenSTL::vector_Vector3d* points)
210 {
211  if (shape->type == shapes::OCTREE)
212  {
213  const shapes::OcTree* oc = dynamic_cast<const shapes::OcTree*>(shape);
214  if (!oc)
215  {
216  RCLCPP_ERROR(getLogger(), "Problem dynamic casting shape that claims to be OcTree");
217  return false;
218  }
219  getOcTreePoints(oc->octree.get(), points);
220  }
221  else
222  {
223  bodies::Body* body = bodies::createEmptyBodyFromShapeType(shape->type);
224  body->setDimensionsDirty(shape);
225  body->setPoseDirty(pose);
226  body->updateInternalData();
227  findInternalPointsConvex(*body, resolution_, *points);
228  delete body;
229  }
230  return true;
231 }
232 
233 void DistanceField::addShapeToField(const shapes::Shape* shape, const Eigen::Isometry3d& pose)
234 {
235  EigenSTL::vector_Vector3d point_vec;
236  getShapePoints(shape, pose, &point_vec);
237  addPointsToField(point_vec);
238 }
239 
240 void DistanceField::getOcTreePoints(const octomap::OcTree* octree, EigenSTL::vector_Vector3d* points)
241 {
242  // lower extent
243  double min_x, min_y, min_z;
244  gridToWorld(0, 0, 0, min_x, min_y, min_z);
245 
246  octomap::point3d bbx_min(min_x, min_y, min_z);
247 
248  int num_x = getXNumCells();
249  int num_y = getYNumCells();
250  int num_z = getZNumCells();
251 
252  // upper extent
253  double max_x, max_y, max_z;
254  gridToWorld(num_x, num_y, num_z, max_x, max_y, max_z);
255 
256  octomap::point3d bbx_max(max_x, max_y, max_z);
257 
258  for (octomap::OcTree::leaf_bbx_iterator it = octree->begin_leafs_bbx(bbx_min, bbx_max), end = octree->end_leafs_bbx();
259  it != end; ++it)
260  {
261  if (octree->isNodeOccupied(*it))
262  {
263  if (it.getSize() <= resolution_)
264  {
265  Eigen::Vector3d point(it.getX(), it.getY(), it.getZ());
266  points->push_back(point);
267  }
268  else
269  {
270  double ceil_val = ceil(it.getSize() / resolution_) * resolution_ / 2.0;
271  for (double x = it.getX() - ceil_val; x <= it.getX() + ceil_val; x += resolution_)
272  {
273  for (double y = it.getY() - ceil_val; y <= it.getY() + ceil_val; y += resolution_)
274  {
275  for (double z = it.getZ() - ceil_val; z <= it.getZ() + ceil_val; z += resolution_)
276  {
277  points->push_back(Eigen::Vector3d(x, y, z));
278  }
279  }
280  }
281  }
282  }
283  }
284 }
285 
286 void DistanceField::addOcTreeToField(const octomap::OcTree* octree)
287 {
288  EigenSTL::vector_Vector3d points;
289  getOcTreePoints(octree, &points);
290  addPointsToField(points);
291 }
292 
293 void DistanceField::moveShapeInField(const shapes::Shape* shape, const Eigen::Isometry3d& old_pose,
294  const Eigen::Isometry3d& new_pose)
295 {
296  if (shape->type == shapes::OCTREE)
297  {
298  RCLCPP_WARN(getLogger(), "Move shape not supported for Octree");
299  return;
300  }
301  bodies::Body* body = bodies::createEmptyBodyFromShapeType(shape->type);
302  body->setDimensionsDirty(shape);
303  body->setPoseDirty(old_pose);
304  body->updateInternalData();
305  EigenSTL::vector_Vector3d old_point_vec;
306  findInternalPointsConvex(*body, resolution_, old_point_vec);
307  body->setPose(new_pose);
308  EigenSTL::vector_Vector3d new_point_vec;
309  findInternalPointsConvex(*body, resolution_, new_point_vec);
310  delete body;
311  updatePointsInField(old_point_vec, new_point_vec);
312 }
313 
314 void DistanceField::removeShapeFromField(const shapes::Shape* shape, const Eigen::Isometry3d& pose)
315 {
316  bodies::Body* body = bodies::createEmptyBodyFromShapeType(shape->type);
317  body->setDimensionsDirty(shape);
318  body->setPoseDirty(pose);
319  body->updateInternalData();
320  EigenSTL::vector_Vector3d point_vec;
321  findInternalPointsConvex(*body, resolution_, point_vec);
322  delete body;
323  removePointsFromField(point_vec);
324 }
325 
326 void DistanceField::getPlaneMarkers(PlaneVisualizationType type, double length, double width, double height,
327  const Eigen::Vector3d& origin, const std::string& frame_id,
328  const rclcpp::Time& stamp, visualization_msgs::msg::Marker& plane_marker) const
329 {
330  plane_marker.header.frame_id = frame_id;
331  plane_marker.header.stamp = stamp;
332  plane_marker.ns = "distance_field_plane";
333  plane_marker.id = 1;
334  plane_marker.type = visualization_msgs::msg::Marker::CUBE_LIST;
335  plane_marker.action = visualization_msgs::msg::Marker::ADD;
336  plane_marker.scale.x = resolution_;
337  plane_marker.scale.y = resolution_;
338  plane_marker.scale.z = resolution_;
339  // plane_marker.lifetime = ros::Duration(30.0);
340 
341  plane_marker.points.reserve(100000);
342  plane_marker.colors.reserve(100000);
343 
344  double min_x = 0;
345  double max_x = 0;
346  double min_y = 0;
347  double max_y = 0;
348  double min_z = 0;
349  double max_z = 0;
350 
351  switch (type)
352  {
353  case XY_PLANE:
354  min_z = height;
355  max_z = height;
356 
357  min_x = -length / 2.0;
358  max_x = length / 2.0;
359  min_y = -width / 2.0;
360  max_y = width / 2.0;
361  break;
362  case XZ_PLANE:
363  min_y = height;
364  max_y = height;
365 
366  min_x = -length / 2.0;
367  max_x = length / 2.0;
368  min_z = -width / 2.0;
369  max_z = width / 2.0;
370  break;
371  case YZ_PLANE:
372  min_x = height;
373  max_x = height;
374 
375  min_y = -length / 2.0;
376  max_y = length / 2.0;
377  min_z = -width / 2.0;
378  max_z = width / 2.0;
379  break;
380  }
381 
382  min_x += origin.x();
383  min_y += origin.y();
384  min_z += origin.z();
385 
386  max_x += origin.x();
387  max_y += origin.y();
388  max_z += origin.z();
389 
390  int min_x_cell = 0;
391  int max_x_cell = 0;
392  int min_y_cell = 0;
393  int max_y_cell = 0;
394  int min_z_cell = 0;
395  int max_z_cell = 0;
396 
397  worldToGrid(min_x, min_y, min_z, min_x_cell, min_y_cell, min_z_cell);
398  worldToGrid(max_x, max_y, max_z, max_x_cell, max_y_cell, max_z_cell);
399  plane_marker.color.a = 1.0;
400  for (int x = min_x_cell; x <= max_x_cell; ++x)
401  {
402  for (int y = min_y_cell; y <= max_y_cell; ++y)
403  {
404  for (int z = min_z_cell; z <= max_z_cell; ++z)
405  {
406  if (!isCellValid(x, y, z))
407  {
408  continue;
409  }
410  double dist = getDistance(x, y, z);
411  int last = plane_marker.points.size();
412  plane_marker.points.resize(last + 1);
413  plane_marker.colors.resize(last + 1);
414  double nx, ny, nz;
415  gridToWorld(x, y, z, nx, ny, nz);
416  Eigen::Vector3d vec(nx, ny, nz);
417  plane_marker.points[last].x = vec.x();
418  plane_marker.points[last].y = vec.y();
419  plane_marker.points[last].z = vec.z();
420  if (dist < 0.0)
421  {
422  plane_marker.colors[last].r = fmax(fmin(0.1 / fabs(dist), 1.0), 0.0);
423  plane_marker.colors[last].g = fmax(fmin(0.05 / fabs(dist), 1.0), 0.0);
424  plane_marker.colors[last].b = fmax(fmin(0.01 / fabs(dist), 1.0), 0.0);
425  }
426  else
427  {
428  plane_marker.colors[last].b = fmax(fmin(0.1 / (dist + 0.001), 1.0), 0.0);
429  plane_marker.colors[last].g = fmax(fmin(0.05 / (dist + 0.001), 1.0), 0.0);
430  plane_marker.colors[last].r = fmax(fmin(0.01 / (dist + 0.001), 1.0), 0.0);
431  }
432  }
433  }
434  }
435 }
436 
437 void DistanceField::setPoint(int xCell, int yCell, int zCell, double dist, geometry_msgs::msg::Point& point,
438  std_msgs::msg::ColorRGBA& color, double max_distance) const
439 {
440  double wx, wy, wz;
441  gridToWorld(xCell, yCell, zCell, wx, wy, wz);
442 
443  point.x = wx;
444  point.y = wy;
445  point.z = wz;
446 
447  color.r = 1.0;
448  color.g = dist / max_distance; // dist/max_distance * 0.5;
449  color.b = dist / max_distance; // dist/max_distance * 0.1;
450 }
451 
452 void DistanceField::getProjectionPlanes(const std::string& frame_id, const rclcpp::Time& stamp, double max_dist,
453  visualization_msgs::msg::Marker& marker) const
454 {
455  int max_x_cell = getXNumCells();
456  int max_y_cell = getYNumCells();
457  int max_z_cell = getZNumCells();
458 
459  double* x_projection = new double[max_y_cell * max_z_cell];
460  double* y_projection = new double[max_z_cell * max_x_cell];
461  double* z_projection = new double[max_x_cell * max_y_cell];
462  double initial_val = sqrt(INT_MAX);
463 
464  // Initialize
465  for (int y = 0; y < max_y_cell; ++y)
466  {
467  for (int x = 0; x < max_x_cell; ++x)
468  z_projection[x + y * max_x_cell] = initial_val;
469  }
470 
471  for (int z = 0; z < max_z_cell; ++z)
472  {
473  for (int y = 0; y < max_y_cell; ++y)
474  x_projection[y + z * max_y_cell] = initial_val;
475  }
476 
477  for (int z = 0; z < max_z_cell; ++z)
478  {
479  for (int x = 0; x < max_x_cell; ++x)
480  y_projection[x + z * max_x_cell] = initial_val;
481  }
482 
483  // Calculate projections
484  for (int z = 0; z < max_z_cell; ++z)
485  {
486  for (int y = 0; y < max_y_cell; ++y)
487  {
488  for (int x = 0; x < max_x_cell; ++x)
489  {
490  double dist = getDistance(x, y, z);
491  z_projection[x + y * max_x_cell] = std::min(dist, z_projection[x + y * max_x_cell]);
492  x_projection[y + z * max_y_cell] = std::min(dist, x_projection[y + z * max_y_cell]);
493  y_projection[x + z * max_x_cell] = std::min(dist, y_projection[x + z * max_x_cell]);
494  }
495  }
496  }
497 
498  // Make markers
499  marker.points.clear();
500  marker.header.frame_id = frame_id;
501  marker.header.stamp = stamp;
502  marker.ns = "distance_field_projection_plane";
503  marker.id = 1;
504  marker.type = visualization_msgs::msg::Marker::CUBE_LIST;
505  marker.action = visualization_msgs::msg::Marker::MODIFY;
506  marker.scale.x = getResolution();
507  marker.scale.y = getResolution();
508  marker.scale.z = getResolution();
509  marker.color.a = 1.0;
510  // marker.lifetime = ros::Duration(30.0);
511 
512  int x, y, z;
513  int index = 0;
514  marker.points.resize(max_x_cell * max_y_cell + max_y_cell * max_z_cell + max_z_cell * max_x_cell);
515  marker.colors.resize(max_x_cell * max_y_cell + max_y_cell * max_z_cell + max_z_cell * max_x_cell);
516 
517  z = 0;
518  for (y = 0; y < max_y_cell; ++y)
519  {
520  for (x = 0; x < max_x_cell; ++x)
521  {
522  double dist = z_projection[x + y * max_x_cell];
523  setPoint(x, y, z, dist, marker.points[index], marker.colors[index], max_dist);
524  index++;
525  }
526  }
527 
528  x = 0;
529  for (z = 0; z < max_z_cell; ++z)
530  {
531  for (y = 0; y < max_y_cell; ++y)
532  {
533  double dist = x_projection[y + z * max_y_cell];
534  setPoint(x, y, z, dist, marker.points[index], marker.colors[index], max_dist);
535  index++;
536  }
537  }
538 
539  y = 0;
540  for (z = 0; z < max_z_cell; ++z)
541  {
542  for (x = 0; x < max_x_cell; ++x)
543  {
544  double dist = y_projection[x + z * max_x_cell];
545  setPoint(x, y, z, dist, marker.points[index], marker.colors[index], max_dist);
546  index++;
547  }
548  }
549 
550  if (x_projection)
551  delete[] x_projection;
552  if (y_projection)
553  delete[] y_projection;
554  if (z_projection)
555  delete[] z_projection;
556 }
557 
558 } // end of namespace distance_field
virtual int getXNumCells() const =0
Gets the number of cells along the X axis.
double resolution_
Resolution of the distance field.
int inv_twice_resolution_
Computed value 1.0/(2.0*resolution_)
virtual void updatePointsInField(const EigenSTL::vector_Vector3d &old_points, const EigenSTL::vector_Vector3d &new_points)=0
This function will remove any obstacle points that are in the old point set but not the new point set...
virtual bool worldToGrid(double world_x, double world_y, double world_z, int &x, int &y, int &z) const =0
Converts from a world location to a set of integer indices. Should return false if the world location...
virtual void removePointsFromField(const EigenSTL::vector_Vector3d &points)=0
Remove a set of obstacle points from the distance field, updating distance values accordingly.
void getIsoSurfaceMarkers(double min_distance, double max_distance, const std::string &frame_id, const rclcpp::Time &stamp, visualization_msgs::msg::Marker &marker) const
Get an iso-surface for visualization in rviz. The iso-surface shows every cell that has a distance in...
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.
virtual double getUninitializedDistance() const =0
Gets a distance value for an invalid cell.
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.
virtual void addPointsToField(const EigenSTL::vector_Vector3d &points)=0
Add a set of obstacle points to the distance field, updating distance values accordingly....
virtual bool isCellValid(int x, int y, int z) const =0
Determines whether or not the cell associated with the supplied indices is valid for this distance fi...
bool getShapePoints(const shapes::Shape *shape, const Eigen::Isometry3d &pose, EigenSTL::vector_Vector3d *points)
Get the points associated with a shape. This is mainly used when the external application needs to ca...
DistanceField(double size_x, double size_y, double size_z, double resolution, double origin_x, double origin_y, double origin_z)
Constructor, where units are arbitrary but are assumed to be 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...
void setPoint(int xCell, int yCell, int zCell, double dist, geometry_msgs::msg::Point &point, std_msgs::msg::ColorRGBA &color, double max_distance) const
Helper function that sets the point value and color given the distance.
void getPlaneMarkers(PlaneVisualizationType type, double length, double width, double height, const Eigen::Vector3d &origin, const std::string &frame_id, const rclcpp::Time &stamp, visualization_msgs::msg::Marker &marker) const
Populates a marker with a slice of the distance field in a particular plane. All cells in the plane w...
void getGradientMarkers(double min_radius, double max_radius, const std::string &frame_id, const rclcpp::Time &stamp, visualization_msgs::msg::MarkerArray &marker_array) const
Populates the supplied marker array with a series of arrows representing gradients of cells that are ...
void getOcTreePoints(const octomap::OcTree *octree, EigenSTL::vector_Vector3d *points)
Get the points associated with an octree.
virtual bool gridToWorld(int x, int y, int z, double &world_x, double &world_y, double &world_z) const =0
Converts from an set of integer indices to a world location given the origin and resolution parameter...
void getProjectionPlanes(const std::string &frame_id, const rclcpp::Time &stamp, double max_distance, visualization_msgs::msg::Marker &marker) const
A function that populates the marker with three planes - one each along the XY, XZ,...
virtual int getYNumCells() const =0
Gets the number of cells along the Y axis.
virtual int getZNumCells() const =0
Gets the number of cells along the Z axis.
virtual double getDistance(double x, double y, double z) const =0
Gets the distance to the closest obstacle at the given location. The particulars of this function are...
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....
PlaneVisualizationType
The plane to visualize.
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
double distance(const urdf::Pose &transform)
Definition: pr2_arm_ik.h:55