AP_InertialSensor: default fast sampling on

if we have a first IMU capable of fast sampling then we want it
enabled by default
This commit is contained in:
Andrew Tridgell 2019-12-23 08:38:57 +11:00 committed by Randy Mackay
parent e4eda95fea
commit 1e2ef205de

View File

@ -34,7 +34,7 @@
#endif
#ifndef HAL_DEFAULT_INS_FAST_SAMPLE
#define HAL_DEFAULT_INS_FAST_SAMPLE 0
#define HAL_DEFAULT_INS_FAST_SAMPLE 1
#endif
extern const AP_HAL::HAL& hal;