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_2D_COSTMAP_2D_PUBLISHER_H_
00039 #define COSTMAP_2D_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,
00059 std::string topic_name, bool always_send_full_costmap = false);
00060
00064 ~Costmap2DPublisher();
00065
00067 void updateBounds(unsigned int x0, unsigned int xn, unsigned int y0, unsigned int yn)
00068 {
00069 x0_ = std::min(x0, x0_);
00070 xn_ = std::max(xn, xn_);
00071 y0_ = std::min(y0, y0_);
00072 yn_ = std::max(yn, yn_);
00073 }
00074
00078 void publishCostmap();
00079
00084 bool active()
00085 {
00086 return active_;
00087 }
00088
00089 private:
00091 void prepareGrid();
00092
00094 void onNewSubscription(const ros::SingleSubscriberPublisher& pub);
00095
00096 ros::NodeHandle* node;
00097 Costmap2D* costmap_;
00098 std::string global_frame_;
00099 unsigned int x0_, xn_, y0_, yn_;
00100 double saved_origin_x_, saved_origin_y_;
00101 bool active_;
00102 bool always_send_full_costmap_;
00103 ros::Publisher costmap_pub_;
00104 ros::Publisher costmap_update_pub_;
00105 nav_msgs::OccupancyGrid grid_;
00106 static char* cost_translation_table_;
00107 };
00108 }
00109 #endif // COSTMAP_2D_COSTMAP_2D_PUBLISHER_H
costmap_2d
Author(s): Eitan Marder-Eppstein, David V. Lu!!, Dave Hershberger, contradict@gmail.com
autogenerated on Sun Mar 3 2019 03:46:15