AP_NavEKF3: Fix bug in wheel odometry timestamp correction

This commit is contained in:
priseborough 2017-07-28 11:29:49 +10:00 committed by Randy Mackay
parent d6d12a8cb1
commit db7c8439c6
1 changed files with 1 additions and 2 deletions

View File

@ -144,12 +144,11 @@ void NavEKF3_core::writeWheelOdom(float delAng, float delTime, uint32_t timeStam
wheelOdmDataNew.delAng = delAng;
wheelOdmDataNew.radius = radius;
wheelOdmDataNew.delTime = delTime;
wheelOdmDataNew.time_ms = timeStamp_ms - (uint32_t)(500.0f * delTime);
wheelOdmMeasTime_ms = timeStamp_ms;
// becasue we are currently converting to an equivalent velocity measurement before fusing
// the measurement time is moved back to the middle of the sampling period
wheelOdmDataNew.time_ms -= (uint32_t)(500.0f * delTime);
wheelOdmDataNew.time_ms = timeStamp_ms - (uint32_t)(500.0f * delTime);
storedWheelOdm.push(wheelOdmDataNew);