mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
AP_NavEKF2: handle uncertain build type
This commit is contained in:
parent
e6312d91ce
commit
aabb9b4e02
@ -50,8 +50,10 @@
|
||||
#define IMU_BUFFER_LENGTH 104 // maximum 260 msec delay at 400 Hz
|
||||
#elif APM_BUILD_TYPE(APM_BUILD_APMrover2)
|
||||
#define IMU_BUFFER_LENGTH 13 // maximum 260 msec delay at 50 Hz
|
||||
#else
|
||||
#elif APM_BUILD_TYPE(APM_BUILD_ArduPlane)
|
||||
#define IMU_BUFFER_LENGTH 13 // maximum 260 msec delay at 50 Hz
|
||||
#else
|
||||
#define IMU_BUFFER_LENGTH 104 // unknown so use max buffer length
|
||||
#endif
|
||||
|
||||
class AP_AHRS;
|
||||
|
Loading…
Reference in New Issue
Block a user