coordinate_conversions.h
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2008, Willow Garage, Inc.
00003  * Copyright (c) 2015-2016, Jiri Horner
00004  * All rights reserved.
00005  *
00006  * Redistribution and use in source and binary forms, with or without
00007  * modification, are permitted provided that the following conditions are met:
00008  *
00009  *     * Redistributions of source code must retain the above copyright
00010  *       notice, this list of conditions and the following disclaimer.
00011  *     * Redistributions in binary form must reproduce the above copyright
00012  *       notice, this list of conditions and the following disclaimer in the
00013  *       documentation and/or other materials provided with the distribution.
00014  *     * Neither the name of the Jiri Horner nor the names of its
00015  *       contributors may be used to endorse or promote products derived from
00016  *       this software without specific prior written permission.
00017  *
00018  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00019  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00020  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00021  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00022  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00023  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00024  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00025  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00026  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00027  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00028  * POSSIBILITY OF SUCH DAMAGE.
00029  *
00030  */
00031 
00032 
00043 #ifndef OCCUPANCY_GRID_UTILS_COORDINATE_CONVERSIONS_H
00044 #define OCCUPANCY_GRID_UTILS_COORDINATE_CONVERSIONS_H
00045 
00046 #include <stdexcept>
00047 #include <cstdlib>
00048 #include <cmath>
00049 
00050 #include <ros/assert.h>
00051 #include <tf/transform_datatypes.h>
00052 #include <nav_msgs/OccupancyGrid.h>
00053 #include <geometry_msgs/Polygon.h>
00054 
00055 namespace occupancy_grid_utils
00056 {
00057 
00058 /************************************************************
00059  * Public interface
00060  ************************************************************/
00061 
00062 typedef uint32_t index_t;
00063 typedef int16_t coord_t;
00064 
00065 struct Cell
00066 {
00067   Cell(const coord_t x=0, const coord_t y=0) : x(x), y(y) {}
00068   coord_t x;
00069   coord_t y;
00070 
00071   bool operator== (const Cell& c) const;
00072   bool operator< (const Cell& c) const;
00073 };
00074 
00075 
00076 // These values have conventional meanings for occupancy grids
00077 const int8_t UNOCCUPIED=0;
00078 const int8_t OCCUPIED=100;
00079 const int8_t UNKNOWN=-1;
00080 
00081 
00085 index_t cellIndex (const nav_msgs::MapMetaData& info, const Cell& c);
00086 
00088 Cell indexCell (const nav_msgs::MapMetaData& info, index_t ind);
00089 
00093 Cell pointCell (const nav_msgs::MapMetaData& info, const geometry_msgs::Point& p);
00094 
00099 index_t pointIndex (const nav_msgs::MapMetaData& info, const geometry_msgs::Point& p);
00100 
00102 geometry_msgs::Point cellCenter (const nav_msgs::MapMetaData& info, const Cell& c);
00103 
00105 geometry_msgs::Polygon cellPolygon (const nav_msgs::MapMetaData& info, const Cell& c);
00106 
00108 bool withinBounds (const nav_msgs::MapMetaData& info, const geometry_msgs::Point& p);
00109 
00111 bool withinBounds (const nav_msgs::MapMetaData& info, const Cell& c);
00112 
00114 geometry_msgs::Polygon gridPolygon (const nav_msgs::MapMetaData& info);
00115 
00118 void verifyDataSize (const nav_msgs::OccupancyGrid& g);
00119 
00120 /************************************************************
00121  * Implementations of inline functions
00122  ************************************************************/
00123 
00124 inline
00125 index_t cellIndex (const nav_msgs::MapMetaData& info, const Cell& c)
00126 {
00127   if (!withinBounds(info, c))
00128     throw std::out_of_range("Cell is off grid according to grid info");
00129   return c.x + c.y*info.width;
00130 }
00131 
00132 inline
00133 Cell indexCell (const nav_msgs::MapMetaData& info, const index_t ind)
00134 {
00135   const div_t result = std::div((int) ind, (int) info.width);
00136   return Cell(result.rem, result.quot);
00137 }
00138 
00139 
00140 inline
00141 tf::Transform mapToWorld (const nav_msgs::MapMetaData& info)
00142 {
00143   tf::Transform world_to_map;
00144   tf::poseMsgToTF (info.origin, world_to_map);
00145   return world_to_map;
00146 }
00147 
00148 inline
00149 tf::Transform worldToMap (const nav_msgs::MapMetaData& info)
00150 {
00151   return mapToWorld(info).inverse();
00152 }
00153 
00154 inline
00155 Cell pointCell (const nav_msgs::MapMetaData& info, const geometry_msgs::Point& p)
00156 {
00157   tf::Point pt;
00158   tf::pointMsgToTF(p, pt);
00159   tf::Point p2 = worldToMap(info)*pt;
00160   return Cell(std::floor(p2.x()/info.resolution), std::floor(p2.y()/info.resolution));
00161 }
00162 
00163 inline 
00164 index_t pointIndex (const nav_msgs::MapMetaData& info, const geometry_msgs::Point& p)
00165 {
00166   return cellIndex(info, pointCell(info, p));
00167 }
00168 
00169 inline
00170 geometry_msgs::Point cellCenter (const nav_msgs::MapMetaData& info, const Cell& c)
00171 {
00172   tf::Point pt((c.x+0.5)*info.resolution, (c.y+0.5)*info.resolution, 0.0);
00173   geometry_msgs::Point p;
00174   tf::pointTFToMsg(mapToWorld(info)*pt, p);
00175   return p;
00176 }
00177 
00178 
00179 inline
00180 bool Cell::operator== (const Cell& c) const
00181 {
00182   return ((this->x == c.x) && (this->y == c.y));
00183 }
00184 
00185 inline
00186 bool Cell::operator< (const Cell& c) const
00187 {
00188   return ((this->x < c.x) || ((this->x == c.x) && (this->y < c.y)));
00189 }
00190 
00191 inline
00192 std::ostream& operator<< (std::ostream& str, const Cell& c)
00193 {
00194   str << "(" << c.x << ", " << c.y << ")";
00195   return str;
00196 }
00197 
00198 inline
00199 bool withinBounds (const nav_msgs::MapMetaData& info, const geometry_msgs::Point& p)
00200 {
00201   return withinBounds(info, pointCell(info, p));
00202 }
00203 
00204 inline
00205 bool withinBounds (const nav_msgs::MapMetaData& info, const Cell& c)
00206 {
00207   return (c.x >= 0) && (c.y >= 0) && (c.x < (coord_t) info.width) && (c.y < (coord_t) info.height);
00208 }
00209 
00210 } // namespace occupancy_grid_utils
00211 
00212 #endif // include guard


map_merge
Author(s): Jiri Horner
autogenerated on Sun Mar 26 2017 03:48:10