35 #ifndef NAV_GRID_PUB_SUB_NAV_GRID_MESSAGE_UTILS_H 36 #define NAV_GRID_PUB_SUB_NAV_GRID_MESSAGE_UTILS_H 39 #include <nav_2d_msgs/NavGridOfChars.h> 40 #include <nav_2d_msgs/NavGridOfCharsUpdate.h> 41 #include <nav_2d_msgs/NavGridOfDoubles.h> 42 #include <nav_2d_msgs/NavGridOfDoublesUpdate.h> 58 template<
typename ROSMsgType,
typename NumericType>
68 unsigned int data_index = 0;
71 msg.data[data_index++] = grid(index);
81 template<
typename ROSMsgType,
typename NumericType>
90 unsigned int data_index = 0;
94 update.data[data_index++] = grid(index);
105 return toMsg<nav_2d_msgs::NavGridOfChars>(grid, stamp);
113 return toMsg<nav_2d_msgs::NavGridOfDoubles>(grid, stamp);
121 return toMsg<nav_2d_msgs::NavGridOfDoubles>(grid, stamp);
130 return toUpdate<nav_2d_msgs::NavGridOfCharsUpdate>(grid, bounds, stamp);
139 return toUpdate<nav_2d_msgs::NavGridOfDoublesUpdate>(grid, bounds, stamp);
148 return toUpdate<nav_2d_msgs::NavGridOfDoublesUpdate>(grid, bounds, stamp);
154 #endif // NAV_GRID_PUB_SUB_NAV_GRID_MESSAGE_UTILS_H ROSMsgType toUpdate(const nav_grid::NavGrid< NumericType > &grid, const nav_core2::UIntBounds &bounds, const ros::Time &stamp)
Generic conversion from a portion of a grid of arbitrary type to an update message of arbitrary type...
nav_2d_msgs::NavGridInfo toMsg(const nav_grid::NavGridInfo &info)
void update(const std::string &key, const XmlRpc::XmlRpcValue &v)
NavGridInfo getInfo() const
unsigned int getHeight() const
unsigned int getWidth() const
ROSMsgType toMsg(const nav_grid::NavGrid< NumericType > &grid, const ros::Time &stamp)
Utilities for converting NavGrid objects to NavGridOfX messages and updates.