Public Member Functions | Private Attributes | List of all members
steering::CC_Dubins_State_Space Class Reference

An implementation of continuous curvature (CC) steer for a Dubins car with arbitrary curvature at the start and goal configuration. More...

#include <cc_dubins_state_space.hpp>

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

Public Member Functions

 CC_Dubins_State_Space (double kappa, double sigma, double discretization=0.1, bool forwards=true)
 Constructor. More...
 
std::vector< Controlget_controls (const State &state1, const State &state2) const
 Returns controls of the shortest path from state1 to state2. More...
 
double get_distance (const State &state1, const State &state2) const
 Returns shortest path length from state1 to state2. More...
 
std::vector< std::pair< State, Control > > predict_state (const State &state, bool forwards) const
 Predicts a state forwards or backwards to zero and max. curvature. More...
 
- Public Member Functions inherited from steering::HC_CC_State_Space
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...
 

Private Attributes

CC00_Dubins_State_Space cc00_dubins_state_space_
 Required state spaces. More...
 
CC0pm_Dubins_State_Space cc0pm_dubins_state_space_
 
CCpm0_Dubins_State_Space ccpm0_dubins_state_space_
 
CCpmpm_Dubins_State_Space ccpmpm_dubins_state_space_
 
bool forwards_
 Driving direction. More...
 

Additional Inherited Members

- Protected Attributes inherited from steering::HC_CC_State_Space
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

An implementation of continuous curvature (CC) steer for a Dubins car with arbitrary curvature at the start and goal configuration.

Definition at line 54 of file cc_dubins_state_space.hpp.

Constructor & Destructor Documentation

◆ CC_Dubins_State_Space()

steering::CC_Dubins_State_Space::CC_Dubins_State_Space ( double  kappa,
double  sigma,
double  discretization = 0.1,
bool  forwards = true 
)

Constructor.

Definition at line 29 of file cc_dubins_state_space.cpp.

Member Function Documentation

◆ get_controls()

vector< Control > steering::CC_Dubins_State_Space::get_controls ( const State state1,
const State state2 
) const
virtual

Returns controls of the shortest path from state1 to state2.

Implements steering::HC_CC_State_Space.

Definition at line 149 of file cc_dubins_state_space.cpp.

◆ get_distance()

double steering::CC_Dubins_State_Space::get_distance ( const State state1,
const State state2 
) const

Returns shortest path length from state1 to state2.

Definition at line 97 of file cc_dubins_state_space.cpp.

◆ predict_state()

vector< pair< State, Control > > steering::CC_Dubins_State_Space::predict_state ( const State state,
bool  forwards 
) const

Predicts a state forwards or backwards to zero and max. curvature.

Definition at line 39 of file cc_dubins_state_space.cpp.

Member Data Documentation

◆ cc00_dubins_state_space_

CC00_Dubins_State_Space steering::CC_Dubins_State_Space::cc00_dubins_state_space_
private

Required state spaces.

Definition at line 89 of file cc_dubins_state_space.hpp.

◆ cc0pm_dubins_state_space_

CC0pm_Dubins_State_Space steering::CC_Dubins_State_Space::cc0pm_dubins_state_space_
private

Definition at line 90 of file cc_dubins_state_space.hpp.

◆ ccpm0_dubins_state_space_

CCpm0_Dubins_State_Space steering::CC_Dubins_State_Space::ccpm0_dubins_state_space_
private

Definition at line 91 of file cc_dubins_state_space.hpp.

◆ ccpmpm_dubins_state_space_

CCpmpm_Dubins_State_Space steering::CC_Dubins_State_Space::ccpmpm_dubins_state_space_
private

Definition at line 92 of file cc_dubins_state_space.hpp.

◆ forwards_

bool steering::CC_Dubins_State_Space::forwards_
private

Driving direction.

Definition at line 86 of file cc_dubins_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