From 6991a1b9e9adb61299011b160165c318a837b249 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 7 Sep 2015 08:58:11 +1000 Subject: [PATCH] AP_Compass: ensure we have payload space to send MAG_CAL messages --- libraries/AP_Compass/AP_Compass_Calibration.cpp | 11 +++++++++++ 1 file changed, 11 insertions(+) diff --git a/libraries/AP_Compass/AP_Compass_Calibration.cpp b/libraries/AP_Compass/AP_Compass_Calibration.cpp index c462a2f0b4..49cfe07324 100644 --- a/libraries/AP_Compass/AP_Compass_Calibration.cpp +++ b/libraries/AP_Compass/AP_Compass_Calibration.cpp @@ -2,6 +2,7 @@ #include #include "Compass.h" #include +#include extern AP_HAL::HAL& hal; @@ -186,6 +187,11 @@ Compass::send_mag_cal_progress(mavlink_channel_t chan) memset(completion_mask, 0, sizeof(completion_mask)); + // ensure we don't try to send with no space available + if (!HAVE_PAYLOAD_SPACE(chan, MAG_CAL_PROGRESS)) { + return; + } + mavlink_msg_mag_cal_progress_send( chan, compass_id, cal_mask, @@ -211,6 +217,11 @@ void Compass::send_mag_cal_report(mavlink_channel_t chan) _calibrator[compass_id].get_calibration(ofs, diag, offdiag); uint8_t autosaved = _calibrator[compass_id].get_autosave(); + // ensure we don't try to send with no space available + if (!HAVE_PAYLOAD_SPACE(chan, MAG_CAL_REPORT)) { + return; + } + mavlink_msg_mag_cal_report_send( chan, compass_id, cal_mask,