Hybrid A* Planner
 All Classes Namespaces Files Functions Variables Friends Pages
Classes | Namespaces | Variables
constants.h File Reference

This is a collection of constants that are used throughout the project. More...

#include <cmath>

Go to the source code of this file.

Classes

struct  HybridAStar::Constants::relPos
 A structure describing the relative position of the occupied cell based on the center of the vehicle. More...
 
struct  HybridAStar::Constants::config
 A structure capturing the lookup for each theta configuration. More...
 
struct  HybridAStar::Constants::color
 A structure to express colors in RGB values. More...
 

Namespaces

 HybridAStar
 The namespace that wraps the entire project.
 
 Constants
 The namespace that wraps constants.h.
 

Variables

static const bool HybridAStar::Constants::coutDEBUG = 1
 A flag for additional debugging output via std::cout
 
static const bool HybridAStar::Constants::manual = 1
 A flag for the mode (true = manual; false = dynamic). Manual for static map or dynamic for dynamic map.
 
static const bool HybridAStar::Constants::visualization = 0 * manual
 A flag for the visualization of 3D nodes (true = on; false = off)
 
static const bool HybridAStar::Constants::visualization2D = 0* manual
 A flag for the visualization of 2D nodes (true = on; false = off)
 
static const bool HybridAStar::Constants::reverse = true
 A flag to toggle reversing (true = on; false = off)
 
static const float HybridAStar::Constants::dubinsShotDistance = 1*1
 [m] — The distance to the goal when the analytical solution (Dubin's shot) first triggers
 
static const float HybridAStar::Constants::reedsSheppShotDistance = 1*1
 /// [m] — The distance to the goal when the analytical solution (ReedsShepp's shot) first triggers
 
static const bool HybridAStar::Constants::reedsShepp = true
 A flag to toggle the ReedsShepp's heuristic.
 
static const bool HybridAStar::Constants::dubins = false
 A flag to toggle the Dubin's heuristic, this should be false, if reversing is enabled (true = on; false = off)
 
static const bool HybridAStar::Constants::dubinsLookup = false * dubins
 A flag to toggle the Dubin's heuristic via lookup, potentially speeding up the search by a lot. More...
 
static const bool HybridAStar::Constants::twoD = true
 A flag to toggle the 2D heuristic (true = on; false = off)
 
static const int HybridAStar::Constants::iterations = 1000000
 [#] — Limits the maximum search depth of the algorithm, possibly terminating without the solution
 
static const double HybridAStar::Constants::bloating = 0.1
 [m] — Uniformly adds a padding around the vehicle
 
static const double HybridAStar::Constants::width = 1.75 + 2 * bloating
 [m] — The width of the vehicle
 
static const double HybridAStar::Constants::length = 2.65 + 2 * bloating
 [m] — The length of the vehicle
 
static const float HybridAStar::Constants::r = 6
 [m] — The minimum turning radius of the vehicle
 
static const int HybridAStar::Constants::headings = 72
 [m] — The number of discretizations in heading
 
static const float HybridAStar::Constants::deltaHeadingDeg = 360 / (float)headings
 [°] — The discretization value of the heading (goal condition)
 
static const float HybridAStar::Constants::deltaHeadingRad = 2 * M_PI / (float)headings
 [c*M_PI] — The discretization value of heading (goal condition)
 
static const float HybridAStar::Constants::deltaHeadingNegRad = 2 * M_PI - deltaHeadingRad
 [c*M_PI] — The heading part of the goal condition
 
static const float HybridAStar::Constants::cellSize = 1
 [m] — The cell size of the 2D grid of the world
 
static const float HybridAStar::Constants::tieBreaker = 0.01
 [m] — The tie breaker breaks ties between nodes expanded in the same cell More...
 
static const float HybridAStar::Constants::factor2D = sqrt(5) / sqrt(2) + 1
 [#] — A factor to ensure admissibility of the holonomic with obstacles heuristic
 
static const float HybridAStar::Constants::penaltyTurning = 1.03
 [#] — A movement cost penalty for turning (choosing non straight motion primitives)
 
static const float HybridAStar::Constants::penaltyReversing = 2.0
 [#] — A movement cost penalty for reversing (choosing motion primitives > 2)
 
static const float HybridAStar::Constants::penaltyCOD = 2.0
 [#] — A movement cost penalty for change of direction (changing from primitives < 3 to primitives > 2)
 
static const float HybridAStar::Constants::dubinsStepSize = 0.5
 [m] — The step size for the analytical solution (Dubin's shot) primarily relevant for collision checking
 
static const int HybridAStar::Constants::dubinsWidth = 15
 [m] — The width of the dubinsArea / 2 for the analytical solution (Dubin's shot)
 
static const int HybridAStar::Constants::dubinsArea = dubinsWidth * dubinsWidth
 [m] — The area of the lookup for the analytical solution (Dubin's shot)
 
static const int HybridAStar::Constants::bbSize = std::ceil((sqrt(width * width + length* length) + 4) / cellSize)
 [m] – The bounding box size length and width to precompute all possible headings
 
static const int HybridAStar::Constants::positionResolution = 10
 [#] — The sqrt of the number of discrete positions per cell
 
static const int HybridAStar::Constants::positions = positionResolution * positionResolution
 [#] — The number of discrete positions per cell
 
static const float HybridAStar::Constants::minRoadWidth = 2
 [m] — The minimum width of a safe road for the vehicle at hand
 
static constexpr color HybridAStar::Constants::teal = {102.f / 255.f, 217.f / 255.f, 239.f / 255.f}
 A definition for a color used for visualization.
 
static constexpr color HybridAStar::Constants::green = {166.f / 255.f, 226.f / 255.f, 46.f / 255.f}
 A definition for a color used for visualization.
 
static constexpr color HybridAStar::Constants::orange = {253.f / 255.f, 151.f / 255.f, 31.f / 255.f}
 A definition for a color used for visualization.
 
static constexpr color HybridAStar::Constants::pink = {249.f / 255.f, 38.f / 255.f, 114.f / 255.f}
 A definition for a color used for visualization.
 
static constexpr color HybridAStar::Constants::purple = {174.f / 255.f, 129.f / 255.f, 255.f / 255.f}
 A definition for a color used for visualization.
 

Detailed Description

This is a collection of constants that are used throughout the project.