diff --git a/Tools/AP_Periph/GCS_MAVLink.cpp b/Tools/AP_Periph/GCS_MAVLink.cpp index 07bc148404..5502087678 100644 --- a/Tools/AP_Periph/GCS_MAVLink.cpp +++ b/Tools/AP_Periph/GCS_MAVLink.cpp @@ -67,7 +67,7 @@ uint8_t GCS_Periph::sysid_this_mav() const return periph.g.sysid_this_mav; } -MAV_RESULT GCS_MAVLINK_Periph::handle_preflight_reboot(const mavlink_command_long_t &packet, const mavlink_message_t &msg) +MAV_RESULT GCS_MAVLINK_Periph::handle_preflight_reboot(const mavlink_command_int_t &packet, const mavlink_message_t &msg) { hal.scheduler->delay(10); periph.prepare_reboot(); diff --git a/Tools/AP_Periph/GCS_MAVLink.h b/Tools/AP_Periph/GCS_MAVLink.h index 98f39b8852..ce1f17b1ba 100644 --- a/Tools/AP_Periph/GCS_MAVLink.h +++ b/Tools/AP_Periph/GCS_MAVLink.h @@ -31,7 +31,7 @@ private: uint32_t telem_delay() const override { return 0; } void handleMessage(const mavlink_message_t &msg) override { handle_common_message(msg); } bool handle_guided_request(AP_Mission::Mission_Command &cmd) override { return true; } - 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; uint8_t sysid_my_gcs() const override; protected: