46 bool nav_grid,
bool subscribe_to_updates)
88 if (info != current_info)
93 unsigned int data_index = 0;
106 unsigned int data_index = 0;
118 if (info != current_info)
123 unsigned int data_index = 0;
136 nav_core2::UIntBounds bounds(update->x, update->y, update->x + update->width - 1, update->y + update->height - 1);
137 unsigned int data_index = 0;
void incomingNav(const nav_2d_msgs::NavGridOfCharsConstPtr &new_map)
virtual void setValue(const unsigned int x, const unsigned int y, const T &value)=0
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
std::string resolveName(const std::string &name, bool remap=true) const
bool subscribe_to_updates_
nav_grid::NavGridInfo fromMsg(const nav_2d_msgs::NavGridInfo &msg)
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 incomingOcc(const nav_msgs::OccupancyGridConstPtr &new_map)
ros::Subscriber update_sub_
void incomingNavUpdate(const nav_2d_msgs::NavGridOfCharsUpdateConstPtr &update)
unsigned char interpretCost(unsigned char original_value, const std::vector< unsigned char > &cost_interpretation_table)
return cost_interpretation_table[original_value] (or original_value if not a valid index) ...
virtual void setInfo(const NavGridInfo &new_info)=0
NavGridInfo getInfo() const
nav_grid::NavGridInfo infoToInfo(const nav_msgs::MapMetaData &metadata)
std::function< void(const nav_core2::UIntBounds &)> NewDataCallback
nav_grid::NavGrid< unsigned char > & data_