Class HC_CC_State_Space

Inheritance Relationships

Derived Types

Class Documentation

class HC_CC_State_Space

Subclassed by steering::CC00_Dubins_State_Space, steering::CC00_Reeds_Shepp_State_Space, steering::CC0pm_Dubins_State_Space, steering::CC_Dubins_State_Space, steering::CCpm0_Dubins_State_Space, steering::CCpmpm_Dubins_State_Space, steering::HC00_Reeds_Shepp_State_Space, steering::HC0pm_Reeds_Shepp_State_Space, steering::HC_Reeds_Shepp_State_Space, steering::HCpm0_Reeds_Shepp_State_Space, steering::HCpmpm_Reeds_Shepp_State_Space

Public Functions

HC_CC_State_Space(double kappa, double sigma, double discretization)

Constructor.

void set_filter_parameters(const Motion_Noise &motion_noise, const Measurement_Noise &measurement_noise, const Controller &controller)

Sets the parameters required by the filter.

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

Virtual function that returns controls of the shortest path from state1 to state2.

std::vector<State> get_path(const State &state1, const State &state2) const

Returns path from state1 to state2.

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.

std::vector<State> integrate(const State &state, const std::vector<Control> &controls) const

Returns integrated states given a start state and controls.

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.

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)

inline 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.

Protected Attributes

double kappa_

Curvature, sharpness of clothoid.

double sigma_
double discretization_

Discretization of path.

HC_CC_Circle_Param hc_cc_circle_param_

Parameters of a hc-/cc-circle.

EKF ekf_

Extended Kalman Filter for uncertainty propagation.