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_PUBLISHER_H_
00038 #define COSTMAP_COSTMAP_2D_PUBLISHER_H_
00039 #include <ros/ros.h>
00040 #include <ros/console.h>
00041 #include <costmap_2d/costmap_2d.h>
00042 #include <nav_msgs/GridCells.h>
00043 #include <boost/thread.hpp>
00044 #include <tf/transform_datatypes.h>
00045
00046 namespace costmap_2d {
00051 class Costmap2DPublisher {
00052 public:
00058 Costmap2DPublisher(ros::NodeHandle ros_node, double publish_frequency, std::string global_frame);
00059
00063 ~Costmap2DPublisher();
00064
00068 void publishFootprint();
00069
00073 void publishCostmap();
00074
00080 void updateCostmapData(const Costmap2D& costmap,
00081 const std::vector<geometry_msgs::Point>& footprint = std::vector<geometry_msgs::Point>(),
00082 const tf::Stamped<tf::Pose>& global_pose = tf::Stamped<tf::Pose>());
00083
00088 bool active() {return active_;}
00089
00090 private:
00091 void mapPublishLoop(double frequency);
00092
00093 std::string global_frame_;
00094 boost::thread* visualizer_thread_;
00095 std::vector< std::pair<double, double> > raw_obstacles_, inflated_obstacles_, unknown_space_;
00096 boost::recursive_mutex lock_;
00097 bool active_, new_data_;
00098 ros::Publisher obs_pub_, inf_obs_pub_, unknown_space_pub_, footprint_pub_;
00099 double resolution_, inscribed_radius_;
00100 std::vector<geometry_msgs::Point> footprint_;
00101 tf::Stamped<tf::Pose> global_pose_;
00102 bool visualizer_thread_shutdown_;
00103 };
00104 };
00105 #endif