5
0
mirror of https://github.com/ArduPilot/ardupilot synced 2025-01-05 23:48:31 -04:00

AP_NavEKF2: 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 8302e0d1e2
commit 025888a7d1

View File

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