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