From c46a50f4281ab941028977589216b7f1a0830433 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 8 Jul 2022 14:15:35 +1000 Subject: [PATCH] AP_NavEKF2: stop using GCS_MAVLINK.h in header files ... by passing through a reference to a link object instead --- libraries/AP_NavEKF2/AP_NavEKF2.cpp | 4 ++-- libraries/AP_NavEKF2/AP_NavEKF2.h | 3 +-- libraries/AP_NavEKF2/AP_NavEKF2_Outputs.cpp | 7 +++++-- libraries/AP_NavEKF2/AP_NavEKF2_core.h | 3 +-- 4 files changed, 9 insertions(+), 8 deletions(-) diff --git a/libraries/AP_NavEKF2/AP_NavEKF2.cpp b/libraries/AP_NavEKF2/AP_NavEKF2.cpp index 5add807783..b9a3b17126 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2.cpp +++ b/libraries/AP_NavEKF2/AP_NavEKF2.cpp @@ -1274,10 +1274,10 @@ void NavEKF2::getFilterGpsStatus(nav_gps_status &status) const } // send an EKF_STATUS_REPORT message to GCS -void NavEKF2::send_status_report(mavlink_channel_t chan) const +void NavEKF2::send_status_report(GCS_MAVLINK &link) const { if (core) { - core[primary].send_status_report(chan); + core[primary].send_status_report(link); } } diff --git a/libraries/AP_NavEKF2/AP_NavEKF2.h b/libraries/AP_NavEKF2/AP_NavEKF2.h index 20362c67b7..8f475a06b1 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2.h +++ b/libraries/AP_NavEKF2/AP_NavEKF2.h @@ -25,7 +25,6 @@ #include #include #include -#include #include class NavEKF2_core; @@ -216,7 +215,7 @@ public: void getFilterStatus(nav_filter_status &status) const; // send an EKF_STATUS_REPORT message to GCS - void send_status_report(mavlink_channel_t chan) const; + void send_status_report(class GCS_MAVLINK &link) const; // provides the height limit to be observed by the control loops // returns false if no height limiting is required diff --git a/libraries/AP_NavEKF2/AP_NavEKF2_Outputs.cpp b/libraries/AP_NavEKF2/AP_NavEKF2_Outputs.cpp index 71ed9127b3..aadafd00d9 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2_Outputs.cpp +++ b/libraries/AP_NavEKF2/AP_NavEKF2_Outputs.cpp @@ -3,6 +3,7 @@ #include "AP_NavEKF2_core.h" #include #include +#include extern const AP_HAL::HAL& hal; @@ -492,8 +493,9 @@ void NavEKF2_core::getFilterGpsStatus(nav_gps_status &faults) const faults.flags.bad_horiz_vel = gpsCheckStatus.bad_horiz_vel; // The GPS horizontal speed is excessive (check assumes the vehicle is static) } +#if HAL_GCS_ENABLED // send an EKF_STATUS message to GCS -void NavEKF2_core::send_status_report(mavlink_channel_t chan) const +void NavEKF2_core::send_status_report(GCS_MAVLINK &link) const { // prepare flags uint16_t flags = 0; @@ -550,8 +552,9 @@ void NavEKF2_core::send_status_report(mavlink_channel_t chan) const } // send message - mavlink_msg_ekf_status_report_send(chan, flags, velVar, posVar, hgtVar, mag_max, temp, tasVar); + mavlink_msg_ekf_status_report_send(link.get_chan(), flags, velVar, posVar, hgtVar, mag_max, temp, tasVar); } +#endif // HAL_GCS_ENABLED // report the reason for why the backend is refusing to initialise const char *NavEKF2_core::prearm_failure_reason(void) const diff --git a/libraries/AP_NavEKF2/AP_NavEKF2_core.h b/libraries/AP_NavEKF2/AP_NavEKF2_core.h index e8987499e7..1a2dc6e840 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2_core.h +++ b/libraries/AP_NavEKF2/AP_NavEKF2_core.h @@ -29,7 +29,6 @@ #include #include #include -#include #include #include "AP_NavEKF/EKFGSF_yaw.h" @@ -247,7 +246,7 @@ public: void getFilterStatus(nav_filter_status &status) const; // send an EKF_STATUS_REPORT message to GCS - void send_status_report(mavlink_channel_t chan) const; + void send_status_report(class GCS_MAVLINK &link) const; // provides the height limit to be observed by the control loops // returns false if no height limiting is required