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