mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_ChibiOS: define AP_INERTIALSENSOR_ENABLED in a new AP_InertialSensor_config.h
This commit is contained in:
parent
8de4195ffc
commit
de54bcbc21
|
@ -2968,6 +2968,12 @@ def add_apperiph_defaults(f):
|
||||||
#ifndef RANGEFINDER_MAX_INSTANCES
|
#ifndef RANGEFINDER_MAX_INSTANCES
|
||||||
#define RANGEFINDER_MAX_INSTANCES 1
|
#define RANGEFINDER_MAX_INSTANCES 1
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
// by default AP_Periphs don't use INS:
|
||||||
|
#ifndef AP_INERTIALSENSOR_ENABLED
|
||||||
|
#define AP_INERTIALSENSOR_ENABLED 0
|
||||||
|
#endif
|
||||||
|
|
||||||
''')
|
''')
|
||||||
|
|
||||||
def add_bootloader_defaults(f):
|
def add_bootloader_defaults(f):
|
||||||
|
@ -2991,6 +2997,11 @@ def add_bootloader_defaults(f):
|
||||||
#define HAL_GCS_ENABLED 0
|
#define HAL_GCS_ENABLED 0
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
// by default bootloaders don't use INS:
|
||||||
|
#ifndef AP_INERTIALSENSOR_ENABLED
|
||||||
|
#define AP_INERTIALSENSOR_ENABLED 0
|
||||||
|
#endif
|
||||||
|
|
||||||
#define HAL_MAX_CAN_PROTOCOL_DRIVERS 0
|
#define HAL_MAX_CAN_PROTOCOL_DRIVERS 0
|
||||||
''')
|
''')
|
||||||
|
|
||||||
|
@ -3010,6 +3021,11 @@ def add_iomcu_firmware_defaults(f):
|
||||||
#ifndef HAL_GYROFFT_ENABLED
|
#ifndef HAL_GYROFFT_ENABLED
|
||||||
#define HAL_GYROFFT_ENABLED 0
|
#define HAL_GYROFFT_ENABLED 0
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
// by default IOMCUs don't use INS:
|
||||||
|
#ifndef AP_INERTIALSENSOR_ENABLED
|
||||||
|
#define AP_INERTIALSENSOR_ENABLED 0
|
||||||
|
#endif
|
||||||
''')
|
''')
|
||||||
|
|
||||||
def add_normal_firmware_defaults(f):
|
def add_normal_firmware_defaults(f):
|
||||||
|
|
Loading…
Reference in New Issue