An implementation of hybrid curvature (HC) steer with either positive (p) or negative (n) max. curvature at the start and goal configuration as described in: H. Banzhaf et al., "Hybrid Curvature Steer: A Novel Extend Function for Sampling-Based Nonholonomic 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 <hcpmpm_reeds_shepp_state_space.hpp>
Classes | |
class | HCpmpm_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 * | hcpmpm_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 * | hcpmpm_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... | |
HCpmpm_Reeds_Shepp_State_Space (double kappa, double sigma, double discretization=0.1) | |
Constructor. More... | |
~HCpmpm_Reeds_Shepp_State_Space () | |
Destructor. More... | |
![]() | |
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 | |
double | cos_mu_ |
std::unique_ptr< HCpmpm_Reeds_Shepp > | hcpmpm_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... | |
double | sin_mu_ |
Sine and cosine of mu. More... | |
Additional Inherited Members | |
![]() | |
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 either positive (p) or negative (n) max. curvature at the start and goal configuration as described in: H. Banzhaf et al., "Hybrid Curvature Steer: A Novel Extend Function for Sampling-Based Nonholonomic 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 hcpmpm_reeds_shepp_state_space.hpp.
steering::HCpmpm_Reeds_Shepp_State_Space::HCpmpm_Reeds_Shepp_State_Space | ( | double | kappa, |
double | sigma, | ||
double | discretization = 0.1 |
||
) |
Constructor.
Definition at line 1555 of file hcpmpm_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 1839 of file hcpmpm_reeds_shepp_state_space.cpp.
double steering::HCpmpm_Reeds_Shepp_State_Space::get_distance | ( | const State & | state1, |
const State & | state2 | ||
) | const |
Returns shortest path length from state1 to state2.
Definition at line 1831 of file hcpmpm_reeds_shepp_state_space.cpp.
HC_CC_RS_Path * steering::HCpmpm_Reeds_Shepp_State_Space::hcpmpm_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 1568 of file hcpmpm_reeds_shepp_state_space.cpp.
HC_CC_RS_Path * steering::HCpmpm_Reeds_Shepp_State_Space::hcpmpm_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 1738 of file hcpmpm_reeds_shepp_state_space.cpp.
|
private |
Definition at line 135 of file hcpmpm_reeds_shepp_state_space.hpp.
|
private |
Pimpl Idiom: unique pointer on class with families
Definition at line 120 of file hcpmpm_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 hcpmpm_reeds_shepp_state_space.hpp.
|
private |
Outer radius of a hc-/cc-circle.
Definition at line 129 of file hcpmpm_reeds_shepp_state_space.hpp.
|
private |
Parameter of a rs-circle.
Definition at line 126 of file hcpmpm_reeds_shepp_state_space.hpp.
|
private |
Sine and cosine of mu.
Definition at line 135 of file hcpmpm_reeds_shepp_state_space.hpp.