Performs a 4-connected dynamic programming search around a given point to find which other points it is connected to in the map. More...
#include <path_finder.h>
Public Member Functions | |
int | getManhattanDistance (const Point2d &pt) |
bool | pathExists (const Point2d &pt) |
PathFinder (const nav_msgs::OccupancyGrid &map, const Point2d &start_pt) | |
Public Attributes | |
std::vector< int > | search_space_ |
int | width_ |
Static Public Attributes | |
static const int | NOT_CONNECTED = -1 |
static const int | OBSTACLE = -2 |
Performs a 4-connected dynamic programming search around a given point to find which other points it is connected to in the map.
Definition at line 48 of file path_finder.h.
bwi_mapper::PathFinder::PathFinder | ( | const nav_msgs::OccupancyGrid & | map, |
const Point2d & | start_pt | ||
) |
Definition at line 41 of file path_finder.cpp.
int bwi_mapper::PathFinder::getManhattanDistance | ( | const Point2d & | pt | ) |
Definition at line 107 of file path_finder.cpp.
bool bwi_mapper::PathFinder::pathExists | ( | const Point2d & | pt | ) |
Definition at line 103 of file path_finder.cpp.
const int bwi_mapper::PathFinder::NOT_CONNECTED = -1 [static] |
Definition at line 53 of file path_finder.h.
const int bwi_mapper::PathFinder::OBSTACLE = -2 [static] |
Definition at line 52 of file path_finder.h.
std::vector<int> bwi_mapper::PathFinder::search_space_ |
Definition at line 63 of file path_finder.h.
/brief the underlying map over which DFS is performed
Definition at line 62 of file path_finder.h.