GCS_MAVLink: allow MAV_CMD_RUN_PREARMS as both long and int

This commit is contained in:
Peter Barker 2023-10-31 13:37:52 +11:00 committed by Andrew Tridgell
parent 26e6a11ba3
commit e162e74c0c
2 changed files with 5 additions and 6 deletions

View File

@ -628,7 +628,7 @@ protected:
bool telemetry_delayed() const;
virtual uint32_t telem_delay() const = 0;
MAV_RESULT handle_command_run_prearm_checks(const mavlink_command_long_t &packet);
MAV_RESULT handle_command_run_prearm_checks(const mavlink_command_int_t &packet);
MAV_RESULT handle_command_flash_bootloader(const mavlink_command_int_t &packet);
// generally this should not be overridden; Plane overrides it to ensure

View File

@ -4435,7 +4435,7 @@ MAV_RESULT GCS_MAVLINK::handle_command_preflight_calibration(const mavlink_comma
return _handle_command_preflight_calibration(packet, msg);
}
MAV_RESULT GCS_MAVLINK::handle_command_run_prearm_checks(const mavlink_command_long_t &packet)
MAV_RESULT GCS_MAVLINK::handle_command_run_prearm_checks(const mavlink_command_int_t &packet)
{
if (hal.util->get_soft_armed()) {
return MAV_RESULT_TEMPORARILY_REJECTED;
@ -4780,10 +4780,6 @@ MAV_RESULT GCS_MAVLINK::handle_command_long_packet(const mavlink_command_long_t
break;
#endif
case MAV_CMD_RUN_PREARM_CHECKS:
result = handle_command_run_prearm_checks(packet);
break;
default:
result = try_command_long_as_command_int(packet, msg);
break;
@ -5148,6 +5144,9 @@ MAV_RESULT GCS_MAVLINK::handle_command_int_packet(const mavlink_command_int_t &p
return handle_servorelay_message(packet);
#endif
case MAV_CMD_RUN_PREARM_CHECKS:
return handle_command_run_prearm_checks(packet);
#if AP_SCRIPTING_ENABLED
case MAV_CMD_SCRIPTING:
{