mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
allows main code to manually set the integrator value
This commit is contained in:
parent
7bef298a46
commit
f6e268395f
@ -113,6 +113,7 @@ public:
|
||||
void kI(const float v) { _ki.set(v); }
|
||||
void imax(const int16_t v) { _imax.set(abs(v)); }
|
||||
float get_integrator() const { return _integrator; }
|
||||
void set_integrator(float i) { _integrator = i; }
|
||||
|
||||
private:
|
||||
AP_Var_group _group;
|
||||
|
Loading…
Reference in New Issue
Block a user