$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 00039 #include "shortest_path_result.h" 00040 #include <occupancy_grid_utils/shortest_path.h> 00041 #include <ros/assert.h> 00042 #include <queue> 00043 00044 namespace occupancy_grid_utils 00045 { 00046 00047 namespace nm=nav_msgs; 00048 namespace gm=geometry_msgs; 00049 00050 using std::vector; 00051 using boost::optional; 00052 using std::max; 00053 00054 TerminationCondition::TerminationCondition () 00055 {} 00056 00057 TerminationCondition::TerminationCondition (const double max_distance, 00058 const bool use_cells) : 00059 max_distance_(max_distance), use_cells_(use_cells) 00060 { 00061 if (use_cells_) 00062 ROS_WARN ("Deprecated usage of version of TerminationCondition that uses" 00063 " distance in cells rather than meters. This API will change" 00064 " in a hard-to-debug way in future!"); 00065 } 00066 00067 TerminationCondition::TerminationCondition (const Cells& goals) : 00068 goals_(goals) 00069 { 00070 } 00071 00072 TerminationCondition::TerminationCondition (const Cells& goals, const double max_distance, 00073 const bool use_cells) : 00074 max_distance_(max_distance), goals_(goals), use_cells_(use_cells) 00075 { 00076 if (use_cells_) 00077 ROS_WARN ("Deprecated usage of version of TerminationCondition that uses" 00078 " distance in cells rather than meters. This API will change" 00079 " in a hard-to-debug way in future!"); 00080 } 00081 00082 00083 typedef vector<Cell> Path; 00084 typedef boost::shared_ptr<nm::OccupancyGrid> GridPtr; 00085 00086 boost::optional<double> distance(ResultPtr res, const Cell& dest) 00087 { 00088 ROS_WARN ("Using deprecated function distance. Use distanceTo instead."); 00089 return res->potential[cellIndex(res->info, dest)]; 00090 } 00091 00092 boost::optional<double> distanceTo(ResultPtr res, const Cell& dest) 00093 { 00094 boost::optional<double> d = res->potential[cellIndex(res->info, dest)]; 00095 if (d) 00096 return *d * res->info.resolution; 00097 else 00098 return d; 00099 } 00100 00101 00102 boost::optional<Path> extractPath(ResultPtr res, const Cell& dest) 00103 { 00104 boost::optional<Path> p; 00105 index_t current=cellIndex(res->info, dest); 00106 if (!res->back_pointers[current]) 00107 return p; // No path exists 00108 00109 index_t max=res->back_pointers.size(); 00110 index_t n=0; 00111 p = Path(); 00112 00113 do { 00114 if (n++ > max) { 00115 ROS_FATAL("Cycle in extractPath"); 00116 ROS_BREAK(); 00117 } 00118 p->push_back(indexCell(res->info, current)); 00119 ROS_ASSERT_MSG(res->back_pointers[current], "Back pointer not found for %u", current); 00120 current=*(res->back_pointers[current]); 00121 } while (current!=res->src_ind); 00122 p->push_back(indexCell(res->info, current)); 00123 reverse(p->begin(), p->end()); 00124 return p; 00125 } 00126 00127 00128 00129 struct QueueItem 00130 { 00131 index_t ind; 00132 double potential; 00133 QueueItem (const index_t ind, const double potential) : 00134 ind(ind), potential(potential) {} 00135 }; 00136 00137 bool operator< (const QueueItem& i1, const QueueItem& i2) 00138 { 00139 return i1.potential > i2.potential; 00140 } 00141 00142 00143 ResultPtr singleSourceShortestPaths (const nm::OccupancyGrid& g, const Cell& src, 00144 const bool manhattan) 00145 { 00146 return singleSourceShortestPaths(g, src, TerminationCondition(), manhattan); 00147 } 00148 00149 ResultPtr singleSourceShortestPaths (const nm::OccupancyGrid& g, const Cell& src, 00150 const TerminationCondition& t, 00151 const bool manhattan) 00152 { 00153 verifyDataSize(g); 00154 ShortestPathResult* res = new ShortestPathResult(); 00155 ResultPtr result(res); 00156 res->info = g.info; 00157 res->src_ind = cellIndex(g.info, src); 00158 res->back_pointers.resize(g.data.size()); 00159 res->potential.resize(g.data.size()); 00160 00161 std::priority_queue<QueueItem> q; 00162 q.push(QueueItem(res->src_ind, 0.0)); 00163 res->potential[res->src_ind] = 0.0; 00164 ROS_DEBUG_NAMED ("shortest_path", "Computing single source shortest paths from %d, %d", src.x, src.y); 00165 00166 Cells remaining_goals; 00167 if (t.goals_) 00168 remaining_goals = *t.goals_; 00169 00170 while (!q.empty()) { 00171 const QueueItem i=q.top(); 00172 q.pop(); 00173 00174 const Cell cell = indexCell(g.info, i.ind); 00175 const double dist = i.potential; 00176 const double dist_in_meters = dist*g.info.resolution; 00177 if (t.max_distance_ && 00178 (*t.max_distance_ < (t.use_cells_ ? dist : dist_in_meters))) 00179 break; 00180 if (t.goals_) { 00181 remaining_goals.erase(cell); 00182 if (remaining_goals.empty()) 00183 break; 00184 } 00185 00186 for (int dx=-1; dx<=1; dx++) { 00187 for (int dy=-1; dy<=1; dy++) { 00188 if ((dx==0) && (dy==0)) 00189 continue; 00190 if ((dx!=0) && (dy!=0) && manhattan) 00191 continue; 00192 const double d = ((dx==0) || (dy==0)) ? 1 : sqrt(2); 00193 const Cell neighbor(cell.x+dx, cell.y+dy); 00194 if (withinBounds(g.info, neighbor)) { 00195 const index_t ind=cellIndex(g.info, neighbor); 00196 const double new_dist = dist+d; 00197 if (g.data[ind]==UNOCCUPIED && 00198 (!res->potential[ind] || *(res->potential[ind]) > new_dist) && 00199 (!t.max_distance_ || 00200 (t.use_cells_ && *t.max_distance_ >= new_dist) || 00201 (!t.use_cells_ && *t.max_distance_ >= new_dist*g.info.resolution))) 00202 { 00203 ROS_DEBUG_NAMED ("shortest_path_propagation", "Adding cell %d, %d, at distance %.2f", 00204 neighbor.x, neighbor.y, new_dist); 00205 res->potential[ind] = new_dist; 00206 res->back_pointers[ind] = i.ind; 00207 q.push(QueueItem(ind, new_dist)); 00208 } 00209 } 00210 } 00211 } 00212 } 00213 ROS_DEBUG_NAMED ("shortest_path", "Done computing single source shortest paths from %d, %d", src.x, src.y); 00214 return result; 00215 } 00216 00217 00218 inline 00219 bool myGt (const signed char x, const signed char y) 00220 { 00221 return (x==-1 && y==0) || x>y; 00222 } 00223 00224 struct InflationQueueItem 00225 { 00226 InflationQueueItem (const Cell& cell, const signed char cost) : 00227 cell(cell), cost(cost) 00228 {} 00229 Cell cell; 00230 signed char cost; 00231 }; 00232 00233 GridPtr inflateObstacles (const nm::OccupancyGrid& g, const double r, 00234 const bool allow_unknown) 00235 { 00236 // Set up optimized 'priority queue' 00237 ROS_ASSERT (r>0); 00238 const int radius = 1+ceil(r/g.info.resolution); 00239 typedef vector<InflationQueueItem> QueueVec; 00240 vector<QueueVec> queues(radius); 00241 GridPtr g2(new nm::OccupancyGrid(g)); 00242 const nm::MapMetaData& geom=g.info; 00243 00244 // Add initial obstacles 00245 for (coord_t x=0; x<(int)geom.width; x++) { 00246 for (coord_t y=0; y<(int)geom.height; y++) { 00247 const Cell cell(x, y); 00248 const signed char val=g.data[cellIndex(geom, cell)]; 00249 if ((allow_unknown && val>=1) || (!allow_unknown && val!=0)) 00250 queues[0].push_back(InflationQueueItem(cell, val)); 00251 } 00252 } 00253 00254 while (true) 00255 { 00256 int ind=-1; 00257 for (int i=0; i<radius; i++) 00258 { 00259 if (queues[i].size()>0) 00260 { 00261 ind=i; 00262 break; 00263 } 00264 } 00265 if (ind<0) 00266 break; 00267 00268 const InflationQueueItem& q=queues[ind].back(); 00269 const index_t index = cellIndex(geom, q.cell); 00270 if (myGt(q.cost, g2->data[index]) || ind==0) 00271 { 00272 g2->data[index] = q.cost; 00273 if (ind<radius-1) 00274 { 00275 for (int vert=0; vert<2; vert ++) 00276 { 00277 for (int d=-1; d<=1; d += 2) 00278 { 00279 const int dx = vert ? 0 : d; 00280 const int dy = vert ? d : 0; 00281 const Cell c2(q.cell.x+dx, q.cell.y+dy); 00282 if (withinBounds(geom, c2)) 00283 { 00284 queues[ind+1].push_back(InflationQueueItem(c2, q.cost)); 00285 } 00286 } 00287 } 00288 } 00289 } 00290 00291 queues[ind].pop_back(); 00292 } 00293 return g2; 00294 } 00295 00296 /************************************************************ 00297 * A* 00298 ***********************************************************/ 00299 00300 typedef std::pair<Path, double> AStarResult; 00301 struct PQItem 00302 { 00303 index_t ind; 00304 double g_cost; 00305 double h_cost; 00306 index_t parent_ind; 00307 PQItem (index_t ind, double g_cost, double h_cost, index_t parent_ind) : 00308 ind(ind), g_cost(g_cost), h_cost(h_cost), parent_ind(parent_ind) {} 00309 00310 bool operator< (const PQItem& i2) const 00311 { 00312 return ((g_cost + h_cost) > (i2.g_cost + i2.h_cost)); 00313 } 00314 }; 00315 00316 00317 inline double manhattanHeuristic (const Cell& c1, const Cell& c2) 00318 { 00319 return fabs(c1.x-c2.x) + fabs(c1.y-c2.y); 00320 } 00321 00322 00323 optional<AStarResult> shortestPathAStar(const nm::OccupancyGrid& g, const Cell& src, const Cell& dest) 00324 { 00325 typedef std::map<index_t, index_t> ParentMap; 00326 00327 const double resolution = g.info.resolution; 00328 std::priority_queue<PQItem> open_list; 00329 const unsigned num_cells = g.info.height*g.info.width; 00330 std::vector<bool> seen(num_cells); // Default initialized to all false 00331 const index_t dest_ind = cellIndex(g.info, dest); 00332 const index_t src_ind = cellIndex(g.info, src); 00333 open_list.push(PQItem(src_ind, 0, resolution*manhattanHeuristic(src, dest), src_ind)); 00334 ParentMap parent; 00335 00336 optional<AStarResult> res; 00337 ROS_DEBUG_STREAM_NAMED ("shortest_path", "Computing shortest path from " << src << " to " << dest); 00338 00339 while (!open_list.empty()) { 00340 const PQItem current = open_list.top(); 00341 open_list.pop(); 00342 const Cell c = indexCell(g.info, current.ind); 00343 if (seen[current.ind]) 00344 continue; 00345 parent[current.ind] = current.parent_ind; 00346 seen[current.ind] = true; 00347 ROS_DEBUG_STREAM_NAMED ("shortest_path_internal", " Considering " << c << " with cost " << 00348 current.g_cost << " + " << current.h_cost); 00349 if (current.ind == dest_ind) { 00350 res = AStarResult(); 00351 res->second = current.g_cost; 00352 break; 00353 } 00354 00355 for (int d=-1; d<=1; d+=2) { 00356 for (int vertical=0; vertical<2; vertical++) { 00357 const int cx = c.x + d*(1-vertical); 00358 const int cy = c.y + d*vertical; 00359 if (cx>=0 && cy>=0) { 00360 const Cell c2((coord_t) cx, (coord_t) cy); 00361 if (withinBounds(g.info, c2)) { 00362 const index_t ind = cellIndex(g.info, c2); 00363 if (g.data[ind]==UNOCCUPIED && !seen[ind]) { 00364 open_list.push(PQItem(ind, current.g_cost + resolution, 00365 resolution*manhattanHeuristic(c2, dest), 00366 current.ind)); 00367 } 00368 ROS_DEBUG_STREAM_COND_NAMED (g.data[ind]!=UNOCCUPIED, "shortest_path_internal", 00369 " Skipping cell " << indexCell(g.info, ind) << 00370 " with cost " << (unsigned) g.data[ind]); 00371 } 00372 } 00373 } 00374 } 00375 } 00376 00377 // Extract path if found 00378 if (res) 00379 { 00380 vector<index_t> path; 00381 path.push_back(dest_ind); 00382 const index_t src_ind = cellIndex(g.info, src); 00383 while (true) 00384 { 00385 index_t last = *(--path.end()); 00386 if (last == src_ind) 00387 break; 00388 ParentMap::const_iterator it = parent.find(last); 00389 ROS_ASSERT (it!=parent.end()); 00390 index_t parent = it->second; 00391 ROS_ASSERT (parent!=last); 00392 path.push_back(parent); 00393 } 00394 for (int i=path.size()-1; i>=0; i--) 00395 res->first.push_back(indexCell(g.info, path[i])); 00396 } 00397 00398 ROS_DEBUG_STREAM_NAMED ("shortest_path", "Computed shortest path. Found = " << (bool) res.is_initialized()); 00399 return res; 00400 } 00401 00402 00403 optional<AStarResult> shortestPath(const nm::OccupancyGrid& g, const Cell& src, const Cell& dest) 00404 { 00405 ROS_WARN ("Using deprecated function shortestPath (use shortestPathAStar)"); 00406 std::priority_queue<PQItem> open_list; 00407 const unsigned num_cells = g.info.height*g.info.width; 00408 std::vector<bool> seen(num_cells); // Default initialized to all false 00409 index_t src_ind = cellIndex(g.info, src); 00410 open_list.push(PQItem(src_ind, 0, manhattanHeuristic(src, dest), src_ind)); 00411 std::vector<index_t> parent(num_cells); 00412 const index_t dest_ind = cellIndex(g.info, dest); 00413 00414 optional<AStarResult> res; 00415 ROS_DEBUG_STREAM_NAMED ("shortest_path", "Computing shortest path from " << src << " to " << dest); 00416 00417 while (!open_list.empty()) { 00418 const PQItem current = open_list.top(); 00419 open_list.pop(); 00420 const Cell c = indexCell(g.info, current.ind); 00421 if (seen[current.ind]) 00422 continue; 00423 seen[current.ind] = true; 00424 ROS_DEBUG_STREAM_NAMED ("shortest_path_internal", " Considering " << c << " with cost " << 00425 current.g_cost << " + " << current.h_cost); 00426 if (current.ind == dest_ind) { 00427 res = AStarResult(); 00428 res->second = current.g_cost; 00429 // Todo fill in path 00430 break; 00431 } 00432 00433 for (int d=-1; d<=1; d+=2) { 00434 for (int vertical=0; vertical<2; vertical++) { 00435 const int cx = c.x + d*(1-vertical); 00436 const int cy = c.y + d*vertical; 00437 if (cx>=0 && cy>=0) { 00438 const Cell c2((coord_t) cx, (coord_t) cy); 00439 if (withinBounds(g.info, c2)) { 00440 const index_t ind = cellIndex(g.info, c2); 00441 if (g.data[ind]==UNOCCUPIED && !seen[ind]) { 00442 open_list.push(PQItem(ind, current.g_cost + 1, manhattanHeuristic(c2, dest), 00443 current.ind)); 00444 parent[ind] = current.ind; 00445 } 00446 ROS_DEBUG_STREAM_COND_NAMED (g.data[ind]!=UNOCCUPIED, "shortest_path_internal", 00447 " Skipping cell " << indexCell(g.info, ind) << 00448 " with cost " << (unsigned) g.data[ind]); 00449 } 00450 } 00451 } 00452 } 00453 } 00454 00455 ROS_DEBUG_STREAM_NAMED ("shortest_path", "Computed shortest path. Found = " << (bool) res.is_initialized()); 00456 return res; 00457 } 00458 00459 00460 00461 00462 00463 /************************************************************ 00464 * Ros message conversion 00465 ************************************************************/ 00466 00468 ResultPtr shortestPathResultFromMessage (const NavigationFunction& msg) 00469 { 00470 ShortestPathResult* res = new ShortestPathResult(); 00471 ResultPtr retval(res); // retval is a pointer to const, so we modify via res 00472 res->info = msg.info; 00473 res->src_ind = msg.source; 00474 00475 const index_t num_cells = msg.valid.size(); 00476 ROS_ASSERT (num_cells == msg.back_pointers.size()); 00477 ROS_ASSERT (num_cells == msg.potential.size()); 00478 res->back_pointers.resize(num_cells); 00479 res->potential.resize(num_cells); 00480 00481 for (index_t i=0; i<num_cells; i++) { 00482 if (i==msg.source) { 00483 // Sanity check 00484 ROS_ASSERT (msg.back_pointers[i] == 123456); 00485 ROS_ASSERT (msg.potential[i] == -1.0); 00486 res->potential[i] = 0.0; 00487 } 00488 else if (msg.valid[i]) { 00489 res->back_pointers[i] = msg.back_pointers[i]; 00490 res->potential[i] = msg.potential[i]; 00491 } 00492 else { 00493 // Sanity check 00494 ROS_ASSERT (msg.back_pointers[i] == 234567); 00495 ROS_ASSERT (msg.potential[i] == -2.0); 00496 } 00497 } 00498 00499 return retval; 00500 } 00501 00503 NavigationFunction shortestPathResultToMessage (ResultPtr res) 00504 { 00505 NavigationFunction msg; 00506 msg.info = res->info; 00507 msg.source = res->src_ind; 00508 00509 const index_t num_cells=res->back_pointers.size(); 00510 ROS_ASSERT (num_cells == res->potential.size()); 00511 msg.valid.resize(num_cells); 00512 msg.back_pointers.resize(num_cells); 00513 msg.potential.resize(num_cells); 00514 00515 for (index_t i=0; i<num_cells; i++) { 00516 if (i==msg.source) { 00517 msg.valid[i] = false; 00518 msg.potential[i] = -1.0; 00519 msg.back_pointers[i] = 123456; 00520 } 00521 else if (res->potential[i]) { 00522 msg.valid[i] = true; 00523 msg.potential[i] = *res->potential[i]; 00524 msg.back_pointers[i] = *res->back_pointers[i]; 00525 } 00526 else { 00527 msg.valid[i] = false; 00528 msg.potential[i] = -2.0; 00529 msg.back_pointers[i] = 234567; 00530 } 00531 } 00532 00533 return msg; 00534 } 00535 00536 00537 00538 } // namespace occupancy_grid_utils