Go to the documentation of this file.
60 #ifndef __REEDS_SHEPP_STATE_SPACE_HPP_
61 #define __REEDS_SHEPP_STATE_SPACE_HPP_
86 class Reeds_Shepp_State_Space
102 class Reeds_Shepp_Path
107 double t = std::numeric_limits<double>::max(),
double u = 0.,
double v = 0.,
double w = 0.,
131 assert(
kappa > 0.0 && discretization > 0.0);
136 void set_filter_parameters(
const Motion_Noise &motion_noise,
const Measurement_Noise &measurement_noise,
137 const Controller &controller);
140 Reeds_Shepp_Path
reeds_shepp(
const State &state1,
const State &state2)
const;
153 const State &state2)
const;
156 std::vector<State>
integrate(
const State &state,
const std::vector<Control> &controls)
const;
160 const std::vector<Control> &controls)
const;
double kappa_inv_
Inverse of curvature.
void set_filter_parameters(const Motion_Noise &motion_noise, const Measurement_Noise &measurement_noise, const Controller &controller)
Sets the parameters required by the filter.
Description of a kinematic car's state.
double discretization_
Discretization of path.
EKF ekf_
Extended Kalman Filter for uncertainty propagation.
std::vector< State_With_Covariance > get_path_with_covariance(const State_With_Covariance &state1, const State &state2) const
Returns shortest path including covariances from state1 to state2 with curvature = kappa_.
Reeds_Shepp_Path_Segment_Type
The Reeds-Shepp path segment types.
static const Reeds_Shepp_Path_Segment_Type reeds_shepp_path_type[18][5]
Reeds-Shepp path types.
const Reeds_Shepp_Path_Segment_Type * type_
Description of a path segment with its corresponding control inputs.
std::vector< State > get_path(const State &state1, const State &state2) const
Returns shortest path from state1 to state2 with curvature = kappa_.
State interpolate(const State &state, const std::vector< Control > &controls, double t) const
Returns interpolated state at distance t in [0,1] (percent of total path length with curvature = kapp...
Reeds_Shepp_Path(const Reeds_Shepp_Path_Segment_Type *type=reeds_shepp_path_type[0], double t=std::numeric_limits< double >::max(), double u=0., double v=0., double w=0., double x=0.)
Constructor of the Reeds_Shepp_Path.
std::vector< Control > get_controls(const State &state1, const State &state2) const
Returns controls of the shortest path from state1 to state2 with curvature = kappa_.
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.
Reeds_Shepp_State_Space(double kappa, double discretization=0.1)
Constructor of the Reeds_Shepp_State_Space.
Description of a kinematic car's state with covariance.
friend class Reeds_Shepp_State_Space
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 with curvature = kapp...
Reeds_Shepp_Path reeds_shepp(const State &state1, const State &state2) const
Returns type and length of segments of path from state1 to state2 with curvature = 1....
double get_distance(const State &state1, const State &state2) const
Returns shortest path length from state1 to state2 with curvature = kappa_.
std::vector< State > integrate(const State &state, const std::vector< Control > &controls) const
Returns integrated states given a start state and controls with curvature = kappa_.