distance_field.h
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2009, Willow Garage, Inc.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of Willow Garage nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *********************************************************************/
00034 
00035 /* Author: Mrinal Kalakrishnan, Ken Anderson, E. Gil Jones */
00036 
00037 #ifndef MOVEIT_DISTANCE_FIELD_DISTANCE_FIELD_H
00038 #define MOVEIT_DISTANCE_FIELD_DISTANCE_FIELD_H
00039 
00040 #include <moveit/macros/class_forward.h>
00041 #include <moveit/macros/deprecation.h>
00042 #include <moveit/distance_field/voxel_grid.h>
00043 #include <vector>
00044 #include <list>
00045 #include <visualization_msgs/Marker.h>
00046 #include <visualization_msgs/MarkerArray.h>
00047 #include <Eigen/Core>
00048 #include <Eigen/Geometry>
00049 #include <eigen_stl_containers/eigen_stl_containers.h>
00050 #include <geometric_shapes/shapes.h>
00051 
00059 namespace distance_field
00060 {
00062 enum PlaneVisualizationType
00063 {
00064   XYPlane,
00065   XZPlane,
00066   YZPlane
00067 };
00068 
00069 MOVEIT_CLASS_FORWARD(DistanceField);
00070 
00086 class DistanceField
00087 {
00088 public:
00101   DistanceField(double size_x, double size_y, double size_z, double resolution, double origin_x, double origin_y,
00102                 double origin_z);
00103 
00104   virtual ~DistanceField();
00105 
00113   virtual void addPointsToField(const EigenSTL::vector_Vector3d& points) = 0;
00114 
00128   virtual void removePointsFromField(const EigenSTL::vector_Vector3d& points) = 0;
00129 
00153   virtual void updatePointsInField(const EigenSTL::vector_Vector3d& old_points,
00154                                    const EigenSTL::vector_Vector3d& new_points) = 0;
00155 
00163   bool getShapePoints(const shapes::Shape* shape, const Eigen::Affine3d& pose, EigenSTL::vector_Vector3d* points);
00164 
00183   void addShapeToField(const shapes::Shape* shape, const Eigen::Affine3d& pose);
00184 
00185   // DEPRECATED form
00186   MOVEIT_DEPRECATED void addShapeToField(const shapes::Shape* shape, const geometry_msgs::Pose& pose);
00187 
00201   void addOcTreeToField(const octomap::OcTree* octree);
00202 
00221   void moveShapeInField(const shapes::Shape* shape, const Eigen::Affine3d& old_pose, const Eigen::Affine3d& new_pose);
00222 
00223   // DEPRECATED form
00224   MOVEIT_DEPRECATED void moveShapeInField(const shapes::Shape* shape, const geometry_msgs::Pose& old_pose,
00225                                           const geometry_msgs::Pose& new_pose);
00226 
00236   void removeShapeFromField(const shapes::Shape* shape, const Eigen::Affine3d& pose);
00237 
00238   // DEPRECATED form
00239   MOVEIT_DEPRECATED void removeShapeFromField(const shapes::Shape* shape, const geometry_msgs::Pose& pose);
00240 
00245   virtual void reset() = 0;
00246 
00266   virtual double getDistance(double x, double y, double z) const = 0;
00267 
00315   double getDistanceGradient(double x, double y, double z, double& gradient_x, double& gradient_y, double& gradient_z,
00316                              bool& in_bounds) const;
00328   virtual double getDistance(int x, int y, int z) const = 0;
00329 
00340   virtual bool isCellValid(int x, int y, int z) const = 0;
00341 
00348   virtual int getXNumCells() const = 0;
00349 
00356   virtual int getYNumCells() const = 0;
00357 
00364   virtual int getZNumCells() const = 0;
00365 
00379   virtual bool gridToWorld(int x, int y, int z, double& world_x, double& world_y, double& world_z) const = 0;
00380 
00397   virtual bool worldToGrid(double world_x, double world_y, double world_z, int& x, int& y, int& z) const = 0;
00398 
00406   virtual bool writeToStream(std::ostream& stream) const = 0;
00407 
00417   virtual bool readFromStream(std::istream& stream) = 0;
00418 
00432   void getIsoSurfaceMarkers(double min_distance, double max_distance, const std::string& frame_id,
00433                             const ros::Time stamp, visualization_msgs::Marker& marker) const;
00434 
00448   void getGradientMarkers(double min_radius, double max_radius, const std::string& frame_id, const ros::Time& stamp,
00449                           visualization_msgs::MarkerArray& marker_array) const;
00450 
00476   void getPlaneMarkers(PlaneVisualizationType type, double length, double width, double height,
00477                        const Eigen::Vector3d& origin, const std::string& frame_id, const ros::Time stamp,
00478                        visualization_msgs::Marker& marker) const;
00495   void getProjectionPlanes(const std::string& frame_id, const ros::Time& stamp, double max_distance,
00496                            visualization_msgs::Marker& marker) const;
00497 
00504   double getSizeX() const
00505   {
00506     return size_x_;
00507   }
00508 
00515   double getSizeY() const
00516   {
00517     return size_y_;
00518   }
00519 
00526   double getSizeZ() const
00527   {
00528     return size_z_;
00529   }
00530 
00537   double getOriginX() const
00538   {
00539     return origin_x_;
00540   }
00541 
00548   double getOriginY() const
00549   {
00550     return origin_y_;
00551   }
00552 
00559   double getOriginZ() const
00560   {
00561     return origin_z_;
00562   }
00563 
00570   double getResolution() const
00571   {
00572     return resolution_;
00573   }
00574 
00581   virtual double getUninitializedDistance() const = 0;
00582 
00583 protected:
00589   void getOcTreePoints(const octomap::OcTree* octree, EigenSTL::vector_Vector3d* points);
00590 
00606   void setPoint(int xCell, int yCell, int zCell, double dist, geometry_msgs::Point& point, std_msgs::ColorRGBA& color,
00607                 double max_distance) const;
00608 
00609   double size_x_;            
00610   double size_y_;            
00611   double size_z_;            
00612   double origin_x_;          
00613   double origin_y_;          
00614   double origin_z_;          
00615   double resolution_;        
00616   int inv_twice_resolution_; 
00617 };
00618 
00619 }  // namespace distance_field
00620 
00621 #endif  // MOVEIT_DISTANCE_FIELD_DISTANCE_FIELD_H


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Wed Jun 19 2019 19:23:49