Hybrid A* Planner
 All Classes Namespaces Files Functions Variables Friends Pages
algorithm.h
1 #ifndef ALGORITHM_H
2 #define ALGORITHM_H
3 
4 #include <ompl/base/spaces/ReedsSheppStateSpace.h>
5 #include <ompl/base/spaces/DubinsStateSpace.h>
6 #include <ompl/base/spaces/SE2StateSpace.h>
7 #include <ompl/base/State.h>
8 #include <ompl/base/ScopedState.h>
9 
10 typedef ompl::base::SE2StateSpace::StateType State;
11 
12 #include "node3d.h"
13 #include "node2d.h"
14 #include "visualize.h"
15 #include "collisiondetection.h"
16 #include "helper.h"
17 #include "vector2d.h"
18 
19 namespace HybridAStar {
20 class Node3D;
21 class Node2D;
22 class Visualize;
23 
27 class Algorithm {
28  public:
30  Algorithm() {}
31 
32  // HYBRID A* ALGORITHM
47  static Node3D* hybridAStar(Node3D& start,
48  const Node3D& goal,
49  Node3D* nodes3D,
50  Node2D* nodes2D,
51  int width,
52  int height,
53  CollisionDetection& configurationSpace,
54  float* dubinsLookup,
55  Visualize& visualization);
56 
57 };
58 }
59 #endif // ALGORITHM_H
A three dimensional node class that is at the heart of the algorithm.
Definition: node3d.h:14
A class that encompasses the functions central to the search.
Definition: algorithm.h:27
The CollisionDetection class determines whether a given configuration q of the robot will result in a...
Definition: collisiondetection.h:31
static Node3D * hybridAStar(Node3D &start, const Node3D &goal, Node3D *nodes3D, Node2D *nodes2D, int width, int height, CollisionDetection &configurationSpace, float *dubinsLookup, Visualize &visualization)
The heart of the planner, the main algorithm starting the search for a collision free and drivable pa...
Definition: algorithm.cpp:31
A two dimensional node class used for the holonomic with obstacles heuristic.
Definition: node2d.h:14
A class for visualizing the hybrid A* search.
Definition: visualize.h:23
Algorithm()
The deault constructor.
Definition: algorithm.h:30
This is a collection of helper functions that are used throughout the project.