ArduCopter: 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 5b0393e280
commit 624cfc8fcc
2 changed files with 2 additions and 2 deletions

View File

@ -673,7 +673,7 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_do_set_roi(const Location &roi_loc
return MAV_RESULT_ACCEPTED; 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 // 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) { if (copter.g.esc_calibrate == (uint8_t)Copter::ESCCalibrationModes::ESCCAL_AUTO) {

View File

@ -33,7 +33,7 @@ protected:
void send_position_target_local_ned() override; void send_position_target_local_ned() override;
MAV_RESULT handle_command_do_set_roi(const Location &roi_loc) 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 #if HAL_MOUNT_ENABLED
MAV_RESULT handle_command_mount(const mavlink_command_int_t &packet, const mavlink_message_t &msg) override; MAV_RESULT handle_command_mount(const mavlink_command_int_t &packet, const mavlink_message_t &msg) override;
#endif #endif