AP_AHRS: punt to correct parent class when no index for getCorrectedDeltaVelocityNED

This commit is contained in:
Peter Barker 2021-07-21 12:08:10 +10:00 committed by Peter Barker
parent b450a96698
commit a6a18fe193

View File

@ -1986,7 +1986,7 @@ void AP_AHRS::getCorrectedDeltaVelocityNED(Vector3f& ret, float& dt) const
#endif
}
if (imu_idx == -1) {
AP_AHRS::getCorrectedDeltaVelocityNED(ret, dt);
AP_AHRS_DCM::getCorrectedDeltaVelocityNED(ret, dt);
return;
}
ret.zero();