Class Reeds_Shepp_State_Space
Defined in File reeds_shepp_state_space.hpp
Nested Relationships
Nested Types
Class Documentation
-
class Reeds_Shepp_State_Space
An SE(2) state space where distance is measured by the length of Reeds-Shepp curves. The notation and solutions are taken from: J.A. Reeds and L.A. Shepp, “Optimal paths for a car that goes both forwards and backwards,” Pacific Journal of Mathematics, 145(2):367–393, 1990. This implementation explicitly computes all 48 Reeds-Shepp curves and returns the shortest valid solution. This can be improved by using the configuration space partition described in: P. Souères and J.-P. Laumond, “Shortest paths synthesis for a car-like robot,” IEEE Trans. on Automatic Control, 41(5):672–688, May 1996.
Public Types
Public Functions
-
inline Reeds_Shepp_State_Space(double kappa, double discretization = 0.1)
Constructor of the Reeds_Shepp_State_Space.
-
void set_filter_parameters(const Motion_Noise &motion_noise, const Measurement_Noise &measurement_noise, const Controller &controller)
Sets the parameters required by the filter.
-
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.0.
-
double get_distance(const State &state1, const State &state2) const
Returns shortest path length from state1 to state2 with curvature = kappa_.
-
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_.
-
std::vector<State> get_path(const State &state1, const State &state2) const
Returns shortest path from state1 to state2 with curvature = kappa_.
-
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_.
-
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_.
-
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 = kappa_.
Public Static Attributes
-
static const Reeds_Shepp_Path_Segment_Type reeds_shepp_path_type[18][5]
Reeds-Shepp path types.
-
class Reeds_Shepp_Path
Complete description of a ReedsShepp path.
Public Functions
-
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.
-
inline double length() const
-
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.)
-
inline Reeds_Shepp_State_Space(double kappa, double discretization = 0.1)