#include <occupancy_grid_utils/coordinate_conversions.h>
#include <occupancy_grid_utils/NavigationFunction.h>
#include <boost/shared_ptr.hpp>
#include <boost/optional.hpp>
#include <set>
Go to the source code of this file.
Classes | |
struct | occupancy_grid_utils::TerminationCondition |
Termination condition for shortest path search max_dist is a distance such that as soon as we see a cell with greater than this distance, we stop goals is a set such that once we've expanded all the cells in this set, we stop. More... | |
Namespaces | |
namespace | occupancy_grid_utils |
Typedefs | |
typedef std::pair< Path, double > | occupancy_grid_utils::AStarResult |
typedef std::set< Cell > | occupancy_grid_utils::Cells |
typedef std::vector< Cell > | occupancy_grid_utils::Path |
typedef boost::shared_ptr < const ShortestPathResult > | occupancy_grid_utils::ResultPtr |
Functions | |
boost::optional< double > | occupancy_grid_utils::distance (ResultPtr shortest_path_result, const Cell &dest) |
From result of single-source shortest paths, extract distance to some destination. | |
boost::optional< Path > | occupancy_grid_utils::extractPath (ResultPtr shortest_path_result, const Cell &dest) |
Extract a path from the result of single-source shortest paths. | |
nav_msgs::OccupancyGrid::Ptr | occupancy_grid_utils::inflateObstacles (const nav_msgs::OccupancyGrid &g, const double r) |
Inflate obstacles in a grid. | |
boost::optional< AStarResult > | occupancy_grid_utils::shortestPath (const nav_msgs::OccupancyGrid &g, const Cell &src, const Cell &dest) |
A* using Manhattan distance cost and heuristic, with only horizontal and vertical neighbors. | |
ResultPtr | occupancy_grid_utils::shortestPathResultFromMessage (const NavigationFunction &msg) |
Convert a shortest path result from a ros message. | |
NavigationFunction | occupancy_grid_utils::shortestPathResultToMessage (ResultPtr res) |
Convert a shortest path result to a ros message. | |
ResultPtr | occupancy_grid_utils::singleSourceShortestPaths (const nav_msgs::OccupancyGrid &g, const Cell &src) |
Single source Dijkstra's algorithm. | |
ResultPtr | occupancy_grid_utils::singleSourceShortestPaths (const nav_msgs::OccupancyGrid &g, const Cell &src, const TerminationCondition &term) |
Single source Dijkstra's algorithm. |
Shortest paths in occupancy grids
Definition in file shortest_path.h.