From 0827ec0aaa7b3ca10dcddb36d495b7efdf744251 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 14 Sep 2022 10:46:55 +1000 Subject: [PATCH] ArduCopter: populate sysid/compid in reboot ACK --- ArduCopter/GCS_Mavlink.cpp | 4 ++-- ArduCopter/GCS_Mavlink.h | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp index 10cb95fb3f..528a8964fb 100644 --- a/ArduCopter/GCS_Mavlink.cpp +++ b/ArduCopter/GCS_Mavlink.cpp @@ -644,7 +644,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) +MAV_RESULT GCS_MAVLINK_Copter::handle_preflight_reboot(const mavlink_command_long_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) { @@ -653,7 +653,7 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_preflight_reboot(const mavlink_command_lon } // call parent - return GCS_MAVLINK::handle_preflight_reboot(packet); + return GCS_MAVLINK::handle_preflight_reboot(packet, msg); } bool GCS_MAVLINK_Copter::set_home_to_current_location(bool _lock) { diff --git a/ArduCopter/GCS_Mavlink.h b/ArduCopter/GCS_Mavlink.h index 4f9c662fd8..a68096a9f5 100644 --- a/ArduCopter/GCS_Mavlink.h +++ b/ArduCopter/GCS_Mavlink.h @@ -28,7 +28,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) override; + MAV_RESULT handle_preflight_reboot(const mavlink_command_long_t &packet, const mavlink_message_t &msg) override; #if HAL_MOUNT_ENABLED MAV_RESULT handle_command_mount(const mavlink_command_long_t &packet) override; #endif