From 624cfc8fccc44530e826a0a6e4ba7e94db4d3fe6 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 13 Sep 2023 19:01:31 +1000 Subject: [PATCH] ArduCopter: handle MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN as INT or LONG --- ArduCopter/GCS_Mavlink.cpp | 2 +- ArduCopter/GCS_Mavlink.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp index be3b2a0809..5b4b38e418 100644 --- a/ArduCopter/GCS_Mavlink.cpp +++ b/ArduCopter/GCS_Mavlink.cpp @@ -673,7 +673,7 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_do_set_roi(const Location &roi_loc return MAV_RESULT_ACCEPTED; } -MAV_RESULT GCS_MAVLINK_Copter::handle_preflight_reboot(const mavlink_command_long_t &packet, const mavlink_message_t &msg) +MAV_RESULT GCS_MAVLINK_Copter::handle_preflight_reboot(const mavlink_command_int_t &packet, const mavlink_message_t &msg) { // reject reboot if user has also specified they want the "Auto" ESC calibration on next reboot if (copter.g.esc_calibrate == (uint8_t)Copter::ESCCalibrationModes::ESCCAL_AUTO) { diff --git a/ArduCopter/GCS_Mavlink.h b/ArduCopter/GCS_Mavlink.h index 2f1ad4402a..a20af1dbee 100644 --- a/ArduCopter/GCS_Mavlink.h +++ b/ArduCopter/GCS_Mavlink.h @@ -33,7 +33,7 @@ protected: void send_position_target_local_ned() override; MAV_RESULT handle_command_do_set_roi(const Location &roi_loc) override; - MAV_RESULT handle_preflight_reboot(const mavlink_command_long_t &packet, const mavlink_message_t &msg) override; + MAV_RESULT handle_preflight_reboot(const mavlink_command_int_t &packet, const mavlink_message_t &msg) override; #if HAL_MOUNT_ENABLED MAV_RESULT handle_command_mount(const mavlink_command_int_t &packet, const mavlink_message_t &msg) override; #endif