From 4a8614fbbdc9a969135005123375088bb9e6ff3c Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 27 Jun 2018 16:00:43 +1000 Subject: [PATCH] GCS_MAVLink: handle MAV_CMD_FLASH_BOOTLOADER --- libraries/GCS_MAVLink/GCS.h | 1 + libraries/GCS_MAVLink/GCS_Common.cpp | 18 ++++++++++++++++++ 2 files changed, 19 insertions(+) diff --git a/libraries/GCS_MAVLink/GCS.h b/libraries/GCS_MAVLink/GCS.h index 565921bf16..19a072ac97 100644 --- a/libraries/GCS_MAVLink/GCS.h +++ b/libraries/GCS_MAVLink/GCS.h @@ -339,6 +339,7 @@ protected: virtual uint32_t telem_delay() const = 0; MAV_RESULT handle_command_preflight_set_sensor_offsets(const mavlink_command_long_t &packet); + MAV_RESULT handle_command_flash_bootloader(const mavlink_command_long_t &packet); // generally this should not be overridden; Plane overrides it to ensure // failsafe isn't triggered during calibation diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index 5b5f7d1d1d..43291fbd38 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -2456,6 +2456,20 @@ void GCS_MAVLINK::send_simstate() const #endif } +MAV_RESULT GCS_MAVLINK::handle_command_flash_bootloader(const mavlink_command_long_t &packet) +{ + if (int(packet.param5) != 290876) { + gcs().send_text(MAV_SEVERITY_INFO, "Magic not set"); + return MAV_RESULT_FAILED; + } + + if (!hal.util->flash_bootloader()) { + return MAV_RESULT_FAILED; + } + + return MAV_RESULT_ACCEPTED; +} + MAV_RESULT GCS_MAVLINK::handle_command_preflight_set_sensor_offsets(const mavlink_command_long_t &packet) { Compass *compass = get_compass(); @@ -2680,6 +2694,10 @@ MAV_RESULT GCS_MAVLINK::handle_command_long_message(mavlink_command_long_t &pack result = handle_command_preflight_calibration(packet); break; + case MAV_CMD_FLASH_BOOTLOADER: + result = handle_command_flash_bootloader(packet); + break; + case MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS: { result = handle_command_preflight_set_sensor_offsets(packet); break;