]> rtime.felk.cvut.cz Git - hubacji1/iamcar.git/blob - decision_control/rrtplanner.cc
Change guided sampling
[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_[IYI(ns->y())].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_[IYI(ns->y())].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_[IYI(ns->y())].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_[IYI(ns->y())].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 GOALFIRST > 0
404         if (this->samples().size() == 0)
405                 rs = this->goal();
406         else
407                 rs = this->sample();
408 #else
409         rs = this->sample();
410 #endif
411         this->samples().push_back(rs);
412         RRTNode *nn = this->nn(rs);
413         if (!nn)
414                 return false;
415         RRTNode *pn = nn;
416         std::vector<RRTNode *> nvs;
417         std::vector<RRTNode *> newly_added;
418         bool en_add = true;
419         int cusps = 0;
420         for (auto ns: this->steer(nn, rs)) {
421                 ns->rs(rs);
422                 if (!en_add) {
423                         delete ns;
424                 } else if (IS_NEAR(pn, ns)) {
425                         delete ns;
426                 } else {
427                         if (sgn(ns->s()) == 0 || sgn(pn->s()) != sgn(ns->s()))
428                                 cusps++;
429                         if (cusps > 4)
430                                 en_add = false;
431                         nvs = this->nv(
432                                         ns,
433                                         MIN(
434                                                 GAMMA_RRTSTAR(
435                                                         this->nodes().size()),
436                                                 0.2)); // TODO const
437                         this->nodes().push_back(ns);
438                         this->add_iy(ns);
439                         // connect
440                         if (!this->connect(pn, ns, nvs)) {
441                                 this->iy_[IYI(ns->y())].pop_back();
442                                 this->nodes().pop_back();
443                                 delete ns;
444                                 en_add = false;
445                         } else {
446                                 this->add_ixy(ns);
447                                 // rewire
448                                 this->rewire(nvs, ns);
449                                 pn = ns;
450                                 newly_added.push_back(pn);
451                                 if (this->goal_found(pn, CO)) {
452                                         this->goal_cost();
453                                         this->tlog(this->findt());
454                                         en_add = false;
455                                 }
456                         }
457                 }
458         }
459         en_add = true;
460         cusps = 0;
461         for (auto ns: this->steer(pn, rs, 0.01)) {
462                 ns->rs(rs);
463                 if (!en_add) {
464                         delete ns;
465                 } else if (IS_NEAR(pn, ns)) {
466                         delete ns;
467                 } else {
468                         if (sgn(ns->s()) == 0 || sgn(pn->s()) != sgn(ns->s()))
469                                 cusps++;
470                         if (cusps > 4)
471                                 en_add = false;
472                         nvs = this->nv(
473                                         ns,
474                                         MIN(
475                                                 GAMMA_RRTSTAR(
476                                                         this->nodes().size()),
477                                                 0.2)); // TODO const
478                         this->nodes().push_back(ns);
479                         this->add_iy(ns);
480                         // connect
481                         if (!this->connect(pn, ns, nvs)) {
482                                 this->iy_[IYI(ns->y())].pop_back();
483                                 this->nodes().pop_back();
484                                 delete ns;
485                                 en_add = false;
486                         } else {
487                                 this->add_ixy(ns);
488                                 // rewire
489                                 this->rewire(nvs, ns);
490                                 pn = ns;
491                                 newly_added.push_back(pn);
492                                 if (this->goal_found(pn, CO)) {
493                                         this->goal_cost();
494                                         this->tlog(this->findt());
495                                         en_add = false;
496                                 }
497                         }
498                 }
499         }
500         if (this->samples().size() <= 1)
501                 return this->goal_found();
502         for (auto na: newly_added) {
503                 pn = na;
504                 en_add = true;
505                 cusps = 0;
506                 for (auto ns: this->steer(na, this->goal())) {
507                         ns->rs(rs);
508                         if (!en_add) {
509                                 delete ns;
510                         } else if (IS_NEAR(pn, ns)) {
511                                 delete ns;
512                         } else {
513                                 if (sgn(pn->s()) != sgn(ns->s()))
514                                         cusps++;
515                                 if (cusps > 4)
516                                         en_add = false;
517                                 this->nodes().push_back(ns);
518                                 this->add_iy(ns);
519                                 pn->add_child(ns, this->cost(pn, ns));
520                                 if (this->collide(pn, ns)) {
521                                         pn->children().pop_back();
522                                         ns->remove_parent();
523                                         this->iy_[IYI(ns->y())].pop_back();
524                                         this->nodes().pop_back();
525                                         delete ns;
526                                         en_add = false;
527                                 } else {
528                                         this->add_ixy(ns);
529                                         this->ocost(ns);
530                                         pn = ns;
531                                         if (this->goal_found(pn, CO)) {
532                                                 this->goal_cost();
533                                                 this->tlog(this->findt());
534                                                 en_add = false;
535                                         }
536                                 }
537                         }
538                 }
539                 en_add = true;
540                 cusps = 0;
541                 for (auto ns: this->steer(pn, this->goal(), 0.01)) {
542                         ns->rs(rs);
543                         if (!en_add) {
544                                 delete ns;
545                         } else if (IS_NEAR(pn, ns)) {
546                                 delete ns;
547                         } else {
548                                 if (sgn(pn->s()) != sgn(ns->s()))
549                                         cusps++;
550                                 if (cusps > 4)
551                                         en_add = false;
552                                 this->nodes().push_back(ns);
553                                 this->add_iy(ns);
554                                 pn->add_child(ns, this->cost(pn, ns));
555                                 if (this->collide(pn, ns)) {
556                                         pn->children().pop_back();
557                                         ns->remove_parent();
558                                         this->iy_[IYI(ns->y())].pop_back();
559                                         this->nodes().pop_back();
560                                         delete ns;
561                                         en_add = false;
562                                 } else {
563                                         this->add_ixy(ns);
564                                         this->ocost(ns);
565                                         pn = ns;
566                                         if (this->goal_found(pn, CO)) {
567                                                 this->goal_cost();
568                                                 this->tlog(this->findt());
569                                                 en_add = false;
570                                         }
571                                 }
572                         }
573                 }
574         }
575         return this->goal_found();
576 }
577
578 float T2::goal_cost()
579 {
580         std::vector<RRTNode *> nvs;
581         nvs = this->nv(this->goal(), 0.2);
582         for (auto nv: nvs) {
583                 if (std::abs(this->goal()->h() - nv->h()) >=
584                                 this->GOAL_FOUND_ANGLE)
585                         continue;
586                 if (nv->ccost() + this->cost(nv, this->goal()) >=
587                                 this->goal()->ccost())
588                         continue;
589                 RRTNode *op; // old parent
590                 float oc; // old cumulative cost
591                 float od; // old direct cost
592                 op = this->goal()->parent();
593                 oc = this->goal()->ccost();
594                 od = this->goal()->dcost();
595                 nv->add_child(this->goal(),
596                                 this->cost(nv, this->goal()));
597                 if (this->collide(nv, this->goal())) {
598                         nv->children().pop_back();
599                         this->goal()->parent(op);
600                         this->goal()->ccost(oc);
601                         this->goal()->dcost(od);
602                 } else {
603                         op->rem_child(this->goal());
604                 }
605         }
606         return this->goal()->ccost();
607 }
608
609 T3::~T3()
610 {
611         for (auto n: this->p_root_.nodes())
612                 if (n != this->p_root_.root() && n != this->p_root_.goal())
613                         delete n;
614         for (auto n: this->p_root_.dnodes())
615                 if (n != this->p_root_.root() && n != this->p_root_.goal())
616                         delete n;
617         for (auto s: this->p_root_.samples())
618                 if (s != this->p_root_.goal())
619                         delete s;
620         for (auto edges: this->p_root_.rlog())
621                 for (auto e: edges)
622                         delete e;
623
624         for (auto n: this->p_goal_.nodes())
625                 if (n != this->p_goal_.root() && n != this->p_goal_.goal())
626                         delete n;
627         for (auto n: this->p_goal_.dnodes())
628                 if (n != this->p_goal_.root() && n != this->p_goal_.goal())
629                         delete n;
630         for (auto s: this->p_goal_.samples())
631                 if (s != this->p_goal_.goal())
632                         delete s;
633         for (auto edges: this->p_goal_.rlog())
634                 for (auto e: edges)
635                         delete e;
636
637         for (auto n: this->nodes())
638                 if (n != this->root())
639                         delete n;
640         for (auto n: this->dnodes())
641                 if (n != this->root() && n != this->goal())
642                         delete n;
643         for (auto s: this->samples())
644                 if (s != this->goal())
645                         delete s;
646         for (auto edges: this->rlog())
647                 for (auto e: edges)
648                         delete e;
649
650         delete this->root();
651         delete this->goal();
652 }
653
654 T3::T3()
655 {
656         srand(static_cast<unsigned>(time(0)));
657 }
658
659 T3::T3(RRTNode *init, RRTNode *goal):
660         RRTBase(init, goal),
661         p_root_(init, goal),
662         p_goal_(goal, init)
663 {
664         srand(static_cast<unsigned>(time(0)));
665 }
666
667 bool T3::next()
668 {
669         RRTNode *ron = nullptr;
670         RRTNode *gon = nullptr;
671         bool ret = false;
672         ret = this->p_root_.next();
673         ret |= this->p_goal_.next();
674         if (this->overlaptrees(&ron, &gon)) {
675                 if (this->connecttrees(ron, gon))
676                         this->goal_found(true);
677                 this->tlog(this->findt());
678                 ret |= true;
679         }
680         return ret;
681 }
682
683 bool T3::link_obstacles(
684         std::vector<CircleObstacle> *cobstacles,
685         std::vector<SegmentObstacle> *sobstacles)
686 {
687         bool ret = false;
688         ret = RRTBase::link_obstacles(cobstacles, sobstacles);
689         ret &= this->p_root_.link_obstacles(cobstacles, sobstacles);
690         ret &= this->p_goal_.link_obstacles(cobstacles, sobstacles);
691         return ret;
692 }
693
694 bool T3::connecttrees(RRTNode *rn, RRTNode *gn)
695 {
696         while (gn != this->goal()) {
697                 this->p_root_.nodes().push_back(new RRTNode(
698                                 gn->x(),
699                                 gn->y(),
700                                 gn->h()));
701                 rn->add_child(
702                                 this->p_root_.nodes().back(),
703                                 this->p_root_.cost(
704                                                 rn,
705                                                 this->p_root_.nodes().back()));
706                 rn = this->p_root_.nodes().back();
707                 gn = gn->parent();
708         }
709         rn->add_child(this->goal(), this->p_root_.cost(rn, this->goal()));
710         return true;
711 }
712
713 bool T3::overlaptrees(RRTNode **ron, RRTNode **gon)
714 {
715         for (auto rn: this->p_root_.nodes()) {
716                 if (rn->parent() == nullptr)
717                         continue;
718                 for (auto gn: this->p_goal_.nodes()) {
719                         if (gn->parent() == nullptr)
720                                 continue;
721                         if (IS_NEAR(rn, gn)) {
722                                 *ron = rn;
723                                 *gon = gn;
724                                 return true;
725                         }
726                 }
727         }
728         return false;
729 }
730
731 Klemm2015::Klemm2015(RRTNode *init, RRTNode *goal):
732         Karaman2011(init, goal),
733         orig_root_(init),
734         orig_goal_(goal)
735 {
736         srand(static_cast<unsigned>(time(0)));
737         this->root()->tree('R');
738         this->goal()->tree('G');
739         this->add_iy(this->goal());
740 }
741
742 bool Klemm2015::next()
743 {
744         RRTNode *xn = nullptr;
745         RRTNode *rs;
746         int ret = 0;
747 #if GOALFIRST > 0
748         if (this->samples().size() == 0)
749                 rs = this->goal();
750         else
751                 rs = this->sample();
752 #else
753         rs = this->sample();
754 #endif
755         this->samples().push_back(rs);
756         //std::cerr << "next" << std::endl;
757         if (this->extendstar1(rs, &xn) != 2) {
758         //        if (xn) {
759         //                std::cerr << "- xn: " << xn->x() << ", " << xn->y();
760         //                std::cerr << std::endl;
761         //        } else {
762         //                std::cerr << "- xn: nullptr" << std::endl;
763         //        }
764                 this->swap();
765                 ret = this->connectstar(xn);
766         } else {
767                 this->swap();
768         }
769         if (ret == 1) {
770                 this->tlog(this->findt());
771                 return true;
772         }
773         return this->goal_found();
774 }
775
776 int Klemm2015::extendstar1(RRTNode *rs, RRTNode **xn)
777 {
778         int ret = 0; // 0 - advanced, 1 - reached, 2 - trapped
779         char tree = this->root()->tree();
780         //std::cerr << "extend*1" << std::endl;
781         //std::cerr << "- tree is " << tree << std::endl;
782         //std::cerr << "  - rs: " << rs->x() << ", " << rs->y() << std::endl;
783         //if (xn && *xn) {
784         //        std::cerr << "  - xn: " << (*xn)->x() << ", " << (*xn)->y();
785         //        std::cerr << std::endl;
786         //}
787         //for (int i = 0; i < IYSIZE; i++) {
788         //        if (this->iy_[i].size() > 0) {
789         //                RRTNode *tmpn = this->iy_[i].back();
790         //                float tmpd = EDIST(tmpn, this->goal());
791
792         //                std::cerr << i << ": " << tmpn->x();
793         //                std::cerr << ", " << tmpn->y();
794         //                std::cerr << ", " << tmpn->tree();
795         //                std::cerr << " (" << tmpd << ")";
796
797         //                if (tmpn == this->root())
798         //                        std::cerr << " root";
799         //                if (tmpn == this->goal())
800         //                        std::cerr << " goal";
801         //                std::cerr << std::endl;
802         //        }
803         //}
804         RRTNode *nn = this->nn(rs);
805         //std::cerr << "  - nn: " << nn->x() << ", " << nn->y() << std::endl;
806         std::vector<RRTNode *> nvs;
807         std::vector<RRTNode *> steered = this->steer(nn, rs);
808         RRTNode *ns = steered[1];
809         ns->tree(tree);
810         nvs = this->nv(
811                         ns,
812                         MIN(
813                                 GAMMA_RRTSTAR(
814                                         this->nodes().size()),
815                                 0.2)); // TODO const
816         this->nodes().push_back(ns);
817         this->add_iy(ns);
818         // connect
819         if (!this->connect(nn, ns, nvs)) {
820                 this->iy_[IYI(ns->y())].pop_back();
821                 ret = 2;
822         } else {
823                 // rewire
824                 this->rewire(nvs, ns);
825         }
826         for (auto n: steered) {
827                 if (n != steered[1])
828                         delete n;
829         }
830         *xn = ns;
831         //std::cerr << "  - xn: " << (*xn)->x() << ", " << (*xn)->y();
832         //std::cerr << std::endl;
833         return ret;
834 }
835
836 int Klemm2015::extendstarC(RRTNode *rs)
837 {
838         int ret = 0; // 0 - advanced, 1 - reached, 2 - trapped
839         char tree = this->root()->tree();
840         //std::cerr << "extend*C" << std::endl;
841         //std::cerr << "- tree is " << tree << std::endl;
842         //std::cerr << "  - rs: " << rs->x() << ", " << rs->y() << std::endl;
843         RRTNode *nn = this->nn(rs);
844         RRTNode *pn = nn;
845         std::vector<RRTNode *> nvs;
846         bool en_add = true;
847         for (auto ns: this->steer(nn, rs)) {
848                 if (!en_add) {
849                         delete ns;
850                 } else {
851                         nvs = this->nv(
852                                         ns,
853                                         MIN(
854                                                 GAMMA_RRTSTAR(
855                                                         this->nodes().size()),
856                                                 0.2)); // TODO const
857                         this->nodes().push_back(ns);
858                         this->add_iy(ns);
859                         // connect
860                         if (!this->connect(pn, ns, nvs)) {
861                                 this->iy_[IYI(ns->y())].pop_back();
862                                 en_add = false;
863                                 ret = 2;
864                         } else {
865                                 // rewire
866                                 this->rewire(nvs, ns);
867                                 pn = ns;
868 if (IS_NEAR(pn, rs)) { // GOAL FOUND !
869         RRTNode *tmp;
870         if (this->orig_root_ == this->root()) { // rs is in G tree
871                 // add all rs parents to pn
872                 tmp = rs->parent();
873         } else { // rs is in R tree
874                 tmp = pn->parent();
875                 pn = rs;
876                 this->swap();
877         }
878         while (tmp != this->goal()) {
879                 this->nodes().push_back(new RRTNode(
880                                 tmp->x(),
881                                 tmp->y(),
882                                 tmp->h()));
883                 this->nodes().back()->s(tmp->s());
884                 this->nodes().back()->tree('R');
885                 pn->add_child(
886                                 this->nodes().back(),
887                                 this->cost(pn, this->nodes().back()));
888                 pn = this->nodes().back();
889                 tmp = tmp->parent();
890         }
891         pn->add_child(tmp, this->cost(pn, tmp)); // add goal()
892         en_add = false;
893         ret = 1;
894 }
895                         }
896                 }
897         }
898         return ret;
899 }
900
901 int Klemm2015::connectstar(RRTNode *x)
902 {
903         int ret = 0; // 0 - advanced, 1 - reached, 2 - trapped
904         //std::cerr << "connect* (start)" << std::endl;
905         ret = this->extendstarC(x);
906         //std::cerr << "connect* (end)" << std::endl;
907         return ret;
908 }
909
910 void Klemm2015::swap()
911 {
912         RRTNode *tmp;
913         tmp = this->root();
914         this->root(this->goal());
915         this->goal(tmp);
916 }