]> rtime.felk.cvut.cz Git - hubacji1/rrts.git/blobdiff - incl/rrtext.hh
Improve docs for (collision) ext 20
[hubacji1/rrts.git] / incl / rrtext.hh
index 4f20a7937897435e698b6b7a69e2d0753e6dcd2a..d8bcfd6eed1c4bcd4a37da59b0950b4a04123927 100644 (file)
 
 namespace rrts {
 
+/*! \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.
@@ -412,6 +430,7 @@ public:
        RRTExt2();
        Json::Value json() const;
        void json(Json::Value jvi);
+       void reset();
 };
 
 /* \brief Different costs extension.