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


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