18 #ifndef HC_CC_STATE_SPACE_HPP 19 #define HC_CC_STATE_SPACE_HPP 48 const State& state2)
const;
51 std::vector<State>
integrate(
const State& state,
const std::vector<Control>& controls)
const;
55 const std::vector<Control>& controls)
const;
double kappa_
Curvature, sharpness of clothoid.
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.
HC_CC_Circle_Param hc_cc_circle_param_
Parameters of a hc-/cc-circle.
HC_CC_State_Space(double kappa, double sigma, double discretization)
Constructor.
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) ...
geometry_msgs::TransformStamped t
EKF ekf_
Extended Kalman Filter for uncertainty propagation.
Parameters of the motion noise model according to the book: Probabilistic Robotics, S. Thrun and others, MIT Press, 2006, p. 127-128 and p.204-206.
Description of a path segment with its corresponding control inputs.
std::vector< State > integrate(const State &state, const std::vector< Control > &controls) const
Returns integrated states given a start state and controls.
Description of a kinematic car's state with covariance.
Parameters of the measurement noise.
Parameters of the feedback controller.
Description of a kinematic car's state.
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.
void set_filter_parameters(const Motion_Noise &motion_noise, const Measurement_Noise &measurement_noise, const Controller &controller)
Sets the parameters required by the filter.
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.
double discretization_
Discretization of path.
std::vector< State > get_path(const State &state1, const State &state2) const
Returns path from state1 to state2.
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. ...