|
Apollo
6.0
Open source self driving car software
|
A mrac controller for actuation system (throttle/brake and steering) More...
#include <mrac_controller.h>

Public Member Functions | |
| void | Init (const MracConf &mrac_conf, const common::LatencyParam &latency_param, const double dt) |
| initialize mrac controller More... | |
| common::Status | SetReferenceModel (const MracConf &mrac_conf) |
| common::Status | SetAdaptionModel (const MracConf &mrac_conf) |
| common::Status | BuildReferenceModel () |
| build mrac (1st or 2nd) order reference model in the discrete-time form, with the bilinear transform (trapezoidal integration) method More... | |
| common::Status | BuildAdaptionModel () |
| build mrac (1st or 2nd) order adaptive dynamic model in the discrete-time form More... | |
| bool | CheckLyapunovPD (const Eigen::MatrixXd matrix_a, const Eigen::MatrixXd matrix_p) const |
| check if the solution of the algebraic Lyapunov Equation is symmetric positive definite More... | |
| void | EstimateInitialGains (const common::LatencyParam &latency_param) |
| estimate the initial states of the adaptive gains via known actuation dynamics approximation More... | |
| void | UpdateReference () |
| execute the reference state interation with respect to the designed inputs in discrete-time form, with the bilinear transform (trapezoidal integration) method More... | |
| void | UpdateAdaption (Eigen::MatrixXd *law_adp, const Eigen::MatrixXd state_adp, const Eigen::MatrixXd gain_adp) |
| execute the adaption interation with respect to the designed law in discrete-time form, with the bilinear transform (trapezoidal integration) method More... | |
| void | AntiWindupCompensation (const double control_command, const double previous_command) |
| calculate the anti-windup compensation with respect to the integral windup issue More... | |
| void | Reset () |
| reset all the variables (including all the states, gains and externally-setting control parameters) for mrac controller More... | |
| void | ResetStates () |
| reset internal states for mrac controller More... | |
| void | ResetGains () |
| reset adaptive gains for mrac controller More... | |
| virtual double | Control (const double command, const Eigen::MatrixXd state, const double input_limit, const double input_rate_limit) |
| compute control value based on the original command More... | |
| int | BoundOutput (const double output_unbounded, const double previous_output, double *output_bounded) |
| bound the system output with the given bound and change-rate bound More... | |
| void | SetInitialReferenceState (const Eigen::MatrixXd &state_reference_init) |
| set initial values for state components in reference model dynamics More... | |
| void | SetInitialActionState (const Eigen::MatrixXd &state_action_init) |
| set initial values for state components in actual actuator dynamics More... | |
| void | SetInitialCommand (const double command_init) |
| set initial command (desired input) More... | |
| void | SetInitialStateAdaptionGain (const Eigen::MatrixXd &gain_state_adaption_init) |
| set initial values of state adaption gains for mrac control More... | |
| void | SetInitialInputAdaptionGain (const double gain_input_adaption_init) |
| set initial value of input adaption gain for mrac control More... | |
| void | SetInitialNonlinearAdaptionGain (const double gain_nonlinear_adaption_init) |
| set initial value of nonlinear adaption gain for mrac control More... | |
| void | SetStateAdaptionRate (const double ratio_state) |
| set convergence ratio for state components in adaptive dynamics More... | |
| void | SetInputAdaptionRate (const double ratio_input) |
| set convergence ratio for input components in adaptive dynamics More... | |
| void | SetNonlinearAdaptionRate (const double ratio_nonlinear) |
| set convergence ratio for nonlinear components in adaptive dynamics More... | |
| double | StateAdaptionRate () const |
| get convergence ratio for state components in adaptive dynamics More... | |
| double | InputAdaptionRate () const |
| get convergence ratio for input components in adaptive dynamics More... | |
| double | NonlinearAdaptionRate () const |
| get convergence ratio for nonlinear components in adaptive dynamics More... | |
| int | ReferenceSaturationStatus () const |
| get saturation status for reference system More... | |
| int | ControlSaturationStatus () const |
| get saturation status for control system More... | |
| Eigen::MatrixXd | CurrentReferenceState () const |
| get current state for reference system More... | |
| Eigen::MatrixXd | CurrentStateAdaptionGain () const |
| get current state adaptive gain for mrac control More... | |
| Eigen::MatrixXd | CurrentInputAdaptionGain () const |
| get current input adaptive gain for mrac control More... | |
| Eigen::MatrixXd | CurrentNonlinearAdaptionGain () const |
| get current nonlinear adaptive gain for mrac control More... | |
A mrac controller for actuation system (throttle/brake and steering)
| void apollo::control::MracController::AntiWindupCompensation | ( | const double | control_command, |
| const double | previous_command | ||
| ) |
calculate the anti-windup compensation with respect to the integral windup issue
| control_command | desired control command for the actuator |
| previous_command | last control command for the actuator |
| dt | control sampling time |
| int apollo::control::MracController::BoundOutput | ( | const double | output_unbounded, |
| const double | previous_output, | ||
| double * | output_bounded | ||
| ) |
bound the system output with the given bound and change-rate bound
| output_unbounded | original system output without bound |
| previous_output | system output in the last step |
| dt | sampling time interval |
| output_bounded | bounded system output |
| common::Status apollo::control::MracController::BuildAdaptionModel | ( | ) |
build mrac (1st or 2nd) order adaptive dynamic model in the discrete-time form
| common::Status apollo::control::MracController::BuildReferenceModel | ( | ) |
build mrac (1st or 2nd) order reference model in the discrete-time form, with the bilinear transform (trapezoidal integration) method
| bool apollo::control::MracController::CheckLyapunovPD | ( | const Eigen::MatrixXd | matrix_a, |
| const Eigen::MatrixXd | matrix_p | ||
| ) | const |
check if the solution of the algebraic Lyapunov Equation is symmetric positive definite
| matrix_a | reference model matrix |
| matrix_p | Lyapunov function matrix |
|
virtual |
compute control value based on the original command
| command | original command as the input of the actuation system |
| state | actual output state of the actuation system |
| dt | sampling time interval |
| input_limit | physical or designed bound of the input |
| input_rate_limit | physical or designed bound of the input changing-rate |
| int apollo::control::MracController::ControlSaturationStatus | ( | ) | const |
get saturation status for control system
| Eigen::MatrixXd apollo::control::MracController::CurrentInputAdaptionGain | ( | ) | const |
get current input adaptive gain for mrac control
| Eigen::MatrixXd apollo::control::MracController::CurrentNonlinearAdaptionGain | ( | ) | const |
get current nonlinear adaptive gain for mrac control
| Eigen::MatrixXd apollo::control::MracController::CurrentReferenceState | ( | ) | const |
get current state for reference system
| Eigen::MatrixXd apollo::control::MracController::CurrentStateAdaptionGain | ( | ) | const |
get current state adaptive gain for mrac control
| void apollo::control::MracController::EstimateInitialGains | ( | const common::LatencyParam & | latency_param | ) |
estimate the initial states of the adaptive gains via known actuation dynamics approximation
| latency_param | configuration for actuation latency parameters |
| void apollo::control::MracController::Init | ( | const MracConf & | mrac_conf, |
| const common::LatencyParam & | latency_param, | ||
| const double | dt | ||
| ) |
initialize mrac controller
| mrac_conf | configuration for mrac controller |
| latency_param | configuration for latency parameter |
| dt | sampling time interval |
| double apollo::control::MracController::InputAdaptionRate | ( | ) | const |
get convergence ratio for input components in adaptive dynamics
| double apollo::control::MracController::NonlinearAdaptionRate | ( | ) | const |
get convergence ratio for nonlinear components in adaptive dynamics
| int apollo::control::MracController::ReferenceSaturationStatus | ( | ) | const |
get saturation status for reference system
| void apollo::control::MracController::Reset | ( | ) |
reset all the variables (including all the states, gains and externally-setting control parameters) for mrac controller
| void apollo::control::MracController::ResetGains | ( | ) |
reset adaptive gains for mrac controller
| void apollo::control::MracController::ResetStates | ( | ) |
reset internal states for mrac controller
| common::Status apollo::control::MracController::SetAdaptionModel | ( | const MracConf & | mrac_conf | ) |
state adaptive gain, desired adaptive gain and nonlinear-component adaptive gain
| mrac_conf | configuration for adaption model |
| void apollo::control::MracController::SetInitialActionState | ( | const Eigen::MatrixXd & | state_action_init | ) |
set initial values for state components in actual actuator dynamics
| state_reference_init | initial action states |
| void apollo::control::MracController::SetInitialCommand | ( | const double | command_init | ) |
set initial command (desired input)
| command_init | initial desired input |
| void apollo::control::MracController::SetInitialInputAdaptionGain | ( | const double | gain_input_adaption_init | ) |
set initial value of input adaption gain for mrac control
| gain_input_adaption_init | initial input adaption gain |
| void apollo::control::MracController::SetInitialNonlinearAdaptionGain | ( | const double | gain_nonlinear_adaption_init | ) |
set initial value of nonlinear adaption gain for mrac control
| gain_nonlinear_adaption_init | initial nonlinear adaption gain |
| void apollo::control::MracController::SetInitialReferenceState | ( | const Eigen::MatrixXd & | state_reference_init | ) |
set initial values for state components in reference model dynamics
| state_reference_init | initial reference states |
| void apollo::control::MracController::SetInitialStateAdaptionGain | ( | const Eigen::MatrixXd & | gain_state_adaption_init | ) |
set initial values of state adaption gains for mrac control
| gain_state_adaption_init | initial state adaption gains |
| void apollo::control::MracController::SetInputAdaptionRate | ( | const double | ratio_input | ) |
set convergence ratio for input components in adaptive dynamics
| ratio_input | convergence ratio for input adaption |
| void apollo::control::MracController::SetNonlinearAdaptionRate | ( | const double | ratio_nonlinear | ) |
set convergence ratio for nonlinear components in adaptive dynamics
| ratio_nonlinear | convergence ratio for additional nonlinear adaption |
| common::Status apollo::control::MracController::SetReferenceModel | ( | const MracConf & | mrac_conf | ) |
time constant, natural frequency and damping ratio
| mrac_conf | configuration for reference model |
| void apollo::control::MracController::SetStateAdaptionRate | ( | const double | ratio_state | ) |
set convergence ratio for state components in adaptive dynamics
| ratio_state | convergence ratio for state adaption |
| double apollo::control::MracController::StateAdaptionRate | ( | ) | const |
get convergence ratio for state components in adaptive dynamics
| void apollo::control::MracController::UpdateAdaption | ( | Eigen::MatrixXd * | law_adp, |
| const Eigen::MatrixXd | state_adp, | ||
| const Eigen::MatrixXd | gain_adp | ||
| ) |
execute the adaption interation with respect to the designed law in discrete-time form, with the bilinear transform (trapezoidal integration) method
| law_adp | adaptive law at k and k-1 steps |
| state_adp | state used in the adaptive law at k and k-1 steps |
| gain_adp | adaptive gain for the given adaptive law |
| void apollo::control::MracController::UpdateReference | ( | ) |
execute the reference state interation with respect to the designed inputs in discrete-time form, with the bilinear transform (trapezoidal integration) method
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
1.8.13