]> rtime.felk.cvut.cz Git - hubacji1/rrts.git/blob - api/rrts.h
Merge branch 'feature/opt-with-last-maneuver'
[hubacji1/rrts.git] / api / rrts.h
1 #ifndef RRTS_H
2 #define RRTS_H
3
4 #include <chrono>
5 #include <functional>
6 #include <jsoncpp/json/json.h>
7 #include <random>
8 #include <vector>
9 #include "bcar.h"
10
11 #define ETA 1.0 // for steer, nv
12 #define GAMMA(cV) ({ \
13         __typeof__ (cV) _cV = (cV); \
14         pow(log(_cV) / _cV, 1.0 / 3.0); \
15 })
16
17 /*! \brief Possible type of RRT node.
18
19 \param cusp The node that is cusp (change in direction).
20 \param connected The node that branches generated steered path.
21 */
22 class RRTNodeType {
23         public:
24                 static const unsigned int cusp = 1 << 0;
25                 static const unsigned int connected = 1 << 1;
26 };
27
28 /*! \brief RRT node basic class.
29
30 \param c Cumulative cost from RRT data structure root.
31 \param p Pointer to parent RRT node.
32 \param t Type of the RRT node (RRTNodeType).
33 // -- from BicycleCar
34 \param x Horizontal coordinate of rear axle center.
35 \param y Vertical coordinate of rear axle center.
36 \param h Heading of the car in the interval [-pi,+pi] radians.
37 \param sp Speed of the car.
38 \param st Steering of the car.
39 */
40 class RRTNode {
41         private:
42                 double c_ = 0;
43                 RRTNode *p_ = nullptr;
44                 unsigned int t_ = 0;
45                 // -- from BicycleCar
46                 // coordinates
47                 double x_ = 0;
48                 double y_ = 0;
49                 double h_ = 0;
50                 // moving
51                 double sp_ = 0;
52                 double st_ = 0;
53         public:
54                 // getters, setters
55                 double c() const { return this->c_; }
56                 void c(double c) { this->c_ = c; }
57
58                 RRTNode *p() const { return this->p_; }
59                 void p(RRTNode *p) { this->p_ = p; }
60
61                 bool t(unsigned int flag) { return this->t_ & flag; }
62                 void set_t(unsigned int flag) { this->t_ |= flag; }
63                 void clear_t(unsigned int flag) { this->t_ &= ~flag; }
64
65                 // -- from BicycleCar
66                 // getters, setters
67                 double x() const { return this->x_; }
68                 void x(double x) { this->x_ = x; }
69
70                 double y() const { return this->y_; }
71                 void y(double y) { this->y_ = y; }
72
73                 double h() const { return this->h_; }
74                 void h(double h)
75                 {
76                         while (h < -M_PI)
77                                 h += 2 * M_PI;
78                         while (h > +M_PI)
79                                 h -= 2 * M_PI;
80                         this->h_ = h;
81                 }
82
83                 double sp() const { return this->sp_; }
84                 void sp(double sp) { this->sp_ = sp; }
85
86                 double st() const { return this->st_; }
87                 void st(double st) { this->st_ = st; }
88
89                 RRTNode();
90                 RRTNode(const BicycleCar &bc);
91                 bool operator==(const RRTNode& n);
92                 friend std::ostream &operator<<(
93                         std::ostream &out,
94                         const RRTNode &bc
95                 )
96                 {
97                         out << "[" << bc.x();
98                         out << "," << bc.y();
99                         out << "," << bc.h();
100                         out << "]";
101                         return out;
102                 }
103 };
104
105 /*! \brief Polygon obstacle basic class.
106
107 \param poly Border polygon of the obstacle.
108 */
109 class Obstacle {
110         private:
111                 std::vector<std::tuple<double, double>> poly_;
112         public:
113                 // getters, setters
114                 std::vector<std::tuple<double, double>> &poly()
115                 {
116                         return this->poly_;
117                 }
118
119                 Obstacle();
120 };
121
122 /*! \brief RRT* algorithm basic class.
123
124 \param icnt RRT algorithm iterations counter.
125 \param goals The vector of goal nodes.
126 \param nodes The vector of all nodes in RRT data structure.
127 \param samples The vector of all samples of RRT algorithm.
128 \param sample_dist_type Random distribution type for sampling function (0 -
129 normal, 1 - uniform, 2 - uniform circle)
130 */
131 class RRTS {
132         private:
133                 unsigned int icnt_ = 0;
134                 std::chrono::high_resolution_clock::time_point tstart_;
135                 double scnt_ = 0;
136                 double pcnt_ = 0;
137                 bool gf_ = false;
138                 int sample_dist_type_ = 0;
139
140                 std::vector<RRTNode> goals_;
141                 std::vector<RRTNode> nodes_;
142                 std::vector<Obstacle> obstacles_;
143                 std::vector<RRTNode> samples_;
144                 std::vector<RRTNode> steered_;
145                 double log_path_time_ = 0.1;
146                 std::vector<double> log_path_cost_;
147
148                 /*! \brief Update and return elapsed time.
149                 */
150                 double elapsed();
151                 /*! \brief Log current path cost.
152                 */
153                 void log_path_cost();
154                 /*! \brief Set normal distribution for sampling.
155                 */
156                 void set_sample_normal(
157                         double x1, double x2,
158                         double y1, double y2,
159                         double h1, double h2
160                 );
161                 /*! \brief Set uniform distribution for sampling.
162                 */
163                 void set_sample_uniform(
164                         double x1, double x2,
165                         double y1, double y2,
166                         double h1, double h2
167                 );
168                 /*! \brief Set uniform circle distribution for sampling.
169                 */
170                 void set_sample_uniform_circle();
171         protected:
172                 double path_cost_before_opt_ = 9999;
173
174                 BicycleCar bc;
175                 /*! \brief Store RRT node to tree data structure.
176                 */
177                 virtual void store_node(RRTNode n);
178
179                 // RRT procedures
180                 std::tuple<bool, unsigned int, unsigned int>
181                 collide(std::vector<std::tuple<double, double>> &poly);
182                 virtual std::tuple<bool, unsigned int, unsigned int>
183                 collide_steered_from(RRTNode &f);
184                 virtual std::tuple<bool, unsigned int, unsigned int>
185                 collide_two_nodes(RRTNode &f, RRTNode &t);
186                 void sample();
187                         std::default_random_engine gen_;
188                         std::normal_distribution<double> ndx_;
189                         std::normal_distribution<double> ndy_;
190                         std::normal_distribution<double> ndh_;
191                         std::uniform_real_distribution<double> udx_;
192                         std::uniform_real_distribution<double> udy_;
193                         std::uniform_real_distribution<double> udh_;
194                 virtual RRTNode *nn(RRTNode &t);
195                 virtual std::vector<RRTNode *> nv(RRTNode &t);
196                 void steer(RRTNode &f, RRTNode &t);
197                 /*! \brief Join steered nodes to RRT data structure
198
199                 \param f RRT node to join steered nodes to.
200                 */
201                 void join_steered(RRTNode *f);
202                 virtual bool goal_found(RRTNode &f);
203                 // RRT* procedures
204                 bool connect();
205                 void rewire();
206         public:
207                 /*! \brief Initialize RRT algorithm if needed.
208                 */
209                 virtual void init();
210                 /*! \brief Deinitialize RRT algorithm if needed.
211                 */
212                 virtual void deinit();
213                 /*! \brief Return path found by RRT*.
214                 */
215                 virtual std::vector<RRTNode *> path();
216                 /*! \brief Return ``true`` if algorithm should stop.
217
218                 Update counters (iteration, seconds, ...) and return if
219                 the current iteration should be the last one.
220                 */
221                 bool should_stop();
222                 /*! \brief Return ``true`` if the algorithm should finish.
223
224                 Finish means that the algorithm will not be resumed.
225                 */
226                 bool should_finish();
227                 /*! \brief Return ``true`` if the algorithm shoud break.
228
229                 Break means that the algorithm can be resumed.
230                 */
231                 bool should_break();
232                 /*! \brief Return ``true`` if algorithm should continue.
233
234                 `pcnt_` is set to `scnt_`, so the difference is 0 and it can
235                 start from scratch. After the `should_continue` is called,
236                 there must be `while (rrts.next()) {}` loop.
237                 */
238                 bool should_continue();
239                 /*! \brief Run next RRT* iteration.
240                 */
241                 bool next();
242                 /*! \brief Set sampling info.
243
244                 Based on `sample_dist_type`, set proper distribution
245                 parameters. The distribution parameters are relative to `front`
246                 node in `nodes` (init).
247
248                 For normal sampling:
249                 \param x1 Mean x value.
250                 \param x2 Standard deviation of x.
251                 \param y1 Mean y value.
252                 \param y2 Standard deviation of y.
253                 \param h1 Mean h value.
254                 \param h2 Standard deviation of h.
255
256                 For uniform sampling:
257                 \param x1 Minimum x value.
258                 \param x2 Maximum x value.
259                 \param y1 Minimum y value.
260                 \param y2 Maximum y value.
261                 \param h1 Minimum h value.
262                 \param h2 Maximum h value.
263
264                 For uniform circle sampling:
265                 \param x1 Ignored.
266                 \param x2 Ignored.
267                 \param y1 Ignored.
268                 \param y2 Ignored.
269                 \param h1 Ignored.
270                 \param h2 Ignored.
271                 */
272                 void set_sample(
273                         double x1, double x2,
274                         double y1, double y2,
275                         double h1, double h2
276                 );
277                 /*! \brief Generate JSON output.
278                 */
279                 Json::Value json();
280                 /*! \brief Load JSON input.
281                 */
282                 void json(Json::Value jvi);
283
284                 // RRT procedures
285                 virtual double cost_build(RRTNode &f, RRTNode &t);
286                 virtual double cost_search(RRTNode &f, RRTNode &t);
287
288                 // getters, setters
289                 unsigned int icnt() const { return this->icnt_; }
290                 double scnt() const { return this->scnt_; }
291                 bool gf() const { return this->gf_; }
292                 void gf(bool f) { this->gf_ = f; }
293                 int sample_dist_type() const { return this->sample_dist_type_;}
294                 void sample_dist_type(int t) { this->sample_dist_type_ = t; }
295                 std::vector<RRTNode> &goals() { return this->goals_; }
296                 std::vector<RRTNode> &nodes() { return this->nodes_; }
297                 std::vector<Obstacle> &obstacles() { return this->obstacles_; }
298                 std::vector<RRTNode> &samples() { return this->samples_; }
299                 std::vector<RRTNode> &steered() { return this->steered_; }
300
301                 RRTS();
302 };
303
304 /*! \brief Compute cumulative cost of RRT node.
305
306 \param t RRT node to compute cumulative cost to.
307 */
308 double cc(RRTNode &t);
309
310 #endif /* RRTS_H */