ArduCopter: populate sysid/compid in reboot ACK

This commit is contained in:
Peter Barker 2022-09-14 10:46:55 +10:00 committed by Peter Barker
parent c8a1fff8ae
commit 0827ec0aaa
2 changed files with 3 additions and 3 deletions

View File

@ -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) {

View File

@ -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