]> rtime.felk.cvut.cz Git - hubacji1/iamcar.git/blob - decision_control/rrtplanner.cc
Use indexing getters
[hubacji1/iamcar.git] / decision_control / rrtplanner.cc
1 /*
2 This file is part of I am car.
3
4 I am car is free software: you can redistribute it and/or modify
5 it under the terms of the GNU General Public License as published by
6 the Free Software Foundation, either version 3 of the License, or
7 (at your option) any later version.
8
9 I am car is distributed in the hope that it will be useful,
10 but WITHOUT ANY WARRANTY; without even the implied warranty of
11 MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
12 GNU General Public License for more details.
13
14 You should have received a copy of the GNU General Public License
15 along with I am car. If not, see <http://www.gnu.org/licenses/>.
16 */
17
18 #include <iostream>
19 #include <cstdlib>
20 #include <ctime>
21 #include "compile.h"
22 #include "nn.h"
23 #include "nv.h"
24 #include "sample.h"
25 #include "steer.h"
26 #include "rrtplanner.h"
27 #include "cost.h"
28
29 #define CATI(a, b) a ## b
30 #define CAT(a, b) CATI(a, b)
31 #define KUWATA2008_CCOST CAT(c, CO)
32 #define KUWATA2008_DCOST CO
33
34 LaValle1998::LaValle1998(RRTNode *init, RRTNode *goal):
35         RRTBase(init, goal)
36 {
37         srand(static_cast<unsigned>(time(0)));
38 }
39
40 bool LaValle1998::next()
41 {
42         RRTNode *rs;
43 #if GOALFIRST > 0
44         if (this->samples().size() == 0)
45                 rs = this->goal();
46         else
47                 rs = this->sample();
48 #else
49         rs = this->sample();
50 #endif
51         this->samples().push_back(rs);
52         RRTNode *nn = this->nn(rs);
53         RRTNode *pn = nn;
54         bool en_add = true;
55         for (auto ns: this->steer(nn, rs)) {
56                 if (!en_add) {
57                         delete ns;
58                 } else {
59                         this->nodes().push_back(ns);
60                         this->add_iy(ns);
61                         pn->add_child(ns, this->cost(pn, ns));
62                         if (this->collide(pn, ns)) {
63                                 pn->children().pop_back();
64                                 ns->remove_parent();
65                                 this->iy_[this->YI(ns)].pop_back();
66                                 en_add = false;
67                         } else {
68                                 this->ocost(ns);
69                                 pn = ns;
70                                 if (this->goal_found(pn, CO)) {
71                                         this->tlog(this->findt());
72                                         en_add = false;
73                                 }
74                         }
75                 }
76         }
77         return this->goal_found();
78 }
79
80 Kuwata2008::Kuwata2008(RRTNode *init, RRTNode *goal):
81         RRTBase(init, goal)
82 {
83         srand(static_cast<unsigned>(time(0)));
84 }
85
86 bool Kuwata2008::next()
87 {
88         RRTNode *rs;
89         if (this->samples().size() == 0) {
90                 rs = this->goal();
91         } else {
92                 rs = this->sample();
93         }
94         this->samples().push_back(rs);
95         float heur = static_cast<float>(rand()) / static_cast<float>(RAND_MAX);
96         if (this->goal_found()) {
97                 if (heur < 0.7)
98                         {}//this->cost = &KUWATA2008_CCOST;
99                 else
100                         {}//this->cost = &KUWATA2008_DCOST;
101         } else {
102                 if (heur < 0.3)
103                         {}//this->cost = &KUWATA2008_CCOST;
104                 else
105                         {}//this->cost = &KUWATA2008_DCOST;
106         }
107         RRTNode *nn = this->nn(rs);
108         RRTNode *pn = nn;
109         std::vector<RRTNode *> newly_added;
110         bool en_add = true;
111         for (auto ns: this->steer(nn, rs)) {
112                 if (!en_add) {
113                         delete ns;
114                 } else {
115                         this->nodes().push_back(ns);
116                         this->add_iy(ns);
117                         pn->add_child(ns, KUWATA2008_DCOST(pn, ns));
118                         if (this->collide(pn, ns)) {
119                                 pn->children().pop_back();
120                                 ns->remove_parent();
121                                 this->iy_[this->YI(ns)].pop_back();
122                                 en_add = false;
123                         } else {
124                                 this->ocost(ns);
125                                 pn = ns;
126                                 newly_added.push_back(pn);
127                                 if (this->goal_found(pn, &KUWATA2008_DCOST)) {
128                                         this->tlog(this->findt());
129                                         en_add = false;
130                                 }
131                         }
132                 }
133         }
134         if (this->samples().size() <= 1)
135                 return this->goal_found();
136         for (auto na: newly_added) {
137                 pn = na;
138                 en_add = true;
139                 for (auto ns: this->steer(na, this->goal())) {
140                         if (!en_add) {
141                                 delete ns;
142                         } else {
143                                 this->nodes().push_back(ns);
144                                 this->add_iy(ns);
145                                 pn->add_child(ns, KUWATA2008_DCOST(pn, ns));
146                                 if (this->collide(pn, ns)) {
147                                         pn->children().pop_back();
148                                         ns->remove_parent();
149                                         this->iy_[this->YI(ns)].pop_back();
150                                         en_add = false;
151                                 } else {
152                                         this->ocost(ns);
153                                         pn = ns;
154                                         if (this->goal_found(pn,
155                                                         &KUWATA2008_DCOST)) {
156                                                 this->tlog(this->findt());
157                                                 en_add = false;
158                                         }
159                                 }
160                         }
161                 }
162         }
163         return this->goal_found();
164 }
165
166 Karaman2011::Karaman2011()
167 {
168         srand(static_cast<unsigned>(time(0)));
169 }
170
171 Karaman2011::Karaman2011(RRTNode *init, RRTNode *goal)
172         : RRTBase(init, goal)
173 {
174         srand(static_cast<unsigned>(time(0)));
175 }
176
177 bool Karaman2011::next()
178 {
179         RRTNode *rs;
180 #if GOALFIRST > 0
181         if (this->samples().size() == 0)
182                 rs = this->goal();
183         else
184                 rs = this->sample();
185 #else
186         rs = this->sample();
187 #endif
188         this->samples().push_back(rs);
189         RRTNode *nn = this->nn(rs);
190         RRTNode *pn = nn;
191         std::vector<RRTNode *> nvs;
192         bool en_add = true;
193         bool skip = false;
194         for (auto ns: this->steer(nn, rs)) {
195                 if (!en_add) {
196                         delete ns;
197                 } else if (IS_NEAR(nn, ns)) {
198                         delete ns;
199                 } else {
200                         if (IS_NEAR(ns, rs))
201                                 en_add = false;
202                         nvs = this->nv(ns,
203                                         MIN(GAMMA_RRTSTAR(
204                                                         this->nodes().size()),
205                                                         0.2));
206                         skip = false;
207                         for (auto nv: nvs) {
208                                 if (IS_NEAR(nv, ns))
209                                         skip = true;
210                         }
211                         if (skip)
212                                 continue;
213                         this->nodes().push_back(ns);
214                         this->add_iy(ns);
215                         // connect
216                         if (!this->connect(pn, ns, nvs)) {
217                                 this->iy_[this->YI(ns)].pop_back();
218                                 en_add = false;
219                         } else {
220                                 // rewire
221                                 this->rewire(nvs, ns);
222                                 pn = ns;
223                                 if (this->goal_found(pn, CO)) {
224                                         this->tlog(this->findt());
225                                         en_add = false;
226                                 }
227                         }
228                 }
229         }
230         return this->goal_found();
231 }
232
233 bool Karaman2011::connect(
234                 RRTNode *pn,
235                 RRTNode *ns,
236                 std::vector<RRTNode *> nvs)
237 {
238         RRTNode *op; // old parent
239         float od; // old direct cost
240         float oc; // old cumulative cost
241         bool connected = false;
242         pn->add_child(ns, this->cost(pn, ns));
243         if (this->collide(pn, ns)) {
244                 pn->children().pop_back();
245                 ns->remove_parent();
246         } else {
247                 this->ocost(ns);
248                 connected = true;
249         }
250         for (auto nv: nvs) {
251                 if (!connected || (nv->ccost() + this->cost(nv, ns) <
252                                 ns->ccost())) {
253                         op = ns->parent();
254                         od = ns->dcost();
255                         oc = ns->ccost();
256                         nv->add_child(ns, this->cost(nv, ns));
257                         if (this->collide(nv, ns)) {
258                                 nv->children().pop_back();
259                                 if (op)
260                                         ns->parent(op);
261                                 else
262                                         ns->remove_parent();
263                                 ns->dcost(od);
264                                 ns->ccost(oc);
265                         } else if (connected) {
266                                 op->children().pop_back();
267                         } else {
268                                 this->ocost(ns);
269                                 connected = true;
270                         }
271                 }
272         }
273         return connected;
274 }
275
276 bool Karaman2011::rewire(std::vector<RRTNode *> nvs, RRTNode *ns)
277 {
278         RRTNode *op; // old parent
279         float od; // old direct cost
280         float oc; // old cumulative cost
281         for (auto nv: nvs) {
282                 if (ns->ccost() + this->cost(ns, nv) < nv->ccost()) {
283                         op = nv->parent();
284                         od = nv->dcost();
285                         oc = nv->ccost();
286                         ns->add_child(nv, this->cost(ns, nv));
287                         if (this->collide(ns, nv)) {
288                                 ns->children().pop_back();
289                                 nv->parent(op);
290                                 nv->dcost(od);
291                                 nv->ccost(oc);
292                         } else {
293                                 op->rem_child(nv);
294                         }
295                 }
296         }
297         return true;
298 }
299
300 T1::T1(RRTNode *init, RRTNode *goal):
301         RRTBase(init, goal)
302 {
303         srand(static_cast<unsigned>(time(0)));
304 }
305
306 bool T1::next()
307 {
308         RRTNode *rs;
309         if (this->samples().size() == 0)
310                 rs = this->goal();
311         else
312                 rs = this->sample();
313         this->samples().push_back(rs);
314         RRTNode *nn = this->nn(rs);
315         RRTNode *pn = nn;
316         std::vector<RRTNode *> nvs;
317         bool connected;
318         RRTNode *op; // old parent
319         float od; // old direct cost
320         float oc; // old cumulative cost
321         std::vector<RRTNode *> steered = this->steer(nn, rs);
322         // RRT* for first node
323         RRTNode *ns = steered[0];
324         {
325                 nvs = this->nv(ns, MIN(
326                                 GAMMA_RRTSTAR(this->nodes().size()),
327                                 0.2)); // TODO const
328                 this->nodes().push_back(ns);
329                 this->add_iy(ns);
330                 connected = false;
331                 pn->add_child(ns, this->cost(pn, ns));
332                 if (this->collide(pn, ns)) {
333                         pn->children().pop_back();
334                 } else {
335                         connected = true;
336                 }
337                 // connect
338                 for (auto nv: nvs) {
339                         if (!connected || (nv->ccost() + this->cost(nv, ns) <
340                                         ns->ccost())) {
341                                 op = ns->parent();
342                                 od = ns->dcost();
343                                 oc = ns->ccost();
344                                 nv->add_child(ns, this->cost(nv, ns));
345                                 if (this->collide(nv, ns)) {
346                                         nv->children().pop_back();
347                                         ns->parent(op);
348                                         ns->dcost(od);
349                                         ns->ccost(oc);
350                                 } else if (connected) {
351                                         op->children().pop_back();
352                                 } else {
353                                         connected = true;
354                                 }
355                         }
356                 }
357                 if (!connected)
358                         return false;
359                 // rewire
360                 for (auto nv: nvs) {
361                         if (ns->ccost() + this->cost(ns, nv) < nv->ccost()) {
362                                 op = nv->parent();
363                                 od = nv->dcost();
364                                 oc = nv->ccost();
365                                 ns->add_child(nv, this->cost(ns, nv));
366                                 if (this->collide(ns, nv)) {
367                                         ns->children().pop_back();
368                                         nv->parent(op);
369                                         nv->dcost(od);
370                                         nv->ccost(oc);
371                                 } else {
372                                         op->rem_child(nv);
373                                 }
374                         }
375                 }
376                 pn = ns;
377                 if (this->goal_found(pn, CO)) {
378                         this->tlog(this->findt());
379                 }
380         }
381         unsigned int i = 0;
382         for (i = 1; i < steered.size(); i++) {
383                 ns = steered[i];
384                 this->nodes().push_back(ns);
385                 this->add_iy(ns);
386                 pn->add_child(ns, this->cost(pn, ns));
387                 if (this->collide(pn, ns)) {
388                         pn->children().pop_back();
389                         break;
390                 }
391                 pn = ns;
392                 if (this->goal_found(pn, CO)) {
393                         this->tlog(this->findt());
394                         break;
395                 }
396         }
397         return this->goal_found();
398 }
399
400 bool T2::next()
401 {
402         RRTNode *rs;
403         if (this->firsts().size() > 0) {
404                 rs = this->firsts().front();
405                 this->firsts().pop();
406         } else {
407                 rs = this->sample();
408         }
409         this->samples().push_back(rs);
410         RRTNode *nn = this->nn(rs);
411         if (!nn)
412                 return false;
413         RRTNode *pn = nn;
414         std::vector<RRTNode *> nvs;
415         std::vector<RRTNode *> newly_added;
416         bool en_add = true;
417         int cusps = 0;
418         for (auto ns: this->steer(nn, rs)) {
419                 ns->rs(rs);
420                 if (!en_add) {
421                         delete ns;
422                 } else if (IS_NEAR(pn, ns)) {
423                         delete ns;
424                 } else {
425                         if (sgn(ns->s()) == 0 || sgn(pn->s()) != sgn(ns->s()))
426                                 cusps++;
427                         if (cusps > 4)
428                                 en_add = false;
429                         nvs = this->nv(
430                                         ns,
431                                         MIN(
432                                                 GAMMA_RRTSTAR(
433                                                         this->nodes().size()),
434                                                 0.2)); // TODO const
435                         this->nodes().push_back(ns);
436                         this->add_iy(ns);
437                         // connect
438                         if (!this->connect(pn, ns, nvs)) {
439                                 this->iy_[this->YI(ns)].pop_back();
440                                 this->nodes().pop_back();
441                                 delete ns;
442                                 en_add = false;
443                         } else {
444                                 this->add_ixy(ns);
445                                 // rewire
446                                 this->rewire(nvs, ns);
447                                 pn = ns;
448                                 newly_added.push_back(pn);
449                                 if (this->goal_found(pn, CO)) {
450                                         this->goal_cost();
451                                         this->tlog(this->findt());
452                                         en_add = false;
453                                 }
454                         }
455                 }
456         }
457         if (this->samples().size() <= 1)
458                 return this->goal_found();
459         // steer to goal
460         for (auto na: newly_added) {
461                 pn = na;
462                 en_add = true;
463                 cusps = 0;
464                 for (auto ns: this->steer(na, this->goal())) {
465                         ns->rs(rs);
466                         if (!en_add) {
467                                 delete ns;
468                         } else if (IS_NEAR(pn, ns)) {
469                                 delete ns;
470                         } else {
471                                 if (sgn(pn->s()) != sgn(ns->s()))
472                                         cusps++;
473                                 if (cusps > 4)
474                                         en_add = false;
475                                 this->nodes().push_back(ns);
476                                 this->add_iy(ns);
477                                 pn->add_child(ns, this->cost(pn, ns));
478                                 if (this->collide(pn, ns)) {
479                                         pn->children().pop_back();
480                                         ns->remove_parent();
481                                         this->iy_[this->YI(ns)].pop_back();
482                                         this->nodes().pop_back();
483                                         delete ns;
484                                         en_add = false;
485                                 } else {
486                                         this->add_ixy(ns);
487                                         this->ocost(ns);
488                                         pn = ns;
489                                         if (this->goal_found(pn, CO)) {
490                                                 this->goal_cost();
491                                                 this->tlog(this->findt());
492                                                 en_add = false;
493                                         }
494                                 }
495                         }
496                 }
497         }
498         // steer to goals
499         for (auto na: newly_added) {
500         for (auto go: this->goals()) {
501                 pn = na;
502                 en_add = true;
503                 cusps = 0;
504                 for (auto ns: this->steer(na, go)) {
505                         ns->rs(rs);
506                         if (!en_add) {
507                                 delete ns;
508                         } else if (IS_NEAR(pn, ns)) {
509                                 delete ns;
510                         } else {
511                                 if (sgn(pn->s()) != sgn(ns->s()))
512                                         cusps++;
513                                 if (cusps > 4)
514                                         en_add = false;
515                                 this->nodes().push_back(ns);
516                                 this->add_iy(ns);
517                                 pn->add_child(ns, this->cost(pn, ns));
518                                 if (this->collide(pn, ns)) {
519                                         pn->children().pop_back();
520                                         ns->remove_parent();
521                                         this->iy_[this->YI(ns)].pop_back();
522                                         this->nodes().pop_back();
523                                         delete ns;
524                                         en_add = false;
525                                 } else {
526                                         this->add_ixy(ns);
527                                         this->ocost(ns);
528                                         pn = ns;
529                                         if (this->goal_found(pn, go)) {
530                                                 this->tlog(this->findt());
531                                                 en_add = false;
532                                         }
533                                 }
534                         }
535                 }
536         }}
537         return this->goal_found();
538 }
539
540 float T2::goal_cost()
541 {
542         std::vector<RRTNode *> nvs;
543         nvs = this->nv(this->goal(), 0.2);
544         for (auto nv: nvs) {
545                 if (std::abs(this->goal()->h() - nv->h()) >=
546                                 this->GOAL_FOUND_ANGLE)
547                         continue;
548                 if (nv->ccost() + this->cost(nv, this->goal()) >=
549                                 this->goal()->ccost())
550                         continue;
551                 RRTNode *op; // old parent
552                 float oc; // old cumulative cost
553                 float od; // old direct cost
554                 op = this->goal()->parent();
555                 oc = this->goal()->ccost();
556                 od = this->goal()->dcost();
557                 nv->add_child(this->goal(),
558                                 this->cost(nv, this->goal()));
559                 if (this->collide(nv, this->goal())) {
560                         nv->children().pop_back();
561                         this->goal()->parent(op);
562                         this->goal()->ccost(oc);
563                         this->goal()->dcost(od);
564                 } else {
565                         op->rem_child(this->goal());
566                 }
567         }
568         return this->goal()->ccost();
569 }
570
571 T3::~T3()
572 {
573         for (auto n: this->p_root_.nodes())
574                 if (n != this->p_root_.root() && n != this->p_root_.goal())
575                         delete n;
576         for (auto n: this->p_root_.dnodes())
577                 if (n != this->p_root_.root() && n != this->p_root_.goal())
578                         delete n;
579         for (auto s: this->p_root_.samples())
580                 if (s != this->p_root_.goal())
581                         delete s;
582         for (auto edges: this->p_root_.rlog())
583                 for (auto e: edges)
584                         delete e;
585
586         for (auto n: this->p_goal_.nodes())
587                 if (n != this->p_goal_.root() && n != this->p_goal_.goal())
588                         delete n;
589         for (auto n: this->p_goal_.dnodes())
590                 if (n != this->p_goal_.root() && n != this->p_goal_.goal())
591                         delete n;
592         for (auto s: this->p_goal_.samples())
593                 if (s != this->p_goal_.goal())
594                         delete s;
595         for (auto edges: this->p_goal_.rlog())
596                 for (auto e: edges)
597                         delete e;
598
599         for (auto n: this->nodes())
600                 if (n != this->root())
601                         delete n;
602         for (auto n: this->dnodes())
603                 if (n != this->root() && n != this->goal())
604                         delete n;
605         for (auto s: this->samples())
606                 if (s != this->goal())
607                         delete s;
608         for (auto edges: this->rlog())
609                 for (auto e: edges)
610                         delete e;
611
612         delete this->root();
613         delete this->goal();
614 }
615
616 T3::T3()
617 {
618         srand(static_cast<unsigned>(time(0)));
619 }
620
621 T3::T3(RRTNode *init, RRTNode *goal):
622         RRTBase(init, goal),
623         p_root_(init, goal),
624         p_goal_(goal, init)
625 {
626         srand(static_cast<unsigned>(time(0)));
627 }
628
629 bool T3::next()
630 {
631         RRTNode *ron = nullptr;
632         RRTNode *gon = nullptr;
633         bool ret = false;
634         ret = this->p_root_.next();
635         ret |= this->p_goal_.next();
636         if (this->overlaptrees(&ron, &gon)) {
637                 if (this->connecttrees(ron, gon))
638                         this->goal_found(true);
639                 this->tlog(this->findt());
640                 ret |= true;
641         }
642         return ret;
643 }
644
645 bool T3::link_obstacles(
646         std::vector<CircleObstacle> *cobstacles,
647         std::vector<SegmentObstacle> *sobstacles)
648 {
649         bool ret = false;
650         ret = RRTBase::link_obstacles(cobstacles, sobstacles);
651         ret &= this->p_root_.link_obstacles(cobstacles, sobstacles);
652         ret &= this->p_goal_.link_obstacles(cobstacles, sobstacles);
653         return ret;
654 }
655
656 bool T3::connecttrees(RRTNode *rn, RRTNode *gn)
657 {
658         while (gn != this->goal()) {
659                 this->p_root_.nodes().push_back(new RRTNode(
660                                 gn->x(),
661                                 gn->y(),
662                                 gn->h()));
663                 rn->add_child(
664                                 this->p_root_.nodes().back(),
665                                 this->p_root_.cost(
666                                                 rn,
667                                                 this->p_root_.nodes().back()));
668                 rn = this->p_root_.nodes().back();
669                 gn = gn->parent();
670         }
671         rn->add_child(this->goal(), this->p_root_.cost(rn, this->goal()));
672         return true;
673 }
674
675 bool T3::overlaptrees(RRTNode **ron, RRTNode **gon)
676 {
677         for (auto rn: this->p_root_.nodes()) {
678                 if (rn->parent() == nullptr)
679                         continue;
680                 for (auto gn: this->p_goal_.nodes()) {
681                         if (gn->parent() == nullptr)
682                                 continue;
683                         if (IS_NEAR(rn, gn)) {
684                                 *ron = rn;
685                                 *gon = gn;
686                                 return true;
687                         }
688                 }
689         }
690         return false;
691 }
692
693 Klemm2015::Klemm2015(RRTNode *init, RRTNode *goal):
694         Karaman2011(init, goal),
695         orig_root_(init),
696         orig_goal_(goal)
697 {
698         srand(static_cast<unsigned>(time(0)));
699         this->root()->tree('R');
700         this->goal()->tree('G');
701         this->add_iy(this->goal());
702 }
703
704 bool Klemm2015::next()
705 {
706         RRTNode *xn = nullptr;
707         RRTNode *rs;
708         int ret = 0;
709 #if GOALFIRST > 0
710         if (this->samples().size() == 0)
711                 rs = this->goal();
712         else
713                 rs = this->sample();
714 #else
715         rs = this->sample();
716 #endif
717         this->samples().push_back(rs);
718         //std::cerr << "next" << std::endl;
719         if (this->extendstar1(rs, &xn) != 2) {
720         //        if (xn) {
721         //                std::cerr << "- xn: " << xn->x() << ", " << xn->y();
722         //                std::cerr << std::endl;
723         //        } else {
724         //                std::cerr << "- xn: nullptr" << std::endl;
725         //        }
726                 this->swap();
727                 ret = this->connectstar(xn);
728         } else {
729                 this->swap();
730         }
731         if (ret == 1) {
732                 this->tlog(this->findt());
733                 return true;
734         }
735         return this->goal_found();
736 }
737
738 int Klemm2015::extendstar1(RRTNode *rs, RRTNode **xn)
739 {
740         int ret = 0; // 0 - advanced, 1 - reached, 2 - trapped
741         char tree = this->root()->tree();
742         //std::cerr << "extend*1" << std::endl;
743         //std::cerr << "- tree is " << tree << std::endl;
744         //std::cerr << "  - rs: " << rs->x() << ", " << rs->y() << std::endl;
745         //if (xn && *xn) {
746         //        std::cerr << "  - xn: " << (*xn)->x() << ", " << (*xn)->y();
747         //        std::cerr << std::endl;
748         //}
749         //for (int i = 0; i < IYSIZE; i++) {
750         //        if (this->iy_[i].size() > 0) {
751         //                RRTNode *tmpn = this->iy_[i].back();
752         //                float tmpd = EDIST(tmpn, this->goal());
753
754         //                std::cerr << i << ": " << tmpn->x();
755         //                std::cerr << ", " << tmpn->y();
756         //                std::cerr << ", " << tmpn->tree();
757         //                std::cerr << " (" << tmpd << ")";
758
759         //                if (tmpn == this->root())
760         //                        std::cerr << " root";
761         //                if (tmpn == this->goal())
762         //                        std::cerr << " goal";
763         //                std::cerr << std::endl;
764         //        }
765         //}
766         RRTNode *nn = this->nn(rs);
767         //std::cerr << "  - nn: " << nn->x() << ", " << nn->y() << std::endl;
768         std::vector<RRTNode *> nvs;
769         std::vector<RRTNode *> steered = this->steer(nn, rs);
770         RRTNode *ns = steered[1];
771         ns->tree(tree);
772         nvs = this->nv(
773                         ns,
774                         MIN(
775                                 GAMMA_RRTSTAR(
776                                         this->nodes().size()),
777                                 0.2)); // TODO const
778         this->nodes().push_back(ns);
779         this->add_iy(ns);
780         // connect
781         if (!this->connect(nn, ns, nvs)) {
782                 this->iy_[this->YI(ns)].pop_back();
783                 ret = 2;
784         } else {
785                 // rewire
786                 this->rewire(nvs, ns);
787         }
788         for (auto n: steered) {
789                 if (n != steered[1])
790                         delete n;
791         }
792         *xn = ns;
793         //std::cerr << "  - xn: " << (*xn)->x() << ", " << (*xn)->y();
794         //std::cerr << std::endl;
795         return ret;
796 }
797
798 int Klemm2015::extendstarC(RRTNode *rs)
799 {
800         int ret = 0; // 0 - advanced, 1 - reached, 2 - trapped
801         char tree = this->root()->tree();
802         //std::cerr << "extend*C" << std::endl;
803         //std::cerr << "- tree is " << tree << std::endl;
804         //std::cerr << "  - rs: " << rs->x() << ", " << rs->y() << std::endl;
805         RRTNode *nn = this->nn(rs);
806         RRTNode *pn = nn;
807         std::vector<RRTNode *> nvs;
808         bool en_add = true;
809         for (auto ns: this->steer(nn, rs)) {
810                 if (!en_add) {
811                         delete ns;
812                 } else {
813                         nvs = this->nv(
814                                         ns,
815                                         MIN(
816                                                 GAMMA_RRTSTAR(
817                                                         this->nodes().size()),
818                                                 0.2)); // TODO const
819                         this->nodes().push_back(ns);
820                         this->add_iy(ns);
821                         // connect
822                         if (!this->connect(pn, ns, nvs)) {
823                                 this->iy_[this->YI(ns)].pop_back();
824                                 en_add = false;
825                                 ret = 2;
826                         } else {
827                                 // rewire
828                                 this->rewire(nvs, ns);
829                                 pn = ns;
830 if (IS_NEAR(pn, rs)) { // GOAL FOUND !
831         RRTNode *tmp;
832         if (this->orig_root_ == this->root()) { // rs is in G tree
833                 // add all rs parents to pn
834                 tmp = rs->parent();
835         } else { // rs is in R tree
836                 tmp = pn->parent();
837                 pn = rs;
838                 this->swap();
839         }
840         while (tmp != this->goal()) {
841                 this->nodes().push_back(new RRTNode(
842                                 tmp->x(),
843                                 tmp->y(),
844                                 tmp->h()));
845                 this->nodes().back()->s(tmp->s());
846                 this->nodes().back()->tree('R');
847                 pn->add_child(
848                                 this->nodes().back(),
849                                 this->cost(pn, this->nodes().back()));
850                 pn = this->nodes().back();
851                 tmp = tmp->parent();
852         }
853         pn->add_child(tmp, this->cost(pn, tmp)); // add goal()
854         en_add = false;
855         ret = 1;
856 }
857                         }
858                 }
859         }
860         return ret;
861 }
862
863 int Klemm2015::connectstar(RRTNode *x)
864 {
865         int ret = 0; // 0 - advanced, 1 - reached, 2 - trapped
866         //std::cerr << "connect* (start)" << std::endl;
867         ret = this->extendstarC(x);
868         //std::cerr << "connect* (end)" << std::endl;
869         return ret;
870 }
871
872 void Klemm2015::swap()
873 {
874         RRTNode *tmp;
875         tmp = this->root();
876         this->root(this->goal());
877         this->goal(tmp);
878 }