#include <algorithm>
-#include "rrts.h"
+#include <cassert>
+#include "rrts.hh"
-#include "reeds_shepp.h"
+namespace rrts {
-template <typename T> int sgn(T val) {
- return (T(0) < val) - (val < T(0));
+void
+Ter::start()
+{
+ this->tstart_ = std::chrono::high_resolution_clock::now();
}
-RRTNode::RRTNode()
+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();
}
-RRTNode::RRTNode(const BicycleCar &bc) : BicycleCar(bc)
+double
+RRTNode::c() const
{
+ return this->c_;
}
-Obstacle::Obstacle()
+void
+RRTNode::c(double c)
{
+ assert(this->p_ != nullptr);
+ this->c_ = c;
+ this->cc_ = this->p_->cc() + c;
}
-double RRTS::elapsed()
+double
+RRTNode::cc() const
{
- 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_;
+ return this->cc_;
}
-bool RRTS::should_stop()
+RRTNode*
+RRTNode::p() const
{
- // the following counters must be updated, do not comment
- this->icnt_++;
- this->elapsed();
- // decide the stop conditions (maybe comment some lines)
- if (this->icnt_ > 999) return true;
- if (this->scnt_ > 10) return true;
- if (this->gf()) return true;
- // but continue by default
- return false;
+ return this->p_;
}
-void RRTS::store_node(RRTNode n)
+void
+RRTNode::p(RRTNode& p)
{
- this->nodes().push_back(n);
+ if (this != &p) {
+ this->p_ = &p;
+ }
}
-// RRT procedures
-std::tuple<bool, unsigned int, unsigned int>
-RRTS::collide(std::vector<std::tuple<double, double>> &poly)
+bool
+RRTNode::operator==(RRTNode const& n)
{
- 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 == &n;
}
-std::tuple<bool, unsigned int, unsigned int>
-RRTS::collide_steered_from(RRTNode &f)
+double
+RRTS::min_gamma_eta() const
{
- std::vector<std::tuple<double, double>> s;
- s.push_back(std::make_tuple(f.x(), f.y()));
- for (auto &n: this->steered()) {
- s.push_back(std::make_tuple(n.lfx(), n.lfy()));
- s.push_back(std::make_tuple(n.lrx(), n.lry()));
- s.push_back(std::make_tuple(n.rrx(), n.rry()));
- s.push_back(std::make_tuple(n.rfx(), n.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;
+ double ns = this->nodes_.size();
+ double gamma = pow(log(ns) / ns, 1.0 / 3.0);
+ return std::min(gamma, this->eta_);
}
-std::tuple<bool, unsigned int, unsigned int>
-RRTS::collide_two_nodes(RRTNode &f, RRTNode &t)
+bool
+RRTS::should_continue() const
{
- std::vector<std::tuple<double, double>> p;
- p.push_back(std::make_tuple(f.lfx(), f.lfy()));
- p.push_back(std::make_tuple(f.lrx(), f.lry()));
- p.push_back(std::make_tuple(f.rrx(), f.rry()));
- p.push_back(std::make_tuple(f.rfx(), f.rfy()));
- p.push_back(std::make_tuple(t.lfx(), t.lfy()));
- p.push_back(std::make_tuple(t.lrx(), t.lry()));
- p.push_back(std::make_tuple(t.rrx(), t.rry()));
- p.push_back(std::make_tuple(t.rfx(), t.rfy()));
- return this->collide(p);
+ return !this->should_finish();
}
-double RRTS::cost_build(RRTNode &f, RRTNode &t)
+void
+RRTS::join_steered(RRTNode* f)
{
- double cost = 0;
- cost = sqrt(pow(t.y() - f.y(), 2) + pow(t.x() - f.x(), 2));
- return cost;
+ 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));
+ this->steered_.erase(this->steered_.begin());
+ f = t;
+ }
}
-double RRTS::cost_search(RRTNode &f, RRTNode &t)
+RRTNode&
+RRTS::nn()
{
- double cost = 0;
- cost = sqrt(pow(t.y() - f.y(), 2) + pow(t.x() - f.x(), 2));
- return cost;
+ return *this->nn_;
}
-void RRTS::sample()
+bool
+RRTS::connect()
{
- double x = this->ndx_(this->gen_);
- double y = this->ndy_(this->gen_);
- double 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* f = this->nn_;
+ RRTNode* t = &this->steered_.front();
+ 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_;
+ }
+ this->store(this->steered_.front());
+ t = &this->nodes_.back();
+ t->p(*f);
+ t->c(this->cost_build(*f, *t));
+ this->steered_.erase(this->steered_.begin());
+ return true;
}
-RRTNode *RRTS::nn(RRTNode &t)
+void
+RRTS::rewire()
{
- 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;
+ 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));
+ }
+ }
}
-std::vector<RRTNode *> RRTS::nv(RRTNode &t)
+bool
+RRTS::goal_drivable_from(RRTNode const& f)
{
- 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;
+ this->bc_.set_pose(f);
+ return this->bc_.drivable(this->goal_);
}
-int cb_rs_steer(double q[4], void *user_data)
+void
+RRTS::store(RRTNode n)
{
- std::vector<RRTNode> *nodes = (std::vector<RRTNode> *) user_data;
- RRTNode *ln = nullptr;
- if (nodes->size() > 0)
- ln = &nodes->back();
- 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 (ln != nullptr && sgn(ln->sp()) != sgn(nodes->back().sp()))
- ln->set_t(RRTNodeType::cusp);
- return 0;
+ this->nodes_.push_back(n);
}
-void RRTS::steer(RRTNode &f, RRTNode &t)
+double
+RRTS::cost_build(RRTNode const& f, RRTNode const& t) const
{
- this->steered().clear();
- double q0[] = {f.x(), f.y(), f.h()};
- double q1[] = {t.x(), t.y(), t.h()};
- ReedsSheppStateSpace rsss(f.mtr());
- rsss.sample(q0, q1, 0.5, cb_rs_steer, &this->steered());
+ return f.edist(t);
}
-void RRTS::join_steered(RRTNode *f)
+double
+RRTS::cost_search(RRTNode const& f, RRTNode const& t) const
{
- 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;
- }
+ return this->cost_build(f, t);
}
-bool RRTS::goal_found(RRTNode &f)
+void
+RRTS::find_nn(RRTNode const& t)
{
- bool found = false;
- for (auto &g: this->goals()) {
- 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) {
- found = true;
- if (g.p() == nullptr || cc(f) + cost < cc(g)) {
- g.p(&f);
- g.c(cost);
- }
- }
- }
- return found;
+ 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);
+ }
+ }
}
-// RRT* procedures
-bool RRTS::connect()
+void
+RRTS::find_nv(RRTNode const& t)
{
- 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;
+ 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::rewire()
+void
+RRTS::compute_path()
{
- 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));
- }
- }
+ 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());
}
-// API
-void RRTS::init()
+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
}
-void RRTS::deinit()
+unsigned int
+RRTS::icnt() const
{
+ return this->icnt_;
}
-std::vector<RRTNode *> RRTS::path()
+void
+RRTS::icnt(unsigned int i)
{
- std::vector<RRTNode *> path;
- if (this->goals().size() == 0)
- return path;
- RRTNode *goal = &this->goals().front();
- for (auto &n: this->goals()) {
- if (
- n.p() != nullptr
- && (n.c() < goal->c() || goal->p() == nullptr)
- ) {
- goal = &n;
- }
- }
- if (goal->p() == nullptr)
- return path;
- while (goal != nullptr) {
- path.push_back(goal);
- goal = goal->p();
- }
- std::reverse(path.begin(), path.end());
- return path;
+ this->icnt_ = i;
}
-bool RRTS::next()
+double
+RRTS::scnt() const
{
- if (this->icnt_ == 0)
- this->tstart_ = std::chrono::high_resolution_clock::now();
- bool next = true;
- if (this->should_stop())
- return false;
- this->sample();
- this->steer(
- *this->nn(this->samples().back()),
- this->samples().back()
- );
- if (std::get<0>(this->collide_steered_from(
- *this->nn(this->samples().back())
- )))
- return next;
- if (!this->connect())
- return next;
- this->rewire();
- unsigned scnt = this->steered().size();
- this->steered().erase(this->steered().begin());
- this->join_steered(&this->nodes().back());
- RRTNode *just_added = &this->nodes().back();
- while (scnt > 0) {
- scnt--;
- for (auto &g: this->goals()) {
- this->steer(*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;
+ return this->ter_.scnt();
}
-void RRTS::set_sample(
- double mx, double dx,
- double my, double dy,
- double mh, double dh
-)
+Json::Value
+RRTS::json() const
{
- this->ndx_ = std::normal_distribution<double>(mx, dx);
- this->ndy_ = std::normal_distribution<double>(my, dy);
- this->ndh_ = std::normal_distribution<double>(mh, dh);
+ 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;
}
-Json::Value RRTS::json()
+void
+RRTS::json(Json::Value jvi)
{
- Json::Value jvo;
- return jvo;
+ assert(jvi["init"] != Json::nullValue);
+ assert(jvi["goal"] != 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());
+ 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());
+ }
}
-RRTS::RRTS()
- : gen_(std::random_device{}())
+bool
+RRTS::next()
+{
+ if (this->icnt_ == 0) {
+ this->ter_.start();
+ }
+ this->icnt_ += 1;
+ auto rs = this->sample();
+#if 1 // anytime RRTs
{
- this->goals().reserve(100);
- this->nodes().reserve(4000000);
- this->samples().reserve(1000);
- this->steered().reserve(20000);
- this->store_node(RRTNode()); // root
+ 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_) {
+ this->icnt_ -= 1;
+ return this->should_continue();
+ }
+}
+#endif
+ this->find_nn(rs);
+ this->steer(this->nn(), rs);
+ if (this->collide_steered()) {
+ return this->should_continue();
+ }
+ this->find_nv(this->steered_.front());
+ if (!this->connect()) {
+ return this->should_continue();
+ }
+ this->rewire();
+ unsigned int ss = this->steered_.size();
+ this->join_steered(&this->nodes_.back());
+ RRTNode* just_added = &this->nodes_.back();
+ while (ss > 0 && just_added->p() != nullptr) {
+ //if (!this->goal_drivable_from(*just_added)) {
+ // ss--;
+ // just_added = just_added->p();
+ // continue;
+ //}
+ 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);
+ this->compute_path();
+ }
+ }
+ ss--;
+ just_added = just_added->p();
+ }
+#if 1 // test if root -> just_added can be steered directly
+ this->steer(this->nodes_.front(), *just_added);
+ ss = this->steered_.size();
+ if (!this->collide_steered() && this->steered_.size() == ss) {
+ this->join_steered(&this->nodes_.front());
+ just_added->p(this->nodes_.back());
+ just_added->c(this->cost_build(this->nodes_.back(),
+ *just_added));
+ }
+#endif
+ ////if (!this->goal_drivable_from(this->nodes_.back())) {
+ //// return this->should_continue();
+ ////}
+ //this->steer(this->nodes_.back(), this->goal_);
+ //if (this->collide_steered()) {
+ // return this->should_continue();
+ //}
+ //this->join_steered(&this->nodes_.back());
+ //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);
+ // this->compute_path();
+ // }
+ //}
+ this->time_ = this->ter_.scnt();
+ return this->should_continue();
}
-double cc(RRTNode &t)
+void
+RRTS::reset()
{
- RRTNode *n = &t;
- double cost = 0;
- while (n != nullptr) {
- cost += n->c();
- n = n->p();
- }
- return cost;
+ if (this->goal_.cc() != 0.0 && this->goal_.cc() < this->last_goal_cc_) {
+ this->last_goal_cc_ = this->goal_.cc();
+ }
+ 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