mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
AP_Compass: ensure we have payload space to send MAG_CAL messages
This commit is contained in:
parent
2baa0ac2f2
commit
6991a1b9e9
@ -2,6 +2,7 @@
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include "Compass.h"
|
||||
#include <AP_Notify/AP_Notify.h>
|
||||
#include <GCS_MAVLink/GCS.h>
|
||||
|
||||
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,
|
||||
|
Loading…
Reference in New Issue
Block a user