]> rtime.felk.cvut.cz Git - hubacji1/rrts.git/blobdiff - src/rrts.cc
Add setters for bc, imax
[hubacji1/rrts.git] / src / rrts.cc
index 74628e3096d18fb28b6fbde28296ae9ad87560a9..2212e597b2eca7e6d32adeb5a8f6f8b175a39443 100644 (file)
+/*
+ * SPDX-FileCopyrightText: 2021 Jiri Vlasak <jiri.vlasak.2@cvut.cz>
+ *
+ * SPDX-License-Identifier: GPL-3.0-only
+ */
+
 #include <algorithm>
-#include "rrts.h"
+#include <cassert>
+#include "rrts.hh"
+
+#ifndef USE_RRTS
+#define USE_RRTS 0  // TODO improve, this solution isn't clear.
+#endif
+
+namespace rrts {
+
+void
+Ter::start()
+{
+       this->tstart_ = std::chrono::high_resolution_clock::now();
+}
+
+double
+Ter::scnt() const
+{
+       using namespace std::chrono;
+       auto t = high_resolution_clock::now() - this->tstart_;
+       auto d = duration_cast<duration<double>>(t);
+       return d.count();
+}
+
+double
+RRTNode::c() const
+{
+       return this->c_;
+}
+
+void
+RRTNode::c(double c)
+{
+       assert(this->p_ != nullptr);
+       this->c_ = c;
+       this->cc_ = this->p_->cc() + c;
+}
+
+double
+RRTNode::cc() const
+{
+       return this->cc_;
+}
+
+RRTNode*
+RRTNode::p() const
+{
+       return this->p_;
+}
+
+void
+RRTNode::p(RRTNode& p)
+{
+       if (this != &p) {
+               this->p_ = &p;
+       }
+}
+
+unsigned int
+RRTNode::cusp() const
+{
+       return this->cusp_;
+}
 
-#include "reeds_shepp.h"
+void
+RRTNode::cusp(RRTNode const& p)
+{
+       this->cusp_ = p.cusp();
+       if (this->sp() != p.sp() || this->sp() == 0.0) {
+               this->cusp_++;
+       }
+}
 
-template <typename T> int sgn(T val) {
-        return (T(0) < val) - (val < T(0));
+bool
+RRTNode::operator==(RRTNode const& n)
+{
+       return this == &n;
 }
 
-RRTNode::RRTNode()
+void
+RRTS::recompute_cc(RRTNode* g)
 {
+       this->path_.clear();
+       while (g != nullptr) {
+               this->path_.push_back(g);
+               g = g->p();
+       }
+       std::reverse(this->path_.begin(), this->path_.end());
+       for (unsigned int i = 1; i < this->path_.size(); i++) {
+               this->path_[i]->c(this->cost_build(*this->path_[i - 1],
+                       *this->path_[i]));
+       }
 }
 
-RRTNode::RRTNode(const BicycleCar &bc)
+void
+RRTS::recompute_path_cc()
 {
-    this->x(bc.x());
-    this->y(bc.y());
-    this->h(bc.h());
-    this->sp(bc.sp());
-    this->st(bc.st());
+       this->recompute_cc(&this->goal_);
 }
 
-bool RRTNode::operator==(const RRTNode& n)
+double
+RRTS::min_gamma_eta() const
 {
-        if (this == &n)
-                return true;
-        return false;
+       double ns = this->nodes_.size();
+       double gamma = pow(log(ns) / ns, 1.0 / 3.0);
+       return std::min(gamma, this->eta_);
 }
 
-Obstacle::Obstacle()
+bool
+RRTS::should_continue() const
 {
+       return !this->should_finish();
 }
 
-double RRTS::elapsed()
+void
+RRTS::join_steered(RRTNode* f)
 {
-        std::chrono::duration<double> dt;
-        dt = std::chrono::duration_cast<std::chrono::duration<double>>(
-                std::chrono::high_resolution_clock::now()
-                - this->tstart_
-        );
-        this->scnt_ = dt.count();
-        return this->scnt_;
+       while (this->steered_.size() > 0) {
+               this->store(this->steered_.front());
+               RRTNode* t = &this->nodes_.back();
+               t->p(*f);
+               t->c(this->cost_build(*f, *t));
+               t->cusp(*f);
+               this->steered_.erase(this->steered_.begin());
+               f = t;
+       }
 }
 
-void RRTS::log_path_cost()
+RRTNode&
+RRTS::nn()
 {
-        this->log_path_cost_.push_back(cc(this->goals().front()));
-        this->log_path_time_ += 0.1;
+       return *this->nn_;
 }
 
-bool RRTS::should_stop()
+bool
+RRTS::connect()
 {
-        // the following counters must be updated, do not comment
-        this->icnt_++;
-        this->elapsed();
-        // current iteration stop conditions
-        if (this->should_finish()) return true;
-        if (this->should_break()) return true;
-        // but continue by default
-        return false;
+       RRTNode* f = this->nn_;
+       RRTNode* t = &this->steered_.front();
+#if USE_RRTS
+       double cost = f->cc() + this->cost_build(*f, *t);
+       for (auto n: this->nv_) {
+               double nc = n->cc() + this->cost_build(*n, *t);
+               if (nc < cost) {
+                       f = n;
+                       cost = nc;
+               }
+       }
+       // Check if it's possible to drive from *f to *t. If not, then fallback
+       // to *f = nn_. This could be also solved by additional steer from *f to
+       // *t instead of the following code.
+       this->bc_.set_pose(*f);
+       if (!this->bc_.drivable(*t)) {
+               f = this->nn_;
+       }
+#endif
+       this->store(this->steered_.front());
+       t = &this->nodes_.back();
+       t->p(*f);
+       t->c(this->cost_build(*f, *t));
+       t->cusp(*f);
+       this->steered_.erase(this->steered_.begin());
+       return true;
 }
 
-bool RRTS::should_finish()
+void
+RRTS::rewire()
 {
-        // decide finish conditions (maybe comment some lines)
-        //if (this->icnt_ > 999) return true;
-        if (this->scnt_ > 2) return true;
-        if (this->finishit) return true;
-        //if (this->gf()) return true;
-        // but continue by default
-        return false;
+       RRTNode *f = &this->nodes_.back();
+       for (auto n: this->nv_) {
+               double fc = f->cc() + this->cost_build(*f, *n);
+               this->bc_.set_pose(*f);
+               bool drivable = this->bc_.drivable(*n);
+               if (drivable && fc < n->cc()) {
+                       n->p(*f);
+                       n->c(this->cost_build(*f, *n));
+               }
+       }
 }
 
-bool RRTS::should_break()
+bool
+RRTS::goal_drivable_from(RRTNode const& f)
 {
-        // decide break conditions (maybe comment some lines)
-        //if (this->scnt_ - this->pcnt_ > 2) return true;
-        // but continue by default
-        return false;
+       this->bc_.set_pose(f);
+       return this->bc_.drivable(this->goal_);
 }
 
-bool RRTS::should_continue()
+void
+RRTS::store(RRTNode n)
 {
-        // decide the stop conditions (maybe comment some lines)
-        // it is exact opposite of `should_stop`
-        //if (this->icnt_ > 999) return false;
-        if (this->scnt_ > 10) return false;
-        if (this->gf()) return false;
-        // and reset pause counter if should continue
-        this->pcnt_ = this->scnt_;
-        return true;
+       this->nodes_.push_back(n);
 }
 
-void RRTS::store_node(RRTNode n)
+double
+RRTS::cost_build(RRTNode const& f, RRTNode const& t) const
 {
-        this->nodes().push_back(n);
+       return f.edist(t);
 }
 
-// RRT procedures
-std::tuple<bool, unsigned int, unsigned int>
-RRTS::collide(std::vector<std::tuple<double, double>> &poly)
+double
+RRTS::cost_search(RRTNode const& f, RRTNode const& t) const
 {
-        for (auto &o: this->obstacles())
-                if (std::get<0>(::collide(poly, o.poly())))
-                        return ::collide(poly, o.poly());
-        return std::make_tuple(false, 0, 0);
+       return this->cost_build(f, t);
 }
 
-std::tuple<bool, unsigned int, unsigned int>
-RRTS::collide_steered_from(RRTNode &f)
-{
-        auto fbc = BicycleCar();
-        fbc.x(f.x());
-        fbc.y(f.y());
-        fbc.h(f.h());
-        std::vector<std::tuple<double, double>> s;
-        s.push_back(std::make_tuple(fbc.x(), fbc.y()));
-        for (auto &n: this->steered()) {
-                auto nbc = BicycleCar();
-                nbc.x(n.x());
-                nbc.y(n.y());
-                nbc.h(n.h());
-                s.push_back(std::make_tuple(nbc.lfx(), nbc.lfy()));
-                s.push_back(std::make_tuple(nbc.lrx(), nbc.lry()));
-                s.push_back(std::make_tuple(nbc.rrx(), nbc.rry()));
-                s.push_back(std::make_tuple(nbc.rfx(), nbc.rfy()));
-        }
-        auto col = this->collide(s);
-        auto strip_from = this->steered().size() - std::get<1>(col) / 4;
-        if (std::get<0>(col) && strip_from > 0) {
-                while (strip_from-- > 0) {
-                        this->steered().pop_back();
-                }
-                return this->collide_steered_from(f);
-        }
-        return col;
-}
-
-std::tuple<bool, unsigned int, unsigned int>
-RRTS::collide_two_nodes(RRTNode &f, RRTNode &t)
-{
-        auto fbc = BicycleCar();
-        fbc.x(f.x());
-        fbc.y(f.y());
-        fbc.h(f.h());
-        auto tbc = BicycleCar();
-        tbc.x(f.x());
-        tbc.y(f.y());
-        tbc.h(f.h());
-        std::vector<std::tuple<double, double>> p;
-        p.push_back(std::make_tuple(fbc.lfx(), fbc.lfy()));
-        p.push_back(std::make_tuple(fbc.lrx(), fbc.lry()));
-        p.push_back(std::make_tuple(fbc.rrx(), fbc.rry()));
-        p.push_back(std::make_tuple(fbc.rfx(), fbc.rfy()));
-        p.push_back(std::make_tuple(tbc.lfx(), tbc.lfy()));
-        p.push_back(std::make_tuple(tbc.lrx(), tbc.lry()));
-        p.push_back(std::make_tuple(tbc.rrx(), tbc.rry()));
-        p.push_back(std::make_tuple(tbc.rfx(), tbc.rfy()));
-        return this->collide(p);
-}
-
-double RRTS::cost_build(RRTNode &f, RRTNode &t)
-{
-        double cost = 0;
-        cost = sqrt(pow(t.y() - f.y(), 2) + pow(t.x() - f.x(), 2));
-        return cost;
-}
-
-double RRTS::cost_search(RRTNode &f, RRTNode &t)
-{
-        double cost = 0;
-        cost = sqrt(pow(t.y() - f.y(), 2) + pow(t.x() - f.x(), 2));
-        return cost;
-}
-
-void RRTS::sample()
-{
-        double x = 0;
-        double y = 0;
-        double h = 0;
-        switch (this->sample_dist_type()) {
-        case 1: // uniform
-                x = this->udx_(this->gen_);
-                y = this->udy_(this->gen_);
-                h = this->udh_(this->gen_);
-                break;
-        case 2: // uniform circle
-        {
-                // see https://stackoverflow.com/questions/5837572/generate-a-random-point-within-a-circle-uniformly/50746409#50746409
-                double R = sqrt(
-                        pow(
-                                this->nodes().front().x()
-                                - this->goals().front().x(),
-                                2
-                        )
-                        + pow(
-                                this->nodes().front().y()
-                                - this->goals().front().y(),
-                                2
-                        )
-                );
-                double a = atan2(
-                        this->goals().front().y() - this->nodes().front().y(),
-                        this->goals().front().x() - this->nodes().front().x()
-                );
-                double cx = this->goals().front().x() - R/2 * cos(a);
-                double cy = this->goals().front().y() - R/2 * sin(a);
-                double r = R * sqrt(this->udx_(this->gen_));
-                double theta = this->udy_(this->gen_) * 2 * M_PI;
-                x = cx + r * cos(theta);
-                y = cy + r * sin(theta);
-                h = this->udh_(this->gen_);
-        }
-                break;
-        case 3: {
-                this->udi_ = std::uniform_int_distribution<unsigned int>(
-                        0,
-                        this->nodes().size() - 1
-                );
-                auto ind = this->udi_(this->gen_);
-                auto n = this->nodes()[ind];
-                x = n.x();
-                y = n.y();
-                h = n.h();
-                break;
-                }
-        default: // normal
-                x = this->ndx_(this->gen_);
-                y = this->ndy_(this->gen_);
-                h = this->ndh_(this->gen_);
-        }
-        this->samples().push_back(RRTNode());
-        this->samples().back().x(x);
-        this->samples().back().y(y);
-        this->samples().back().h(h);
-}
-
-RRTNode *RRTS::nn(RRTNode &t)
-{
-        RRTNode *nn = &this->nodes().front();
-        double cost = this->cost_search(*nn, t);
-        for (auto &f: this->nodes()) {
-                if (this->cost_search(f, t) < cost) {
-                        nn = &f;
-                        cost = this->cost_search(f, t);
-                }
-        }
-        return nn;
-}
-
-std::vector<RRTNode *> RRTS::nv(RRTNode &t)
-{
-        std::vector<RRTNode *> nv;
-        double cost = std::min(GAMMA(this->nodes().size()), ETA);
-        for (auto &f: this->nodes())
-                if (this->cost_search(f, t) < cost)
-                        nv.push_back(&f);
-        return nv;
-}
-
-int cb_rs_steer(double q[4], void *user_data)
-{
-        std::vector<RRTNode> *nodes = (std::vector<RRTNode> *) user_data;
-        nodes->push_back(RRTNode());
-        nodes->back().x(q[0]);
-        nodes->back().y(q[1]);
-        nodes->back().h(q[2]);
-        nodes->back().sp(q[3]);
-        if (nodes->back().sp() == 0) {
-                nodes->back().set_t(RRTNodeType::cusp);
-        } else if (nodes->size() >= 2) {
-                RRTNode* lln = nodes->back().p();
-                RRTNode* ln = &nodes->back();
-                if (lln != nullptr && ln != nullptr && sgn(lln->sp()) != sgn(ln->sp()))
-                        ln->set_t(RRTNodeType::cusp);
-        }
-        return 0;
-}
-
-void RRTS::steer(RRTNode &f, RRTNode &t)
-{
-        this->steered().clear();
-        double q0[] = {f.x(), f.y(), f.h()};
-        double q1[] = {t.x(), t.y(), t.h()};
-        ReedsSheppStateSpace rsss(this->bc.mtr());
-        rsss.sample(q0, q1, 0.2, cb_rs_steer, &this->steered());
-}
-
-void RRTS::steer1(RRTNode &f, RRTNode &t)
-{
-    return this->steer(f, t);
-}
-
-void RRTS::steer2(RRTNode &f, RRTNode &t)
-{
-    return this->steer(f, t);
-}
-
-void RRTS::join_steered(RRTNode *f)
-{
-        while (this->steered().size() > 0) {
-                this->store_node(this->steered().front());
-                RRTNode *t = &this->nodes().back();
-                t->p(f);
-                t->c(this->cost_build(*f, *t));
-                this->steered().erase(this->steered().begin());
-                f = t;
-        }
-}
-
-bool RRTS::goal_found(RRTNode &f)
-{
-        auto &g = this->goals().front();
-        double cost = this->cost_build(f, g);
-        double edist = sqrt(
-                pow(f.x() - g.x(), 2)
-                + pow(f.y() - g.y(), 2)
-        );
-        double adist = std::abs(f.h() - g.h());
-        if (edist < 0.05 && adist < M_PI / 32) {
-                if (g.p() == nullptr || cc(f) + cost < cc(g)) {
-                        g.p(&f);
-                        g.c(cost);
-                }
-                return true;
-        }
-        return false;
-}
-
-// RRT* procedures
-bool RRTS::connect()
-{
-        RRTNode *t = &this->steered().front();
-        RRTNode *f = this->nn(this->samples().back());
-        double cost = this->cost_search(*f, *t);
-        for (auto n: this->nv(*t)) {
-                if (
-                        !std::get<0>(this->collide_two_nodes(*n, *t))
-                        && this->cost_search(*n, *t) < cost
-                ) {
-                        f = n;
-                        cost = this->cost_search(*n, *t);
-                }
-        }
-        this->store_node(this->steered().front());
-        t = &this->nodes().back();
-        t->p(f);
-        t->c(this->cost_build(*f, *t));
-        t->set_t(RRTNodeType::connected);
-        return true;
-}
-
-void RRTS::rewire()
-{
-        RRTNode *f = &this->nodes().back();
-        for (auto n: this->nv(*f)) {
-                if (
-                        !std::get<0>(this->collide_two_nodes(*f, *n))
-                        && cc(*f) + this->cost_search(*f, *n) < cc(*n)
-                ) {
-                        n->p(f);
-                        n->c(this->cost_build(*f, *n));
-                }
-        }
-}
-
-// API
-void RRTS::init()
-{
-}
-
-void RRTS::deinit()
-{
-        this->nodes().clear();
-        this->samples().clear();
-        this->steered().clear();
-        this->store_node(RRTNode()); // root
-        this->icnt_ = 0;
-        this->scnt_ = 0;
-        this->pcnt_ = 0;
-        this->gf_ = false;
-}
-
-std::vector<RRTNode *> RRTS::path()
-{
-        std::vector<RRTNode *> path;
-        if (this->goals().size() == 0)
-                return path;
-        RRTNode *goal = &this->goals().back();
-        if (goal->p() == nullptr)
-                return path;
-        while (goal != nullptr) {
-                path.push_back(goal);
-                goal = goal->p();
-        }
-        std::reverse(path.begin(), path.end());
-        return path;
-}
-
-bool RRTS::next()
-{
-        if (this->icnt_ == 0)
-                this->tstart_ = std::chrono::high_resolution_clock::now();
-        bool next = true;
-        if (this->scnt_ > this->log_path_time_)
-            this->log_path_cost();
-        if (this->should_stop())
-                return false;
-        if (this->samples().size() == 0) {
-                this->samples().push_back(RRTNode());
-                this->samples().back().x(this->goals().front().x());
-                this->samples().back().y(this->goals().front().y());
-                this->samples().back().h(this->goals().front().h());
-        } else {
-                this->sample();
-        }
-        this->steer1(
-                *this->nn(this->samples().back()),
-                this->samples().back()
-        );
-        if (this->steered().size() == 0)
-                return next;
-        auto col = this->collide_steered_from(
-                *this->nn(this->samples().back())
-        );
-        if (std::get<0>(col)) {
-                auto rcnt = this->steered().size() - std::get<1>(col);
-                while (rcnt-- > 0) {
-                        this->steered().pop_back();
-                }
-        }
-        if (!this->connect())
-                return next;
-        this->rewire();
-        unsigned scnt = this->steered().size();
-        this->join_steered(&this->nodes().back());
-        RRTNode *just_added = &this->nodes().back();
-        while (scnt > 0) {
-                scnt--;
-                auto &g = this->goals().front();
-                this->steer2(*just_added, g);
-                if (std::get<0>(this->collide_steered_from(
-                        *just_added
-                )))
-                        continue;
-                this->join_steered(just_added);
-                this->gf(this->goal_found(this->nodes().back()));
-                just_added = just_added->p();
-        }
-        return next;
-}
-
-void RRTS::set_sample_normal(
-        double mx, double dx,
-        double my, double dy,
-        double mh, double dh
-)
-{
-        this->ndx_ = std::normal_distribution<double>(mx, dx);
-        this->ndy_ = std::normal_distribution<double>(my, dy);
-        this->ndh_ = std::normal_distribution<double>(mh, dh);
-}
-void RRTS::set_sample_uniform(
-        double xmin, double xmax,
-        double ymin, double ymax,
-        double hmin, double hmax
-)
-{
-        this->udx_ = std::uniform_real_distribution<double>(xmin,xmax);
-        this->udy_ = std::uniform_real_distribution<double>(ymin,ymax);
-        this->udh_ = std::uniform_real_distribution<double>(hmin,hmax);
-}
-void RRTS::set_sample_uniform_circle()
-{
-        this->udx_ = std::uniform_real_distribution<double>(0, 1);
-        this->udy_ = std::uniform_real_distribution<double>(0, 1);
-        this->udh_ = std::uniform_real_distribution<double>(0, 2 * M_PI);
-}
-void RRTS::set_sample(
-        double x1, double x2,
-        double y1, double y2,
-        double h1, double h2
-)
-{
-        switch (this->sample_dist_type()) {
-        case 1: // uniform
-                x1 += this->nodes().front().x();
-                x2 += this->nodes().front().x();
-                y1 += this->nodes().front().y();
-                y2 += this->nodes().front().y();
-                this->set_sample_uniform(x1, x2, y1, y2, h1, h2);
-                break;
-        case 2: // uniform circle
-                this->set_sample_uniform_circle();
-                break;
-        case 3: // uniform index of node in nodes
-                this->set_sample_uniform_circle();
-                break;
-        default: // normal
-                this->set_sample_normal(x1, x2, y1, y2, h1, h2);
-        }
-}
-
-Json::Value RRTS::json()
-{
-        Json::Value jvo;
-        {
-                jvo["time"] = this->scnt();
-        }
-        {
-                jvo["iterations"] = this->icnt();
-        }
-        {
-                jvo["init"][0] = this->nodes().front().x();
-                jvo["init"][1] = this->nodes().front().y();
-                jvo["init"][2] = this->nodes().front().h();
-        }
-        {
-                jvo["path_cost_before_opt"] = this->path_cost_before_opt_;
-        }
-        {
-                if (this->path().size() > 0) {
-                        jvo["cost"] = cc(*this->path().back());
-                        jvo["entry"][0] = this->goals().front().x();
-                        jvo["entry"][1] = this->goals().front().y();
-                        jvo["entry"][2] = this->goals().front().h();
-                        jvo["goal"][0] = this->goals().back().x();
-                        jvo["goal"][1] = this->goals().back().y();
-                        jvo["goal"][2] = this->goals().back().h();
-                }
-        }
-        {
-                unsigned int cu = 0;
-                unsigned int co = 0;
-                unsigned int pcnt = 0;
-                for (auto n: this->path()) {
-                        jvo["path"][pcnt][0] = n->x();
-                        jvo["path"][pcnt][1] = n->y();
-                        jvo["path"][pcnt][2] = n->h();
-                        if (n->t(RRTNodeType::cusp))
-                                cu++;
-                        if (n->t(RRTNodeType::connected))
-                                co++;
-                        pcnt++;
-                }
-                jvo["cusps-in-path"] = cu;
-                jvo["connecteds-in-path"] = co;
-        }
-        {
-                unsigned int gcnt = 0;
-                for (auto g: this->goals()) {
-                        jvo["goals"][gcnt][0] = g.x();
-                        jvo["goals"][gcnt][1] = g.y();
-                        jvo["goals"][gcnt][2] = g.h();
-                        gcnt++;
-                }
-        }
-        {
-                unsigned int ocnt = 0;
-                for (auto o: this->obstacles()) {
-                        unsigned int ccnt = 0;
-                        for (auto c: o.poly()) {
-                                jvo["obst"][ocnt][ccnt][0] = std::get<0>(c);
-                                jvo["obst"][ocnt][ccnt][1] = std::get<1>(c);
-                                ccnt++;
-                        }
-                        ocnt++;
-                }
-        }
-        {
-                jvo["nodes"] = (unsigned int) this->nodes().size();
-        }
-        {
-                unsigned int cnt = 0;
-                for (auto i: this->log_path_cost_)
-                        jvo["log_path_cost"][cnt++] = i;
-        }
-        //{
-        //        unsigned int ncnt = 0;
-        //        for (auto n: this->nodes()) {
-        //                jvo["nodes_x"][ncnt] = n.x();
-        //                jvo["nodes_y"][ncnt] = n.y();
-        //                //jvo["nodes_h"][ncnt] = n.h();
-        //                ncnt++;
-        //        }
-        //}
-        return jvo;
-}
-
-void RRTS::json(Json::Value jvi)
-{
-        assert(jvi["init"] != Json::nullValue);
-        assert(jvi["goals"] != Json::nullValue);
-        assert(jvi["obst"] != Json::nullValue);
-
-        this->nodes().front().x(jvi["init"][0].asDouble());
-        this->nodes().front().y(jvi["init"][1].asDouble());
-        this->nodes().front().h(jvi["init"][2].asDouble());
-        {
-                RRTNode* gp = nullptr;
-                if (jvi["entry"] != Json::nullValue) {
-                        this->entry_set = true;
-                        this->entry.x = jvi["entry"][0].asDouble();
-                        this->entry.y = jvi["entry"][1].asDouble();
-                        this->entry.b = jvi["entry"][2].asDouble();
-                        this->entry.e = jvi["entry"][3].asDouble();
-                        RRTNode tmp_node;
-                        tmp_node.x(this->entry.x);
-                        tmp_node.y(this->entry.y);
-                        tmp_node.h((this->entry.b + this->entry.e) / 2.0);
-                        this->goals().push_back(tmp_node);
-                        this->goals().back().p(gp);
-                        gp = &this->goals().back();
-                }
-                for (auto g: jvi["goals"]) {
-                        RRTNode tmp_node;
-                        tmp_node.x(g[0].asDouble());
-                        tmp_node.y(g[1].asDouble());
-                        tmp_node.h(g[2].asDouble());
-                        this->goals().push_back(tmp_node);
-                        this->goals().back().p(gp);
-                        gp = &this->goals().back();
-                }
-                this->goals().front().set_t(RRTNodeType::cusp);
-                this->goals().back().set_t(RRTNodeType::cusp);
-        }
-        {
-                Obstacle tmp_obstacle;
-                for (auto o: jvi["obst"]) {
-                        tmp_obstacle.poly().clear();
-                        for (auto c: o) {
-                                double tmp_x = c[0].asDouble();
-                                double tmp_y = c[1].asDouble();
-                                auto tmp_tuple = std::make_tuple(tmp_x, tmp_y);
-                                tmp_obstacle.poly().push_back(tmp_tuple);
-                        }
-                        this->obstacles().push_back(tmp_obstacle);
-                }
-        }
-        {
-                double edist_init_goal = sqrt(
-                        pow(
-                                this->nodes().front().x()
-                                - this->goals().front().x(),
-                                2
-                        )
-                        + pow(
-                                this->nodes().front().y()
-                                - this->goals().front().y(),
-                                2
-                        )
-                );
-                this->set_sample(
-                        this->nodes().front().x(), edist_init_goal,
-                        this->nodes().front().y(), edist_init_goal,
-                        0, 2 * M_PI
-                );
-        }
-}
-
-RRTS::RRTS()
-        : gen_(std::random_device{}())
-{
-        this->goals().reserve(100);
-        this->nodes().reserve(4000000);
-        this->samples().reserve(1000);
-        this->steered().reserve(20000);
-        this->store_node(RRTNode()); // root
-}
-
-double cc(RRTNode &t)
-{
-        RRTNode *n = &t;
-        double cost = 0;
-        while (n != nullptr) {
-                cost += n->c();
-                n = n->p();
-        }
-        return cost;
+void
+RRTS::find_nn(RRTNode const& t)
+{
+       this->nn_ = &this->nodes_.front();
+       this->cost_ = this->cost_search(*this->nn_, t);
+       for (auto& f: this->nodes_) {
+               if (this->cost_search(f, t) < this->cost_) {
+                       this->nn_ = &f;
+                       this->cost_ = this->cost_search(f, t);
+               }
+       }
 }
+
+void
+RRTS::find_nv(RRTNode const& t)
+{
+       this->nv_.clear();
+       this->cost_ = this->min_gamma_eta();
+       for (auto& f: this->nodes_) {
+               if (this->cost_search(f, t) < this->cost_) {
+                       this->nv_.push_back(&f);
+               }
+       }
+}
+
+void
+RRTS::compute_path()
+{
+       this->path_.clear();
+       RRTNode *g = &this->goal_;
+       if (g->p() == nullptr) {
+               return;
+       }
+       while (g != nullptr && this->path_.size() < 10000) {
+               /* FIXME in ext13
+                *
+                * There shouldn't be this->path_.size() < 10000 condition.
+                * However, the RRTS::compute_path() called from
+                * RRTExt13::compute_path tends to re-allocate this->path_
+                * infinitely. There's probably node->p() = &node somewhere...
+                */
+               this->path_.push_back(g);
+               g = g->p();
+       }
+       std::reverse(this->path_.begin(), this->path_.end());
+}
+
+RRTS::RRTS() : gen_(std::random_device{}()), goal_(0.0, 0.0, 0.0, 0.0)
+{
+       this->nodes_.reserve(4000000);
+       this->steered_.reserve(1000);
+       this->path_.reserve(10000);
+       this->nv_.reserve(1000);
+       this->store(RRTNode()); // root
+}
+
+BicycleCar &
+RRTS::bc()
+{
+       return this->bc_;
+}
+
+void
+RRTS::set_imax_reset(unsigned int i)
+{
+       this->_imax = i;
+}
+
+unsigned int
+RRTS::icnt() const
+{
+       return this->icnt_;
+}
+
+void
+RRTS::icnt(unsigned int i)
+{
+       this->icnt_ = i;
+}
+
+double
+RRTS::scnt() const
+{
+       return this->ter_.scnt();
+}
+
+Json::Value
+RRTS::json() const
+{
+       Json::Value jvo;
+       unsigned int i = 0;
+       for (auto n: this->path_) {
+               jvo["path"][i][0] = n->x();
+               jvo["path"][i][1] = n->y();
+               jvo["path"][i][2] = n->h();
+               i++;
+       }
+       jvo["goal_cc"] = this->goal_.cc();
+       jvo["time"] = this->time_;
+       return jvo;
+}
+
+void
+RRTS::json(Json::Value jvi)
+{
+       assert(jvi["init"] != Json::nullValue);
+       assert(jvi["goal"] != Json::nullValue);
+       this->nodes_.front().x(jvi["init"][0].asDouble());
+       this->nodes_.front().y(jvi["init"][1].asDouble());
+       this->nodes_.front().h(jvi["init"][2].asDouble());
+       if (jvi["goal"].size() == 4) {
+               this->goal_ = RRTGoal(jvi["goal"][0].asDouble(),
+                       jvi["goal"][1].asDouble(),
+                       jvi["goal"][2].asDouble(),
+                       jvi["goal"][3].asDouble());
+       } else {
+               this->goal_ = RRTGoal(jvi["goal"][0].asDouble(),
+                       jvi["goal"][1].asDouble(),
+                       jvi["goal"][2].asDouble(),
+                       jvi["goal"][2].asDouble());
+       }
+}
+
+bool
+RRTS::next()
+{
+       if (this->icnt_ == 0) {
+               this->ter_.start();
+       }
+       this->icnt_ += 1;
+       auto rs = this->sample();
+#if 1 // anytime RRTs
+{
+       double d1 = this->cost_search(this->nodes_.front(), rs);
+       double d2 = this->cost_search(rs, this->goal_);
+       if (this->last_goal_cc_ != 0.0 && d1 + d2 > this->last_goal_cc_) {
+               rs = this->last_path_[rand() % this->last_path_.size()];
+       }
+}
+#endif
+       this->find_nn(rs);
+       this->steer(this->nn(), rs);
+       if (this->collide_steered()) {
+               return this->should_continue();
+       }
+#if USE_RRTS
+       this->find_nv(this->steered_.front());
+#endif
+       if (!this->connect()) {
+               return this->should_continue();
+       }
+#if USE_RRTS
+       this->rewire();
+#endif
+       unsigned int ss = this->steered_.size();
+       this->join_steered(&this->nodes_.back());
+       RRTNode* just_added = &this->nodes_.back();
+       bool gf = false;
+       while (ss > 0 && just_added->p() != nullptr) {
+               this->steer(*just_added, this->goal_);
+               if (this->collide_steered()) {
+                       ss--;
+                       just_added = just_added->p();
+                       continue;
+               }
+               this->join_steered(just_added);
+               bool gn = this->goal_.edist(this->nodes_.back()) < this->eta_;
+               bool gd = this->goal_drivable_from(this->nodes_.back());
+               if (gn && gd) {
+                       double nc = this->cost_build(this->nodes_.back(),
+                               this->goal_);
+                       double ncc = this->nodes_.back().cc() + nc;
+                       if (this->goal_.p() == nullptr
+                                       || ncc < this->goal_.cc()) {
+                               this->goal_.p(this->nodes_.back());
+                               this->goal_.c(nc);
+                               gf = true;
+                       }
+               }
+               ss--;
+               just_added = just_added->p();
+       }
+       if (gf) {
+               this->compute_path();
+       }
+       this->time_ = this->ter_.scnt();
+       return this->should_continue();
+}
+
+void
+RRTS::reset()
+{
+       if (this->goal_.cc() != 0.0 && this->goal_.cc() < this->last_goal_cc_) {
+               this->last_goal_cc_ = this->goal_.cc();
+               this->last_path_.clear();
+               for (auto n: this->path_) {
+                       this->last_path_.push_back(*n);
+               }
+       }
+       this->goal_ = RRTGoal(this->goal_.x(), this->goal_.y(), this->goal_.b(),
+               this->goal_.e());
+       this->path_.clear();
+       this->steered_.clear();
+       this->nodes_.erase(this->nodes_.begin() + 1, this->nodes_.end());
+       this->nv_.clear();
+       this->nn_ = nullptr;
+}
+
+} // namespace rrts