occ_grid_message_utils.h
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2018, Locus Robotics
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of the copyright holder nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  */
34 
35 #ifndef NAV_GRID_PUB_SUB_OCC_GRID_MESSAGE_UTILS_H
36 #define NAV_GRID_PUB_SUB_OCC_GRID_MESSAGE_UTILS_H
37 
40 #include <nav_msgs/OccupancyGrid.h>
41 #include <map_msgs/OccupancyGridUpdate.h>
42 #include <nav_core2/bounds.h>
45 #include <algorithm>
46 #include <limits>
47 #include <vector>
48 
49 
50 namespace nav_grid_pub_sub
51 {
52 
56 inline nav_msgs::OccupancyGrid toOccupancyGrid(const nav_grid::NavGrid<unsigned char>& grid,
57  const ros::Time& stamp = ros::Time(0),
58  const std::vector<unsigned char> cost_interpretation_table = std::vector<unsigned char>())
59 {
60  nav_msgs::OccupancyGrid ogrid;
61  const nav_grid::NavGridInfo& info = grid.getInfo();
62  ogrid.header.frame_id = info.frame_id;
63  ogrid.header.stamp = stamp;
64  ogrid.info = nav_2d_utils::infoToInfo(info);
65  ogrid.data.resize(info.width * info.height);
66 
67  unsigned int data_index = 0;
68  for (const nav_grid::Index& index : nav_grid_iterators::WholeGrid(info))
69  {
70  ogrid.data[data_index++] = interpretCost(grid(index), cost_interpretation_table);
71  }
72  return ogrid;
73 }
74 
78 inline map_msgs::OccupancyGridUpdate toOccupancyGridUpdate(const nav_grid::NavGrid<unsigned char>& grid,
79  const nav_core2::UIntBounds& bounds, const ros::Time& stamp = ros::Time(0),
80  const std::vector<unsigned char> cost_interpretation_table = std::vector<unsigned char>())
81 {
82  map_msgs::OccupancyGridUpdate update;
83  const nav_grid::NavGridInfo& info = grid.getInfo();
84  update.header.stamp = stamp;
85  update.header.frame_id = info.frame_id;
86  update.x = bounds.getMinX();
87  update.y = bounds.getMinY();
88  update.width = bounds.getWidth();
89  update.height = bounds.getHeight();
90  update.data.resize(update.width * update.height);
91 
92  unsigned int data_index = 0;
93  for (const nav_grid::Index& index : nav_grid_iterators::SubGrid(&info, bounds))
94  {
95  update.data[data_index++] = interpretCost(grid(index), cost_interpretation_table);
96  }
97  return update;
98 }
99 
100 
101 
107 template<typename NumericType>
108 nav_msgs::OccupancyGrid toOccupancyGrid(const nav_grid::NavGrid<NumericType>& grid,
109  const NumericType min_value, const NumericType max_value,
110  const NumericType unknown_value,
111  const ros::Time& stamp = ros::Time(0))
112 {
113  nav_msgs::OccupancyGrid ogrid;
114  const nav_grid::NavGridInfo& info = grid.getInfo();
115  ogrid.header.frame_id = info.frame_id;
116  ogrid.header.stamp = stamp;
117  ogrid.info = nav_2d_utils::infoToInfo(info);
118  ogrid.data.resize(info.width * info.height);
119 
120  NumericType denominator = max_value - min_value;
121  if (denominator == 0)
122  {
123  denominator = 1;
124  }
125 
126  unsigned int data_index = 0;
127  for (const nav_grid::Index& index : nav_grid_iterators::WholeGrid(info))
128  {
129  ogrid.data[data_index++] = interpretValue(grid(index), min_value, denominator, unknown_value);
130  }
131  return ogrid;
132 }
133 
137 template<typename NumericType>
138 inline void getExtremeValues(const nav_grid::NavGrid<NumericType>& grid, const NumericType unknown_value,
139  NumericType& min_val, NumericType& max_val)
140 {
141  max_val = std::numeric_limits<NumericType>::min();
142  min_val = std::numeric_limits<NumericType>::max();
143 
144  for (const nav_grid::Index& index : nav_grid_iterators::WholeGrid(grid.getInfo()))
145  {
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);
150  }
151 }
152 
158 template<typename NumericType>
159 nav_msgs::OccupancyGrid toOccupancyGrid(const nav_grid::NavGrid<NumericType>& grid,
160  const NumericType unknown_value = std::numeric_limits<NumericType>::max(),
161  const ros::Time& stamp = ros::Time(0))
162 {
163  NumericType min_val, max_val;
164  getExtremeValues(grid, unknown_value, min_val, max_val);
165  return toOccupancyGrid(grid, min_val, max_val, unknown_value, stamp);
166 }
167 
173 template<typename NumericType>
174 map_msgs::OccupancyGridUpdate toOccupancyGridUpdate(const nav_grid::NavGrid<NumericType>& grid,
175  const nav_core2::UIntBounds& bounds,
176  const NumericType min_value, const NumericType max_value,
177  const NumericType unknown_value,
178  const ros::Time& stamp = ros::Time(0))
179 {
180  map_msgs::OccupancyGridUpdate update;
181  const nav_grid::NavGridInfo& info = grid.getInfo();
182  update.header.stamp = stamp;
183  update.header.frame_id = info.frame_id;
184  update.x = bounds.getMinX();
185  update.y = bounds.getMinY();
186  update.width = bounds.getWidth();
187  update.height = bounds.getHeight();
188  update.data.resize(update.width * update.height);
189  NumericType denominator = max_value - min_value;
190  if (denominator == 0)
191  {
192  denominator = 1;
193  }
194 
195  unsigned int data_index = 0;
196  for (const nav_grid::Index& index : nav_grid_iterators::SubGrid(&info, bounds))
197  {
198  update.data[data_index++] = interpretValue(grid(index), min_value, denominator, unknown_value);
199  }
200  return update;
201 }
202 
203 } // namespace nav_grid_pub_sub
204 
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.


nav_grid_pub_sub
Author(s):
autogenerated on Wed Jun 26 2019 20:06:28