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>
50 static const rclcpp::Logger LOGGER = rclcpp::get_logger(
"moveit_distance_field.distance_field");
53 double origin_y,
double origin_z)
60 , resolution_(resolution)
61 , inv_twice_resolution_(1.0 / (2.0 * resolution_))
68 double& gradient_z,
bool& in_bounds)
const
94 const rclcpp::Time& stamp, visualization_msgs::msg::Marker& inf_marker)
const
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";
101 inf_marker.type = visualization_msgs::msg::Marker::CUBE_LIST;
102 inf_marker.action = visualization_msgs::msg::Marker::MODIFY;
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;
112 inf_marker.points.reserve(100000);
121 if (dist >= min_distance && dist <= max_distance)
123 int last = inf_marker.points.size();
124 inf_marker.points.resize(last + 1);
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();
138 const rclcpp::Time& stamp,
139 visualization_msgs::msg::MarkerArray& marker_array)
const
153 double world_x, world_y, world_z;
156 double gradient_x, gradient_y, gradient_z;
161 if (in_bounds &&
distance >= min_distance &&
distance <= max_distance && gradient.norm() > 0)
163 visualization_msgs::msg::Marker marker;
166 marker.header.stamp = stamp;
168 marker.ns =
"distance_field_gradient";
170 marker.type = visualization_msgs::msg::Marker::ARROW;
171 marker.action = visualization_msgs::msg::Marker::ADD;
173 marker.pose.position.x = world_x;
174 marker.pose.position.y = world_y;
175 marker.pose.position.z = world_z;
190 marker.color.r = 0.0;
191 marker.color.g = 0.0;
192 marker.color.b = 1.0;
193 marker.color.a = 1.0;
195 marker_array.markers.push_back(marker);
203 EigenSTL::vector_Vector3d* points)
205 if (shape->type == shapes::OCTREE)
207 const shapes::OcTree* oc =
dynamic_cast<const shapes::OcTree*
>(shape);
210 RCLCPP_ERROR(LOGGER,
"Problem dynamic casting shape that claims to be OcTree");
217 bodies::Body* body = bodies::createEmptyBodyFromShapeType(shape->type);
218 body->setDimensionsDirty(shape);
219 body->setPoseDirty(pose);
220 body->updateInternalData();
229 EigenSTL::vector_Vector3d point_vec;
237 Eigen::Isometry3d pose_e;
238 tf2::fromMsg(pose, pose_e);
245 double min_x, min_y, min_z;
248 octomap::point3d bbx_min(min_x, min_y, min_z);
255 double max_x, max_y, max_z;
256 gridToWorld(num_x, num_y, num_z, max_x, max_y, max_z);
258 octomap::point3d bbx_max(max_x, max_y, max_z);
260 for (octomap::OcTree::leaf_bbx_iterator it = octree->begin_leafs_bbx(bbx_min, bbx_max), end = octree->end_leafs_bbx();
263 if (octree->isNodeOccupied(*it))
268 points->push_back(point);
273 for (
double x = it.getX() - ceil_val;
x <= it.getX() + ceil_val;
x +=
resolution_)
275 for (
double y = it.getY() - ceil_val;
y <= it.getY() + ceil_val;
y +=
resolution_)
277 for (
double z = it.getZ() - ceil_val;
z <= it.getZ() + ceil_val;
z +=
resolution_)
290 EigenSTL::vector_Vector3d points;
296 const Eigen::Isometry3d& new_pose)
298 if (shape->type == shapes::OCTREE)
300 RCLCPP_WARN(LOGGER,
"Move shape not supported for Octree");
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;
309 body->setPose(new_pose);
310 EigenSTL::vector_Vector3d new_point_vec;
318 const geometry_msgs::msg::Pose& new_pose)
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);
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;
341 Eigen::Isometry3d pose_e;
342 tf2::fromMsg(pose, pose_e);
348 const rclcpp::Time& stamp, visualization_msgs::msg::Marker& plane_marker)
const
350 plane_marker.header.frame_id =
frame_id;
351 plane_marker.header.stamp = stamp;
352 plane_marker.ns =
"distance_field_plane";
354 plane_marker.type = visualization_msgs::msg::Marker::CUBE_LIST;
355 plane_marker.action = visualization_msgs::msg::Marker::ADD;
361 plane_marker.points.reserve(100000);
362 plane_marker.colors.reserve(100000);
377 min_x = -length / 2.0;
378 max_x = length / 2.0;
379 min_y = -width / 2.0;
386 min_x = -length / 2.0;
387 max_x = length / 2.0;
388 min_z = -width / 2.0;
395 min_y = -length / 2.0;
396 max_y = length / 2.0;
397 min_z = -width / 2.0;
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)
422 for (
int y = min_y_cell;
y <= max_y_cell; ++
y)
424 for (
int z = min_z_cell;
z <= max_z_cell; ++
z)
431 int last = plane_marker.points.size();
432 plane_marker.points.resize(last + 1);
433 plane_marker.colors.resize(last + 1);
437 plane_marker.points[last].x = vec.x();
438 plane_marker.points[last].y = vec.y();
439 plane_marker.points[last].z = vec.z();
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);
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);
458 std_msgs::msg::ColorRGBA& color,
double max_distance)
const
468 color.g = dist / max_distance;
469 color.b = dist / max_distance;
473 visualization_msgs::msg::Marker& marker)
const
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);
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;
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;
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;
498 for (
int z = 0;
z < max_z_cell; ++
z)
500 for (
int y = 0;
y < max_y_cell; ++
y)
502 for (
int x = 0;
x < max_x_cell; ++
x)
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]);
513 marker.points.clear();
515 marker.header.stamp = stamp;
516 marker.ns =
"distance_field_projection_plane";
518 marker.type = visualization_msgs::msg::Marker::CUBE_LIST;
519 marker.action = visualization_msgs::msg::Marker::MODIFY;
523 marker.color.a = 1.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);
532 for (
y = 0;
y < max_y_cell; ++
y)
534 for (
x = 0;
x < max_x_cell; ++
x)
536 double dist = z_projection[
x +
y * max_x_cell];
537 setPoint(
x,
y,
z, dist, marker.points[index], marker.colors[index], max_dist);
543 for (
z = 0;
z < max_z_cell; ++
z)
545 for (
y = 0;
y < max_y_cell; ++
y)
547 double dist = x_projection[
y +
z * max_y_cell];
548 setPoint(
x,
y,
z, dist, marker.points[index], marker.colors[index], max_dist);
554 for (
z = 0;
z < max_z_cell; ++
z)
556 for (
x = 0;
x < max_x_cell; ++
x)
558 double dist = y_projection[
x +
z * max_x_cell];
559 setPoint(
x,
y,
z, dist, marker.points[index], marker.colors[index], max_dist);
565 delete[] x_projection;
567 delete[] y_projection;
569 delete[] z_projection;
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
double distance(const urdf::Pose &transform)