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