Browse Source

AP_SpdHgtControl: added get_max_sinkrate()

zr-v5.1
Andrew Tridgell 4 years ago
parent
commit
eba1d499d4
  1. 3
      libraries/AP_SpdHgtControl/AP_SpdHgtControl.h

3
libraries/AP_SpdHgtControl/AP_SpdHgtControl.h

@ -50,6 +50,9 @@ public: @@ -50,6 +50,9 @@ public:
// return maximum climb rate
virtual float get_max_climbrate(void) const = 0;
// return maximum sink rate (+ve number)
virtual float get_max_sinkrate(void) const = 0;
// added to let SoaringController reset pitch integrator to zero
virtual void reset_pitch_I(void) = 0;

Loading…
Cancel
Save