moveit2
The MoveIt Motion Planning Framework for ROS 2.
distance_field.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2009, 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 
37 #pragma once
38 
41 #include <visualization_msgs/msg/marker.hpp>
42 #include <visualization_msgs/msg/marker_array.hpp>
43 #include <Eigen/Core>
44 #include <Eigen/Geometry>
45 #include <eigen_stl_containers/eigen_stl_containers.h>
47 #include <rclcpp/rclcpp.hpp>
48 
49 namespace shapes
50 {
51 MOVEIT_CLASS_FORWARD(Shape); // Defines ShapePtr, ConstPtr, WeakPtr... etc
52 }
53 namespace octomap
54 {
55 class OcTree;
56 }
57 
65 namespace distance_field
66 {
69 {
72  YZ_PLANE
73 };
74 
75 MOVEIT_CLASS_FORWARD(DistanceField); // Defines DistanceFieldPtr, ConstPtr, WeakPtr... etc
76 
93 {
94 public:
107  DistanceField(double size_x, double size_y, double size_z, double resolution, double origin_x, double origin_y,
108  double origin_z);
109 
110  virtual ~DistanceField();
111 
119  virtual void addPointsToField(const EigenSTL::vector_Vector3d& points) = 0;
120 
134  virtual void removePointsFromField(const EigenSTL::vector_Vector3d& points) = 0;
135 
159  virtual void updatePointsInField(const EigenSTL::vector_Vector3d& old_points,
160  const EigenSTL::vector_Vector3d& new_points) = 0;
161 
169  bool getShapePoints(const shapes::Shape* shape, const Eigen::Isometry3d& pose, EigenSTL::vector_Vector3d* points);
170 
189  void addShapeToField(const shapes::Shape* shape, const Eigen::Isometry3d& pose);
190 
191  // DEPRECATED form
192  [[deprecated]] void addShapeToField(const shapes::Shape* shape, const geometry_msgs::msg::Pose& pose);
193 
207  void addOcTreeToField(const octomap::OcTree* octree);
208 
227  void moveShapeInField(const shapes::Shape* shape, const Eigen::Isometry3d& old_pose,
228  const Eigen::Isometry3d& new_pose);
229 
230  // DEPRECATED form
231  [[deprecated]] void moveShapeInField(const shapes::Shape* shape, const geometry_msgs::msg::Pose& old_pose,
232  const geometry_msgs::msg::Pose& new_pose);
233 
243  void removeShapeFromField(const shapes::Shape* shape, const Eigen::Isometry3d& pose);
244 
245  // DEPRECATED form
246  [[deprecated]] void removeShapeFromField(const shapes::Shape* shape, const geometry_msgs::msg::Pose& pose);
247 
252  virtual void reset() = 0;
253 
273  virtual double getDistance(double x, double y, double z) const = 0;
274 
322  double getDistanceGradient(double x, double y, double z, double& gradient_x, double& gradient_y, double& gradient_z,
323  bool& in_bounds) const;
335  virtual double getDistance(int x, int y, int z) const = 0;
336 
347  virtual bool isCellValid(int x, int y, int z) const = 0;
348 
355  virtual int getXNumCells() const = 0;
356 
363  virtual int getYNumCells() const = 0;
364 
371  virtual int getZNumCells() const = 0;
372 
386  virtual bool gridToWorld(int x, int y, int z, double& world_x, double& world_y, double& world_z) const = 0;
387 
404  virtual bool worldToGrid(double world_x, double world_y, double world_z, int& x, int& y, int& z) const = 0;
405 
413  virtual bool writeToStream(std::ostream& stream) const = 0;
414 
424  virtual bool readFromStream(std::istream& stream) = 0;
425 
439  void getIsoSurfaceMarkers(double min_distance, double max_distance, const std::string& frame_id,
440  const rclcpp::Time& stamp, visualization_msgs::msg::Marker& marker) const;
441 
455  void getGradientMarkers(double min_radius, double max_radius, const std::string& frame_id, const rclcpp::Time& stamp,
456  visualization_msgs::msg::MarkerArray& marker_array) const;
457 
483  void getPlaneMarkers(PlaneVisualizationType type, double length, double width, double height,
484  const Eigen::Vector3d& origin, const std::string& frame_id, const rclcpp::Time& stamp,
485  visualization_msgs::msg::Marker& marker) const;
502  void getProjectionPlanes(const std::string& frame_id, const rclcpp::Time& stamp, double max_distance,
503  visualization_msgs::msg::Marker& marker) const;
504 
511  double getSizeX() const
512  {
513  return size_x_;
514  }
515 
522  double getSizeY() const
523  {
524  return size_y_;
525  }
526 
533  double getSizeZ() const
534  {
535  return size_z_;
536  }
537 
544  double getOriginX() const
545  {
546  return origin_x_;
547  }
548 
555  double getOriginY() const
556  {
557  return origin_y_;
558  }
559 
566  double getOriginZ() const
567  {
568  return origin_z_;
569  }
570 
577  double getResolution() const
578  {
579  return resolution_;
580  }
581 
588  virtual double getUninitializedDistance() const = 0;
589 
590 protected:
596  void getOcTreePoints(const octomap::OcTree* octree, EigenSTL::vector_Vector3d* points);
597 
613  void setPoint(int xCell, int yCell, int zCell, double dist, geometry_msgs::msg::Point& point,
614  std_msgs::msg::ColorRGBA& color, double max_distance) const;
615 
616  double size_x_;
617  double size_y_;
618  double size_z_;
619  double origin_x_;
620  double origin_y_;
621  double origin_z_;
622  double resolution_;
624 };
625 
626 } // namespace distance_field
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.
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...
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.
MOVEIT_CLASS_FORWARD(DistanceField)
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
Definition: world.h:49
MOVEIT_CLASS_FORWARD(Shape)