Tools: handle MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN as INT or LONG

This commit is contained in:
Peter Barker 2023-09-13 19:01:31 +10:00 committed by Andrew Tridgell
parent 624cfc8fcc
commit 5ed1344115
2 changed files with 2 additions and 2 deletions

View File

@ -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();

View File

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