Class HC00_Reeds_Shepp_State_Space

Inheritance Relationships

Base Type

Class Documentation

class HC00_Reeds_Shepp_State_Space : public steering::HC_CC_State_Space

An implementation of hybrid curvature (HC) steer with zero curvature at the start and goal configuration as described in: H. Banzhaf et al., “Hybrid Curvature Steer: A Novel Extend Function for Sampling-Based Non-

holonomic Motion Planning in Tight Environments,” IEEE International Conference on Intelligent Transportation Systems (Oct. 2017). It evaluates all Reeds-Shepp families plus the four families TTT, TcST, TScT, TcScT, where “T” stands for a turn, “S” for a straight line and “c” for a cusp, and returns the shortest path.

Public Functions

HC00_Reeds_Shepp_State_Space(double kappa, double sigma, double discretization = 0.1)

Constructor.

~HC00_Reeds_Shepp_State_Space()

Destructor.

HC_CC_RS_Path *hc00_circles_rs_path(const HC_CC_Circle &c1, const HC_CC_Circle &c2) const

Returns a sequence of turns and straight lines connecting the two circles c1 and c2.

HC_CC_RS_Path *hc00_reeds_shepp(const State &state1, const State &state2) const

Returns a sequence of turns and straight lines connecting a start and an end configuration.

double get_distance(const State &state1, const State &state2) const

Returns shortest path length from state1 to state2.

virtual std::vector<Control> get_controls(const State &state1, const State &state2) const

Returns controls of the shortest path from state1 to state2.