]> rtime.felk.cvut.cz Git - hubacji1/rrts.git/blobdiff - src/rrtext20.cc
Add occupancy grid-based collision check
[hubacji1/rrts.git] / src / rrtext20.cc
diff --git a/src/rrtext20.cc b/src/rrtext20.cc
new file mode 100644 (file)
index 0000000..d82ad5f
--- /dev/null
@@ -0,0 +1,55 @@
+/*
+ * SPDX-FileCopyrightText: 2022 Jiri Vlasak
+ *
+ * SPDX-License-Identifier: GPL-3.0-only
+ */
+
+#include <cassert>
+#include "rrtext.hh"
+
+namespace rrts {
+
+bool
+RRTExt20::collide_steered()
+{
+       assert(this->_points_to_check != nullptr);
+       std::vector<bcar::Point> points_to_check(*this->_points_to_check);
+       unsigned int i = 0;
+       for (auto &n: this->steered_) {
+               for (auto &p: points_to_check) {
+                       Point const n_p(n);
+                       CarSize const n_cs(this->bc());
+                       if (p.inside_of(n_p, n_cs.edist_to_rr())) {
+                               break;
+                       }
+                       if (p.edist(n_p) < n_cs.edist_to_lf()
+                                       && p.edist(n_p) > n_cs.edist_to_rr()) {
+                               BicycleCar n_bc(this->bc());
+                               n_bc.x(n.x());
+                               n_bc.y(n.y());
+                               n_bc.h(n.h());
+                               std::vector<Point> poly;
+                               poly.push_back(n_bc.lf());
+                               poly.push_back(n_bc.lr());
+                               poly.push_back(n_bc.rr());
+                               poly.push_back(n_bc.rf());
+                               poly.push_back(n_bc.lf());
+                               if (p.inside_of(poly)) {
+                                       break;
+                               }
+
+                       }
+               }
+               i++;
+       }
+       this->steered_.erase(this->steered_.begin() + i, this->steered_.end());
+       return this->steered_.size() == 0;
+}
+
+void
+RRTExt20::set_points_to_check(std::vector<bcar::Point> const *p)
+{
+       this->_points_to_check = p;
+}
+
+} /* namespace rrts */