]> rtime.felk.cvut.cz Git - hubacji1/rrts.git/blobdiff - incl/rrtext.hh
Fix missing docs group of ext 21
[hubacji1/rrts.git] / incl / rrtext.hh
index 69f9175b204752a28b95ad13d49ecad320518f07..b20d1af0bda5e5605d272b75b55ab91868407693 100644 (file)
@@ -1,3 +1,9 @@
+/*
+ * SPDX-FileCopyrightText: 2021 Jiri Vlasak <jiri.vlasak.2@cvut.cz>
+ *
+ * SPDX-License-Identifier: GPL-3.0-only
+ */
+
 /*! \brief RRT* extensions.
  *
  * The extensions are used to implement or change the default behavior of the
 
 namespace rrts {
 
+/*! \brief Collision check based on enlarged occupancy grid.
+ *
+ * \ingroup ext-col
+ */
+class RRTExt21 : public virtual RRTS {
+private:
+       unsigned int _grid_width = 0;
+       unsigned int _grid_height = 0;
+       float _grid_res = 0.0;
+       int8_t const *_grid_data = nullptr;
+       double _origin_x = 0.0;
+       double _origin_y = 0.0;
+       bool collide(RRTNode const &n);
+       bool collide_steered();
+public:
+       void set_grid_to_check(unsigned int w, unsigned int h, float r,
+                       int8_t const *d, double x, double y);
+};
+
+/*! \brief Collision check based on occupancy grid.
+ *
+ * This approach expects obstacles to be represented by points and the collision
+ * occures whenever the point is inside the frame given by the car pose and the
+ * car size.
+ *
+ * \ingroup ext-col
+ */
+class RRTExt20 : public virtual RRTS {
+private:
+       std::vector<bcar::Point> const *_points_to_check = nullptr;
+       bool collide_steered();
+public:
+       void set_points_to_check(std::vector<bcar::Point> const *p);
+};
+
+/*! \brief Use Dubins paths-based steering procedure.
+ *
+ * \ingroup ext-steer
+ * \see https://github.com/AndrewWalker/Dubins-Curves
+ */
+class RRTExt19 : public virtual RRTS {
+private:
+       void steer(RRTNode const &f, RRTNode const &t);
+};
+
 /*! \brief Finish when more than 1000 iterations.
  *
  * \ingroup ext-aux
@@ -104,6 +155,7 @@ private:
                RRTNode* node = nullptr;
                unsigned int i = 0;
                bool v = false;
+               double d = 0.0;
                bool vi();
                DijkstraNode(RRTNode* n);
        };
@@ -111,11 +163,16 @@ private:
        public:
                int operator() (DijkstraNode const& n1, DijkstraNode const& n2);
        };
+       class DijkstraNodeBackwardComparator {
+       public:
+               int operator() (DijkstraNode const& n1, DijkstraNode const& n2);
+       };
        std::vector<RRTNode*> opath_;
        double ogoal_cc_ = 0.0;
        double otime_ = 0.0;
        std::vector<DijkstraNode> dn_;
-       void pick_interesting();
+       void interesting_forward();
+       void interesting_backward();
        void dijkstra_forward();
        void dijkstra_backward();
        void compute_path();
@@ -149,7 +206,8 @@ class RRTExt11 : public virtual RRTS {
 /*! \brief Reeds & Shepp (build) and Euclidean + abs angle (search).
  *
  * Use Reeds & Shepp path length for building tree data structure and Euclidean
- * distance plus (abs) heading difference for searching it.
+ * distance + (abs) heading difference + 0.1 * backward-forward direction
+ * changes for searching it.
  *
  * \ingroup ext-cost
  * \see https://doi.org/10.1109/TITS.2015.2477355
@@ -391,6 +449,7 @@ public:
        RRTExt2();
        Json::Value json() const;
        void json(Json::Value jvi);
+       void reset();
 };
 
 /* \brief Different costs extension.