Public Member Functions | Protected Member Functions | Protected Attributes
dlux_global_planner::DluxGlobalPlanner Class Reference

Plugin-based global wavefront planner that conforms to the `nav_core2` GlobalPlanner interface. More...

#include <dlux_global_planner.h>

Inheritance diagram for dlux_global_planner::DluxGlobalPlanner:
Inheritance graph
[legend]

List of all members.

Public Member Functions

 DluxGlobalPlanner ()
void initialize (const ros::NodeHandle &parent, const std::string &name, TFListenerPtr tf, nav_core2::Costmap::Ptr costmap) override
virtual bool isPlanValid (const nav_2d_msgs::Path2D &path) const
 Check the costmap for any obstacles on this path.
nav_2d_msgs::Path2D makePlan (const nav_2d_msgs::Pose2DStamped &start, const nav_2d_msgs::Pose2DStamped &goal) override

Protected Member Functions

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.
virtual bool shouldReturnCachedPathImmediately () const
 Whether the planner should always return a valid cached path without running the planning algorithm.
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?

Protected Attributes

unsigned int cached_goal_x_
unsigned int cached_goal_y_
nav_2d_msgs::Path2D cached_path_
double cached_path_cost_
pluginlib::ClassLoader
< PotentialCalculator
calc_loader_
boost::shared_ptr
< PotentialCalculator
calculator_
CostInterpreter::Ptr cost_interpreter_
nav_core2::Costmap::Ptr costmap_
double improvement_threshold_
bool path_caching_
PotentialGrid potential_grid_
nav_grid_pub_sub::ScaleGridPublisher
< float > 
potential_pub_
bool print_statistics_
TFListenerPtr tf_
boost::shared_ptr< Tracebacktraceback_
pluginlib::ClassLoader< Tracebacktraceback_loader_

Detailed Description

Plugin-based global wavefront planner that conforms to the `nav_core2` GlobalPlanner interface.

Definition at line 55 of file dlux_global_planner.h.


Constructor & Destructor Documentation

Definition at line 45 of file dlux_global_planner.cpp.


Member Function Documentation

bool dlux_global_planner::DluxGlobalPlanner::hasValidCachedPath ( const geometry_msgs::Pose2D &  local_goal,
unsigned int  goal_x,
unsigned int  goal_y 
) [protected, virtual]

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_goalPrecise (floating point) goal
goal_xx coordinate of the goal in the grid
goal_yy 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 169 of file dlux_global_planner.cpp.

void dlux_global_planner::DluxGlobalPlanner::initialize ( const ros::NodeHandle parent,
const std::string &  name,
TFListenerPtr  tf,
nav_core2::Costmap::Ptr  costmap 
) [override]

Definition at line 52 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:
pathPath to check
Returns:
True if there are no obstacles

Definition at line 85 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 
) [override, virtual]

Implements nav_core2::GlobalPlanner.

Definition at line 101 of file dlux_global_planner.cpp.

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 179 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 [protected, virtual]

Given a cached path is available and a new path, should the new path be the one returned?

Parameters:
new_pathThe new path
new_path_costThe 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 185 of file dlux_global_planner.cpp.


Member Data Documentation

Definition at line 122 of file dlux_global_planner.h.

Definition at line 122 of file dlux_global_planner.h.

Definition at line 121 of file dlux_global_planner.h.

Definition at line 123 of file dlux_global_planner.h.

Definition at line 107 of file dlux_global_planner.h.

Definition at line 108 of file dlux_global_planner.h.

Definition at line 116 of file dlux_global_planner.h.

nav_core2::Costmap::Ptr dlux_global_planner::DluxGlobalPlanner::costmap_ [protected]

Definition at line 113 of file dlux_global_planner.h.

Definition at line 120 of file dlux_global_planner.h.

Definition at line 119 of file dlux_global_planner.h.

Definition at line 115 of file dlux_global_planner.h.

Definition at line 126 of file dlux_global_planner.h.

Definition at line 129 of file dlux_global_planner.h.

Definition at line 114 of file dlux_global_planner.h.

Definition at line 110 of file dlux_global_planner.h.

Definition at line 109 of file dlux_global_planner.h.


The documentation for this class was generated from the following files:


dlux_global_planner
Author(s):
autogenerated on Wed Jun 26 2019 20:09:53