From a325ddbfa980d7e0703c66d64cee559afd5f8bf0 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 25 Jun 2024 19:05:25 +1000 Subject: [PATCH] AP_AHRS: rename ins get_primary_accel to get_first_usable_accel --- libraries/AP_AHRS/AP_AHRS.cpp | 10 +++++----- libraries/AP_AHRS/AP_AHRS_Backend.h | 4 ++-- 2 files changed, 7 insertions(+), 7 deletions(-) diff --git a/libraries/AP_AHRS/AP_AHRS.cpp b/libraries/AP_AHRS/AP_AHRS.cpp index 8b7c1faa0c..c87382d5d3 100644 --- a/libraries/AP_AHRS/AP_AHRS.cpp +++ b/libraries/AP_AHRS/AP_AHRS.cpp @@ -591,8 +591,8 @@ void AP_AHRS::update_EKF2(void) // Use the primary EKF to select the primary gyro const AP_InertialSensor &_ins = AP::ins(); const int8_t primary_imu = EKF2.getPrimaryCoreIMUIndex(); - const uint8_t primary_gyro = primary_imu>=0?primary_imu:_ins.get_primary_gyro(); - const uint8_t primary_accel = primary_imu>=0?primary_imu:_ins.get_primary_accel(); + const uint8_t primary_gyro = primary_imu>=0?primary_imu:_ins.get_first_usable_gyro(); + const uint8_t primary_accel = primary_imu>=0?primary_imu:_ins.get_first_usable_accel(); // get gyro bias for primary EKF and change sign to give gyro drift // Note sign convention used by EKF is bias = measurement - truth @@ -660,8 +660,8 @@ void AP_AHRS::update_EKF3(void) // Use the primary EKF to select the primary gyro const int8_t primary_imu = EKF3.getPrimaryCoreIMUIndex(); - const uint8_t primary_gyro = primary_imu>=0?primary_imu:_ins.get_primary_gyro(); - const uint8_t primary_accel = primary_imu>=0?primary_imu:_ins.get_primary_accel(); + const uint8_t primary_gyro = primary_imu>=0?primary_imu:_ins.get_first_usable_gyro(); + const uint8_t primary_accel = primary_imu>=0?primary_imu:_ins.get_first_usable_accel(); // get gyro bias for primary EKF and change sign to give gyro drift // Note sign convention used by EKF is bias = measurement - truth @@ -3215,7 +3215,7 @@ uint8_t AP_AHRS::_get_primary_IMU_index() const #endif } if (imu == -1) { - imu = AP::ins().get_primary_gyro(); + imu = AP::ins().get_first_usable_gyro(); } return imu; } diff --git a/libraries/AP_AHRS/AP_AHRS_Backend.h b/libraries/AP_AHRS/AP_AHRS_Backend.h index ae71df9c0a..c309084b48 100644 --- a/libraries/AP_AHRS/AP_AHRS_Backend.h +++ b/libraries/AP_AHRS/AP_AHRS_Backend.h @@ -77,7 +77,7 @@ public: // get the index of the current primary accelerometer sensor virtual uint8_t get_primary_accel_index(void) const { #if AP_INERTIALSENSOR_ENABLED - return AP::ins().get_primary_accel(); + return AP::ins().get_first_usable_accel(); #else return 0; #endif @@ -86,7 +86,7 @@ public: // get the index of the current primary gyro sensor virtual uint8_t get_primary_gyro_index(void) const { #if AP_INERTIALSENSOR_ENABLED - return AP::ins().get_primary_gyro(); + return AP::ins().get_first_usable_gyro(); #else return 0; #endif