mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
AP_TECS: added function to reset integrator
This commit is contained in:
parent
acddf6bdf3
commit
a3f3097941
@ -78,6 +78,11 @@ public:
|
||||
return _maxClimbRate;
|
||||
}
|
||||
|
||||
// added to let SoaringContoller reset pitch integrator to zero
|
||||
void reset_pitch_I(void) {
|
||||
_integSEB_state = 0.0f;
|
||||
}
|
||||
|
||||
// return landing sink rate
|
||||
float get_land_sinkrate(void) const {
|
||||
return _land_sink;
|
||||
|
Loading…
Reference in New Issue
Block a user