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;
92 unsigned int data_index = 0;
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;
189 NumericType denominator = max_value - min_value;
190 if (denominator == 0)
195 unsigned int data_index = 0;
206 template<
typename NumericType>
208 const std::vector<NumericType>& cost_interpretation_table)
212 if (info != current_info)
217 unsigned int data_index = 0;
223 nav_grid_pub_sub::interpretCost<NumericType, unsigned char>(msg.data[data_index++], cost_interpretation_table);
232 template<
typename NumericType>
235 const std::vector<NumericType>& cost_interpretation_table)
240 unsigned int data_index = 0;
246 nav_grid_pub_sub::interpretCost<NumericType, unsigned char>(
update.data[data_index++], cost_interpretation_table);
254 #endif // NAV_GRID_PUB_SUB_OCC_GRID_MESSAGE_UTILS_H