-
Notifications
You must be signed in to change notification settings - Fork 1
/
Copy pathhybrid_breadth_first.h
41 lines (37 loc) · 1.03 KB
/
hybrid_breadth_first.h
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
#pragma once
#ifndef HYBRID_BREADTH_FIRST_H
#define HYBRID_BREADTH_FIRST_H
#include<iostream>
#include<sstream>
#include<fstream>
#include<math.h>
#include<vector>
using namespace std;
class HBF {
public:
int NUM_THETA_CELLS = 90;
double SPEED = 1.45;
double LENGTH = 0.5;
struct maze_s {
int g;
int f;
double x;
double y;
double theta;
};
struct maze_path {
vector< vector< vector<int> > > closed;
vector< vector< vector<maze_s> > > came_from;
maze_s final;
};
HBF();
virtual ~HBF();
static bool compare_maze_s(const HBF::maze_s &lhs, const HBF::maze_s &rhs);
double heuristic(double x, double y, vector<int> goal);
int theta_to_stack_number(double theta);
int idx(double float_num);
vector<maze_s> expand(maze_s state, vector<int> goal);
maze_path search(vector<vector<int>> grid, vector<double> start, vector<int> goal);
vector<maze_s> reconstruct_path(vector<vector<vector<maze_s>>> came_from, vector<double> start, HBF::maze_s final);
};
#endif // !HYBRID_BREADTH_FIRST_H