Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
dlux_global_planner::Traceback Class Referenceabstract

Plugin interface for using the potential to trace a path from the start position back to the goal position. More...

#include <traceback.h>

Public Member Functions

virtual nav_2d_msgs::Path2D getPath (const PotentialGrid &potential_grid, const geometry_msgs::Pose2D &start, const geometry_msgs::Pose2D &goal, double &path_cost)=0
 Create the path from start to goal. More...
 
virtual void initialize (ros::NodeHandle &private_nh, CostInterpreter::Ptr cost_interpreter)
 Initialize function. More...
 
 Traceback ()
 
virtual ~Traceback ()=default
 

Protected Member Functions

nav_2d_msgs::Path2D mapPathToWorldPath (const nav_2d_msgs::Path2D &original, const nav_grid::NavGridInfo &info)
 Helper function to convert a path in Grid coordinates to World coordinates. More...
 

Protected Attributes

CostInterpreter::Ptr cost_interpreter_
 

Detailed Description

Plugin interface for using the potential to trace a path from the start position back to the goal position.

See README for more details

Definition at line 52 of file traceback.h.

Constructor & Destructor Documentation

dlux_global_planner::Traceback::Traceback ( )
inline

Definition at line 55 of file traceback.h.

virtual dlux_global_planner::Traceback::~Traceback ( )
virtualdefault

Member Function Documentation

virtual nav_2d_msgs::Path2D dlux_global_planner::Traceback::getPath ( const PotentialGrid potential_grid,
const geometry_msgs::Pose2D &  start,
const geometry_msgs::Pose2D &  goal,
double &  path_cost 
)
pure virtual

Create the path from start to goal.

Parameters
potential_grid[in]potential grid
start[in]start pose
goal[in]goal pose
path_cost[out]A number representing the cost of taking this path. Open to intepretation.
Returns
The path, in the same frame as the PotentialGrid
virtual void dlux_global_planner::Traceback::initialize ( ros::NodeHandle private_nh,
CostInterpreter::Ptr  cost_interpreter 
)
inlinevirtual

Initialize function.

Can be overridden to grab parameters

Parameters
private_nhNodeHandle to read parameters from
cost_interpreterCostInterpreter pointer

Definition at line 66 of file traceback.h.

nav_2d_msgs::Path2D dlux_global_planner::Traceback::mapPathToWorldPath ( const nav_2d_msgs::Path2D &  original,
const nav_grid::NavGridInfo info 
)
inlineprotected

Helper function to convert a path in Grid coordinates to World coordinates.

Does not use nav_grid::gridToWorld because that takes integer inputs, whereas the input path can be located anywhere within the grid cell.

Definition at line 88 of file traceback.h.

Member Data Documentation

CostInterpreter::Ptr dlux_global_planner::Traceback::cost_interpreter_
protected

Definition at line 100 of file traceback.h.


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


dlux_global_planner
Author(s):
autogenerated on Sun Jan 10 2021 04:08:52