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>
59 double origin_y,
double origin_z)
66 , resolution_(resolution)
67 , inv_twice_resolution_(1.0 / (2.0 * resolution_))
74 double& gradient_z,
bool& in_bounds)
const
100 const rclcpp::Time& stamp, visualization_msgs::msg::Marker& inf_marker)
const
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";
107 inf_marker.type = visualization_msgs::msg::Marker::CUBE_LIST;
108 inf_marker.action = visualization_msgs::msg::Marker::MODIFY;
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;
118 inf_marker.points.reserve(100000);
127 if (dist >= min_distance && dist <= max_distance)
129 int last = inf_marker.points.size();
130 inf_marker.points.resize(last + 1);
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();
144 const rclcpp::Time& stamp,
145 visualization_msgs::msg::MarkerArray& marker_array)
const
147 Eigen::Vector3d unit_x(1, 0, 0);
148 Eigen::Vector3d unit_y(0, 1, 0);
149 Eigen::Vector3d unit_z(0, 0, 1);
159 double world_x, world_y, world_z;
162 double gradient_x, gradient_y, gradient_z;
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);
167 if (in_bounds && distance >= min_distance && distance <= max_distance && gradient.norm() > 0)
169 visualization_msgs::msg::Marker marker;
171 marker.header.frame_id = frame_id;
172 marker.header.stamp = stamp;
174 marker.ns =
"distance_field_gradient";
176 marker.type = visualization_msgs::msg::Marker::ARROW;
177 marker.action = visualization_msgs::msg::Marker::ADD;
179 marker.pose.position.x = world_x;
180 marker.pose.position.y = world_y;
181 marker.pose.position.z = world_z;
196 marker.color.r = 0.0;
197 marker.color.g = 0.0;
198 marker.color.b = 1.0;
199 marker.color.a = 1.0;
201 marker_array.markers.push_back(marker);
209 EigenSTL::vector_Vector3d* points)
211 if (shape->type == shapes::OCTREE)
213 const shapes::OcTree* oc =
dynamic_cast<const shapes::OcTree*
>(shape);
216 RCLCPP_ERROR(getLogger(),
"Problem dynamic casting shape that claims to be OcTree");
223 bodies::Body* body = bodies::createEmptyBodyFromShapeType(shape->type);
224 body->setDimensionsDirty(shape);
225 body->setPoseDirty(pose);
226 body->updateInternalData();
235 EigenSTL::vector_Vector3d point_vec;
243 double min_x, min_y, min_z;
246 octomap::point3d bbx_min(min_x, min_y, min_z);
253 double max_x, max_y, max_z;
254 gridToWorld(num_x, num_y, num_z, max_x, max_y, max_z);
256 octomap::point3d bbx_max(max_x, max_y, max_z);
258 for (octomap::OcTree::leaf_bbx_iterator it = octree->begin_leafs_bbx(bbx_min, bbx_max), end = octree->end_leafs_bbx();
261 if (octree->isNodeOccupied(*it))
265 Eigen::Vector3d point(it.getX(), it.getY(), it.getZ());
266 points->push_back(point);
271 for (
double x = it.getX() - ceil_val; x <= it.getX() + ceil_val; x +=
resolution_)
273 for (
double y = it.getY() - ceil_val; y <= it.getY() + ceil_val; y +=
resolution_)
275 for (
double z = it.getZ() - ceil_val; z <= it.getZ() + ceil_val; z +=
resolution_)
277 points->push_back(Eigen::Vector3d(x, y, z));
288 EigenSTL::vector_Vector3d points;
294 const Eigen::Isometry3d& new_pose)
296 if (shape->type == shapes::OCTREE)
298 RCLCPP_WARN(getLogger(),
"Move shape not supported for Octree");
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;
307 body->setPose(new_pose);
308 EigenSTL::vector_Vector3d new_point_vec;
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;
327 const Eigen::Vector3d& origin,
const std::string& frame_id,
328 const rclcpp::Time& stamp, visualization_msgs::msg::Marker& plane_marker)
const
330 plane_marker.header.frame_id = frame_id;
331 plane_marker.header.stamp = stamp;
332 plane_marker.ns =
"distance_field_plane";
334 plane_marker.type = visualization_msgs::msg::Marker::CUBE_LIST;
335 plane_marker.action = visualization_msgs::msg::Marker::ADD;
341 plane_marker.points.reserve(100000);
342 plane_marker.colors.reserve(100000);
357 min_x = -length / 2.0;
358 max_x = length / 2.0;
359 min_y = -width / 2.0;
366 min_x = -length / 2.0;
367 max_x = length / 2.0;
368 min_z = -width / 2.0;
375 min_y = -length / 2.0;
376 max_y = length / 2.0;
377 min_z = -width / 2.0;
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)
402 for (
int y = min_y_cell; y <= max_y_cell; ++y)
404 for (
int z = min_z_cell; z <= max_z_cell; ++z)
411 int last = plane_marker.points.size();
412 plane_marker.points.resize(last + 1);
413 plane_marker.colors.resize(last + 1);
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();
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);
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);
438 std_msgs::msg::ColorRGBA& color,
double max_distance)
const
448 color.g = dist / max_distance;
449 color.b = dist / max_distance;
453 visualization_msgs::msg::Marker& marker)
const
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);
465 for (
int y = 0; y < max_y_cell; ++y)
467 for (
int x = 0; x < max_x_cell; ++x)
468 z_projection[x + y * max_x_cell] = initial_val;
471 for (
int z = 0; z < max_z_cell; ++z)
473 for (
int y = 0; y < max_y_cell; ++y)
474 x_projection[y + z * max_y_cell] = initial_val;
477 for (
int z = 0; z < max_z_cell; ++z)
479 for (
int x = 0; x < max_x_cell; ++x)
480 y_projection[x + z * max_x_cell] = initial_val;
484 for (
int z = 0; z < max_z_cell; ++z)
486 for (
int y = 0; y < max_y_cell; ++y)
488 for (
int x = 0; x < max_x_cell; ++x)
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]);
499 marker.points.clear();
500 marker.header.frame_id = frame_id;
501 marker.header.stamp = stamp;
502 marker.ns =
"distance_field_projection_plane";
504 marker.type = visualization_msgs::msg::Marker::CUBE_LIST;
505 marker.action = visualization_msgs::msg::Marker::MODIFY;
509 marker.color.a = 1.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);
518 for (y = 0; y < max_y_cell; ++y)
520 for (x = 0; x < max_x_cell; ++x)
522 double dist = z_projection[x + y * max_x_cell];
523 setPoint(x, y, z, dist, marker.points[index], marker.colors[index], max_dist);
529 for (z = 0; z < max_z_cell; ++z)
531 for (y = 0; y < max_y_cell; ++y)
533 double dist = x_projection[y + z * max_y_cell];
534 setPoint(x, y, z, dist, marker.points[index], marker.colors[index], max_dist);
540 for (z = 0; z < max_z_cell; ++z)
542 for (x = 0; x < max_x_cell; ++x)
544 double dist = y_projection[x + z * max_x_cell];
545 setPoint(x, y, z, dist, marker.points[index], marker.colors[index], max_dist);
551 delete[] x_projection;
553 delete[] y_projection;
555 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...
rclcpp::Logger getLogger()
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.
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.