mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
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:
parent
e4eda95fea
commit
1e2ef205de
@ -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;
|
||||
|
Loading…
Reference in New Issue
Block a user