From 9ac0514e8ebdd42e22cd0846cfb03d8ad1accfa2 Mon Sep 17 00:00:00 2001 From: Tom Pittenger Date: Wed, 4 Jan 2023 20:51:59 -0800 Subject: [PATCH] AP_AHRS: move AP_NMEA_OUTPUT to a first class library --- libraries/AP_AHRS/AP_AHRS.cpp | 11 ----------- libraries/AP_AHRS/AP_AHRS.h | 5 ----- 2 files changed, 16 deletions(-) diff --git a/libraries/AP_AHRS/AP_AHRS.cpp b/libraries/AP_AHRS/AP_AHRS.cpp index 4c8d6b2346..4aa60860cc 100644 --- a/libraries/AP_AHRS/AP_AHRS.cpp +++ b/libraries/AP_AHRS/AP_AHRS.cpp @@ -236,10 +236,6 @@ void AP_AHRS::init() // init backends dcm.init(); -#if HAL_NMEA_OUTPUT_ENABLED - _nmea_out = AP_NMEA_Output::probe(); -#endif - #if !APM_BUILD_TYPE(APM_BUILD_AP_Periph) // convert to new custom rotaton // PARAMETER_CONVERSION - Added: Nov-2021 @@ -390,13 +386,6 @@ void AP_AHRS::update(bool skip_ins_update) // update AOA and SSA update_AOA_SSA(); -#if HAL_NMEA_OUTPUT_ENABLED - // update NMEA output - if (_nmea_out != nullptr) { - _nmea_out->update(); - } -#endif - EKFType active = active_EKF_type(); if (active != last_active_ekf_type) { last_active_ekf_type = active; diff --git a/libraries/AP_AHRS/AP_AHRS.h b/libraries/AP_AHRS/AP_AHRS.h index f38e7056d9..fc2fca819d 100644 --- a/libraries/AP_AHRS/AP_AHRS.h +++ b/libraries/AP_AHRS/AP_AHRS.h @@ -37,7 +37,6 @@ class AP_AHRS_View; #define AP_AHRS_NAVEKF_SETTLE_TIME_MS 20000 // time in milliseconds the ekf needs to settle after being started -#include // fwd declare GSF estimator class EKFGSF_yaw; @@ -823,10 +822,6 @@ private: void Write_AHRS2(void) const; // write POS (canonical vehicle position) message out: void Write_POS(void) const; - -#if HAL_NMEA_OUTPUT_ENABLED - class AP_NMEA_Output* _nmea_out; -#endif }; namespace AP {