From 380a1fe738f9acd66ce61e051768aea616976217 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 23 Aug 2023 17:38:07 +1000 Subject: [PATCH] Rover: accept MAV_CMD_NAV_RETURN_TO_LAUNCH as both long and int --- Rover/GCS_Mavlink.cpp | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/Rover/GCS_Mavlink.cpp b/Rover/GCS_Mavlink.cpp index 88323f303a..2eef43bd6f 100644 --- a/Rover/GCS_Mavlink.cpp +++ b/Rover/GCS_Mavlink.cpp @@ -657,6 +657,12 @@ MAV_RESULT GCS_MAVLINK_Rover::handle_command_int_packet(const mavlink_command_in rover.control_mode->set_reversed(is_equal(packet.param1,1.0f)); return MAV_RESULT_ACCEPTED; + case MAV_CMD_NAV_RETURN_TO_LAUNCH: + if (rover.set_mode(rover.mode_rtl, ModeReason::GCS_COMMAND)) { + return MAV_RESULT_ACCEPTED; + } + return MAV_RESULT_FAILED; + default: return GCS_MAVLINK::handle_command_int_packet(packet, msg); } @@ -666,12 +672,6 @@ MAV_RESULT GCS_MAVLINK_Rover::handle_command_long_packet(const mavlink_command_l { switch (packet.command) { - case MAV_CMD_NAV_RETURN_TO_LAUNCH: - if (rover.set_mode(rover.mode_rtl, ModeReason::GCS_COMMAND)) { - return MAV_RESULT_ACCEPTED; - } - return MAV_RESULT_FAILED; - case MAV_CMD_MISSION_START: if (rover.set_mode(rover.mode_auto, ModeReason::GCS_COMMAND)) { return MAV_RESULT_ACCEPTED;