From 43e83f18bee60f5b458eb4e85ada7bc2c8b36de8 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 5 Oct 2021 15:42:13 +1100 Subject: [PATCH] AP_AHRS: do not send EKF_STATUS_REPORT from DCM This means that even if you configure DCM as your primary you won't get its status. Given the status was currently garbage, this isn't necessarily a bad thing at the moment. --- libraries/AP_AHRS/AP_AHRS_DCM.cpp | 2 -- 1 file changed, 2 deletions(-) diff --git a/libraries/AP_AHRS/AP_AHRS_DCM.cpp b/libraries/AP_AHRS/AP_AHRS_DCM.cpp index c15224b555..efcc560d99 100644 --- a/libraries/AP_AHRS/AP_AHRS_DCM.cpp +++ b/libraries/AP_AHRS/AP_AHRS_DCM.cpp @@ -1235,6 +1235,4 @@ bool AP_AHRS_DCM::get_relative_position_D_origin(float &posD) const void AP_AHRS_DCM::send_ekf_status_report(mavlink_channel_t chan) const { - // send zero status report - mavlink_msg_ekf_status_report_send(chan, 0, 0, 0, 0, 0, 0, 0); }