occ_grid_message_utils.h
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2018, Locus Robotics
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of the copyright holder nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  */
00034 
00035 #ifndef NAV_GRID_PUB_SUB_OCC_GRID_MESSAGE_UTILS_H
00036 #define NAV_GRID_PUB_SUB_OCC_GRID_MESSAGE_UTILS_H
00037 
00038 #include <nav_2d_utils/conversions.h>
00039 #include <nav_grid_pub_sub/cost_interpretation.h>
00040 #include <nav_msgs/OccupancyGrid.h>
00041 #include <map_msgs/OccupancyGridUpdate.h>
00042 #include <nav_core2/bounds.h>
00043 #include <nav_grid_iterators/whole_grid.h>
00044 #include <nav_grid_iterators/sub_grid.h>
00045 #include <algorithm>
00046 #include <limits>
00047 #include <vector>
00048 
00049 
00050 namespace nav_grid_pub_sub
00051 {
00052 
00056 inline nav_msgs::OccupancyGrid toOccupancyGrid(const nav_grid::NavGrid<unsigned char>& grid,
00057     const ros::Time& stamp = ros::Time(0),
00058     const std::vector<unsigned char> cost_interpretation_table = std::vector<unsigned char>())
00059 {
00060   nav_msgs::OccupancyGrid ogrid;
00061   const nav_grid::NavGridInfo& info = grid.getInfo();
00062   ogrid.header.frame_id = info.frame_id;
00063   ogrid.header.stamp = stamp;
00064   ogrid.info = nav_2d_utils::infoToInfo(info);
00065   ogrid.data.resize(info.width * info.height);
00066 
00067   unsigned int data_index = 0;
00068   for (const nav_grid::Index& index : nav_grid_iterators::WholeGrid(info))
00069   {
00070     ogrid.data[data_index++] = interpretCost(grid(index), cost_interpretation_table);
00071   }
00072   return ogrid;
00073 }
00074 
00078 inline map_msgs::OccupancyGridUpdate toOccupancyGridUpdate(const nav_grid::NavGrid<unsigned char>& grid,
00079     const nav_core2::UIntBounds& bounds, const ros::Time& stamp = ros::Time(0),
00080     const std::vector<unsigned char> cost_interpretation_table = std::vector<unsigned char>())
00081 {
00082   map_msgs::OccupancyGridUpdate update;
00083   const nav_grid::NavGridInfo& info = grid.getInfo();
00084   update.header.stamp = stamp;
00085   update.header.frame_id = info.frame_id;
00086   update.x = bounds.getMinX();
00087   update.y = bounds.getMinY();
00088   update.width = bounds.getWidth();
00089   update.height = bounds.getHeight();
00090   update.data.resize(update.width * update.height);
00091 
00092   unsigned int data_index = 0;
00093   for (const nav_grid::Index& index : nav_grid_iterators::SubGrid(&info, bounds))
00094   {
00095     update.data[data_index++] = interpretCost(grid(index), cost_interpretation_table);
00096   }
00097   return update;
00098 }
00099 
00100 
00101 
00107 template<typename NumericType>
00108 nav_msgs::OccupancyGrid toOccupancyGrid(const nav_grid::NavGrid<NumericType>& grid,
00109                                         const NumericType min_value, const NumericType max_value,
00110                                         const NumericType unknown_value,
00111                                         const ros::Time& stamp = ros::Time(0))
00112 {
00113   nav_msgs::OccupancyGrid ogrid;
00114   const nav_grid::NavGridInfo& info = grid.getInfo();
00115   ogrid.header.frame_id = info.frame_id;
00116   ogrid.header.stamp = stamp;
00117   ogrid.info = nav_2d_utils::infoToInfo(info);
00118   ogrid.data.resize(info.width * info.height);
00119 
00120   NumericType denominator = max_value - min_value;
00121   if (denominator == 0)
00122   {
00123     denominator = 1;
00124   }
00125 
00126   unsigned int data_index = 0;
00127   for (const nav_grid::Index& index : nav_grid_iterators::WholeGrid(info))
00128   {
00129     ogrid.data[data_index++] = interpretValue(grid(index), min_value, denominator, unknown_value);
00130   }
00131   return ogrid;
00132 }
00133 
00137 template<typename NumericType>
00138 inline void getExtremeValues(const nav_grid::NavGrid<NumericType>& grid, const NumericType unknown_value,
00139                              NumericType& min_val, NumericType& max_val)
00140 {
00141   max_val = std::numeric_limits<NumericType>::min();
00142   min_val = std::numeric_limits<NumericType>::max();
00143 
00144   for (const nav_grid::Index& index : nav_grid_iterators::WholeGrid(grid.getInfo()))
00145   {
00146     const NumericType& value = grid(index);
00147     if (value == unknown_value) continue;
00148     max_val = std::max(value, max_val);
00149     min_val = std::min(value, min_val);
00150   }
00151 }
00152 
00158 template<typename NumericType>
00159 nav_msgs::OccupancyGrid toOccupancyGrid(const nav_grid::NavGrid<NumericType>& grid,
00160                                         const NumericType unknown_value = std::numeric_limits<NumericType>::max(),
00161                                         const ros::Time& stamp = ros::Time(0))
00162 {
00163   NumericType min_val, max_val;
00164   getExtremeValues(grid, unknown_value, min_val, max_val);
00165   return toOccupancyGrid(grid, min_val, max_val, unknown_value, stamp);
00166 }
00167 
00173 template<typename NumericType>
00174 map_msgs::OccupancyGridUpdate toOccupancyGridUpdate(const nav_grid::NavGrid<NumericType>& grid,
00175                                         const nav_core2::UIntBounds& bounds,
00176                                         const NumericType min_value, const NumericType max_value,
00177                                         const NumericType unknown_value,
00178                                         const ros::Time& stamp = ros::Time(0))
00179 {
00180   map_msgs::OccupancyGridUpdate update;
00181   const nav_grid::NavGridInfo& info = grid.getInfo();
00182   update.header.stamp = stamp;
00183   update.header.frame_id = info.frame_id;
00184   update.x = bounds.getMinX();
00185   update.y = bounds.getMinY();
00186   update.width = bounds.getWidth();
00187   update.height = bounds.getHeight();
00188   update.data.resize(update.width * update.height);
00189   NumericType denominator = max_value - min_value;
00190   if (denominator == 0)
00191   {
00192     denominator = 1;
00193   }
00194 
00195   unsigned int data_index = 0;
00196   for (const nav_grid::Index& index : nav_grid_iterators::SubGrid(&info, bounds))
00197   {
00198     update.data[data_index++] = interpretValue(grid(index), min_value, denominator, unknown_value);
00199   }
00200   return update;
00201 }
00202 
00203 }  // namespace nav_grid_pub_sub
00204 
00205 #endif  // NAV_GRID_PUB_SUB_OCC_GRID_MESSAGE_UTILS_H


nav_grid_pub_sub
Author(s):
autogenerated on Wed Jun 26 2019 20:09:52