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

This class takes a path object and smoothes the nodes of the path. More...

#include <smoother.h>

Public Member Functions

void smoothPath (DynamicVoronoi &voronoi)
 This function takes a path consisting of nodes and attempts to iteratively smooth the same using gradient descent. More...
 
double tracePath (const Node3D *node, int i=0, std::vector< Node3D > path=std::vector< Node3D >(), double length=0)
 Given a node pointer the path to the root node will be traced recursively. More...
 
std::vector< Node3DgetPath ()
 returns the path of the smoother object
 
Vector2D obstacleTerm (Vector2D xi)
 obstacleCost - pushes the path away from obstacles
 
Vector2D curvatureTerm (Vector2D xi0, Vector2D xi1, Vector2D xi2)
 curvatureCost - forces a maximum curvature of 1/R along the path ensuring drivability
 
Vector2D smoothnessTerm (Vector2D xim2, Vector2D xim1, Vector2D xi, Vector2D xip1, Vector2D xip2)
 smoothnessCost - attempts to spread nodes equidistantly and with the same orientation
 
Vector2D voronoiTerm ()
 voronoiCost - trade off between path length and closeness to obstaclesg
 
bool isOnGrid (Vector2D vec)
 a boolean test, whether vector is on the grid or not
 

Private Attributes

float kappaMax = 1.f / (Constants::r * 1.1)
 maximum possible curvature of the non-holonomic vehicle
 
float obsDMax = Constants::minRoadWidth
 maximum distance to obstacles that is penalized
 
float vorObsDMax = Constants::minRoadWidth
 maximum distance for obstacles to influence the voronoi field
 
float alpha = 0.1
 falloff rate for the voronoi field
 
float wObstacle = 0.2
 weight for the obstacle term
 
float wVoronoi = 0
 weight for the voronoi term
 
float wCurvature = 0
 weight for the curvature term
 
float wSmoothness = 0.2
 weight for the smoothness term
 
DynamicVoronoi voronoi
 voronoi diagram describing the topology of the map
 
int width
 width of the map
 
int height
 height of the map
 
std::vector< Node3Dpath
 path to be smoothed
 

Detailed Description

This class takes a path object and smoothes the nodes of the path.

It also uses the Voronoi diagram as well as the configuration space.

Member Function Documentation

void Smoother::smoothPath ( DynamicVoronoi voronoi)

This function takes a path consisting of nodes and attempts to iteratively smooth the same using gradient descent.

During the different interations the following cost are being calculated obstacleCost curvatureCost smoothnessCost voronoiCost

double Smoother::tracePath ( const Node3D node,
int  i = 0,
std::vector< Node3D path = std::vector<Node3D>(),
double  length = 0 
)

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: