00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00040 #ifndef OCCUPANCY_GRID_UTILS_SHORTEST_PATH_H
00041 #define OCCUPANCY_GRID_UTILS_SHORTEST_PATH_H
00042
00043 #include <occupancy_grid_utils/coordinate_conversions.h>
00044 #include <occupancy_grid_utils/NavigationFunction.h>
00045 #include <boost/shared_ptr.hpp>
00046 #include <boost/optional.hpp>
00047 #include <set>
00048
00049 namespace occupancy_grid_utils
00050 {
00051
00052
00053
00054
00055
00064 nav_msgs::OccupancyGrid::Ptr inflateObstacles (const nav_msgs::OccupancyGrid& g,
00065 double r,
00066 bool allow_unknown=false);
00067
00068
00069
00070
00071
00072
00073 struct ShortestPathResult;
00074 typedef boost::shared_ptr<const ShortestPathResult> ResultPtr;
00075 typedef std::set<Cell> Cells;
00076 typedef std::vector<Cell> Path;
00077 typedef std::pair<Path, double> AStarResult;
00078
00079
00083 struct TerminationCondition
00084 {
00085 TerminationCondition ();
00086 TerminationCondition (double max_distance);
00087 TerminationCondition (const Cells& goals);
00088 TerminationCondition (const Cells& goals, const double max_distance);
00089
00090 boost::optional<double> max_distance_;
00091 boost::optional<std::set<Cell> > goals_;
00092 };
00093
00100 ResultPtr singleSourceShortestPaths (const nav_msgs::OccupancyGrid& g, const Cell& src);
00101
00102
00111 ResultPtr singleSourceShortestPaths (const nav_msgs::OccupancyGrid& g, const Cell& src,
00112 const TerminationCondition& term);
00113
00117 boost::optional<Path> extractPath (ResultPtr shortest_path_result, const Cell& dest);
00118
00121 boost::optional<double> distance(ResultPtr shortest_path_result, const Cell& dest);
00122
00124 ResultPtr shortestPathResultFromMessage (const NavigationFunction& msg);
00125
00127 NavigationFunction shortestPathResultToMessage (ResultPtr res);
00128
00129
00134 boost::optional<AStarResult> shortestPath(const nav_msgs::OccupancyGrid& g,
00135 const Cell& src, const Cell& dest);
00136 }
00137
00138 #endif // include guard
00139
00140
00141