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
00038 #ifndef COSTMAP_COSTMAP_2D_PUBLISHER_H_
00039 #define COSTMAP_COSTMAP_2D_PUBLISHER_H_
00040 #include <ros/ros.h>
00041 #include <costmap_2d/costmap_2d.h>
00042 #include <nav_msgs/OccupancyGrid.h>
00043 #include <map_msgs/OccupancyGridUpdate.h>
00044 #include <tf/transform_datatypes.h>
00045
00046 namespace costmap_2d
00047 {
00052 class Costmap2DPublisher
00053 {
00054 public:
00058 Costmap2DPublisher(ros::NodeHandle * ros_node, Costmap2D* costmap, std::string global_frame, std::string topic_name, bool always_send_full_costmap = false);
00059
00063 ~Costmap2DPublisher();
00064
00066 void updateBounds(unsigned int x0, unsigned int xn, unsigned int y0, unsigned int yn)
00067 {
00068 x0_ = std::min(x0, x0_);
00069 xn_ = std::max(xn, xn_);
00070 y0_ = std::min(y0, y0_);
00071 yn_ = std::max(yn, yn_);
00072 }
00073
00077 void publishCostmap();
00078
00083 bool active()
00084 {
00085 return active_;
00086 }
00087
00088 private:
00090 void prepareGrid();
00091
00093 void onNewSubscription( const ros::SingleSubscriberPublisher& pub );
00094
00095 ros::NodeHandle* node;
00096 Costmap2D* costmap_;
00097 std::string global_frame_;
00098 unsigned int x0_, xn_, y0_, yn_;
00099 bool active_;
00100 bool always_send_full_costmap_;
00101 ros::Publisher costmap_pub_;
00102 ros::Publisher costmap_update_pub_;
00103 nav_msgs::OccupancyGrid grid_;
00104 static char* cost_translation_table_;
00105 };
00106 }
00107 #endif
costmap_2d
Author(s): Eitan Marder-Eppstein, David V. Lu!!, Dave Hershberger, contradict@gmail.com
autogenerated on Thu Aug 27 2015 14:06:55