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)) {
424 } else if (IS_NEAR(pn, ns)) {
427 if (sgn(ns->s()) == 0 || sgn(pn->s()) != sgn(ns->s()))
435 this->nodes().size()),
437 this->nodes().push_back(ns);
440 if (!this->connect(pn, ns, nvs)) {
441 this->iy_[IYI(ns->y())].pop_back();
442 this->nodes().pop_back();
448 this->rewire(nvs, ns);
450 newly_added.push_back(pn);
451 if (this->goal_found(pn, CO)) {
453 this->tlog(this->findt());
461 for (auto ns: this->steer(pn, rs, 0.01)) {
465 } else if (IS_NEAR(pn, ns)) {
468 if (sgn(ns->s()) == 0 || sgn(pn->s()) != sgn(ns->s()))
476 this->nodes().size()),
478 this->nodes().push_back(ns);
481 if (!this->connect(pn, ns, nvs)) {
482 this->iy_[IYI(ns->y())].pop_back();
483 this->nodes().pop_back();
489 this->rewire(nvs, ns);
491 newly_added.push_back(pn);
492 if (this->goal_found(pn, CO)) {
494 this->tlog(this->findt());
500 if (this->samples().size() <= 1)
501 return this->goal_found();
502 for (auto na: newly_added) {
506 for (auto ns: this->steer(na, this->goal())) {
510 } else if (IS_NEAR(pn, ns)) {
513 if (sgn(pn->s()) != sgn(ns->s()))
517 this->nodes().push_back(ns);
519 pn->add_child(ns, this->cost(pn, ns));
520 if (this->collide(pn, ns)) {
521 pn->children().pop_back();
523 this->iy_[IYI(ns->y())].pop_back();
524 this->nodes().pop_back();
531 if (this->goal_found(pn, CO)) {
533 this->tlog(this->findt());
541 for (auto ns: this->steer(pn, this->goal(), 0.01)) {
545 } else if (IS_NEAR(pn, ns)) {
548 if (sgn(pn->s()) != sgn(ns->s()))
552 this->nodes().push_back(ns);
554 pn->add_child(ns, this->cost(pn, ns));
555 if (this->collide(pn, ns)) {
556 pn->children().pop_back();
558 this->iy_[IYI(ns->y())].pop_back();
559 this->nodes().pop_back();
566 if (this->goal_found(pn, CO)) {
568 this->tlog(this->findt());
575 return this->goal_found();
578 float T2::goal_cost()
580 std::vector<RRTNode *> nvs;
581 nvs = this->nv(this->goal(), 0.2);
583 if (std::abs(this->goal()->h() - nv->h()) >=
584 this->GOAL_FOUND_ANGLE)
586 if (nv->ccost() + this->cost(nv, this->goal()) >=
587 this->goal()->ccost())
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);
603 op->rem_child(this->goal());
606 return this->goal()->ccost();
611 for (auto n: this->p_root_.nodes())
612 if (n != this->p_root_.root() && n != this->p_root_.goal())
614 for (auto n: this->p_root_.dnodes())
615 if (n != this->p_root_.root() && n != this->p_root_.goal())
617 for (auto s: this->p_root_.samples())
618 if (s != this->p_root_.goal())
620 for (auto edges: this->p_root_.rlog())
624 for (auto n: this->p_goal_.nodes())
625 if (n != this->p_goal_.root() && n != this->p_goal_.goal())
627 for (auto n: this->p_goal_.dnodes())
628 if (n != this->p_goal_.root() && n != this->p_goal_.goal())
630 for (auto s: this->p_goal_.samples())
631 if (s != this->p_goal_.goal())
633 for (auto edges: this->p_goal_.rlog())
637 for (auto n: this->nodes())
638 if (n != this->root())
640 for (auto n: this->dnodes())
641 if (n != this->root() && n != this->goal())
643 for (auto s: this->samples())
644 if (s != this->goal())
646 for (auto edges: this->rlog())
656 srand(static_cast<unsigned>(time(0)));
659 T3::T3(RRTNode *init, RRTNode *goal):
664 srand(static_cast<unsigned>(time(0)));
669 RRTNode *ron = nullptr;
670 RRTNode *gon = nullptr;
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());
683 bool T3::link_obstacles(
684 std::vector<CircleObstacle> *cobstacles,
685 std::vector<SegmentObstacle> *sobstacles)
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);
694 bool T3::connecttrees(RRTNode *rn, RRTNode *gn)
696 while (gn != this->goal()) {
697 this->p_root_.nodes().push_back(new RRTNode(
702 this->p_root_.nodes().back(),
705 this->p_root_.nodes().back()));
706 rn = this->p_root_.nodes().back();
709 rn->add_child(this->goal(), this->p_root_.cost(rn, this->goal()));
713 bool T3::overlaptrees(RRTNode **ron, RRTNode **gon)
715 for (auto rn: this->p_root_.nodes()) {
716 if (rn->parent() == nullptr)
718 for (auto gn: this->p_goal_.nodes()) {
719 if (gn->parent() == nullptr)
721 if (IS_NEAR(rn, gn)) {
731 Klemm2015::Klemm2015(RRTNode *init, RRTNode *goal):
732 Karaman2011(init, goal),
736 srand(static_cast<unsigned>(time(0)));
737 this->root()->tree('R');
738 this->goal()->tree('G');
739 this->add_iy(this->goal());
742 bool Klemm2015::next()
744 RRTNode *xn = nullptr;
748 if (this->samples().size() == 0)
755 this->samples().push_back(rs);
756 //std::cerr << "next" << std::endl;
757 if (this->extendstar1(rs, &xn) != 2) {
759 // std::cerr << "- xn: " << xn->x() << ", " << xn->y();
760 // std::cerr << std::endl;
762 // std::cerr << "- xn: nullptr" << std::endl;
765 ret = this->connectstar(xn);
770 this->tlog(this->findt());
773 return this->goal_found();
776 int Klemm2015::extendstar1(RRTNode *rs, RRTNode **xn)
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;
784 // std::cerr << " - xn: " << (*xn)->x() << ", " << (*xn)->y();
785 // std::cerr << std::endl;
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());
792 // std::cerr << i << ": " << tmpn->x();
793 // std::cerr << ", " << tmpn->y();
794 // std::cerr << ", " << tmpn->tree();
795 // std::cerr << " (" << tmpd << ")";
797 // if (tmpn == this->root())
798 // std::cerr << " root";
799 // if (tmpn == this->goal())
800 // std::cerr << " goal";
801 // std::cerr << std::endl;
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];
814 this->nodes().size()),
816 this->nodes().push_back(ns);
819 if (!this->connect(nn, ns, nvs)) {
820 this->iy_[IYI(ns->y())].pop_back();
824 this->rewire(nvs, ns);
826 for (auto n: steered) {
831 //std::cerr << " - xn: " << (*xn)->x() << ", " << (*xn)->y();
832 //std::cerr << std::endl;
836 int Klemm2015::extendstarC(RRTNode *rs)
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);
845 std::vector<RRTNode *> nvs;
847 for (auto ns: this->steer(nn, rs)) {
855 this->nodes().size()),
857 this->nodes().push_back(ns);
860 if (!this->connect(pn, ns, nvs)) {
861 this->iy_[IYI(ns->y())].pop_back();
866 this->rewire(nvs, ns);
868 if (IS_NEAR(pn, rs)) { // GOAL FOUND !
870 if (this->orig_root_ == this->root()) { // rs is in G tree
871 // add all rs parents to pn
873 } else { // rs is in R tree
878 while (tmp != this->goal()) {
879 this->nodes().push_back(new RRTNode(
883 this->nodes().back()->s(tmp->s());
884 this->nodes().back()->tree('R');
886 this->nodes().back(),
887 this->cost(pn, this->nodes().back()));
888 pn = this->nodes().back();
891 pn->add_child(tmp, this->cost(pn, tmp)); // add goal()
901 int Klemm2015::connectstar(RRTNode *x)
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;
910 void Klemm2015::swap()
914 this->root(this->goal());