ArduSub: add support for mavlink in-progress message

This commit is contained in:
Peter Barker 2022-12-08 17:47:13 +11:00 committed by Peter Barker
parent c18276e19b
commit 3bbe5ee3ff
2 changed files with 5 additions and 5 deletions

View File

@ -416,7 +416,7 @@ bool GCS_MAVLINK_Sub::handle_guided_request(AP_Mission::Mission_Command &cmd)
return sub.do_guided(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()) { if (sub.motors.armed()) {
gcs().send_text(MAV_SEVERITY_INFO, "Disarm before calibration."); 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; 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)) { if (is_equal(packet.param6,1.0f)) {
// compassmot calibration // compassmot calibration
@ -440,7 +440,7 @@ MAV_RESULT GCS_MAVLINK_Sub::_handle_command_preflight_calibration(const mavlink_
return MAV_RESULT_UNSUPPORTED; 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) MAV_RESULT GCS_MAVLINK_Sub::handle_command_do_set_roi(const Location &roi_loc)

View File

@ -19,8 +19,8 @@ protected:
uint8_t sysid_my_gcs() const override; uint8_t sysid_my_gcs() const 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_command_preflight_calibration_baro() 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) 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; MAV_RESULT handle_command_long_packet(const mavlink_command_long_t &packet) override;
// override sending of scaled_pressure3 to send on-board temperature: // override sending of scaled_pressure3 to send on-board temperature: