mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 21:48:28 -04:00
AP_HAL_ChibiOS: specify AP_STATS_ENABLED for periph in chibios_hwdef.py
This commit is contained in:
parent
806f0bf97a
commit
18b574a400
@ -2897,6 +2897,10 @@ def add_apperiph_defaults(f):
|
|||||||
#define AP_AIRSPEED_AUTOCAL_ENABLE 0
|
#define AP_AIRSPEED_AUTOCAL_ENABLE 0
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#ifndef AP_STATS_ENABLED
|
||||||
|
#define AP_STATS_ENABLED 0
|
||||||
|
#endif
|
||||||
|
|
||||||
#ifndef AP_VOLZ_ENABLED
|
#ifndef AP_VOLZ_ENABLED
|
||||||
#define AP_VOLZ_ENABLED 0
|
#define AP_VOLZ_ENABLED 0
|
||||||
#endif
|
#endif
|
||||||
|
Loading…
Reference in New Issue
Block a user