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_2d_msgs/NavGridOfDoubles.h> 44 #include <nav_2d_msgs/NavGridOfDoublesUpdate.h> 45 #include <nav_msgs/OccupancyGrid.h> 46 #include <map_msgs/OccupancyGridUpdate.h> 55 template<
typename NumericType,
typename NavGr
idOfX,
typename NavGr
idOfXUpdate>
63 bool nav_grid =
true,
bool subscribe_to_updates =
true)
165 #endif // NAV_GRID_PUB_SUB_NAV_GRID_SUBSCRIBER_H
void setCostInterpretation(const std::vector< NumericType > &cost_interpretation_table)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
bool subscribe_to_updates_
std::string resolveName(const std::string &name, bool remap=true) const
NewDataCallback callback_
ros::Subscriber update_sub_
void fromOccupancyGrid(const nav_msgs::OccupancyGrid &msg, nav_grid::NavGrid< NumericType > &grid, const std::vector< NumericType > &cost_interpretation_table)
generic OccupancyGrid to NavGrid conversion using cost_interpretation_table
void incomingNav(const NavGridOfX &new_map)
void incomingOcc(const nav_msgs::OccupancyGridConstPtr &new_map)
std::vector< NumericType > cost_interpretation_table_
std::function< void(const nav_core2::UIntBounds &)> NewDataCallback
void incomingOccUpdate(const map_msgs::OccupancyGridUpdateConstPtr &update)
nav_core2::UIntBounds fromOccupancyGridUpdate(const map_msgs::OccupancyGridUpdate &update, nav_grid::NavGrid< NumericType > &grid, const std::vector< NumericType > &cost_interpretation_table)
generic OccupancyGridUpdate to NavGrid conversion using cost_interpretation_table.
void init(ros::NodeHandle &nh, NewDataCallback callback, const std::string &topic="map", bool nav_grid=true, bool subscribe_to_updates=true)
nav_grid::NavGrid< NumericType > & data_
NavGridInfo getInfo() const
nav_core2::UIntBounds getFullUIntBounds(const nav_grid::NavGridInfo &info)
void fromMsg(const ROSMsgType &msg, nav_grid::NavGrid< NumericType > &grid)
Generic conversion from message of arbitrary type to grid of arbitrary type.
void incomingNavUpdate(const NavGridOfXUpdate &update)
nav_core2::UIntBounds fromUpdate(const ROSMsgType &update, nav_grid::NavGrid< NumericType > &grid)
Generic conversion from an update message to a portion of a grid of arbitrary type.
GenericNavGridSubscriber(nav_grid::NavGrid< NumericType > &data)