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_ |
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.
|
inline |
Definition at line 55 of file traceback.h.
|
virtualdefault |
|
pure virtual |
Create the path from start to goal.
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. |
|
inlinevirtual |
Initialize function.
Can be overridden to grab parameters
private_nh | NodeHandle to read parameters from |
cost_interpreter | CostInterpreter pointer |
Definition at line 66 of file traceback.h.
|
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.
|
protected |
Definition at line 100 of file traceback.h.