]> rtime.felk.cvut.cz Git - hubacji1/rrts.git/blob - incl/rrtext.hh
Update self source file with license
[hubacji1/rrts.git] / incl / rrtext.hh
1 /*
2  * SPDX-FileCopyrightText: 2021 Jiri Vlasak <jiri.vlasak.2@cvut.cz>
3  *
4  * SPDX-License-Identifier: GPL-3.0-only
5  */
6
7 /*! \brief RRT* extensions.
8  *
9  * The extensions are used to implement or change the default behavior of the
10  * RRT* algorithm.
11  *
12  * \file
13  * \defgroup ext-col Collision detection extensions
14  * \defgroup ext-store Node storage and searching tree extensions
15  * \defgroup ext-cost Cost extensions
16  * \defgroup ext-opt Path optimization extensions
17  * \defgroup ext-sampl Random sampling extensions
18  * \defgroup ext-steer Steering procedure extensions
19  * \defgroup ext-aux Auxilliary extensions
20  */
21 #ifndef RRTS_RRTEXT_H
22 #define RRTS_RRTEXT_H
23
24 #include "rrts.hh"
25
26 // ext2
27 #include "cute_c2.h"
28
29 // ext4
30 #define GRID 1 // in meters
31 #define GRID_WIDTH 40 // in meters
32 #define GRID_HEIGHT 40 // in meters
33 #define GRID_MAX_XI ((unsigned int) floor(GRID_WIDTH / GRID)) // min is 0
34 #define GRID_MAX_YI ((unsigned int) floor(GRID_HEIGHT / GRID)) // min is 0
35
36 // ext9
37 #define GRID_MAX_HI 60
38
39 namespace rrts {
40
41 /*! \brief Finish when more than 1000 iterations.
42  *
43  * \ingroup ext-aux
44  */
45 class RRTExt18 : public virtual RRTS {
46 private:
47         bool should_finish() const;
48 };
49
50 /*! \brief Finish when goal found or more than 1000 iterations.
51  *
52  * \ingroup ext-aux
53  */
54 class RRTExt17 : public virtual RRTS {
55 private:
56         bool should_finish() const;
57 };
58
59 /*! \brief Use Reeds & Shepp steering procedure.
60  *
61  * \ingroup ext-steer
62  */
63 class RRTExt16 : public virtual RRTS {
64 private:
65         void steer(RRTNode const& f, RRTNode const& t);
66 };
67
68 /*! \brief Log goal's cumulative cost each iteration.
69  *
70  * \ingroup ext-aux
71  */
72 class RRTExt15 : public virtual RRTS {
73 private:
74         std::vector<double> log_path_cost_;
75 public:
76         Json::Value json() const;
77         void json(Json::Value jvi);
78         bool next();
79 };
80
81 /*! \brief Random sampling in the circuit between root and goal.
82  *
83  * \ingroup ext-sampl
84  * \see https://stackoverflow.com/questions/5837572/generate-a-random-point-within-a-circle-uniformly/50746409#50746409
85  */
86 class RRTExt14 : public virtual RRTS {
87 private:
88         Point circle_c_;
89         double circle_r_ = 0.0;
90         std::uniform_real_distribution<double> udr_;
91         std::uniform_real_distribution<double> udt_;
92         std::uniform_real_distribution<double> udh_;
93         RRTNode sample();
94 public:
95         RRTExt14();
96         void reset();
97 };
98
99 /*! \brief Use Dijkstra algorithm to find path between interesting nodes.
100  *
101  * The search for interesting nodes starts at root, the last drivable nodes is
102  * added to interesting nodes until goal is reached.
103  *
104  * \ingroup ext-opt
105  */
106 class RRTExt13 : public virtual RRTS {
107 private:
108         class DijkstraNode {
109         public:
110                 RRTNode* node = nullptr;
111                 unsigned int i = 0;
112                 bool v = false;
113                 double d = 0.0;
114                 bool vi();
115                 DijkstraNode(RRTNode* n);
116         };
117         class DijkstraNodeComparator {
118         public:
119                 int operator() (DijkstraNode const& n1, DijkstraNode const& n2);
120         };
121         class DijkstraNodeBackwardComparator {
122         public:
123                 int operator() (DijkstraNode const& n1, DijkstraNode const& n2);
124         };
125         std::vector<RRTNode*> opath_;
126         double ogoal_cc_ = 0.0;
127         double otime_ = 0.0;
128         std::vector<DijkstraNode> dn_;
129         void interesting_forward();
130         void interesting_backward();
131         void dijkstra_forward();
132         void dijkstra_backward();
133         void compute_path();
134 public:
135         RRTExt13();
136         Json::Value json() const;
137         void json(Json::Value jvi);
138         void reset();
139 };
140
141 /* \brief Different `steer` procedures.
142
143 Use sampling in control input for `steer1`. Use R&S steering for `steer2`.
144 */
145 class RRTExt12 : public virtual RRTS {
146         protected:
147                 void steer1(RRTNode &f, RRTNode &t);
148                 bool connect();
149         public:
150                 bool next();
151 };
152
153 /* \brief Goal Zone.
154
155 */
156 class RRTExt11 : public virtual RRTS {
157         protected:
158                 bool goal_found(RRTNode &f);
159 };
160
161 /*! \brief Reeds & Shepp (build) and Euclidean + abs angle (search).
162  *
163  * Use Reeds & Shepp path length for building tree data structure and Euclidean
164  * distance plus (abs) heading difference for searching it.
165  *
166  * \ingroup ext-cost
167  * \see https://doi.org/10.1109/TITS.2015.2477355
168  */
169 class RRTExt10 : public virtual RRTS {
170 protected:
171         double cost_build(RRTNode const& f, RRTNode const& t) const;
172         double cost_search(RRTNode const& f, RRTNode const& t) const;
173 };
174
175 /* \brief Use grid data structure to store RRT nodes.
176
177 This approach speeds up the search process for the nearest neighbor and
178 the near vertices procedures.
179 */
180 class RRTExt9 : public virtual RRTS {
181         private:
182                 class Cell {
183                         private:
184                                 bool changed_ = false;
185                                 std::vector<RRTNode *> nodes_;
186                         public:
187                                 void nn(RRTNode *t, RRTNode **nn, RRTS *p);
188                                 void store_node(RRTNode *n);
189
190                                 // getter, setter
191                                 bool changed() const
192                                 {
193                                         return this->changed_;
194                                 }
195                                 std::vector<RRTNode *> &nodes()
196                                 {
197                                         return this->nodes_;
198                                 }
199
200                                 Cell();
201                 };
202                 Cell grid_[GRID_MAX_XI][GRID_MAX_YI][GRID_MAX_HI];
203                 double x_min_ = 0;
204                 double x_max_ = 0;
205                 double y_min_ = 0;
206                 double y_max_ = 0;
207                 double h_min_ = 0;
208                 double h_max_ = 2 * M_PI;
209
210                 unsigned int xi(RRTNode n);
211                 unsigned int yi(RRTNode n);
212                 unsigned int hi(RRTNode n);
213         public:
214                 void init();
215                 void deinit();
216                 void store_node(RRTNode n);
217                 RRTNode *nn(RRTNode &t);
218                 std::vector<RRTNode *> nv(RRTNode &t);
219 };
220
221 /*! \brief Use 3D k-d tree data structure to store RRT nodes.
222  *
223  * This approach speeds up the search process for the nearest neighbor and the
224  * near vertices procedures. This extension implements 3D K-d tree.
225  *
226  * \ingroup ext-store
227  * \see https://en.wikipedia.org/wiki/K-d_tree
228  */
229 class RRTExt8 : public virtual RRTS {
230 private:
231         class KdNode {
232         public:
233                 RRTNode* node = nullptr;
234                 KdNode* left = nullptr;
235                 KdNode* right = nullptr;
236                 KdNode(RRTNode* n);
237         };
238         KdNode* kdroot_ = nullptr;
239         std::vector<KdNode> kdnodes_;
240         void store(RRTNode* n, KdNode*& ref, unsigned int lvl);
241         void find_nn(RRTNode const& t, KdNode const* const r, unsigned int lvl);
242         void find_nv(RRTNode const& t, KdNode const* const r, unsigned int lvl);
243 public:
244         RRTExt8();
245         void reset();
246         void store(RRTNode n);
247         void find_nn(RRTNode const& t);
248         void find_nv(RRTNode const& t);
249 };
250
251 /* \brief Use k-d tree data structure to store RRT nodes.
252
253 This approach speeds up the search process for the nearest neighbor and
254 the near vertices procedures. This extension implements 2D K-d tree.
255
256 \see https://en.wikipedia.org/wiki/K-d_tree
257 */
258 class RRTExt7 : public virtual RRTS {
259         private:
260                 class KdNode {
261                         private:
262                                 RRTNode *node_ = nullptr;
263                                 KdNode *left_ = nullptr;
264                                 KdNode *right_ = nullptr;
265                         public:
266                                 // getter, setter
267                                 RRTNode *node() const { return this->node_; }
268                                 KdNode *&left() { return this->left_; }
269                                 KdNode *&right() { return this->right_; }
270                                 KdNode(RRTNode *n);
271                 };
272                 KdNode *kdroot_ = nullptr;
273                 void delete_kd_nodes(KdNode *n);
274                 void store_node(RRTNode *n, KdNode *&r, int l);
275                 void nn(RRTNode *&n, RRTNode &t, KdNode *r, int l, double &d);
276         public:
277                 void init();
278                 void deinit();
279                 void store_node(RRTNode n);
280                 RRTNode *nn(RRTNode &t);
281                 std::vector<RRTNode *> nv(RRTNode &t);
282 };
283
284 /*! \brief Reeds & Shepp (build, search).
285  *
286  * Use Reeds & Shepp path length for building tree data structure as well as for
287  * searching it.
288  *
289  * \ingroup ext-cost
290  */
291 class RRTExt6 : public virtual RRTS {
292 private:
293         double cost_build(RRTNode const& f, RRTNode const& t) const;
294         double cost_search(RRTNode const& f, RRTNode const& t) const;
295 };
296
297 /* \brief Different costs extension.
298
299 Use different cost for bulding tree data structure and searching in the
300 structure. This one is complementary to `rrtext1.cc`.
301 */
302 class RRTExt5 : public virtual RRTS {
303         public:
304                 /* \brief Reeds and Shepp path length.
305                 */
306                 double cost_build(RRTNode &f, RRTNode &t);
307                 /* \brief Euclidean distance.
308                 */
309                 double cost_search(RRTNode &f, RRTNode &t);
310 };
311
312 /* \brief Use grid data structure to store RRT nodes.
313
314 This approach speeds up the search process for the nearest neighbor and
315 the near vertices procedures.
316 */
317 class RRTExt4 : public virtual RRTS {
318         private:
319                 class Cell {
320                         private:
321                                 bool changed_ = false;
322                                 std::vector<RRTNode *> nodes_;
323                         public:
324                                 void nn(RRTNode *t, RRTNode **nn, RRTS *p);
325                                 void store_node(RRTNode *n);
326
327                                 // getter, setter
328                                 bool changed() const
329                                 {
330                                         return this->changed_;
331                                 }
332                                 std::vector<RRTNode *> &nodes()
333                                 {
334                                         return this->nodes_;
335                                 }
336
337                                 Cell();
338                 };
339                 Cell grid_[GRID_MAX_XI][GRID_MAX_YI]; // [0, 0] is bottom left
340                 double x_min_ = 0;
341                 double x_max_ = 0;
342                 double y_min_ = 0;
343                 double y_max_ = 0;
344
345                 unsigned int xi(RRTNode n);
346                 unsigned int yi(RRTNode n);
347         public:
348                 void init();
349                 void deinit();
350                 void store_node(RRTNode n);
351                 RRTNode *nn(RRTNode &t);
352                 std::vector<RRTNode *> nv(RRTNode &t);
353 };
354
355 /* \brief Use Dijkstra algorithm to find the shorter path.
356 */
357 class RRTExt3 : public virtual RRTS {
358         private:
359         public:
360                 void reset();
361                 std::vector<RRTNode *> orig_path_;
362                 double orig_path_cost_ = 9999;
363                 std::vector<RRTNode *> first_optimized_path_;
364                 double first_optimized_path_cost_ = 9999;
365                 void first_path_optimization();
366                 void second_path_optimization();
367                 void compute_path();
368                 Json::Value json();
369                 void json(Json::Value jvi);
370
371                 // getter, setter
372                 std::vector<RRTNode *> &orig_path()
373                 {
374                         return this->orig_path_;
375                 };
376                 double &orig_path_cost() { return this->orig_path_cost_; }
377                 void orig_path_cost(double c) { this->orig_path_cost_ = c; }
378                 std::vector<RRTNode *> &first_optimized_path()
379                 {
380                         return this->first_optimized_path_;
381                 };
382                 double &first_optimized_path_cost() {
383                         return this->first_optimized_path_cost_;
384                 }
385                 void first_optimized_path_cost(double c) {
386                         this->first_optimized_path_cost_ = c;
387                 }
388 };
389
390 /*! \brief Use cute_c2 library for collision detection.
391  *
392  * \ingroup ext-col
393  * \see https://github.com/RandyGaul/cute_headers/blob/master/cute_c2.h
394  */
395 class RRTExt2 : public virtual RRTS {
396 private:
397         c2Poly c2_bc_;
398         c2x c2x_bc_;
399         std::vector<c2Poly> c2_obstacles_;
400         bool collide(RRTNode const& n);
401         bool collide_steered();
402 public:
403         RRTExt2();
404         Json::Value json() const;
405         void json(Json::Value jvi);
406 };
407
408 /* \brief Different costs extension.
409
410 Use different cost for bulding tree data structure and searching in the
411 structure.
412 */
413 class RRTExt1 : public virtual RRTS {
414         public:
415                 /* \brief Reeds and Shepp path length.
416                 */
417                 double cost_build(RRTNode &f, RRTNode &t);
418                 /* \brief Matej's heuristics.
419                 */
420                 double cost_search(RRTNode &f, RRTNode &t);
421 };
422
423 } // namespace rrts
424 #endif /* RRTS_RRTEXT_H */