diff --git a/ArduPlane/ArduPlane.cpp b/ArduPlane/ArduPlane.cpp index eb66712843..d203b68b64 100644 --- a/ArduPlane/ArduPlane.cpp +++ b/ArduPlane/ArduPlane.cpp @@ -863,6 +863,7 @@ bool Plane::set_land_descent_rate(float descent_rate) #endif return false; } +#endif // AP_SCRIPTING_ENABLED // returns true if vehicle is landing. bool Plane::is_landing() const @@ -886,8 +887,6 @@ bool Plane::is_taking_off() const return control_mode->is_taking_off(); } -#endif // AP_SCRIPTING_ENABLED - // correct AHRS pitch for TRIM_PITCH_CD in non-VTOL modes, and return VTOL view in VTOL void Plane::get_osd_roll_pitch_rad(float &roll, float &pitch) const { diff --git a/ArduPlane/Plane.h b/ArduPlane/Plane.h index 00f7490d32..c68bd006e0 100644 --- a/ArduPlane/Plane.h +++ b/ArduPlane/Plane.h @@ -1237,6 +1237,8 @@ private: public: void failsafe_check(void); + bool is_landing() const override; + bool is_taking_off() const override; #if AP_SCRIPTING_ENABLED bool set_target_location(const Location& target_loc) override; bool get_target_location(Location& target_loc) override; @@ -1245,8 +1247,6 @@ public: // allow for landing descent rate to be overridden by a script, may be -ve to climb bool set_land_descent_rate(float descent_rate) override; - bool is_landing() const override; - bool is_taking_off() const override; #endif // AP_SCRIPTING_ENABLED };