From 440d17e0de1fe54e10237bb1f52f57b41368245e Mon Sep 17 00:00:00 2001 From: Samuel Tabor Date: Mon, 7 Sep 2020 12:51:56 +0100 Subject: [PATCH] AP_Soaring: Add accessor for SOAR_ALT_CUTOFF. --- libraries/AP_Soaring/AP_Soaring.h | 2 ++ 1 file changed, 2 insertions(+) diff --git a/libraries/AP_Soaring/AP_Soaring.h b/libraries/AP_Soaring/AP_Soaring.h index 2df2305805..47b5e12999 100644 --- a/libraries/AP_Soaring/AP_Soaring.h +++ b/libraries/AP_Soaring/AP_Soaring.h @@ -125,6 +125,8 @@ public: void set_pilot_desired_state(ActiveStatus pilot_desired_state) {_pilot_desired_state = pilot_desired_state;}; + float get_alt_cutoff() const {return alt_cutoff;} + private: // slow down messages if they are the same. During loiter we could smap the same message. Only show new messages during loiters LoiterStatus _cruise_criteria_msg_last;