From 9ac892aceac0fba95400cef9b0bb115e9ff94073 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Fri, 22 May 2015 22:19:48 +0900 Subject: [PATCH] Copter: fix MISSION_START support Vehicle must already be armed Set auto-armed to true to allow take-off without pilot raising throttle --- ArduCopter/GCS_Mavlink.pde | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/ArduCopter/GCS_Mavlink.pde b/ArduCopter/GCS_Mavlink.pde index 1b76648223..2513f19f99 100644 --- a/ArduCopter/GCS_Mavlink.pde +++ b/ArduCopter/GCS_Mavlink.pde @@ -1149,7 +1149,8 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) break; case MAV_CMD_MISSION_START: - if (set_mode(AUTO)) { + if (motors.armed() && set_mode(AUTO)) { + set_auto_armed(true); result = MAV_RESULT_ACCEPTED; } break;