AP_NavEKF3: rename ins get_primary_accel to get_first_usable_accel

This commit is contained in:
Peter Barker 2024-06-25 19:05:26 +10:00 committed by Andrew Tridgell
parent 025888a7d1
commit 563c3e7c62

View File

@ -387,13 +387,13 @@ void NavEKF3_core::readIMUData()
if (ins.use_accel(imu_index)) { if (ins.use_accel(imu_index)) {
accel_active = imu_index; accel_active = imu_index;
} else { } else {
accel_active = ins.get_primary_accel(); accel_active = ins.get_first_usable_accel();
} }
if (ins.use_gyro(imu_index)) { if (ins.use_gyro(imu_index)) {
gyro_active = imu_index; gyro_active = imu_index;
} else { } else {
gyro_active = ins.get_primary_gyro(); gyro_active = ins.get_first_usable_gyro();
} }
if (gyro_active != gyro_index_active) { if (gyro_active != gyro_index_active) {