]> 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 0c8cd06660ae2d4ecc9f058e1f0f3dd49182f996..b20d1af0bda5e5605d272b75b55ab91868407693 100644 (file)
 
 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