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