Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
dlux_plugins::GradientPath Class Reference

Traceback function that creates a smooth gradient from the start to the goal. More...

#include <gradient_path.h>

Inheritance diagram for dlux_plugins::GradientPath:
Inheritance graph
[legend]

Public Member Functions

nav_2d_msgs::Path2D getPath (const dlux_global_planner::PotentialGrid &potential_grid, const geometry_msgs::Pose2D &start, const geometry_msgs::Pose2D &goal, double &path_cost) override
 
void initialize (ros::NodeHandle &private_nh, dlux_global_planner::CostInterpreter::Ptr cost_interpreter) override
 
- Public Member Functions inherited from dlux_global_planner::Traceback
 Traceback ()
 
virtual ~Traceback ()=default
 

Protected Member Functions

void calculateGradient (const dlux_global_planner::PotentialGrid &potential_grid, const nav_grid::Index &index)
 
nav_grid::Index gridStep (const dlux_global_planner::PotentialGrid &potential_grid, const nav_grid::Index &index)
 
bool shouldGridStep (const dlux_global_planner::PotentialGrid &potential_grid, const nav_grid::Index &index)
 
- Protected Member Functions inherited from dlux_global_planner::Traceback
nav_2d_msgs::Path2D mapPathToWorldPath (const nav_2d_msgs::Path2D &original, const nav_grid::NavGridInfo &info)
 

Protected Attributes

nav_grid::VectorNavGrid< double > gradx_
 
nav_grid::VectorNavGrid< double > grady_
 
bool grid_step_near_high_
 
double iteration_factor_
 
double lethal_cost_
 
double step_size_
 
- Protected Attributes inherited from dlux_global_planner::Traceback
CostInterpreter::Ptr cost_interpreter_
 

Detailed Description

Traceback function that creates a smooth gradient from the start to the goal.

Definition at line 47 of file gradient_path.h.

Member Function Documentation

void dlux_plugins::GradientPath::calculateGradient ( const dlux_global_planner::PotentialGrid potential_grid,
const nav_grid::Index index 
)
inlineprotected

Definition at line 361 of file gradient_path.cpp.

nav_2d_msgs::Path2D dlux_plugins::GradientPath::getPath ( const dlux_global_planner::PotentialGrid potential_grid,
const geometry_msgs::Pose2D &  start,
const geometry_msgs::Pose2D &  goal,
double &  path_cost 
)
overridevirtual

Implements dlux_global_planner::Traceback.

Definition at line 63 of file gradient_path.cpp.

nav_grid::Index dlux_plugins::GradientPath::gridStep ( const dlux_global_planner::PotentialGrid potential_grid,
const nav_grid::Index index 
)
protected

Definition at line 255 of file gradient_path.cpp.

void dlux_plugins::GradientPath::initialize ( ros::NodeHandle private_nh,
dlux_global_planner::CostInterpreter::Ptr  cost_interpreter 
)
overridevirtual

Reimplemented from dlux_global_planner::Traceback.

Definition at line 48 of file gradient_path.cpp.

bool dlux_plugins::GradientPath::shouldGridStep ( const dlux_global_planner::PotentialGrid potential_grid,
const nav_grid::Index index 
)
protected

Definition at line 235 of file gradient_path.cpp.

Member Data Documentation

nav_grid::VectorNavGrid<double> dlux_plugins::GradientPath::gradx_
protected

Definition at line 64 of file gradient_path.h.

nav_grid::VectorNavGrid<double> dlux_plugins::GradientPath::grady_
protected

Definition at line 64 of file gradient_path.h.

bool dlux_plugins::GradientPath::grid_step_near_high_
protected

Definition at line 63 of file gradient_path.h.

double dlux_plugins::GradientPath::iteration_factor_
protected

Definition at line 62 of file gradient_path.h.

double dlux_plugins::GradientPath::lethal_cost_
protected

Definition at line 61 of file gradient_path.h.

double dlux_plugins::GradientPath::step_size_
protected

Definition at line 60 of file gradient_path.h.


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


dlux_plugins
Author(s):
autogenerated on Sun Jan 10 2021 04:08:54