Plugin-based global wavefront planner that conforms to the nav_core2
GlobalPlanner interface.
More...
#include <dlux_global_planner.h>
|
virtual bool | hasValidCachedPath (const geometry_msgs::Pose2D &local_goal, unsigned int goal_x, unsigned int goal_y) |
| Check whether there is a valid cached path where the goal hasn't changed. More...
|
|
virtual bool | shouldReturnCachedPathImmediately () const |
| Whether the planner should always return a valid cached path without running the planning algorithm. More...
|
|
virtual bool | shouldReturnNewPath (const nav_2d_msgs::Path2D &new_path, const double new_path_cost) const |
| Given a cached path is available and a new path, should the new path be the one returned? More...
|
|
Plugin-based global wavefront planner that conforms to the nav_core2
GlobalPlanner interface.
Definition at line 55 of file dlux_global_planner.h.
dlux_global_planner::DluxGlobalPlanner::DluxGlobalPlanner |
( |
| ) |
|
bool dlux_global_planner::DluxGlobalPlanner::hasValidCachedPath |
( |
const geometry_msgs::Pose2D & |
local_goal, |
|
|
unsigned int |
goal_x, |
|
|
unsigned int |
goal_y |
|
) |
| |
|
protectedvirtual |
Check whether there is a valid cached path where the goal hasn't changed.
The precise goal and the grid coordinates of the goal are passed (redundantly) so the implementing method can decide what precision to require for the goal to be the same. The default implementation uses the grid coords.
Also sets the cached goal data member(s)
- Parameters
-
local_goal | Precise (floating point) goal |
goal_x | x coordinate of the goal in the grid |
goal_y | y coordinate of the goal in the grid |
- Returns
- True if a path has been cached, the goal is the same as the cached paths, and the plan is valid
Definition at line 171 of file dlux_global_planner.cpp.
bool dlux_global_planner::DluxGlobalPlanner::isPlanValid |
( |
const nav_2d_msgs::Path2D & |
path | ) |
const |
|
virtual |
Check the costmap for any obstacles on this path.
- Parameters
-
- Returns
- True if there are no obstacles
Definition at line 87 of file dlux_global_planner.cpp.
nav_2d_msgs::Path2D dlux_global_planner::DluxGlobalPlanner::makePlan |
( |
const nav_2d_msgs::Pose2DStamped & |
start, |
|
|
const nav_2d_msgs::Pose2DStamped & |
goal |
|
) |
| |
|
overridevirtual |
bool dlux_global_planner::DluxGlobalPlanner::shouldReturnCachedPathImmediately |
( |
| ) |
const |
|
protectedvirtual |
Whether the planner should always return a valid cached path without running the planning algorithm.
- Returns
- True if the valid cached path should be returned without running the planning algorithm
Definition at line 181 of file dlux_global_planner.cpp.
bool dlux_global_planner::DluxGlobalPlanner::shouldReturnNewPath |
( |
const nav_2d_msgs::Path2D & |
new_path, |
|
|
const double |
new_path_cost |
|
) |
| const |
|
protectedvirtual |
Given a cached path is available and a new path, should the new path be the one returned?
- Parameters
-
new_path | The new path |
new_path_cost | The cost of the new path, according to the traceback |
- Returns
- True if the new path should be the one returned. If False, return the cached one
Definition at line 187 of file dlux_global_planner.cpp.
unsigned int dlux_global_planner::DluxGlobalPlanner::cached_goal_x_ |
|
protected |
unsigned int dlux_global_planner::DluxGlobalPlanner::cached_goal_y_ |
|
protected |
nav_2d_msgs::Path2D dlux_global_planner::DluxGlobalPlanner::cached_path_ |
|
protected |
double dlux_global_planner::DluxGlobalPlanner::cached_path_cost_ |
|
protected |
double dlux_global_planner::DluxGlobalPlanner::improvement_threshold_ |
|
protected |
bool dlux_global_planner::DluxGlobalPlanner::path_caching_ |
|
protected |
PotentialGrid dlux_global_planner::DluxGlobalPlanner::potential_grid_ |
|
protected |
bool dlux_global_planner::DluxGlobalPlanner::print_statistics_ |
|
protected |
The documentation for this class was generated from the following files: