Public Member Functions | Protected Attributes | List of all members
steering::HC_CC_State_Space Class Referenceabstract

#include <hc_cc_state_space.hpp>

Inheritance diagram for steering::HC_CC_State_Space:
Inheritance graph
[legend]

Public Member Functions

virtual std::vector< Controlget_controls (const State &state1, const State &state2) const =0
 Virtual function that returns controls of the shortest path from state1 to state2. More...
 
std::vector< Stateget_path (const State &state1, const State &state2) const
 Returns path from state1 to state2. More...
 
std::vector< State_With_Covarianceget_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< Stateintegrate (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_Covarianceintegrate_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...
 

Protected Attributes

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_
 

Detailed Description

Definition at line 45 of file hc_cc_state_space.hpp.

Constructor & Destructor Documentation

◆ HC_CC_State_Space()

steering::HC_CC_State_Space::HC_CC_State_Space ( double  kappa,
double  sigma,
double  discretization 
)

Constructor.

Definition at line 28 of file hc_cc_state_space.cpp.

Member Function Documentation

◆ get_controls()

virtual std::vector<Control> steering::HC_CC_State_Space::get_controls ( const State state1,
const State state2 
) const
pure virtual

◆ get_path()

vector< State > steering::HC_CC_State_Space::get_path ( const State state1,
const State state2 
) const

Returns path from state1 to state2.

Definition at line 68 of file hc_cc_state_space.cpp.

◆ get_path_with_covariance()

vector< State_With_Covariance > steering::HC_CC_State_Space::get_path_with_covariance ( const State_With_Covariance state1,
const State state2 
) const

Returns path including covariances from state1 to state2.

Definition at line 74 of file hc_cc_state_space.cpp.

◆ integrate()

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

Returns integrated states given a start state and controls.

Definition at line 81 of file hc_cc_state_space.cpp.

◆ integrate_ODE()

State steering::HC_CC_State_Space::integrate_ODE ( const State state,
const Control control,
double  integration_step 
) const
inline

Returns integrated state given a start state, a control, and an integration step.

Definition at line 281 of file hc_cc_state_space.cpp.

◆ integrate_with_covariance()

vector< State_With_Covariance > steering::HC_CC_State_Space::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.

Definition at line 137 of file hc_cc_state_space.cpp.

◆ interpolate()

State steering::HC_CC_State_Space::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)

Definition at line 212 of file hc_cc_state_space.cpp.

◆ set_filter_parameters()

void steering::HC_CC_State_Space::set_filter_parameters ( const Motion_Noise motion_noise,
const Measurement_Noise measurement_noise,
const Controller controller 
)

Sets the parameters required by the filter.

Definition at line 62 of file hc_cc_state_space.cpp.

Member Data Documentation

◆ discretization_

double steering::HC_CC_State_Space::discretization_
protected

Discretization of path.

Definition at line 98 of file hc_cc_state_space.hpp.

◆ ekf_

EKF steering::HC_CC_State_Space::ekf_
protected

Extended Kalman Filter for uncertainty propagation.

Definition at line 104 of file hc_cc_state_space.hpp.

◆ hc_cc_circle_param_

HC_CC_Circle_Param steering::HC_CC_State_Space::hc_cc_circle_param_
protected

Parameters of a hc-/cc-circle.

Definition at line 101 of file hc_cc_state_space.hpp.

◆ kappa_

double steering::HC_CC_State_Space::kappa_
protected

Curvature, sharpness of clothoid.

Definition at line 95 of file hc_cc_state_space.hpp.

◆ sigma_

double steering::HC_CC_State_Space::sigma_
protected

Definition at line 95 of file hc_cc_state_space.hpp.


The documentation for this class was generated from the following files:


steering_functions
Author(s): Holger Banzhaf
autogenerated on Mon Dec 11 2023 03:27:44