Go to the documentation of this file.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
00062 nav_msgs::OccupancyGrid::Ptr inflateObstacles (const nav_msgs::OccupancyGrid& g, const double r);
00063
00064
00065
00066
00067
00068
00069 struct ShortestPathResult;
00070 typedef boost::shared_ptr<const ShortestPathResult> ResultPtr;
00071 typedef std::set<Cell> Cells;
00072 typedef std::vector<Cell> Path;
00073 typedef std::pair<Path, double> AStarResult;
00074
00075
00079 struct TerminationCondition
00080 {
00081 TerminationCondition ();
00082 TerminationCondition (double max_distance);
00083 TerminationCondition (const Cells& goals);
00084 TerminationCondition (const Cells& goals, const double max_distance);
00085
00086 boost::optional<double> max_distance_;
00087 boost::optional<std::set<Cell> > goals_;
00088 };
00089
00096 ResultPtr singleSourceShortestPaths (const nav_msgs::OccupancyGrid& g, const Cell& src);
00097
00098
00107 ResultPtr singleSourceShortestPaths (const nav_msgs::OccupancyGrid& g, const Cell& src,
00108 const TerminationCondition& term);
00109
00113 boost::optional<Path> extractPath (ResultPtr shortest_path_result, const Cell& dest);
00114
00117 boost::optional<double> distance(ResultPtr shortest_path_result, const Cell& dest);
00118
00120 ResultPtr shortestPathResultFromMessage (const NavigationFunction& msg);
00121
00123 NavigationFunction shortestPathResultToMessage (ResultPtr res);
00124
00125
00130 boost::optional<AStarResult> shortestPath(const nav_msgs::OccupancyGrid& g,
00131 const Cell& src, const Cell& dest);
00132 }
00133
00134 #endif // include guard
00135
00136
00137