An implementation of hybrid curvature (HC) steer with zero curvature at the start configuration and either positive (p) or negative (n) max. curvature at the goal configuration, also see: 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. More...
#include <hc0pm_reeds_shepp_state_space.hpp>

Classes | |
| class | HC0pm_Reeds_Shepp |
Public Member Functions | |
| std::vector< Control > | get_controls (const State &state1, const State &state2) const |
| Returns controls of the shortest path from state1 to state2. More... | |
| double | get_distance (const State &state1, const State &state2) const |
| Returns shortest path length from state1 to state2. More... | |
| HC_CC_RS_Path * | hc0pm_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. More... | |
| HC_CC_RS_Path * | hc0pm_reeds_shepp (const State &state1, const State &state2) const |
| Returns a sequence of turns and straight lines connecting a start and an end configuration. More... | |
| HC0pm_Reeds_Shepp_State_Space (double kappa, double sigma, double discretization=0.1) | |
| Constructor. More... | |
| ~HC0pm_Reeds_Shepp_State_Space () | |
| Destructor. More... | |
Public Member Functions inherited from steering::HC_CC_State_Space | |
| std::vector< State > | get_path (const State &state1, const State &state2) const |
| Returns path from state1 to state2. More... | |
| std::vector< State_With_Covariance > | get_path_with_covariance (const State_With_Covariance &state1, const State &state2) const |
| Returns path including covariances from state1 to state2. More... | |
| HC_CC_State_Space (double kappa, double sigma, double discretization) | |
| Constructor. More... | |
| std::vector< State > | integrate (const State &state, const std::vector< Control > &controls) const |
| Returns integrated states given a start state and controls. More... | |
| State | integrate_ODE (const State &state, const Control &control, double integration_step) const |
| Returns integrated state given a start state, a control, and an integration step. More... | |
| std::vector< State_With_Covariance > | integrate_with_covariance (const State_With_Covariance &state, const std::vector< Control > &controls) const |
| Returns integrated states including covariance given a start state and controls. More... | |
| State | interpolate (const State &state, const std::vector< Control > &controls, double t) const |
| Returns interpolated state at distance t in [0,1] (percentage of total path length) More... | |
| void | set_filter_parameters (const Motion_Noise &motion_noise, const Measurement_Noise &measurement_noise, const Controller &controller) |
| Sets the parameters required by the filter. More... | |
Private Attributes | |
| std::unique_ptr< HC0pm_Reeds_Shepp > | hc0pm_reeds_shepp_ |
| Pimpl Idiom: unique pointer on class with families More... | |
| double | mu_ |
| Angle between a configuration on the hc-/cc-circle and the tangent to the circle at that position. More... | |
| double | radius_ |
| Outer radius of a hc-/cc-circle. More... | |
| HC_CC_Circle_Param | rs_circle_param_ |
| Parameter of a rs-circle. More... | |
Additional Inherited Members | |
Protected Attributes inherited from steering::HC_CC_State_Space | |
| double | discretization_ |
| Discretization of path. More... | |
| EKF | ekf_ |
| Extended Kalman Filter for uncertainty propagation. More... | |
| HC_CC_Circle_Param | hc_cc_circle_param_ |
| Parameters of a hc-/cc-circle. More... | |
| double | kappa_ |
| Curvature, sharpness of clothoid. More... | |
| double | sigma_ |
An implementation of hybrid curvature (HC) steer with zero curvature at the start configuration and either positive (p) or negative (n) max. curvature at the goal configuration, also see: 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.
Definition at line 74 of file hc0pm_reeds_shepp_state_space.hpp.
| steering::HC0pm_Reeds_Shepp_State_Space::HC0pm_Reeds_Shepp_State_Space | ( | double | kappa, |
| double | sigma, | ||
| double | discretization = 0.1 |
||
| ) |
Constructor.
Definition at line 1523 of file hc0pm_reeds_shepp_state_space.cpp.
|
default |
Destructor.
|
virtual |
Returns controls of the shortest path from state1 to state2.
Implements steering::HC_CC_State_Space.
Definition at line 1793 of file hc0pm_reeds_shepp_state_space.cpp.
| double steering::HC0pm_Reeds_Shepp_State_Space::get_distance | ( | const State & | state1, |
| const State & | state2 | ||
| ) | const |
Returns shortest path length from state1 to state2.
Definition at line 1785 of file hc0pm_reeds_shepp_state_space.cpp.
| HC_CC_RS_Path * steering::HC0pm_Reeds_Shepp_State_Space::hc0pm_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.
Definition at line 1534 of file hc0pm_reeds_shepp_state_space.cpp.
| HC_CC_RS_Path * steering::HC0pm_Reeds_Shepp_State_Space::hc0pm_reeds_shepp | ( | const State & | state1, |
| const State & | state2 | ||
| ) | const |
Returns a sequence of turns and straight lines connecting a start and an end configuration.
Definition at line 1702 of file hc0pm_reeds_shepp_state_space.cpp.
|
private |
Pimpl Idiom: unique pointer on class with families
Definition at line 120 of file hc0pm_reeds_shepp_state_space.hpp.
|
private |
Angle between a configuration on the hc-/cc-circle and the tangent to the circle at that position.
Definition at line 132 of file hc0pm_reeds_shepp_state_space.hpp.
|
private |
Outer radius of a hc-/cc-circle.
Definition at line 129 of file hc0pm_reeds_shepp_state_space.hpp.
|
private |
Parameter of a rs-circle.
Definition at line 126 of file hc0pm_reeds_shepp_state_space.hpp.