From 805901dc18100da2593e779927b1fe6640ebc7b3 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 4 Oct 2023 23:20:30 +1100 Subject: [PATCH] GCS_MAVLink: allow PREFLIGHT_STORAGE as COMMAND_INT and COMMAND_LONG --- libraries/GCS_MAVLink/GCS_Common.cpp | 16 ++++++++-------- 1 file changed, 8 insertions(+), 8 deletions(-) diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index afbb77055ea44..4fc2997b986f5 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -4830,14 +4830,6 @@ MAV_RESULT GCS_MAVLINK::handle_command_long_packet(const mavlink_command_long_t result = handle_command_set_ekf_source_set(packet); break; - case MAV_CMD_PREFLIGHT_STORAGE: - if (is_equal(packet.param1, 2.0f)) { - AP_Param::erase_all(); - send_text(MAV_SEVERITY_WARNING, "All parameters reset, reboot board"); - result= MAV_RESULT_ACCEPTED; - } - break; - default: result = try_command_long_as_command_int(packet, msg); break; @@ -5141,6 +5133,14 @@ MAV_RESULT GCS_MAVLINK::handle_command_int_packet(const mavlink_command_int_t &p case MAV_CMD_PREFLIGHT_CALIBRATION: return handle_command_preflight_calibration(packet, msg); + case MAV_CMD_PREFLIGHT_STORAGE: + if (is_equal(packet.param1, 2.0f)) { + AP_Param::erase_all(); + send_text(MAV_SEVERITY_WARNING, "All parameters reset, reboot board"); + return MAV_RESULT_ACCEPTED; + } + return MAV_RESULT_DENIED; + case MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN: return handle_preflight_reboot(packet, msg);