Hybrid A* Planner
 All Classes Namespaces Files Functions Variables Friends Pages
Public Member Functions | Private Attributes | List of all members
HybridAStar::Path Class Reference

A class for tracing and visualizing the path generated by the Planner. More...

#include <path.h>

Public Member Functions

 Path (bool smoothed=false)
 The default constructor initializing the path object and setting publishers for the same.
 
void updatePath (std::vector< Node3D > nodePath)
 Given a node pointer the path to the root node will be traced recursively. More...
 
void addSegment (const Node3D &node)
 Adds a segment to the path. More...
 
void addNode (const Node3D &node, int i)
 Adds a node to the path. More...
 
void addVehicle (const Node3D &node, int i)
 Adds a vehicle shape to the path. More...
 
void clear ()
 Clears the path.
 
void publishPath ()
 Publishes the path.
 
void publishPathNodes ()
 Publishes the nodes of the path.
 
void publishPathVehicles ()
 Publishes the vehicle along the path.
 

Private Attributes

ros::NodeHandle n
 A handle to the ROS node.
 
ros::Publisher pubPath
 Publisher for the path as a spline.
 
ros::Publisher pubPathNodes
 Publisher for the nodes on the path.
 
ros::Publisher pubPathVehicles
 Publisher for the vehicle along the path.
 
nav_msgs::Path path
 Path data structure for visualization.
 
visualization_msgs::MarkerArray pathNodes
 Nodes data structure for visualization.
 
visualization_msgs::MarkerArray pathVehicles
 Vehicle data structure for visualization.
 
bool smoothed = false
 Value that indicates that the path is smoothed/post processed.
 

Detailed Description

A class for tracing and visualizing the path generated by the Planner.

Member Function Documentation

void Path::addNode ( const Node3D node,
int  i 
)

Adds a node to the path.

Parameters
nodea 3D node
ia parameter for counting the number of nodes
void Path::addSegment ( const Node3D node)

Adds a segment to the path.

Parameters
nodea 3D node
void Path::addVehicle ( const Node3D node,
int  i 
)

Adds a vehicle shape to the path.

Parameters
nodea 3D node
ia parameter for counting the number of nodes
void Path::updatePath ( std::vector< Node3D nodePath)

Given a node pointer the path to the root node will be traced recursively.

Parameters
nodea 3D node, usually the goal node
ia parameter for counting the number of nodes

Given a node pointer the path to the root node will be traced recursively

Parameters
nodea 3D node, usually the goal node
ia parameter for counting the number of nodes

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