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


occupancy_grid_utils
Author(s): Bhaskara Marthi
autogenerated on Thu Dec 12 2013 13:17:54