$search
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 00040 #include <occupancy_grid_utils/combine_grids.h> 00041 #include <occupancy_grid_utils/coordinate_conversions.h> 00042 #include <ros/assert.h> 00043 #include <boost/foreach.hpp> 00044 #include <boost/optional.hpp> 00045 #include <boost/bind.hpp> 00046 #include <boost/ref.hpp> 00047 #include <set> 00048 #include "gcc_version.h" 00049 00050 00051 namespace occupancy_grid_utils 00052 { 00053 00054 namespace nm=nav_msgs; 00055 namespace gm=geometry_msgs; 00056 00057 using boost::bind; 00058 using boost::ref; 00059 using std::vector; 00060 using std::multiset; 00061 using std::set; 00062 using std::min; 00063 using std::max; 00064 00065 typedef boost::shared_ptr<nm::OccupancyGrid> GridPtr; 00066 typedef boost::shared_ptr<nm::OccupancyGrid const> GridConstPtr; 00067 00068 inline Cell point32Cell (const nm::MapMetaData& info, const gm::Point32& p) 00069 { 00070 gm::Point pt; 00071 pt.x = p.x; 00072 pt.y = p.y; 00073 pt.z = p.z; 00074 return pointCell(info, pt); 00075 } 00076 00077 // Does this cell contain a vertex of this polygon? 00078 inline bool containsVertex (const nm::MapMetaData& info, const Cell& c, const gm::Polygon& poly) 00079 { 00080 BOOST_FOREACH (const gm::Point32& p, poly.points) { 00081 if (point32Cell(info, p)==c) 00082 return true; 00083 } 00084 return false; 00085 } 00086 00087 00088 // Do the two cells (on different grids) intersect? 00089 inline bool cellsIntersect (const nm::MapMetaData& info1, const Cell& c1, const nm::MapMetaData& info2, const Cell& c2) 00090 { 00091 const gm::Polygon p1=cellPolygon(info1, c1); 00092 const gm::Polygon p2=cellPolygon(info2, c2); 00093 return containsVertex(info1, c1, p2) || containsVertex(info2, c2, p1); 00094 } 00095 00096 inline gm::Polygon expandPolygon(const gm::Polygon& p, const double r) 00097 { 00098 double sx=0; 00099 double sy=0; 00100 double sz=0; 00101 const size_t n = p.points.size(); 00102 for (unsigned i=0; i<n; i++) { 00103 sx += p.points[i].x; 00104 sy += p.points[i].y; 00105 sz += p.points[i].z; 00106 } 00107 sx /= n; 00108 sy /= n; 00109 sz /= n; 00110 gm::Polygon p2; 00111 p2.points.resize(n); 00112 for (unsigned i=0; i<n; i++) { 00113 p2.points[i].x = sx + r*(p.points[i].x-sx); 00114 p2.points[i].y = sy + r*(p.points[i].y-sy); 00115 p2.points[i].z = sz + r*(p.points[i].z-sz); 00116 } 00117 return p2; 00118 } 00119 00120 // Return set of intersecting cells in grid info, of cell cell2 in info2 00121 set<Cell> intersectingCells (const nm::MapMetaData& info, const nm::MapMetaData& info2, const Cell& cell2) 00122 { 00123 // The expansion is to avoid weird effects due to rounding when intersecting parallel grids 00124 const gm::Polygon poly=expandPolygon(cellPolygon(info2, cell2), 1.0001); 00125 00126 // Figure out the candidates 00127 vector<Cell> corners(4); 00128 transform(poly.points.begin(), poly.points.end(), corners.begin(), 00129 bind(point32Cell, ref(info), _1)); 00130 const coord_t min_x=min(corners[0].x, min(corners[1].x, min(corners[2].x, corners[3].x))); 00131 const coord_t min_y=min(corners[0].y, min(corners[1].y, min(corners[2].y, corners[3].y))); 00132 const coord_t max_x=max(corners[0].x, max(corners[1].x, max(corners[2].x, corners[3].x))); 00133 const coord_t max_y=max(corners[0].y, max(corners[1].y, max(corners[2].y, corners[3].y))); 00134 00135 set<Cell> cells; 00136 for (coord_t x=min_x; x<=max_x; x++) { 00137 for (coord_t y=min_y; y<=max_y; y++) { 00138 const Cell candidate(x, y); 00139 if (withinBounds(info, candidate) && 00140 cellsIntersect(info, candidate, info2, cell2)) 00141 cells.insert(candidate); 00142 } 00143 } 00144 00145 return cells; 00146 } 00147 00148 double minX (const nm::MapMetaData& info) 00149 { 00150 const gm::Polygon p=gridPolygon(info); 00151 return min(p.points[0].x, min(p.points[1].x, min(p.points[2].x, p.points[3].x))); 00152 } 00153 00154 double maxX (const nm::MapMetaData& info) 00155 { 00156 const gm::Polygon p=gridPolygon(info); 00157 return max(p.points[0].x, max(p.points[1].x, max(p.points[2].x, p.points[3].x))); 00158 } 00159 00160 double minY (const nm::MapMetaData& info) 00161 { 00162 const gm::Polygon p=gridPolygon(info); 00163 return min(p.points[0].y, min(p.points[1].y, min(p.points[2].y, p.points[3].y))); 00164 } 00165 00166 double maxY (const nm::MapMetaData& info) 00167 { 00168 const gm::Polygon p=gridPolygon(info); 00169 return max(p.points[0].y, max(p.points[1].y, max(p.points[2].y, p.points[3].y))); 00170 } 00171 00172 gm::Pose transformPose (const tf::Pose trans, const gm::Pose p) 00173 { 00174 tf::Pose pose; 00175 tf::poseMsgToTF(p, pose); 00176 gm::Pose transformed; 00177 tf::poseTFToMsg(trans*pose, transformed); 00178 return transformed; 00179 } 00180 00181 // Get the dimensions of a combined grid 00182 nm::MapMetaData getCombinedGridInfo (const vector<GridConstPtr>& grids, const double resolution) 00183 { 00184 ROS_ASSERT (grids.size() > 0); 00185 nm::MapMetaData info; 00186 info.resolution = resolution; 00187 tf::Pose trans; 00188 tf::poseMsgToTF(grids[0]->info.origin, trans); 00189 00190 00191 #ifdef GRID_UTILS_GCC_46 00192 #pragma GCC diagnostic push 00193 #pragma GCC diagnostic ignored "-Wuninitialized" 00194 #endif 00195 00196 boost::optional<double> min_x, max_x, min_y, max_y; 00197 BOOST_FOREACH (const GridConstPtr& g, grids) { 00198 nm::MapMetaData grid_info = g->info; 00199 grid_info.origin = transformPose(trans.inverse(), g->info.origin); 00200 if (!(min_x && *min_x < minX(grid_info))) 00201 min_x = minX(grid_info); 00202 if (!(min_y && *min_y < minY(grid_info))) 00203 min_y = minY(grid_info); 00204 if (!(max_x && *max_x > maxX(grid_info))) 00205 max_x = maxX(grid_info); 00206 if (!(max_y && *max_y > maxY(grid_info))) 00207 max_y = maxY(grid_info); 00208 } 00209 00210 #ifdef GRID_UTILS_GCC_46 00211 #pragma GCC diagnostic pop 00212 #endif 00213 00214 const double dx = *max_x - *min_x; 00215 const double dy = *max_y - *min_y; 00216 ROS_ASSERT ((dx > 0) && (dy > 0)); 00217 gm::Pose pose_in_grid_frame; 00218 pose_in_grid_frame.position.x = *min_x; 00219 pose_in_grid_frame.position.y = *min_y; 00220 pose_in_grid_frame.orientation.w = 1.0; 00221 info.origin = transformPose(trans, pose_in_grid_frame); 00222 info.height = ceil(dy/info.resolution); 00223 info.width = ceil(dx/info.resolution); 00224 00225 return info; 00226 } 00227 00228 00229 // Main function 00230 GridPtr combineGrids (const vector<GridConstPtr>& grids, const double resolution) 00231 { 00232 GridPtr combined_grid(new nm::OccupancyGrid()); 00233 combined_grid->info = getCombinedGridInfo(grids, resolution); 00234 combined_grid->data.resize(combined_grid->info.width*combined_grid->info.height); 00235 fill(combined_grid->data.begin(), combined_grid->data.end(), -1); 00236 ROS_DEBUG_NAMED ("combine_grids", "Combining %zu grids", grids.size()); 00237 00238 BOOST_FOREACH (const GridConstPtr& grid, grids) { 00239 for (coord_t x=0; x<(int)grid->info.width; x++) { 00240 for (coord_t y=0; y<(int)grid->info.height; y++) { 00241 const Cell cell(x, y); 00242 const signed char value=grid->data[cellIndex(grid->info, cell)]; 00243 00244 // Only proceed if the value is not unknown 00245 if ((value>=0) && (value<=100)) { 00246 BOOST_FOREACH (const Cell& intersecting_cell, 00247 intersectingCells(combined_grid->info, grid->info, cell)) { 00248 const index_t ind = cellIndex(combined_grid->info, intersecting_cell); 00249 combined_grid->data[ind] = max(combined_grid->data[ind], value); 00250 } 00251 } 00252 } 00253 } 00254 } 00255 00256 ROS_DEBUG_NAMED ("combine_grids", "Done combining grids"); 00257 return combined_grid; 00258 } 00259 00260 00261 GridPtr combineGrids (const vector<GridConstPtr>& grids) 00262 { 00263 ROS_ASSERT (grids.size()>0); 00264 return combineGrids(grids, grids[0]->info.resolution); 00265 } 00266 00267 00268 } // namespace occupancy_grid_utils 00269 00270 00271 00272