From ed5303d1b853f3a069defd67e1abf527a81d5367 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 20 Jul 2021 22:16:31 +1000 Subject: [PATCH] AP_OpticalFlow: rename for AHRS restructuring --- libraries/AP_OpticalFlow/AP_OpticalFlow_CXOF.cpp | 2 +- libraries/AP_OpticalFlow/AP_OpticalFlow_Pixart.cpp | 2 +- libraries/AP_OpticalFlow/AP_OpticalFlow_UPFLOW.cpp | 2 +- libraries/AP_OpticalFlow/OpticalFlow.cpp | 10 +++++----- libraries/AP_OpticalFlow/OpticalFlow.h | 2 +- .../AP_OpticalFlow_test/AP_OpticalFlow_test.cpp | 2 +- 6 files changed, 10 insertions(+), 10 deletions(-) diff --git a/libraries/AP_OpticalFlow/AP_OpticalFlow_CXOF.cpp b/libraries/AP_OpticalFlow/AP_OpticalFlow_CXOF.cpp index 3e41551908..0bd3184582 100644 --- a/libraries/AP_OpticalFlow/AP_OpticalFlow_CXOF.cpp +++ b/libraries/AP_OpticalFlow/AP_OpticalFlow_CXOF.cpp @@ -98,7 +98,7 @@ void AP_OpticalFlow_CXOF::update(void) // record gyro values as long as they are being used // the sanity check of dt below ensures old gyro values are not used if (gyro_sum_count < 1000) { - const Vector3f& gyro = AP::ahrs_navekf().get_gyro(); + const Vector3f& gyro = AP::ahrs().get_gyro(); gyro_sum.x += gyro.x; gyro_sum.y += gyro.y; gyro_sum_count++; diff --git a/libraries/AP_OpticalFlow/AP_OpticalFlow_Pixart.cpp b/libraries/AP_OpticalFlow/AP_OpticalFlow_Pixart.cpp index 4ca794d555..f0d1d5c64d 100644 --- a/libraries/AP_OpticalFlow/AP_OpticalFlow_Pixart.cpp +++ b/libraries/AP_OpticalFlow/AP_OpticalFlow_Pixart.cpp @@ -285,7 +285,7 @@ void AP_OpticalFlow_Pixart::timer(void) uint32_t dt_us = last_burst_us - integral.last_frame_us; float dt = dt_us * 1.0e-6; - const Vector3f &gyro = AP::ahrs_navekf().get_gyro(); + const Vector3f &gyro = AP::ahrs().get_gyro(); { WITH_SEMAPHORE(_sem); diff --git a/libraries/AP_OpticalFlow/AP_OpticalFlow_UPFLOW.cpp b/libraries/AP_OpticalFlow/AP_OpticalFlow_UPFLOW.cpp index a1a28d14ed..d3dc8f6463 100644 --- a/libraries/AP_OpticalFlow/AP_OpticalFlow_UPFLOW.cpp +++ b/libraries/AP_OpticalFlow/AP_OpticalFlow_UPFLOW.cpp @@ -100,7 +100,7 @@ void AP_OpticalFlow_UPFLOW::update(void) gyro_sum.zero(); gyro_sum_count = 0; } - const Vector3f& gyro = AP::ahrs_navekf().get_gyro(); + const Vector3f& gyro = AP::ahrs().get_gyro(); gyro_sum.x += gyro.x; gyro_sum.y += gyro.y; gyro_sum_count++; diff --git a/libraries/AP_OpticalFlow/OpticalFlow.cpp b/libraries/AP_OpticalFlow/OpticalFlow.cpp index ddc0982e7e..211628e9c9 100644 --- a/libraries/AP_OpticalFlow/OpticalFlow.cpp +++ b/libraries/AP_OpticalFlow/OpticalFlow.cpp @@ -203,11 +203,11 @@ void OpticalFlow::update_state(const OpticalFlow_state &state) _last_update_ms = AP_HAL::millis(); // write to log and send to EKF if new data has arrived - AP::ahrs_navekf().writeOptFlowMeas(quality(), - _state.flowRate, - _state.bodyRate, - _last_update_ms, - get_pos_offset()); + AP::ahrs().writeOptFlowMeas(quality(), + _state.flowRate, + _state.bodyRate, + _last_update_ms, + get_pos_offset()); Log_Write_Optflow(); } diff --git a/libraries/AP_OpticalFlow/OpticalFlow.h b/libraries/AP_OpticalFlow/OpticalFlow.h index c4384f9389..8ea4ef6f35 100644 --- a/libraries/AP_OpticalFlow/OpticalFlow.h +++ b/libraries/AP_OpticalFlow/OpticalFlow.h @@ -30,7 +30,7 @@ #endif class OpticalFlow_backend; -class AP_AHRS_NavEKF; +class AP_AHRS; class OpticalFlow { diff --git a/libraries/AP_OpticalFlow/examples/AP_OpticalFlow_test/AP_OpticalFlow_test.cpp b/libraries/AP_OpticalFlow/examples/AP_OpticalFlow_test/AP_OpticalFlow_test.cpp index fb7e4d97a0..e6b59c1e39 100644 --- a/libraries/AP_OpticalFlow/examples/AP_OpticalFlow_test/AP_OpticalFlow_test.cpp +++ b/libraries/AP_OpticalFlow/examples/AP_OpticalFlow_test/AP_OpticalFlow_test.cpp @@ -27,7 +27,7 @@ public: AP_InertialSensor ins; AP_SerialManager serial_manager; RangeFinder sonar; - AP_AHRS_NavEKF ahrs{AP_AHRS_NavEKF::FLAG_ALWAYS_USE_EKF}; + AP_AHRS ahrs{AP_AHRS::FLAG_ALWAYS_USE_EKF}; }; static DummyVehicle vehicle;