$search

shortest_path.h File Reference

#include <occupancy_grid_utils/coordinate_conversions.h>
#include <occupancy_grid_utils/NavigationFunction.h>
#include <boost/shared_ptr.hpp>
#include <boost/optional.hpp>
#include <set>
Include dependency graph for shortest_path.h:
This graph shows which files directly or indirectly include this file:

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. Note that, confusingly, max_dist is in cells though shortest path returns meters by default. Currently, we warn if use_cells is set to true below. In future (H-turtle), this api will actually change to only allow meters. 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::vector< Celloccupancy_grid_utils::Path
typedef boost::shared_ptr
< 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< double > occupancy_grid_utils::distanceTo (ResultPtr shortest_path_result, const Cell &dest)
 From result of single-source shortest paths, extract distance to some destination.
boost::optional< Pathoccupancy_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, double r, bool allow_unknown=false)
 Inflate obstacles in a grid.
boost::optional< AStarResult > occupancy_grid_utils::shortestPath (const nav_msgs::OccupancyGrid &g, const Cell &src, const Cell &dest)
 A* search that returns distance in cells. Deprecated; use shortestPathAStar instead.using Manhattan distance cost and heuristic, with only horizontal and vertical neighbors.
boost::optional< AStarResult > occupancy_grid_utils::shortestPathAStar (const nav_msgs::OccupancyGrid &g, const Cell &src, const Cell &dest)
 A* search 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, const TerminationCondition &term, bool manhattan=false)
 Single source Dijkstra's algorithm.
ResultPtr occupancy_grid_utils::singleSourceShortestPaths (const nav_msgs::OccupancyGrid &g, const Cell &src, bool manhattan=false)
 Single source Dijkstra's algorithm.

Detailed Description

Shortest paths in occupancy grids

Author:
Bhaskara Marthi

Definition in file shortest_path.h.

 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends Defines


occupancy_grid_utils
Author(s): Bhaskara Marthi
autogenerated on Fri Mar 1 16:19:40 2013