AP_HAL: move defaulting of HAL_DSHOT_ALARM into hwdef

This commit is contained in:
Peter Barker 2022-08-15 15:27:28 +10:00 committed by Peter Barker
parent 28a0336423
commit 0f49b7f3ab
4 changed files with 4 additions and 10 deletions

View File

@ -285,6 +285,10 @@
#define AP_SIGNED_FIRMWARE 0
#endif
#ifndef HAL_DSHOT_ALARM_ENABLED
#define HAL_DSHOT_ALARM_ENABLED 0
#endif
#ifndef HAL_HNF_MAX_FILTERS
// On an F7 The difference in CPU load between 1 notch and 24 notches is about 2%
// The difference in CPU load between 1Khz backend and 2Khz backend is about 10%

View File

@ -111,14 +111,6 @@
#define HAL_SUPPORT_RCOUT_SERIAL !defined(HAL_BUILD_AP_PERIPH)
#endif
#ifndef HAL_DSHOT_ALARM
#if !defined(HAL_BUILD_AP_PERIPH) && !defined(HAL_BOOTLOADER_BUILD) && HAL_PWM_COUNT > 0
#define HAL_DSHOT_ALARM 1
#else
#define HAL_DSHOT_ALARM 0
#endif
#endif
// by default assume first I2C bus is internal
#ifndef HAL_I2C_INTERNAL_MASK
#define HAL_I2C_INTERNAL_MASK 1

View File

@ -7,7 +7,6 @@
#define HAL_OS_SOCKETS 1
#define HAL_STORAGE_SIZE 16384
#define HAL_STORAGE_SIZE_AVAILABLE HAL_STORAGE_SIZE
#define HAL_DSHOT_ALARM 0
// make sensor selection clearer
#define PROBE_IMU_I2C(driver, bus, addr, args ...) ADD_BACKEND(AP_InertialSensor_ ## driver::probe(*this,GET_I2C_DEVICE(bus, addr),##args))

View File

@ -5,7 +5,6 @@
#define HAL_MEM_CLASS HAL_MEM_CLASS_1000
#define HAL_OS_POSIX_IO 1
#define HAL_OS_SOCKETS 1
#define HAL_DSHOT_ALARM 0
#define HAL_WITH_ESC_TELEM 1
#define AP_FLASHSTORAGE_TYPE 3