From f5c28cc12d3d2e908b422445d0b839d095330a4e Mon Sep 17 00:00:00 2001
From: snktshrma <sharma.sanket272@gmail.com>
Date: Thu, 21 Nov 2024 13:30:16 +0530
Subject: [PATCH] AP_Vehicle: Added method to takeoff for use by external
 control

---
 libraries/AP_Vehicle/AP_Vehicle.h | 3 ++-
 1 file changed, 2 insertions(+), 1 deletion(-)

diff --git a/libraries/AP_Vehicle/AP_Vehicle.h b/libraries/AP_Vehicle/AP_Vehicle.h
index 02895d1bc2..9b88404739 100644
--- a/libraries/AP_Vehicle/AP_Vehicle.h
+++ b/libraries/AP_Vehicle/AP_Vehicle.h
@@ -172,6 +172,8 @@ public:
     virtual bool is_crashed() const;
 
 #if AP_SCRIPTING_ENABLED || AP_EXTERNAL_CONTROL_ENABLED
+    // Method to takeoff for use by external control
+    virtual bool start_takeoff(const float alt) { return false; }
     // Method to control vehicle position for use by external control
     virtual bool set_target_location(const Location& target_loc) { return false; }
 #endif // AP_SCRIPTING_ENABLED || AP_EXTERNAL_CONTROL_ENABLED
@@ -179,7 +181,6 @@ public:
     /*
       methods to control vehicle for use by scripting
     */
-    virtual bool start_takeoff(float alt) { return false; }
     virtual bool set_target_pos_NED(const Vector3f& target_pos, bool use_yaw, float yaw_deg, bool use_yaw_rate, float yaw_rate_degs, bool yaw_relative, bool terrain_alt) { return false; }
     virtual bool set_target_posvel_NED(const Vector3f& target_pos, const Vector3f& target_vel) { return false; }
     virtual bool set_target_posvelaccel_NED(const Vector3f& target_pos, const Vector3f& target_vel, const Vector3f& target_accel, bool use_yaw, float yaw_deg, bool use_yaw_rate, float yaw_rate_degs, bool yaw_relative) { return false; }