35 #ifndef NAV_GRID_PUB_SUB_NAV_GRID_SUBSCRIBER_H 36 #define NAV_GRID_PUB_SUB_NAV_GRID_SUBSCRIBER_H 41 #include <nav_2d_msgs/NavGridOfChars.h> 42 #include <nav_2d_msgs/NavGridOfCharsUpdate.h> 43 #include <nav_msgs/OccupancyGrid.h> 44 #include <map_msgs/OccupancyGridUpdate.h> 57 bool nav_grid =
true,
bool subscribe_to_updates =
true);
67 void incomingNav(
const nav_2d_msgs::NavGridOfCharsConstPtr& new_map);
70 void incomingOcc(
const nav_msgs::OccupancyGridConstPtr& new_map);
87 #endif // NAV_GRID_PUB_SUB_NAV_GRID_SUBSCRIBER_H void incomingNav(const nav_2d_msgs::NavGridOfCharsConstPtr &new_map)
bool subscribe_to_updates_
void setCostInterpretation(const std::vector< unsigned char > &cost_interpretation_table)
void incomingOccUpdate(const map_msgs::OccupancyGridUpdateConstPtr &update)
std::vector< unsigned char > cost_interpretation_table_
void init(ros::NodeHandle &nh, NewDataCallback callback, const std::string &topic="map", bool nav_grid=true, bool subscribe_to_updates=true)
NewDataCallback callback_
void update(const std::string &key, const XmlRpc::XmlRpcValue &v)
void incomingOcc(const nav_msgs::OccupancyGridConstPtr &new_map)
ros::Subscriber update_sub_
void incomingNavUpdate(const nav_2d_msgs::NavGridOfCharsUpdateConstPtr &update)
NavGridSubscriber(nav_grid::NavGrid< unsigned char > &data)
std::function< void(const nav_core2::UIntBounds &)> NewDataCallback
nav_grid::NavGrid< unsigned char > & data_