ArduPlane: support preflight calibration via command_int

This commit is contained in:
Peter Barker 2023-09-07 20:13:30 +10:00 committed by Peter Barker
parent 619b1ecd47
commit c1b5e9a446
2 changed files with 2 additions and 2 deletions

View File

@ -696,7 +696,7 @@ void GCS_MAVLINK_Plane::handle_change_alt_request(AP_Mission::Mission_Command &c
}
MAV_RESULT GCS_MAVLINK_Plane::handle_command_preflight_calibration(const mavlink_command_long_t &packet, const mavlink_message_t &msg)
MAV_RESULT GCS_MAVLINK_Plane::handle_command_preflight_calibration(const mavlink_command_int_t &packet, const mavlink_message_t &msg)
{
plane.in_calibration = true;
MAV_RESULT ret = GCS_MAVLINK::handle_command_preflight_calibration(packet, msg);

View File

@ -23,7 +23,7 @@ protected:
bool sysid_enforce() const override;
MAV_RESULT handle_command_preflight_calibration(const mavlink_command_long_t &packet, const mavlink_message_t &msg) override;
MAV_RESULT handle_command_preflight_calibration(const mavlink_command_int_t &packet, const mavlink_message_t &msg) override;
MAV_RESULT handle_command_int_packet(const mavlink_command_int_t &packet, const mavlink_message_t &msg) override;
MAV_RESULT handle_command_long_packet(const mavlink_command_long_t &packet, const mavlink_message_t &msg) override;
MAV_RESULT handle_command_do_set_mission_current(const mavlink_command_long_t &packet) override;