From 29d2eed9e4555ee4aaa0e979f1d0caae89deb0c9 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 26 Aug 2021 14:55:18 +1000 Subject: [PATCH] Sub: view update does not take skip_ins_update --- ArduSub/ArduSub.cpp | 2 +- libraries/AP_AHRS/AP_AHRS.cpp | 2 +- libraries/AP_AHRS/AP_AHRS_Backend.h | 2 +- libraries/AP_AHRS/AP_AHRS_DCM.cpp | 2 +- libraries/AP_AHRS/AP_AHRS_DCM.h | 2 +- 5 files changed, 5 insertions(+), 5 deletions(-) diff --git a/ArduSub/ArduSub.cpp b/ArduSub/ArduSub.cpp index 59bb1b2749..91d9cd328a 100644 --- a/ArduSub/ArduSub.cpp +++ b/ArduSub/ArduSub.cpp @@ -293,7 +293,7 @@ void Sub::read_AHRS() //----------------------------------------------- // tells AHRS to skip INS update as we have already done it in fast_loop() ahrs.update(true); - ahrs_view.update(true); + ahrs_view.update(); } // read baro and rangefinder altitude at 10hz diff --git a/libraries/AP_AHRS/AP_AHRS.cpp b/libraries/AP_AHRS/AP_AHRS.cpp index 10239a50ae..18ce1af884 100644 --- a/libraries/AP_AHRS/AP_AHRS.cpp +++ b/libraries/AP_AHRS/AP_AHRS.cpp @@ -410,7 +410,7 @@ void AP_AHRS::update_DCM() yaw = _dcm_attitude.z; update_cd_values(); - AP_AHRS_DCM::update(); + AP_AHRS_DCM::_update(); // keep DCM attitude available for get_secondary_attitude() _dcm_attitude = {roll, pitch, yaw}; diff --git a/libraries/AP_AHRS/AP_AHRS_Backend.h b/libraries/AP_AHRS/AP_AHRS_Backend.h index a5732b4a17..0b6f75706e 100644 --- a/libraries/AP_AHRS/AP_AHRS_Backend.h +++ b/libraries/AP_AHRS/AP_AHRS_Backend.h @@ -78,7 +78,7 @@ public: } // Methods - virtual void update() = 0; + virtual void _update() = 0; // returns false if we fail arming checks, in which case the buffer will be populated with a failure message // requires_position should be true if horizontal position configuration should be checked diff --git a/libraries/AP_AHRS/AP_AHRS_DCM.cpp b/libraries/AP_AHRS/AP_AHRS_DCM.cpp index 851e39262d..b3cf473e52 100644 --- a/libraries/AP_AHRS/AP_AHRS_DCM.cpp +++ b/libraries/AP_AHRS/AP_AHRS_DCM.cpp @@ -65,7 +65,7 @@ void AP_AHRS::load_watchdog_home() // run a full DCM update round void -AP_AHRS_DCM::update() +AP_AHRS_DCM::_update() { AP_InertialSensor &_ins = AP::ins(); diff --git a/libraries/AP_AHRS/AP_AHRS_DCM.h b/libraries/AP_AHRS/AP_AHRS_DCM.h index 029bde0df2..f2b5bb7383 100644 --- a/libraries/AP_AHRS/AP_AHRS_DCM.h +++ b/libraries/AP_AHRS/AP_AHRS_DCM.h @@ -58,7 +58,7 @@ public: void reset_gyro_drift() override; // Methods - void update() override; + void _update() override; void reset(bool recover_eulers = false) override; // return true if yaw has been initialised