From cf0b7cf01658bf568ce3fc204f8c8480abc87973 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 1 Aug 2019 11:04:18 +1000 Subject: [PATCH] GCS_MAVLink: pass link object in place of channel to compass cal Also eliminate intermediate function as just adding noise --- libraries/GCS_MAVLink/GCS.h | 1 - libraries/GCS_MAVLink/GCS_Common.cpp | 24 +++--------------------- 2 files changed, 3 insertions(+), 22 deletions(-) diff --git a/libraries/GCS_MAVLink/GCS.h b/libraries/GCS_MAVLink/GCS.h index 8fdfd98f55..b24ae23070 100644 --- a/libraries/GCS_MAVLink/GCS.h +++ b/libraries/GCS_MAVLink/GCS.h @@ -396,7 +396,6 @@ protected: virtual void send_global_position_int(); // message sending functions: - bool try_send_compass_message(enum ap_message id); bool try_send_mission_message(enum ap_message id); void send_hwstatus(); void handle_data_packet(const mavlink_message_t &msg); diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index a10ccebea1..c584534730 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -3757,26 +3757,6 @@ void GCS_MAVLINK::handle_command_int(const mavlink_message_t &msg) hal.util->persistent_data.last_mavlink_cmd = 0; } -bool GCS_MAVLINK::try_send_compass_message(const enum ap_message id) -{ - Compass &compass = AP::compass(); - bool ret = true; - switch (id) { - case MSG_MAG_CAL_PROGRESS: - compass.send_mag_cal_progress(chan); - ret = true;; - break; - case MSG_MAG_CAL_REPORT: - compass.send_mag_cal_report(chan); - ret = true; - break; - default: - ret = true; - break; - } - return ret; -} - void GCS::try_send_queued_message_for_type(MAV_MISSION_TYPE type) { MissionItemProtocol *prot = get_prot_for_mission_type(type); if (prot == nullptr) { @@ -4053,8 +4033,10 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id) break; case MSG_MAG_CAL_PROGRESS: + ret = AP::compass().send_mag_cal_progress(*this); + break; case MSG_MAG_CAL_REPORT: - ret = try_send_compass_message(id); + ret = AP::compass().send_mag_cal_report(*this); break; case MSG_BATTERY_STATUS: