2 This file is part of I am car.
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.
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.
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/>.
26 #include "rrtplanner.h"
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
34 LaValle1998::LaValle1998(RRTNode *init, RRTNode *goal):
37 srand(static_cast<unsigned>(time(0)));
40 bool LaValle1998::next()
44 if (this->samples().size() == 0)
51 this->samples().push_back(rs);
52 RRTNode *nn = this->nn(rs);
55 for (auto ns: this->steer(nn, rs)) {
59 this->nodes().push_back(ns);
61 pn->add_child(ns, this->cost(pn, ns));
62 if (this->collide(pn, ns)) {
63 pn->children().pop_back();
65 this->iy_[IYI(ns->y())].pop_back();
70 if (this->goal_found(pn, CO)) {
71 this->tlog(this->findt());
77 return this->goal_found();
80 Kuwata2008::Kuwata2008(RRTNode *init, RRTNode *goal):
83 srand(static_cast<unsigned>(time(0)));
86 bool Kuwata2008::next()
89 if (this->samples().size() == 0) {
94 this->samples().push_back(rs);
95 float heur = static_cast<float>(rand()) / static_cast<float>(RAND_MAX);
96 if (this->goal_found()) {
98 {}//this->cost = &KUWATA2008_CCOST;
100 {}//this->cost = &KUWATA2008_DCOST;
103 {}//this->cost = &KUWATA2008_CCOST;
105 {}//this->cost = &KUWATA2008_DCOST;
107 RRTNode *nn = this->nn(rs);
109 std::vector<RRTNode *> newly_added;
111 for (auto ns: this->steer(nn, rs)) {
115 this->nodes().push_back(ns);
117 pn->add_child(ns, KUWATA2008_DCOST(pn, ns));
118 if (this->collide(pn, ns)) {
119 pn->children().pop_back();
121 this->iy_[IYI(ns->y())].pop_back();
126 newly_added.push_back(pn);
127 if (this->goal_found(pn, &KUWATA2008_DCOST)) {
128 this->tlog(this->findt());
134 if (this->samples().size() <= 1)
135 return this->goal_found();
136 for (auto na: newly_added) {
139 for (auto ns: this->steer(na, this->goal())) {
143 this->nodes().push_back(ns);
145 pn->add_child(ns, KUWATA2008_DCOST(pn, ns));
146 if (this->collide(pn, ns)) {
147 pn->children().pop_back();
149 this->iy_[IYI(ns->y())].pop_back();
154 if (this->goal_found(pn,
155 &KUWATA2008_DCOST)) {
156 this->tlog(this->findt());
163 return this->goal_found();
166 Karaman2011::Karaman2011()
168 srand(static_cast<unsigned>(time(0)));
171 Karaman2011::Karaman2011(RRTNode *init, RRTNode *goal):
174 srand(static_cast<unsigned>(time(0)));
177 bool Karaman2011::next()
181 if (this->samples().size() == 0)
188 this->samples().push_back(rs);
189 RRTNode *nn = this->nn(rs);
191 std::vector<RRTNode *> nvs;
194 for (auto ns: this->steer(nn, rs)) {
197 } else if (IS_NEAR(nn, ns)) {
204 this->nodes().size()),
213 this->nodes().push_back(ns);
216 if (!this->connect(pn, ns, nvs)) {
217 this->iy_[IYI(ns->y())].pop_back();
221 this->rewire(nvs, ns);
223 if (this->goal_found(pn, CO)) {
224 this->tlog(this->findt());
230 return this->goal_found();
233 bool Karaman2011::connect(
236 std::vector<RRTNode *> nvs)
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();
251 if (!connected || (nv->ccost() + this->cost(nv, ns) <
256 nv->add_child(ns, this->cost(nv, ns));
257 if (this->collide(nv, ns)) {
258 nv->children().pop_back();
265 } else if (connected) {
266 op->children().pop_back();
276 bool Karaman2011::rewire(std::vector<RRTNode *> nvs, RRTNode *ns)
278 RRTNode *op; // old parent
279 float od; // old direct cost
280 float oc; // old cumulative cost
282 if (ns->ccost() + this->cost(ns, nv) < nv->ccost()) {
286 ns->add_child(nv, this->cost(ns, nv));
287 if (this->collide(ns, nv)) {
288 ns->children().pop_back();
300 T1::T1(RRTNode *init, RRTNode *goal):
303 srand(static_cast<unsigned>(time(0)));
309 if (this->samples().size() == 0)
313 this->samples().push_back(rs);
314 RRTNode *nn = this->nn(rs);
316 std::vector<RRTNode *> nvs;
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];
325 nvs = this->nv(ns, MIN(
326 GAMMA_RRTSTAR(this->nodes().size()),
328 this->nodes().push_back(ns);
331 pn->add_child(ns, this->cost(pn, ns));
332 if (this->collide(pn, ns)) {
333 pn->children().pop_back();
339 if (!connected || (nv->ccost() + this->cost(nv, ns) <
344 nv->add_child(ns, this->cost(nv, ns));
345 if (this->collide(nv, ns)) {
346 nv->children().pop_back();
350 } else if (connected) {
351 op->children().pop_back();
361 if (ns->ccost() + this->cost(ns, nv) < nv->ccost()) {
365 ns->add_child(nv, this->cost(ns, nv));
366 if (this->collide(ns, nv)) {
367 ns->children().pop_back();
377 if (this->goal_found(pn, CO)) {
378 this->tlog(this->findt());
382 for (i = 1; i < steered.size(); i++) {
384 this->nodes().push_back(ns);
386 pn->add_child(ns, this->cost(pn, ns));
387 if (this->collide(pn, ns)) {
388 pn->children().pop_back();
392 if (this->goal_found(pn, CO)) {
393 this->tlog(this->findt());
397 return this->goal_found();
404 if (this->samples().size() == 0)
411 this->samples().push_back(rs);
412 RRTNode *nn = this->nn(rs);
416 std::vector<RRTNode *> nvs;
417 std::vector<RRTNode *> newly_added;
420 for (auto ns: this->steer(nn, rs)) {
423 } else if (IS_NEAR(pn, ns)) {
426 if (sgn(ns->s()) == 0 || sgn(pn->s()) != sgn(ns->s()))
434 this->nodes().size()),
436 this->nodes().push_back(ns);
439 if (!this->connect(pn, ns, nvs)) {
440 this->iy_[IYI(ns->y())].pop_back();
441 this->nodes().pop_back();
447 this->rewire(nvs, ns);
449 newly_added.push_back(pn);
450 if (this->goal_found(pn, CO)) {
452 this->tlog(this->findt());
460 for (auto ns: this->steer(pn, rs, 0.01)) {
463 } else if (IS_NEAR(pn, ns)) {
466 if (sgn(ns->s()) == 0 || sgn(pn->s()) != sgn(ns->s()))
474 this->nodes().size()),
476 this->nodes().push_back(ns);
479 if (!this->connect(pn, ns, nvs)) {
480 this->iy_[IYI(ns->y())].pop_back();
481 this->nodes().pop_back();
487 this->rewire(nvs, ns);
489 newly_added.push_back(pn);
490 if (this->goal_found(pn, CO)) {
492 this->tlog(this->findt());
498 if (this->samples().size() <= 1)
499 return this->goal_found();
500 for (auto na: newly_added) {
504 for (auto ns: this->steer(na, this->goal())) {
507 } else if (IS_NEAR(pn, ns)) {
510 if (sgn(pn->s()) != sgn(ns->s()))
514 this->nodes().push_back(ns);
516 pn->add_child(ns, this->cost(pn, ns));
517 if (this->collide(pn, ns)) {
518 pn->children().pop_back();
520 this->iy_[IYI(ns->y())].pop_back();
521 this->nodes().pop_back();
528 if (this->goal_found(pn, CO)) {
530 this->tlog(this->findt());
538 for (auto ns: this->steer(pn, this->goal(), 0.01)) {
541 } else if (IS_NEAR(pn, ns)) {
544 if (sgn(pn->s()) != sgn(ns->s()))
548 this->nodes().push_back(ns);
550 pn->add_child(ns, this->cost(pn, ns));
551 if (this->collide(pn, ns)) {
552 pn->children().pop_back();
554 this->iy_[IYI(ns->y())].pop_back();
555 this->nodes().pop_back();
562 if (this->goal_found(pn, CO)) {
564 this->tlog(this->findt());
571 return this->goal_found();
574 float T2::goal_cost()
576 std::vector<RRTNode *> nvs;
577 nvs = this->nv(this->goal(), 0.2);
579 if (std::abs(this->goal()->h() - nv->h()) >=
580 this->GOAL_FOUND_ANGLE)
582 if (nv->ccost() + this->cost(nv, this->goal()) >=
583 this->goal()->ccost())
585 RRTNode *op; // old parent
586 float oc; // old cumulative cost
587 float od; // old direct cost
588 op = this->goal()->parent();
589 oc = this->goal()->ccost();
590 od = this->goal()->dcost();
591 nv->add_child(this->goal(),
592 this->cost(nv, this->goal()));
593 if (this->collide(nv, this->goal())) {
594 nv->children().pop_back();
595 this->goal()->parent(op);
596 this->goal()->ccost(oc);
597 this->goal()->dcost(od);
599 op->rem_child(this->goal());
602 return this->goal()->ccost();
607 for (auto n: this->p_root_.nodes())
608 if (n != this->p_root_.root() && n != this->p_root_.goal())
610 for (auto n: this->p_root_.dnodes())
611 if (n != this->p_root_.root() && n != this->p_root_.goal())
613 for (auto s: this->p_root_.samples())
614 if (s != this->p_root_.goal())
616 for (auto edges: this->p_root_.rlog())
620 for (auto n: this->p_goal_.nodes())
621 if (n != this->p_goal_.root() && n != this->p_goal_.goal())
623 for (auto n: this->p_goal_.dnodes())
624 if (n != this->p_goal_.root() && n != this->p_goal_.goal())
626 for (auto s: this->p_goal_.samples())
627 if (s != this->p_goal_.goal())
629 for (auto edges: this->p_goal_.rlog())
633 for (auto n: this->nodes())
634 if (n != this->root())
636 for (auto n: this->dnodes())
637 if (n != this->root() && n != this->goal())
639 for (auto s: this->samples())
640 if (s != this->goal())
642 for (auto edges: this->rlog())
652 srand(static_cast<unsigned>(time(0)));
655 T3::T3(RRTNode *init, RRTNode *goal):
660 srand(static_cast<unsigned>(time(0)));
665 RRTNode *ron = nullptr;
666 RRTNode *gon = nullptr;
668 ret = this->p_root_.next();
669 ret |= this->p_goal_.next();
670 if (this->overlaptrees(&ron, &gon)) {
671 if (this->connecttrees(ron, gon))
672 this->goal_found(true);
673 this->tlog(this->findt());
679 bool T3::link_obstacles(
680 std::vector<CircleObstacle> *cobstacles,
681 std::vector<SegmentObstacle> *sobstacles)
684 ret = RRTBase::link_obstacles(cobstacles, sobstacles);
685 ret &= this->p_root_.link_obstacles(cobstacles, sobstacles);
686 ret &= this->p_goal_.link_obstacles(cobstacles, sobstacles);
690 bool T3::connecttrees(RRTNode *rn, RRTNode *gn)
692 while (gn != this->goal()) {
693 this->p_root_.nodes().push_back(new RRTNode(
698 this->p_root_.nodes().back(),
701 this->p_root_.nodes().back()));
702 rn = this->p_root_.nodes().back();
705 rn->add_child(this->goal(), this->p_root_.cost(rn, this->goal()));
709 bool T3::overlaptrees(RRTNode **ron, RRTNode **gon)
711 for (auto rn: this->p_root_.nodes()) {
712 if (rn->parent() == nullptr)
714 for (auto gn: this->p_goal_.nodes()) {
715 if (gn->parent() == nullptr)
717 if (IS_NEAR(rn, gn)) {
727 Klemm2015::Klemm2015(RRTNode *init, RRTNode *goal):
728 Karaman2011(init, goal),
732 srand(static_cast<unsigned>(time(0)));
733 this->root()->tree('R');
734 this->goal()->tree('G');
735 this->add_iy(this->goal());
738 bool Klemm2015::next()
740 RRTNode *xn = nullptr;
744 if (this->samples().size() == 0)
751 this->samples().push_back(rs);
752 //std::cerr << "next" << std::endl;
753 if (this->extendstar1(rs, &xn) != 2) {
755 // std::cerr << "- xn: " << xn->x() << ", " << xn->y();
756 // std::cerr << std::endl;
758 // std::cerr << "- xn: nullptr" << std::endl;
761 ret = this->connectstar(xn);
766 this->tlog(this->findt());
769 return this->goal_found();
772 int Klemm2015::extendstar1(RRTNode *rs, RRTNode **xn)
774 int ret = 0; // 0 - advanced, 1 - reached, 2 - trapped
775 char tree = this->root()->tree();
776 //std::cerr << "extend*1" << std::endl;
777 //std::cerr << "- tree is " << tree << std::endl;
778 //std::cerr << " - rs: " << rs->x() << ", " << rs->y() << std::endl;
780 // std::cerr << " - xn: " << (*xn)->x() << ", " << (*xn)->y();
781 // std::cerr << std::endl;
783 //for (int i = 0; i < IYSIZE; i++) {
784 // if (this->iy_[i].size() > 0) {
785 // RRTNode *tmpn = this->iy_[i].back();
786 // float tmpd = EDIST(tmpn, this->goal());
788 // std::cerr << i << ": " << tmpn->x();
789 // std::cerr << ", " << tmpn->y();
790 // std::cerr << ", " << tmpn->tree();
791 // std::cerr << " (" << tmpd << ")";
793 // if (tmpn == this->root())
794 // std::cerr << " root";
795 // if (tmpn == this->goal())
796 // std::cerr << " goal";
797 // std::cerr << std::endl;
800 RRTNode *nn = this->nn(rs);
801 //std::cerr << " - nn: " << nn->x() << ", " << nn->y() << std::endl;
802 std::vector<RRTNode *> nvs;
803 std::vector<RRTNode *> steered = this->steer(nn, rs);
804 RRTNode *ns = steered[1];
810 this->nodes().size()),
812 this->nodes().push_back(ns);
815 if (!this->connect(nn, ns, nvs)) {
816 this->iy_[IYI(ns->y())].pop_back();
820 this->rewire(nvs, ns);
822 for (auto n: steered) {
827 //std::cerr << " - xn: " << (*xn)->x() << ", " << (*xn)->y();
828 //std::cerr << std::endl;
832 int Klemm2015::extendstarC(RRTNode *rs)
834 int ret = 0; // 0 - advanced, 1 - reached, 2 - trapped
835 char tree = this->root()->tree();
836 //std::cerr << "extend*C" << std::endl;
837 //std::cerr << "- tree is " << tree << std::endl;
838 //std::cerr << " - rs: " << rs->x() << ", " << rs->y() << std::endl;
839 RRTNode *nn = this->nn(rs);
841 std::vector<RRTNode *> nvs;
843 for (auto ns: this->steer(nn, rs)) {
851 this->nodes().size()),
853 this->nodes().push_back(ns);
856 if (!this->connect(pn, ns, nvs)) {
857 this->iy_[IYI(ns->y())].pop_back();
862 this->rewire(nvs, ns);
864 if (IS_NEAR(pn, rs)) { // GOAL FOUND !
866 if (this->orig_root_ == this->root()) { // rs is in G tree
867 // add all rs parents to pn
869 } else { // rs is in R tree
874 while (tmp != this->goal()) {
875 this->nodes().push_back(new RRTNode(
879 this->nodes().back()->s(tmp->s());
880 this->nodes().back()->tree('R');
882 this->nodes().back(),
883 this->cost(pn, this->nodes().back()));
884 pn = this->nodes().back();
887 pn->add_child(tmp, this->cost(pn, tmp)); // add goal()
897 int Klemm2015::connectstar(RRTNode *x)
899 int ret = 0; // 0 - advanced, 1 - reached, 2 - trapped
900 //std::cerr << "connect* (start)" << std::endl;
901 ret = this->extendstarC(x);
902 //std::cerr << "connect* (end)" << std::endl;
906 void Klemm2015::swap()
910 this->root(this->goal());