coordinate_conversions.cpp
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 
00039 #include <occupancy_grid_utils/coordinate_conversions.h>
00040 
00041 namespace occupancy_grid_utils
00042 {
00043 
00044 namespace gm=geometry_msgs;
00045 namespace nm=nav_msgs;
00046 
00047 gm::Polygon cellPolygon (const nm::MapMetaData& info, const Cell& c)
00048 {
00049   const float dx[4] = {0.0, 0.0, 1.0, 1.0};
00050   const float dy[4] = {0.0, 1.0, 1.0, 0.0};
00051   
00052   const tf::Transform trans = mapToWorld(info);
00053   gm::Polygon p;
00054   p.points.resize(4);
00055   for (unsigned i=0; i<4; i++) {
00056     tf::Point pt((c.x+dx[i])*info.resolution, (c.y+dy[i])*info.resolution, 0.0);
00057     tf::Point transformed = trans*pt;
00058     p.points[i].x = transformed.x();
00059     p.points[i].y = transformed.y();
00060     p.points[i].z = transformed.z();
00061   }
00062   return p;
00063 }
00064   
00065 
00066 gm::Polygon gridPolygon (const nm::MapMetaData& info)
00067 {
00068   const float x[4] = {0.0, 0.0, 1.0, 1.0};
00069   const float y[4] = {0.0, 1.0, 1.0, 0.0};
00070 
00071   const tf::Transform trans = mapToWorld(info);
00072   gm::Polygon p;
00073   p.points.resize(4);
00074 
00075   for (unsigned i=0; i<4; i++) {
00076     tf::Point pt(x[i]*info.resolution*info.width, y[i]*info.resolution*info.height, 0.0);
00077     tf::Point transformed=trans*pt;
00078     p.points[i].x = transformed.x();
00079     p.points[i].y = transformed.y();
00080     p.points[i].z = transformed.z();
00081   }
00082   return p;
00083 }
00084 
00085 void verifyDataSize (const nm::OccupancyGrid& g)
00086 {
00087   const size_t expected = g.info.height*g.info.width;
00088   if (expected!=g.data.size())
00089     throw DataSizeException(expected, g.data.size());
00090 }
00091 
00092 
00093 } // namespace


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