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

A class that creates the interface for the hybrid A* algorithm. More...

#include <planner.h>

Public Member Functions

 Planner ()
 The default constructor.
 
void initializeLookups ()
 Initializes the collision as well as heuristic lookup table. More...
 
void setMap (const nav_msgs::OccupancyGrid::Ptr map)
 Sets the map e.g. through a callback from a subscriber listening to map updates. More...
 
void setStart (const geometry_msgs::PoseWithCovarianceStamped::ConstPtr &start)
 setStart More...
 
void setGoal (const geometry_msgs::PoseStamped::ConstPtr &goal)
 setGoal More...
 
void plan ()
 The central function entry point making the necessary preparations to start the planning.
 

Private Attributes

ros::NodeHandle n
 The node handle.
 
ros::Publisher pubStart
 A publisher publishing the start position for RViz.
 
ros::Subscriber subMap
 A subscriber for receiving map updates.
 
ros::Subscriber subGoal
 A subscriber for receiving goal updates.
 
ros::Subscriber subStart
 A subscriber for receiving start updates.
 
tf::TransformListener listener
 A listener that awaits transforms.
 
tf::StampedTransform transform
 A transform for moving start positions.
 
Path path
 The path produced by the hybrid A* algorithm.
 
Smoother smoother
 The smoother used for optimizing the path.
 
Path smoothedPath = Path(true)
 The path smoothed and ready for the controller.
 
Visualize visualization
 The visualization used for search visualization.
 
CollisionDetection configurationSpace
 The collission detection for testing specific configurations.
 
DynamicVoronoi voronoiDiagram
 The voronoi diagram.
 
nav_msgs::OccupancyGrid::Ptr grid
 A pointer to the grid the planner runs on.
 
geometry_msgs::PoseWithCovarianceStamped start
 The start pose set through RViz.
 
geometry_msgs::PoseStamped goal
 The goal pose set through RViz.
 
bool validStart = false
 Flags for allowing the planner to plan.
 
bool validGoal = false
 Flags for allowing the planner to plan.
 
Constants::config collisionLookup [Constants::headings *Constants::positions]
 A lookup table for configurations of the vehicle and their spatial occupancy enumeration.
 
float * dubinsLookup = new float [Constants::headings * Constants::headings * Constants::dubinsWidth * Constants::dubinsWidth]
 A lookup of analytical solutions (Dubin's paths)
 

Detailed Description

A class that creates the interface for the hybrid A* algorithm.

Member Function Documentation

void Planner::initializeLookups ( )

Initializes the collision as well as heuristic lookup table.

Todo:
probably removed
void Planner::setGoal ( const geometry_msgs::PoseStamped::ConstPtr &  goal)

setGoal

Parameters
goalthe goal pose
void Planner::setMap ( const nav_msgs::OccupancyGrid::Ptr  map)

Sets the map e.g. through a callback from a subscriber listening to map updates.

Parameters
mapthe map or occupancy grid
void Planner::setStart ( const geometry_msgs::PoseWithCovarianceStamped::ConstPtr &  start)

setStart

Parameters
startthe start pose

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