AP_AHRS: rename ins get_primary_accel to get_first_usable_accel

This commit is contained in:
Peter Barker 2024-06-25 19:05:25 +10:00 committed by Andrew Tridgell
parent b45b07d539
commit a325ddbfa9
2 changed files with 7 additions and 7 deletions

View File

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

View File

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