41#include <visualization_msgs/msg/marker.hpp>
42#include <visualization_msgs/msg/marker_array.hpp>
44#include <Eigen/Geometry>
45#include <eigen_stl_containers/eigen_stl_containers.h>
47#include <rclcpp/rclcpp.hpp>
107 DistanceField(
double size_x,
double size_y,
double size_z,
double resolution,
double origin_x,
double origin_y,
160 const EigenSTL::vector_Vector3d& new_points) = 0;
169 bool getShapePoints(
const shapes::Shape* shape,
const Eigen::Isometry3d& pose, EigenSTL::vector_Vector3d* points);
189 void addShapeToField(
const shapes::Shape* shape,
const Eigen::Isometry3d& pose);
224 void moveShapeInField(
const shapes::Shape* shape,
const Eigen::Isometry3d& old_pose,
225 const Eigen::Isometry3d& new_pose);
263 virtual double getDistance(
double x,
double y,
double z)
const = 0;
312 double getDistanceGradient(
double x,
double y,
double z,
double& gradient_x,
double& gradient_y,
double& gradient_z,
313 bool& in_bounds)
const;
376 virtual bool gridToWorld(
int x,
int y,
int z,
double& world_x,
double& world_y,
double& world_z)
const = 0;
394 virtual bool worldToGrid(
double world_x,
double world_y,
double world_z,
int& x,
int& y,
int& z)
const = 0;
429 void getIsoSurfaceMarkers(
double min_distance,
double max_distance,
const std::string& frame_id,
430 const rclcpp::Time& stamp, visualization_msgs::msg::Marker& marker)
const;
445 void getGradientMarkers(
double min_radius,
double max_radius,
const std::string& frame_id,
const rclcpp::Time& stamp,
446 visualization_msgs::msg::MarkerArray& marker_array)
const;
474 const Eigen::Vector3d& origin,
const std::string& frame_id,
const rclcpp::Time& stamp,
475 visualization_msgs::msg::Marker& marker)
const;
492 void getProjectionPlanes(
const std::string& frame_id,
const rclcpp::Time& stamp,
double max_distance,
493 visualization_msgs::msg::Marker& marker)
const;
586 void getOcTreePoints(
const octomap::OcTree* octree, EigenSTL::vector_Vector3d* points);
603 void setPoint(
int xCell,
int yCell,
int zCell,
double dist, geometry_msgs::msg::Point& point,
604 std_msgs::msg::ColorRGBA& color,
double max_distance)
const;
#define MOVEIT_CLASS_FORWARD(C)
DistanceField is an abstract base class for computing distances from sets of 3D obstacle points....
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...
double size_z_
Z size of the distance field.
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 ...
double origin_z_
Z origin of the distance field.
void removeShapeFromField(const shapes::Shape *shape, const Eigen::Isometry3d &pose)
All points corresponding to the shape are removed from the distance field.
double getOriginY() const
Gets the origin (minimum value) along the Y dimension.
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 void reset()=0
Resets all points in the distance field to an uninitialize value.
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...
virtual bool readFromStream(std::istream &stream)=0
Reads, parameterizes, and populates the distance field based on the supplied stream.
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...
virtual double getDistance(int x, int y, int z) const =0
Gets the distance to the closest obstacle at the given integer cell location. The particulars of this...
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.
double getOriginZ() const
Gets the origin (minimum value) along the Z dimension.
virtual bool writeToStream(std::ostream &stream) const =0
Writes the contents of the distance field to the supplied stream.
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...
double getOriginX() const
Gets the origin (minimum value) along the X dimension.
double origin_x_
X origin of the distance field.
double size_y_
Y size of the distance field.
double getSizeX() const
Gets the distance field size along the X dimension in meters.
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 ...
double size_x_
X size of the distance field.
void getOcTreePoints(const octomap::OcTree *octree, EigenSTL::vector_Vector3d *points)
Get the points associated with an octree.
double getSizeY() const
Gets the distance field size along the Y dimension in meters.
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.
double getSizeZ() const
Gets the distance field size along the Z dimension in meters.
double origin_y_
Y origin of the distance field.
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.
PlaneVisualizationType
The plane to visualize.