namespace rrts {
+ /*! \brief Collision check based on enlarged occupancy grid.
+ *
+ */
+ 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
*/