#include <vector>
#include "bcar.h"
+/*! \brief Possible type of RRT node.
+
+\param cusp The node that is cusp (change in direction).
+\param connected The node that branches generated steered path.
+*/
+class RRTNodeType {
+ public:
+ static const unsigned int cusp = 1 << 0;
+ static const unsigned int connected = 1 << 1;
+};
+
/*! \brief RRT node basic class.
\param c Cumulative cost from RRT data structure root.
private:
double c_ = 0;
RRTNode *p_ = nullptr;
+ unsigned int t_ = 0;
public:
// getters, setters
double c() const { return this->c_; }
RRTNode *p() const { return this->p_; }
void p(RRTNode *p) { this->p_ = p; }
+ bool t(unsigned int flag) { return this->t_ & flag; }
+ void set_t(unsigned int flag) { this->t_ |= flag; }
+ void clear_t(unsigned int flag) { this->t_ &= ~flag; }
+
RRTNode();
RRTNode(const BicycleCar &bc);
};