mirror of https://github.com/ArduPilot/ardupilot
APM_Control: added access to time constant
This commit is contained in:
parent
1f7b4dcef6
commit
f6069c35f4
|
@ -44,6 +44,7 @@ public:
|
|||
AP_Float &kI(void) { return rate_pid.kI(); }
|
||||
AP_Float &kD(void) { return rate_pid.kD(); }
|
||||
AP_Float &kFF(void) { return rate_pid.ff(); }
|
||||
AP_Float &tau(void) { return gains.tau; }
|
||||
|
||||
void convert_pid();
|
||||
|
||||
|
|
|
@ -51,6 +51,7 @@ public:
|
|||
AP_Float &kI(void) { return rate_pid.kI(); }
|
||||
AP_Float &kD(void) { return rate_pid.kD(); }
|
||||
AP_Float &kFF(void) { return rate_pid.ff(); }
|
||||
AP_Float &tau(void) { return gains.tau; }
|
||||
|
||||
void convert_pid();
|
||||
|
||||
|
|
Loading…
Reference in New Issue