directed_dfs.h
Go to the documentation of this file.
00001 
00039 #ifndef BWI_MAPPER_DIRECTED_DFS_H_
00040 #define BWI_MAPPER_DIRECTED_DFS_H_
00041 
00042 #include <nav_msgs/OccupancyGrid.h>
00043 #include <bwi_mapper/structures/point.h>
00044 
00045 namespace bwi_mapper {
00046 
00053   class DirectedDFS {
00054 
00055     public:
00056       
00061       DirectedDFS(const nav_msgs::OccupancyGrid& map) : map_(map) {}
00062 
00063       
00070       bool searchForPath(const Point2d &start, const Point2d &goal, 
00071           uint32_t depth, bool in_obstacle_space = true);
00072 
00073     private:
00074 
00083       bool searchForPath(const Point2d &start, const Point2d &goal, 
00084           uint32_t depth, std::vector<bool> &visited, 
00085           bool in_obstacle_space = true);
00086 
00094       void getOrderedNeighbours(const Point2d &from, const Point2d &goal, 
00095           const std::vector<bool> &visited, std::vector<Point2d> &neighbours,
00096           bool in_obstacle_space = true);
00097 
00099       const nav_msgs::OccupancyGrid& map_;
00100 
00101   };
00102 
00103 } /* bwi_mapper */
00104 
00105 #endif /* end of include guard: BWI_MAPPER_DIRECTED_DFS_H_ */


bwi_mapper
Author(s): Piyush Khandelwal
autogenerated on Fri Aug 28 2015 10:14:35