00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #ifndef COSTMAP_COSTMAP_2D_ROS_H_
00038 #define COSTMAP_COSTMAP_2D_ROS_H_
00039
00040 #include <XmlRpc.h>
00041 #include <ros/ros.h>
00042 #include <ros/console.h>
00043 #include <costmap_2d/costmap_2d.h>
00044 #include <costmap_2d/costmap_2d_publisher.h>
00045 #include <costmap_2d/observation_buffer.h>
00046 #include <costmap_2d/voxel_costmap_2d.h>
00047 #include <costmap_2d/VoxelGrid.h>
00048 #include <nav_msgs/OccupancyGrid.h>
00049 #include <map>
00050 #include <vector>
00051 #include <string>
00052 #include <sstream>
00053
00054 #include <tf/transform_datatypes.h>
00055
00056 #include <tf/message_filter.h>
00057 #include <message_filters/subscriber.h>
00058
00059 #include <tf/transform_listener.h>
00060
00061 #include <sensor_msgs/LaserScan.h>
00062 #include <laser_geometry/laser_geometry.h>
00063
00064 #include <sensor_msgs/PointCloud.h>
00065
00066
00067 #include <sensor_msgs/PointCloud2.h>
00068
00069
00070 #include <boost/thread.hpp>
00071 #include <boost/shared_ptr.hpp>
00072
00073 namespace costmap_2d {
00074
00081 class Costmap2DROS {
00082 public:
00088 Costmap2DROS(std::string name, tf::TransformListener& tf);
00089
00093 ~Costmap2DROS();
00094
00101 void addObservationBuffer(const boost::shared_ptr<ObservationBuffer>& buffer);
00102
00108 bool getMarkingObservations(std::vector<Observation>& marking_observations) const;
00109
00115 bool getClearingObservations(std::vector<Observation>& clearing_observations) const;
00116
00121 void updateMap();
00122
00130 void getOrientedFootprint(double x, double y, double theta, std::vector<geometry_msgs::Point>& oriented_footprint) const;
00131
00136 void getOrientedFootprint(std::vector<geometry_msgs::Point>& oriented_footprint) const;
00137
00143 bool getRobotPose(tf::Stamped<tf::Pose>& global_pose) const;
00144
00148 void clearRobotFootprint();
00149
00154 void clearRobotFootprint(const tf::Stamped<tf::Pose>& global_pose);
00155
00162 bool setConvexPolygonCost(const std::vector<geometry_msgs::Point>& polygon, unsigned char cost_value);
00163
00169 void resetMapOutsideWindow(double size_x, double size_y);
00170
00176 void clearNonLethalWindow(double size_x, double size_y);
00177
00182 void getCostmapCopy(Costmap2D& costmap) const;
00183
00190 void updateStaticMap(const nav_msgs::OccupancyGrid& new_map);
00191
00200 void getCostmapWindowCopy(double win_size_x, double win_size_y, Costmap2D& costmap) const;
00201
00212 void getCostmapWindowCopy(double win_center_x, double win_center_y, double win_size_x, double win_size_y, Costmap2D& costmap) const;
00213
00218 unsigned int getSizeInCellsX() const;
00219
00224 unsigned int getSizeInCellsY() const;
00225
00230 double getResolution() const;
00231
00236 std::string getGlobalFrameID() const;
00237
00242 std::string getBaseFrameID() const;
00243
00248 double getInscribedRadius() const;
00249
00254 double getCircumscribedRadius() const;
00255
00260 double getInflationRadius() const;
00261
00266 std::vector<geometry_msgs::Point> getRobotFootprint() const;
00267
00272 bool isCurrent() {return current_;}
00273
00279 void start();
00280
00284 void stop();
00285
00286
00290 void pause() {
00291 stop_updates_ = true;
00292 initialized_ = false;
00293 }
00294
00295
00299 void resume(){
00300 stop_updates_ = false;
00301
00302
00303 ros::Rate r(100.0);
00304 while(!initialized_)
00305 r.sleep();
00306 }
00307
00308 private:
00315 void incomingMap(const nav_msgs::OccupancyGridConstPtr& new_map);
00316
00321 void initFromMap(const nav_msgs::OccupancyGrid& map);
00322
00328 void laserScanCallback(const sensor_msgs::LaserScanConstPtr& message, const boost::shared_ptr<ObservationBuffer>& buffer);
00329
00335 void pointCloudCallback(const sensor_msgs::PointCloudConstPtr& message, const boost::shared_ptr<ObservationBuffer>& buffer);
00336
00342 void pointCloud2Callback(const sensor_msgs::PointCloud2ConstPtr& message, const boost::shared_ptr<ObservationBuffer>& buffer);
00343
00348 void mapUpdateLoop(double frequency);
00349
00353 std::vector<geometry_msgs::Point> loadRobotFootprint(ros::NodeHandle node, double inscribed_radius, double circumscribed_radius);
00354
00358 double distanceToLine(double pX, double pY, double x0, double y0, double x1, double y1);
00359
00360 inline double distance(double x0, double y0, double x1, double y1){
00361 return sqrt((x1 - x0) * (x1 - x0) + (y1 - y0) * (y1 - y0));
00362 }
00363
00364 std::string name_;
00365 tf::TransformListener& tf_;
00366 laser_geometry::LaserProjection projector_;
00367 Costmap2D* costmap_;
00368 std::string global_frame_;
00369 std::string robot_base_frame_;
00370 boost::thread* map_update_thread_;
00371
00372 std::vector<boost::shared_ptr<tf::MessageFilterBase> > observation_notifiers_;
00373 std::vector<boost::shared_ptr<message_filters::SubscriberBase> > observation_subscribers_;
00374 std::vector<boost::shared_ptr<ObservationBuffer> > observation_buffers_;
00375 std::vector<boost::shared_ptr<ObservationBuffer> > marking_buffers_;
00376 std::vector<boost::shared_ptr<ObservationBuffer> > clearing_buffers_;
00377 bool rolling_window_;
00378 bool current_;
00379 double transform_tolerance_;
00380 Costmap2DPublisher* costmap_publisher_;
00381 bool stop_updates_, initialized_, stopped_;
00382 bool publish_voxel_;
00383 std::vector<geometry_msgs::Point> footprint_spec_;
00384 ros::Publisher voxel_pub_;
00385 mutable boost::recursive_mutex lock_;
00386 bool map_update_thread_shutdown_;
00387 bool save_debug_pgm_;
00388 ros::Subscriber map_sub_;
00389 bool map_initialized_;
00390 std::string tf_prefix_;
00391
00392
00393
00394
00395
00396 boost::recursive_mutex map_data_lock_;
00397 nav_msgs::MapMetaData map_meta_data_;
00398 std::vector<unsigned char> input_data_;
00399 bool costmap_initialized_;
00400
00401
00402 };
00403 };
00404
00405 #endif
00406