Apollo  6.0
Open source self driving car software
Public Member Functions | Protected Attributes | List of all members
apollo::control::MracController Class Reference

A mrac controller for actuation system (throttle/brake and steering) More...

#include <mrac_controller.h>

Collaboration diagram for apollo::control::MracController:
Collaboration graph

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

Protected Attributes

bool reference_model_enabled_ = false
 
bool adaption_model_enabled_ = false
 
bool adaption_clamping_enabled = false
 
int model_order_ = 1
 
double tau_reference_ = 0.0
 
double tau_clamping_ = 0.0
 
double wn_reference_ = 0.0
 
double zeta_reference_ = 0.0
 
double ts_ = 0.01
 
Eigen::MatrixXd gamma_state_adaption_
 
Eigen::MatrixXd gamma_input_adaption_
 
Eigen::MatrixXd gamma_nonlinear_adaption_
 
double gamma_ratio_state_ = 1.0
 
double gamma_ratio_input_ = 1.0
 
double gamma_ratio_nonlinear_ = 1.0
 
Eigen::MatrixXd matrix_a_reference_
 
Eigen::MatrixXd matrix_b_reference_
 
Eigen::MatrixXd matrix_p_adaption_
 
Eigen::MatrixXd matrix_b_adaption_
 
Eigen::MatrixXd input_desired_
 
Eigen::MatrixXd state_action_
 
Eigen::MatrixXd state_reference_
 
Eigen::MatrixXd gain_state_adaption_
 
Eigen::MatrixXd gain_input_adaption_
 
Eigen::MatrixXd gain_nonlinear_adaption_
 
Eigen::MatrixXd gain_state_clamping_
 
Eigen::MatrixXd gain_input_clamping_
 
Eigen::MatrixXd gain_nonlinear_clamping_
 
Eigen::MatrixXd gain_state_adaption_init_
 
Eigen::MatrixXd gain_input_adaption_init_
 
Eigen::MatrixXd gain_nonlinear_adaption_init_
 
double control_previous_ = 0.0
 
double bound_ratio_ = 0.0
 
double bound_command_ = 0.0
 
double bound_command_rate_ = 0.0
 
int saturation_status_reference_ = 0
 
int saturation_status_control_ = 0
 
Eigen::MatrixXd gain_anti_windup_
 
Eigen::MatrixXd compensation_anti_windup_
 

Detailed Description

A mrac controller for actuation system (throttle/brake and steering)

Member Function Documentation

◆ AntiWindupCompensation()

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

Parameters
control_commanddesired control command for the actuator
previous_commandlast control command for the actuator
dtcontrol sampling time

◆ BoundOutput()

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

Parameters
output_unboundedoriginal system output without bound
previous_outputsystem output in the last step
dtsampling time interval
output_boundedbounded system output
Returns
saturation_status system saturation status indicator

◆ BuildAdaptionModel()

common::Status apollo::control::MracController::BuildAdaptionModel ( )

build mrac (1st or 2nd) order adaptive dynamic model in the discrete-time form

Returns
Status adaption model initialization status

◆ BuildReferenceModel()

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

Returns
Status reference model initialization status

◆ CheckLyapunovPD()

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

Parameters
matrix_areference model matrix
matrix_pLyapunov function matrix
Returns
indicator of the symmetric positive definite matrix

◆ Control()

virtual double apollo::control::MracController::Control ( const double  command,
const Eigen::MatrixXd  state,
const double  input_limit,
const double  input_rate_limit 
)
virtual

compute control value based on the original command

Parameters
commandoriginal command as the input of the actuation system
stateactual output state of the actuation system
dtsampling time interval
input_limitphysical or designed bound of the input
input_rate_limitphysical or designed bound of the input changing-rate
Returns
control value based on mrac controller architecture

◆ ControlSaturationStatus()

int apollo::control::MracController::ControlSaturationStatus ( ) const

get saturation status for control system

Returns
saturation status

◆ CurrentInputAdaptionGain()

Eigen::MatrixXd apollo::control::MracController::CurrentInputAdaptionGain ( ) const

get current input adaptive gain for mrac control

Returns
current input adaptive gain

◆ CurrentNonlinearAdaptionGain()

Eigen::MatrixXd apollo::control::MracController::CurrentNonlinearAdaptionGain ( ) const

get current nonlinear adaptive gain for mrac control

Returns
current nonlinear adaptive gain

◆ CurrentReferenceState()

Eigen::MatrixXd apollo::control::MracController::CurrentReferenceState ( ) const

get current state for reference system

Returns
current state

◆ CurrentStateAdaptionGain()

Eigen::MatrixXd apollo::control::MracController::CurrentStateAdaptionGain ( ) const

get current state adaptive gain for mrac control

Returns
current state adaptive gain

◆ EstimateInitialGains()

void apollo::control::MracController::EstimateInitialGains ( const common::LatencyParam &  latency_param)

estimate the initial states of the adaptive gains via known actuation dynamics approximation

Parameters
latency_paramconfiguration for actuation latency parameters

◆ Init()

void apollo::control::MracController::Init ( const MracConf &  mrac_conf,
const common::LatencyParam &  latency_param,
const double  dt 
)

initialize mrac controller

Parameters
mrac_confconfiguration for mrac controller
latency_paramconfiguration for latency parameter
dtsampling time interval

◆ InputAdaptionRate()

double apollo::control::MracController::InputAdaptionRate ( ) const

get convergence ratio for input components in adaptive dynamics

Returns
input adaption ratio

◆ NonlinearAdaptionRate()

double apollo::control::MracController::NonlinearAdaptionRate ( ) const

get convergence ratio for nonlinear components in adaptive dynamics

Returns
nonlinear adaption ratio

◆ ReferenceSaturationStatus()

int apollo::control::MracController::ReferenceSaturationStatus ( ) const

get saturation status for reference system

Returns
saturation status

◆ Reset()

void apollo::control::MracController::Reset ( )

reset all the variables (including all the states, gains and externally-setting control parameters) for mrac controller

◆ ResetGains()

void apollo::control::MracController::ResetGains ( )

reset adaptive gains for mrac controller

◆ ResetStates()

void apollo::control::MracController::ResetStates ( )

reset internal states for mrac controller

◆ SetAdaptionModel()

common::Status apollo::control::MracController::SetAdaptionModel ( const MracConf &  mrac_conf)

state adaptive gain, desired adaptive gain and nonlinear-component adaptive gain

Parameters
mrac_confconfiguration for adaption model
Returns
Status parameter initialization status

◆ SetInitialActionState()

void apollo::control::MracController::SetInitialActionState ( const Eigen::MatrixXd &  state_action_init)

set initial values for state components in actual actuator dynamics

Parameters
state_reference_initinitial action states

◆ SetInitialCommand()

void apollo::control::MracController::SetInitialCommand ( const double  command_init)

set initial command (desired input)

Parameters
command_initinitial desired input

◆ SetInitialInputAdaptionGain()

void apollo::control::MracController::SetInitialInputAdaptionGain ( const double  gain_input_adaption_init)

set initial value of input adaption gain for mrac control

Parameters
gain_input_adaption_initinitial input adaption gain

◆ SetInitialNonlinearAdaptionGain()

void apollo::control::MracController::SetInitialNonlinearAdaptionGain ( const double  gain_nonlinear_adaption_init)

set initial value of nonlinear adaption gain for mrac control

Parameters
gain_nonlinear_adaption_initinitial nonlinear adaption gain

◆ SetInitialReferenceState()

void apollo::control::MracController::SetInitialReferenceState ( const Eigen::MatrixXd &  state_reference_init)

set initial values for state components in reference model dynamics

Parameters
state_reference_initinitial reference states

◆ SetInitialStateAdaptionGain()

void apollo::control::MracController::SetInitialStateAdaptionGain ( const Eigen::MatrixXd &  gain_state_adaption_init)

set initial values of state adaption gains for mrac control

Parameters
gain_state_adaption_initinitial state adaption gains

◆ SetInputAdaptionRate()

void apollo::control::MracController::SetInputAdaptionRate ( const double  ratio_input)

set convergence ratio for input components in adaptive dynamics

Parameters
ratio_inputconvergence ratio for input adaption

◆ SetNonlinearAdaptionRate()

void apollo::control::MracController::SetNonlinearAdaptionRate ( const double  ratio_nonlinear)

set convergence ratio for nonlinear components in adaptive dynamics

Parameters
ratio_nonlinearconvergence ratio for additional nonlinear adaption

◆ SetReferenceModel()

common::Status apollo::control::MracController::SetReferenceModel ( const MracConf &  mrac_conf)

time constant, natural frequency and damping ratio

Parameters
mrac_confconfiguration for reference model
Returns
Status parameter initialization status

◆ SetStateAdaptionRate()

void apollo::control::MracController::SetStateAdaptionRate ( const double  ratio_state)

set convergence ratio for state components in adaptive dynamics

Parameters
ratio_stateconvergence ratio for state adaption

◆ StateAdaptionRate()

double apollo::control::MracController::StateAdaptionRate ( ) const

get convergence ratio for state components in adaptive dynamics

Returns
state adaption ratio

◆ UpdateAdaption()

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

Parameters
law_adpadaptive law at k and k-1 steps
state_adpstate used in the adaptive law at k and k-1 steps
gain_adpadaptive gain for the given adaptive law

◆ UpdateReference()

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

Member Data Documentation

◆ adaption_clamping_enabled

bool apollo::control::MracController::adaption_clamping_enabled = false
protected

◆ adaption_model_enabled_

bool apollo::control::MracController::adaption_model_enabled_ = false
protected

◆ bound_command_

double apollo::control::MracController::bound_command_ = 0.0
protected

◆ bound_command_rate_

double apollo::control::MracController::bound_command_rate_ = 0.0
protected

◆ bound_ratio_

double apollo::control::MracController::bound_ratio_ = 0.0
protected

◆ compensation_anti_windup_

Eigen::MatrixXd apollo::control::MracController::compensation_anti_windup_
protected

◆ control_previous_

double apollo::control::MracController::control_previous_ = 0.0
protected

◆ gain_anti_windup_

Eigen::MatrixXd apollo::control::MracController::gain_anti_windup_
protected

◆ gain_input_adaption_

Eigen::MatrixXd apollo::control::MracController::gain_input_adaption_
protected

◆ gain_input_adaption_init_

Eigen::MatrixXd apollo::control::MracController::gain_input_adaption_init_
protected

◆ gain_input_clamping_

Eigen::MatrixXd apollo::control::MracController::gain_input_clamping_
protected

◆ gain_nonlinear_adaption_

Eigen::MatrixXd apollo::control::MracController::gain_nonlinear_adaption_
protected

◆ gain_nonlinear_adaption_init_

Eigen::MatrixXd apollo::control::MracController::gain_nonlinear_adaption_init_
protected

◆ gain_nonlinear_clamping_

Eigen::MatrixXd apollo::control::MracController::gain_nonlinear_clamping_
protected

◆ gain_state_adaption_

Eigen::MatrixXd apollo::control::MracController::gain_state_adaption_
protected

◆ gain_state_adaption_init_

Eigen::MatrixXd apollo::control::MracController::gain_state_adaption_init_
protected

◆ gain_state_clamping_

Eigen::MatrixXd apollo::control::MracController::gain_state_clamping_
protected

◆ gamma_input_adaption_

Eigen::MatrixXd apollo::control::MracController::gamma_input_adaption_
protected

◆ gamma_nonlinear_adaption_

Eigen::MatrixXd apollo::control::MracController::gamma_nonlinear_adaption_
protected

◆ gamma_ratio_input_

double apollo::control::MracController::gamma_ratio_input_ = 1.0
protected

◆ gamma_ratio_nonlinear_

double apollo::control::MracController::gamma_ratio_nonlinear_ = 1.0
protected

◆ gamma_ratio_state_

double apollo::control::MracController::gamma_ratio_state_ = 1.0
protected

◆ gamma_state_adaption_

Eigen::MatrixXd apollo::control::MracController::gamma_state_adaption_
protected

◆ input_desired_

Eigen::MatrixXd apollo::control::MracController::input_desired_
protected

◆ matrix_a_reference_

Eigen::MatrixXd apollo::control::MracController::matrix_a_reference_
protected

◆ matrix_b_adaption_

Eigen::MatrixXd apollo::control::MracController::matrix_b_adaption_
protected

◆ matrix_b_reference_

Eigen::MatrixXd apollo::control::MracController::matrix_b_reference_
protected

◆ matrix_p_adaption_

Eigen::MatrixXd apollo::control::MracController::matrix_p_adaption_
protected

◆ model_order_

int apollo::control::MracController::model_order_ = 1
protected

◆ reference_model_enabled_

bool apollo::control::MracController::reference_model_enabled_ = false
protected

◆ saturation_status_control_

int apollo::control::MracController::saturation_status_control_ = 0
protected

◆ saturation_status_reference_

int apollo::control::MracController::saturation_status_reference_ = 0
protected

◆ state_action_

Eigen::MatrixXd apollo::control::MracController::state_action_
protected

◆ state_reference_

Eigen::MatrixXd apollo::control::MracController::state_reference_
protected

◆ tau_clamping_

double apollo::control::MracController::tau_clamping_ = 0.0
protected

◆ tau_reference_

double apollo::control::MracController::tau_reference_ = 0.0
protected

◆ ts_

double apollo::control::MracController::ts_ = 0.01
protected

◆ wn_reference_

double apollo::control::MracController::wn_reference_ = 0.0
protected

◆ zeta_reference_

double apollo::control::MracController::zeta_reference_ = 0.0
protected

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