AP_AHRS: move AP_NMEA_OUTPUT to a first class library

This commit is contained in:
Tom Pittenger 2023-01-04 20:51:59 -08:00 committed by Peter Barker
parent 468d773391
commit 9ac0514e8e
2 changed files with 0 additions and 16 deletions

View File

@ -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;

View File

@ -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 <AP_NMEA_Output/AP_NMEA_Output.h>
// 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 {