]> rtime.felk.cvut.cz Git - hubacji1/rrts.git/blob - api/rrts.h
974a3fd3df44b2543766fb223bafcbc7b6368114
[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                         std::uniform_int_distribution<unsigned int> udi_;
195                 virtual RRTNode *nn(RRTNode &t);
196                 virtual std::vector<RRTNode *> nv(RRTNode &t);
197                 void steer(RRTNode &f, RRTNode &t);
198                 virtual void steer1(RRTNode &f, RRTNode &t);
199                 virtual void steer2(RRTNode &f, RRTNode &t);
200                 /*! \brief Join steered nodes to RRT data structure
201
202                 \param f RRT node to join steered nodes to.
203                 */
204                 void join_steered(RRTNode *f);
205                 virtual bool goal_found(RRTNode &f);
206                 // RRT* procedures
207                 bool connect();
208                 void rewire();
209         public:
210                 /// ---
211                 struct { double x=0; double y=0; double b=0; double e=0; } entry;
212                 bool entry_set = false;
213                 /// ---
214                 /*! \brief Initialize RRT algorithm if needed.
215                 */
216                 virtual void init();
217                 /*! \brief Deinitialize RRT algorithm if needed.
218                 */
219                 virtual void deinit();
220                 /*! \brief Return path found by RRT*.
221                 */
222                 virtual std::vector<RRTNode *> path();
223                 /*! \brief Return ``true`` if algorithm should stop.
224
225                 Update counters (iteration, seconds, ...) and return if
226                 the current iteration should be the last one.
227                 */
228                 bool should_stop();
229                 /*! \brief Return ``true`` if the algorithm should finish.
230
231                 Finish means that the algorithm will not be resumed.
232                 */
233                 bool should_finish();
234                 /*! \brief Return ``true`` if the algorithm shoud break.
235
236                 Break means that the algorithm can be resumed.
237                 */
238                 bool should_break();
239                 /*! \brief Return ``true`` if algorithm should continue.
240
241                 `pcnt_` is set to `scnt_`, so the difference is 0 and it can
242                 start from scratch. After the `should_continue` is called,
243                 there must be `while (rrts.next()) {}` loop.
244                 */
245                 bool should_continue();
246                 /*! \brief Run next RRT* iteration.
247                 */
248                 bool next();
249                 /*! \brief Set sampling info.
250
251                 Based on `sample_dist_type`, set proper distribution
252                 parameters. The distribution parameters are relative to `front`
253                 node in `nodes` (init).
254
255                 For normal sampling:
256                 \param x1 Mean x value.
257                 \param x2 Standard deviation of x.
258                 \param y1 Mean y value.
259                 \param y2 Standard deviation of y.
260                 \param h1 Mean h value.
261                 \param h2 Standard deviation of h.
262
263                 For uniform sampling:
264                 \param x1 Minimum x value.
265                 \param x2 Maximum x value.
266                 \param y1 Minimum y value.
267                 \param y2 Maximum y value.
268                 \param h1 Minimum h value.
269                 \param h2 Maximum h value.
270
271                 For uniform circle sampling:
272                 \param x1 Ignored.
273                 \param x2 Ignored.
274                 \param y1 Ignored.
275                 \param y2 Ignored.
276                 \param h1 Ignored.
277                 \param h2 Ignored.
278                 */
279                 void set_sample(
280                         double x1, double x2,
281                         double y1, double y2,
282                         double h1, double h2
283                 );
284                 /*! \brief Generate JSON output.
285                 */
286                 Json::Value json();
287                 /*! \brief Load JSON input.
288                 */
289                 void json(Json::Value jvi);
290
291                 // RRT procedures
292                 virtual double cost_build(RRTNode &f, RRTNode &t);
293                 virtual double cost_search(RRTNode &f, RRTNode &t);
294
295                 // getters, setters
296                 unsigned int icnt() const { return this->icnt_; }
297                 double scnt() const { return this->scnt_; }
298                 bool gf() const { return this->gf_; }
299                 void gf(bool f) { this->gf_ = f; }
300                 int sample_dist_type() const { return this->sample_dist_type_;}
301                 void sample_dist_type(int t) { this->sample_dist_type_ = t; }
302                 std::vector<RRTNode> &goals() { return this->goals_; }
303                 std::vector<RRTNode> &nodes() { return this->nodes_; }
304                 std::vector<Obstacle> &obstacles() { return this->obstacles_; }
305                 std::vector<RRTNode> &samples() { return this->samples_; }
306                 std::vector<RRTNode> &steered() { return this->steered_; }
307
308                 RRTS();
309 };
310
311 /*! \brief Compute cumulative cost of RRT node.
312
313 \param t RRT node to compute cumulative cost to.
314 */
315 double cc(RRTNode &t);
316
317 #endif /* RRTS_H */