From 9fcfea5404be53fa78384c78298e770ec3d8b9a3 Mon Sep 17 00:00:00 2001 From: Valentin Brossard Date: Thu, 29 May 2014 17:04:53 +0200 Subject: [PATCH] Copter: accept DO_CHANGE_SPEED outside of missions https://github.com/diydrones/ardupilot/issues/1095 --- ArduCopter/GCS_Mavlink.pde | 13 +++++++++++++ 1 file changed, 13 insertions(+) diff --git a/ArduCopter/GCS_Mavlink.pde b/ArduCopter/GCS_Mavlink.pde index ac2c53fb45..d1a4750a10 100644 --- a/ArduCopter/GCS_Mavlink.pde +++ b/ArduCopter/GCS_Mavlink.pde @@ -1098,6 +1098,19 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) } break; + case MAV_CMD_DO_CHANGE_SPEED: + // param1 : unused + // param2 : new speed in m/s + // param3 : unused + // param4 : unused + if (packet.param2 > 0.0f) { + wp_nav.set_speed_xy(packet.param2 * 100.0f); + result = MAV_RESULT_ACCEPTED; + } else { + result = MAV_RESULT_FAILED; + } + break; + case MAV_CMD_MISSION_START: if (set_mode(AUTO)) { result = MAV_RESULT_ACCEPTED;