The directed DFS class. Checks whether 2 points are close inside the map in obstacle space. Uses euclidean distance to goal to guide the search. More...
#include <directed_dfs.h>
Public Member Functions | |
DirectedDFS (const nav_msgs::OccupancyGrid &map) | |
Constructor initializing underlying map. | |
bool | searchForPath (const Point2d &start, const Point2d &goal, uint32_t depth, bool in_obstacle_space=true) |
Non-recusrive start point for performing DFS. | |
Private Member Functions | |
void | getOrderedNeighbours (const Point2d &from, const Point2d &goal, const std::vector< bool > &visited, std::vector< Point2d > &neighbours, bool in_obstacle_space=true) |
Gets neighbours for a given node iff they are also obstacles and have not been visited before. | |
bool | searchForPath (const Point2d &start, const Point2d &goal, uint32_t depth, std::vector< bool > &visited, bool in_obstacle_space=true) |
Recursive function performing DFS. | |
Private Attributes | |
const nav_msgs::OccupancyGrid & | map_ |
The directed DFS class. Checks whether 2 points are close inside the map in obstacle space. Uses euclidean distance to goal to guide the search.
Definition at line 53 of file directed_dfs.h.
bwi_mapper::DirectedDFS::DirectedDFS | ( | const nav_msgs::OccupancyGrid & | map | ) | [inline] |
Constructor initializing underlying map.
map | OccupancyGrid representing underlying map |
Definition at line 61 of file directed_dfs.h.
void bwi_mapper::DirectedDFS::getOrderedNeighbours | ( | const Point2d & | from, |
const Point2d & | goal, | ||
const std::vector< bool > & | visited, | ||
std::vector< Point2d > & | neighbours, | ||
bool | in_obstacle_space = true |
||
) | [private] |
Gets neighbours for a given node iff they are also obstacles and have not been visited before.
visited | a boolean vector of size height * width containing information whether a map_idx has been visited already or not |
neighbours | returned neighbours |
Definition at line 95 of file directed_dfs.cpp.
bool bwi_mapper::DirectedDFS::searchForPath | ( | const Point2d & | start, |
const Point2d & | goal, | ||
uint32_t | depth, | ||
bool | in_obstacle_space = true |
||
) |
Non-recusrive start point for performing DFS.
depth | DFS attempts an 8 connected search. This is the max pixel depth that we perform the search to. |
Definition at line 46 of file directed_dfs.cpp.
bool bwi_mapper::DirectedDFS::searchForPath | ( | const Point2d & | start, |
const Point2d & | goal, | ||
uint32_t | depth, | ||
std::vector< bool > & | visited, | ||
bool | in_obstacle_space = true |
||
) | [private] |
Recursive function performing DFS.
Recusrive function performing DFS.
depth | DFS attempts an 8 connected search. This is the max pixel depth that we perform the search to. |
visited | a boolean vector of size height * width containing information whether a map_idx has been visited already or not |
Definition at line 56 of file directed_dfs.cpp.
const nav_msgs::OccupancyGrid& bwi_mapper::DirectedDFS::map_ [private] |
/brief the underlying map over which DFS is performed
Definition at line 99 of file directed_dfs.h.