mirror of https://github.com/ArduPilot/ardupilot
AP_TECS: added get_max_sinkrate() API
This commit is contained in:
parent
77ee922473
commit
a789bb372b
|
@ -81,6 +81,11 @@ public:
|
||||||
return _maxClimbRate;
|
return _maxClimbRate;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// return maximum sink rate (+ve number down)
|
||||||
|
float get_max_sinkrate(void) const override {
|
||||||
|
return _maxSinkRate;
|
||||||
|
}
|
||||||
|
|
||||||
// added to let SoaringContoller reset pitch integrator to zero
|
// added to let SoaringContoller reset pitch integrator to zero
|
||||||
void reset_pitch_I(void) override {
|
void reset_pitch_I(void) override {
|
||||||
_integSEB_state = 0.0f;
|
_integSEB_state = 0.0f;
|
||||||
|
|
Loading…
Reference in New Issue