35 #ifndef NAV_GRID_PUB_SUB_OCC_GRID_MESSAGE_UTILS_H 36 #define NAV_GRID_PUB_SUB_OCC_GRID_MESSAGE_UTILS_H 40 #include <nav_msgs/OccupancyGrid.h> 41 #include <map_msgs/OccupancyGridUpdate.h> 58 const std::vector<unsigned char> cost_interpretation_table = std::vector<unsigned char>())
60 nav_msgs::OccupancyGrid ogrid;
63 ogrid.header.stamp = stamp;
67 unsigned int data_index = 0;
70 ogrid.data[data_index++] =
interpretCost(grid(index), cost_interpretation_table);
80 const std::vector<unsigned char> cost_interpretation_table = std::vector<unsigned char>())
82 map_msgs::OccupancyGridUpdate
update;
84 update.header.stamp = stamp;
90 update.data.resize(update.width * update.height);
92 unsigned int data_index = 0;
95 update.data[data_index++] =
interpretCost(grid(index), cost_interpretation_table);
107 template<
typename NumericType>
109 const NumericType min_value,
const NumericType max_value,
110 const NumericType unknown_value,
113 nav_msgs::OccupancyGrid ogrid;
116 ogrid.header.stamp = stamp;
120 NumericType denominator = max_value - min_value;
121 if (denominator == 0)
126 unsigned int data_index = 0;
129 ogrid.data[data_index++] =
interpretValue(grid(index), min_value, denominator, unknown_value);
137 template<
typename NumericType>
139 NumericType& min_val, NumericType& max_val)
141 max_val = std::numeric_limits<NumericType>::min();
142 min_val = std::numeric_limits<NumericType>::max();
146 const NumericType& value = grid(index);
147 if (value == unknown_value)
continue;
148 max_val = std::max(value, max_val);
149 min_val = std::min(value, min_val);
158 template<
typename NumericType>
160 const NumericType unknown_value = std::numeric_limits<NumericType>::max(),
163 NumericType min_val, max_val;
173 template<
typename NumericType>
176 const NumericType min_value,
const NumericType max_value,
177 const NumericType unknown_value,
180 map_msgs::OccupancyGridUpdate
update;
182 update.header.stamp = stamp;
188 update.data.resize(update.width * update.height);
189 NumericType denominator = max_value - min_value;
190 if (denominator == 0)
195 unsigned int data_index = 0;
198 update.data[data_index++] =
interpretValue(grid(index), min_value, denominator, unknown_value);
205 #endif // NAV_GRID_PUB_SUB_OCC_GRID_MESSAGE_UTILS_H unsigned int getMinX() const
unsigned int getMinY() const
unsigned char interpretValue(const NumericType value, const NumericType min_value, const NumericType denominator, const NumericType unknown_value)
Scale the given value to fit within [0, 100] (unless its ignore_value, then its -1) ...
void update(const std::string &key, const XmlRpc::XmlRpcValue &v)
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) ...
NavGridInfo getInfo() const
unsigned int getHeight() const
map_msgs::OccupancyGridUpdate toOccupancyGridUpdate(const nav_grid::NavGrid< unsigned char > &grid, const nav_core2::UIntBounds &bounds, const ros::Time &stamp=ros::Time(0), const std::vector< unsigned char > cost_interpretation_table=std::vector< unsigned char >())
NavGrid<unsigned char> to OccupancyGridUpdate using cost_interpretation_table.
unsigned int getWidth() const
nav_grid::NavGridInfo infoToInfo(const nav_msgs::MapMetaData &metadata)
void getExtremeValues(const nav_grid::NavGrid< NumericType > &grid, const NumericType unknown_value, NumericType &min_val, NumericType &max_val)
Retrieve the minimum and maximum values from a grid, ignoring the unknown_value.
nav_msgs::OccupancyGrid toOccupancyGrid(const nav_grid::NavGrid< unsigned char > &grid, const ros::Time &stamp=ros::Time(0), const std::vector< unsigned char > cost_interpretation_table=std::vector< unsigned char >())
NavGrid<unsigned char> to OccupancyGrid using cost_interpretation_table.