mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 14:48:28 -04:00
AP_NavEKF3: fixed build of standalone replay link test
parameter conversion not needed for replay
This commit is contained in:
parent
3366ee9496
commit
7eea13f86f
@ -680,8 +680,10 @@ bool NavEKF3::InitialiseFilter(void)
|
|||||||
// expected number of IMU frames per prediction
|
// expected number of IMU frames per prediction
|
||||||
_framesPerPrediction = uint8_t((EKF_TARGET_DT / (_frameTimeUsec * 1.0e-6) + 0.5));
|
_framesPerPrediction = uint8_t((EKF_TARGET_DT / (_frameTimeUsec * 1.0e-6) + 0.5));
|
||||||
|
|
||||||
|
#if !APM_BUILD_TYPE(APM_BUILD_AP_DAL_Standalone)
|
||||||
// convert parameters if necessary
|
// convert parameters if necessary
|
||||||
convert_parameters();
|
convert_parameters();
|
||||||
|
#endif
|
||||||
|
|
||||||
// initialise sources
|
// initialise sources
|
||||||
sources.init();
|
sources.init();
|
||||||
|
Loading…
Reference in New Issue
Block a user