From df01bed14fc7bdf402025c62897f9c5c3c896bfd Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 1 Aug 2019 11:05:22 +1000 Subject: [PATCH] AP_Compass: take GCS link in place of channel to calibration routines --- libraries/AP_Compass/AP_Compass.h | 4 +-- .../AP_Compass/AP_Compass_Calibration.cpp | 28 ++++++++++++------- 2 files changed, 20 insertions(+), 12 deletions(-) diff --git a/libraries/AP_Compass/AP_Compass.h b/libraries/AP_Compass/AP_Compass.h index dc77d14823..fe68d386db 100644 --- a/libraries/AP_Compass/AP_Compass.h +++ b/libraries/AP_Compass/AP_Compass.h @@ -150,8 +150,8 @@ public: */ MAV_RESULT handle_mag_cal_command(const mavlink_command_long_t &packet); - void send_mag_cal_progress(mavlink_channel_t chan); - void send_mag_cal_report(mavlink_channel_t chan); + bool send_mag_cal_progress(const class GCS_MAVLINK& link); + bool send_mag_cal_report(const class GCS_MAVLINK& link); // check if the compasses are pointing in the same direction bool consistent() const; diff --git a/libraries/AP_Compass/AP_Compass_Calibration.cpp b/libraries/AP_Compass/AP_Compass_Calibration.cpp index a9ff73d5d5..6e51e93ede 100644 --- a/libraries/AP_Compass/AP_Compass_Calibration.cpp +++ b/libraries/AP_Compass/AP_Compass_Calibration.cpp @@ -186,15 +186,17 @@ Compass::_accept_calibration_mask(uint8_t mask) return success; } -void -Compass::send_mag_cal_progress(mavlink_channel_t chan) +bool Compass::send_mag_cal_progress(const GCS_MAVLINK& link) { uint8_t cal_mask = _get_cal_mask(); for (uint8_t compass_id=0; compass_id