From 3bbe5ee3ff9f9603ce184cf27dc6ba5f729c19a5 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 8 Dec 2022 17:47:13 +1100 Subject: [PATCH] ArduSub: add support for mavlink in-progress message --- ArduSub/GCS_Mavlink.cpp | 6 +++--- ArduSub/GCS_Mavlink.h | 4 ++-- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/ArduSub/GCS_Mavlink.cpp b/ArduSub/GCS_Mavlink.cpp index 0884c0f2d0..f078629041 100644 --- a/ArduSub/GCS_Mavlink.cpp +++ b/ArduSub/GCS_Mavlink.cpp @@ -416,7 +416,7 @@ bool GCS_MAVLINK_Sub::handle_guided_request(AP_Mission::Mission_Command &cmd) return sub.do_guided(cmd); } -MAV_RESULT GCS_MAVLINK_Sub::_handle_command_preflight_calibration_baro() +MAV_RESULT GCS_MAVLINK_Sub::_handle_command_preflight_calibration_baro(const mavlink_message_t &msg) { if (sub.motors.armed()) { gcs().send_text(MAV_SEVERITY_INFO, "Disarm before calibration."); @@ -431,7 +431,7 @@ MAV_RESULT GCS_MAVLINK_Sub::_handle_command_preflight_calibration_baro() return MAV_RESULT_ACCEPTED; } -MAV_RESULT GCS_MAVLINK_Sub::_handle_command_preflight_calibration(const mavlink_command_long_t &packet) +MAV_RESULT GCS_MAVLINK_Sub::_handle_command_preflight_calibration(const mavlink_command_long_t &packet, const mavlink_message_t &msg) { if (is_equal(packet.param6,1.0f)) { // compassmot calibration @@ -440,7 +440,7 @@ MAV_RESULT GCS_MAVLINK_Sub::_handle_command_preflight_calibration(const mavlink_ return MAV_RESULT_UNSUPPORTED; } - return GCS_MAVLINK::_handle_command_preflight_calibration(packet); + return GCS_MAVLINK::_handle_command_preflight_calibration(packet, msg); } MAV_RESULT GCS_MAVLINK_Sub::handle_command_do_set_roi(const Location &roi_loc) diff --git a/ArduSub/GCS_Mavlink.h b/ArduSub/GCS_Mavlink.h index 1193e7611d..937224027c 100644 --- a/ArduSub/GCS_Mavlink.h +++ b/ArduSub/GCS_Mavlink.h @@ -19,8 +19,8 @@ protected: uint8_t sysid_my_gcs() const override; MAV_RESULT handle_command_do_set_roi(const Location &roi_loc) override; - MAV_RESULT _handle_command_preflight_calibration_baro() override; - MAV_RESULT _handle_command_preflight_calibration(const mavlink_command_long_t &packet) override; + MAV_RESULT _handle_command_preflight_calibration_baro(const mavlink_message_t &msg) override; + MAV_RESULT _handle_command_preflight_calibration(const mavlink_command_long_t &packet, const mavlink_message_t &msg) override; MAV_RESULT handle_command_long_packet(const mavlink_command_long_t &packet) override; // override sending of scaled_pressure3 to send on-board temperature: