mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
AP_NavEKF2: Fix casting build error
This commit is contained in:
parent
53df8a0238
commit
6952d83f00
@ -240,8 +240,8 @@ void NavEKF2_core::setAidingMode()
|
||||
}
|
||||
posAidLossCritical = (imuSampleTime_ms - lastRngBcnPassTime_ms > maxLossTime_ms) &&
|
||||
(imuSampleTime_ms - lastPosPassTime_ms > maxLossTime_ms);
|
||||
posAidLossPending = (imuSampleTime_ms - lastRngBcnPassTime_ms > frontend->_gsfResetDelay) &&
|
||||
(imuSampleTime_ms - lastPosPassTime_ms > frontend->_gsfResetDelay);
|
||||
posAidLossPending = (imuSampleTime_ms - lastRngBcnPassTime_ms > (uint32_t)frontend->_gsfResetDelay) &&
|
||||
(imuSampleTime_ms - lastPosPassTime_ms > (uint32_t)frontend->_gsfResetDelay);
|
||||
}
|
||||
|
||||
if (attAidLossCritical) {
|
||||
|
Loading…
Reference in New Issue
Block a user