Go to the documentation of this file.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 <ros/ros.h>
00041
00042 #include <costmap_2d/costmap_2d.h>
00043 #include <costmap_2d/costmap_2d_publisher.h>
00044 #include <costmap_2d/observation_buffer.h>
00045
00046 #include <nav_msgs/OccupancyGrid.h>
00047
00048 #include <vector>
00049 #include <string>
00050
00051
00052 #include <boost/algorithm/string.hpp>
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 #include <stdlib.h>
00074 #include <dynamic_reconfigure/server.h>
00075 #include <costmap_2d/Costmap2DConfig.h>
00076
00077 namespace costmap_2d {
00078
00085 class Costmap2DROS {
00086 public:
00092 Costmap2DROS(std::string name, tf::TransformListener& tf);
00093
00097 ~Costmap2DROS();
00098
00105 void addObservationBuffer(const boost::shared_ptr<ObservationBuffer>& buffer);
00106
00112 bool getMarkingObservations(std::vector<Observation>& marking_observations) const;
00113
00119 bool getClearingObservations(std::vector<Observation>& clearing_observations) const;
00120
00125 void updateMap();
00126
00134 void getOrientedFootprint(double x, double y, double theta, std::vector<geometry_msgs::Point>& oriented_footprint) const;
00135
00140 void getOrientedFootprint(std::vector<geometry_msgs::Point>& oriented_footprint) const;
00141
00147 bool getRobotPose(tf::Stamped<tf::Pose>& global_pose) const;
00148
00152 void clearRobotFootprint();
00153
00158 void clearRobotFootprint(const tf::Stamped<tf::Pose>& global_pose);
00159
00166 bool setConvexPolygonCost(const std::vector<geometry_msgs::Point>& polygon, unsigned char cost_value);
00167
00173 void resetMapOutsideWindow(double size_x, double size_y);
00174
00180 void clearNonLethalWindow(double size_x, double size_y);
00181
00186 void getCostmapCopy(Costmap2D& costmap) const;
00187
00194 void updateStaticMap(const nav_msgs::OccupancyGrid& new_map);
00195
00204 void getCostmapWindowCopy(double win_size_x, double win_size_y, Costmap2D& costmap) const;
00205
00216 void getCostmapWindowCopy(double win_center_x, double win_center_y, double win_size_x, double win_size_y, Costmap2D& costmap) const;
00217
00222 unsigned int getSizeInCellsX() const;
00223
00228 unsigned int getSizeInCellsY() const;
00229
00234 double getResolution() const;
00235
00240 std::string getGlobalFrameID() const;
00241
00246 std::string getBaseFrameID() const;
00247
00252 double getInscribedRadius() const;
00253
00258 double getCircumscribedRadius() const;
00259
00264 double getInflationRadius() const;
00265
00270 std::vector<geometry_msgs::Point> getRobotFootprint() const;
00271
00276 bool isCurrent() {return current_;}
00277
00283 void start();
00284
00288 void stop();
00289
00290
00294 void pause() {
00295 stop_updates_ = true;
00296 initialized_ = false;
00297 }
00298
00299
00303 void resume(){
00304 stop_updates_ = false;
00305
00306
00307 ros::Rate r(100.0);
00308 while(!initialized_)
00309 r.sleep();
00310 }
00311
00312 private:
00316 void reconfigureCB(costmap_2d::Costmap2DConfig &config, uint32_t level);
00317
00318 void movementCB(const ros::TimerEvent &event);
00319
00326 void incomingMap(const nav_msgs::OccupancyGridConstPtr& new_map);
00327
00332 void initFromMap(const nav_msgs::OccupancyGrid& map);
00333
00339 void laserScanCallback(const sensor_msgs::LaserScanConstPtr& message, const boost::shared_ptr<ObservationBuffer>& buffer);
00340
00346 void laserScanValidInfCallback(const sensor_msgs::LaserScanConstPtr& message, const boost::shared_ptr<ObservationBuffer>& buffer);
00347
00353 void pointCloudCallback(const sensor_msgs::PointCloudConstPtr& message, const boost::shared_ptr<ObservationBuffer>& buffer);
00354
00360 void pointCloud2Callback(const sensor_msgs::PointCloud2ConstPtr& message, const boost::shared_ptr<ObservationBuffer>& buffer);
00361
00366 void mapUpdateLoop(double frequency);
00367
00371 std::vector<geometry_msgs::Point> loadRobotFootprint(ros::NodeHandle node, double inscribed_radius, double circumscribed_radius);
00372
00376 double distanceToLine(double pX, double pY, double x0, double y0, double x1, double y1);
00377
00378 inline double distance(double x0, double y0, double x1, double y1){
00379 return sqrt((x1 - x0) * (x1 - x0) + (y1 - y0) * (y1 - y0));
00380 }
00381
00382 std::string name_;
00383 tf::TransformListener& tf_;
00384 laser_geometry::LaserProjection projector_;
00385 Costmap2D* costmap_;
00386 std::string global_frame_;
00387 std::string robot_base_frame_;
00388 boost::thread* map_update_thread_;
00389
00390 std::vector<boost::shared_ptr<tf::MessageFilterBase> > observation_notifiers_;
00391 std::vector<boost::shared_ptr<message_filters::SubscriberBase> > observation_subscribers_;
00392 std::vector<boost::shared_ptr<ObservationBuffer> > observation_buffers_;
00393 std::vector<boost::shared_ptr<ObservationBuffer> > marking_buffers_;
00394 std::vector<boost::shared_ptr<ObservationBuffer> > clearing_buffers_;
00395 bool rolling_window_;
00396 bool current_;
00397 double transform_tolerance_;
00398 Costmap2DPublisher* costmap_publisher_;
00399 bool stop_updates_, initialized_, stopped_;
00400 bool publish_voxel_;
00401 std::vector<geometry_msgs::Point> footprint_spec_;
00402 ros::Publisher voxel_pub_;
00403 mutable boost::recursive_mutex lock_;
00404 bool map_update_thread_shutdown_;
00405 bool save_debug_pgm_;
00406 ros::Subscriber map_sub_;
00407 bool map_initialized_;
00408 std::string tf_prefix_;
00409
00410
00411
00412
00413
00414 boost::recursive_mutex map_data_lock_;
00415 nav_msgs::MapMetaData map_meta_data_;
00416 std::vector<unsigned char> input_data_;
00417 bool costmap_initialized_;
00418
00419 bool robot_stopped_, setup_, static_map_;
00420
00421 dynamic_reconfigure::Server<costmap_2d::Costmap2DConfig> *dsrv_;
00422 boost::mutex map_update_mutex_;
00423 boost::recursive_mutex configuration_mutex_;
00424 costmap_2d::Costmap2DConfig last_config_;
00425 costmap_2d::Costmap2DConfig maptype_config_;
00426 costmap_2d::Costmap2DConfig default_config_;
00427 ros::Timer timer_;
00428 tf::Stamped<tf::Pose> old_pose_;
00429 };
00430 };
00431
00432 #endif
00433