mirror of https://github.com/ArduPilot/ardupilot
AP_NavEKF3: include writeWheelOdom symbol even if no body-odom
like the method above it, we need this symbol or we won't compile
This commit is contained in:
parent
a9a40242af
commit
2af6a05fa2
|
@ -137,9 +137,9 @@ void NavEKF3_core::writeBodyFrameOdom(float quality, const Vector3f &delPos, con
|
|||
#endif // EK3_FEATURE_BODY_ODOM
|
||||
}
|
||||
|
||||
#if EK3_FEATURE_BODY_ODOM
|
||||
void NavEKF3_core::writeWheelOdom(float delAng, float delTime, uint32_t timeStamp_ms, const Vector3f &posOffset, float radius)
|
||||
{
|
||||
#if EK3_FEATURE_BODY_ODOM
|
||||
// This is a simple hack to get wheel encoder data into the EKF and verify the interface sign conventions and units
|
||||
// It uses the exisiting body frame velocity fusion.
|
||||
// TODO implement a dedicated wheel odometry observation model
|
||||
|
@ -162,8 +162,8 @@ void NavEKF3_core::writeWheelOdom(float delAng, float delTime, uint32_t timeStam
|
|||
wheelOdmDataNew.time_ms = timeStamp_ms - (uint32_t)(500.0f * delTime);
|
||||
|
||||
storedWheelOdm.push(wheelOdmDataNew);
|
||||
}
|
||||
#endif // EK3_FEATURE_BODY_ODOM
|
||||
}
|
||||
|
||||
// write the raw optical flow measurements
|
||||
// this needs to be called externally.
|
||||
|
|
Loading…
Reference in New Issue