hwdef: replace defined(HAL_DISABLE_LOOP_DELAY) with HAL_SCHEDULER_LOOP_DELAY_ENABLED
This commit is contained in:
parent
764f6863ea
commit
5fb4e1e285
@ -44,6 +44,10 @@
|
||||
#define SERIAL0_BAUD DEFAULT_SERIAL0_BAUD
|
||||
#endif
|
||||
|
||||
#ifndef HAL_SCHEDULER_LOOP_DELAY_ENABLED
|
||||
#define HAL_SCHEDULER_LOOP_DELAY_ENABLED 1
|
||||
#endif
|
||||
|
||||
#ifndef HAL_NO_UARTDRIVER
|
||||
static HAL_SERIAL0_DRIVER;
|
||||
static HAL_SERIAL1_DRIVER;
|
||||
@ -296,6 +300,7 @@ static void main_loop()
|
||||
while (true) {
|
||||
g_callbacks->loop();
|
||||
|
||||
#if HAL_SCHEDULER_LOOP_DELAY_ENABLED && !APM_BUILD_TYPE(APM_BUILD_Replay)
|
||||
/*
|
||||
give up 50 microseconds of time if the INS loop hasn't
|
||||
called delay_microseconds_boost(), to ensure low priority
|
||||
@ -304,7 +309,6 @@ static void main_loop()
|
||||
time from the main loop, so we don't need to do it again
|
||||
here
|
||||
*/
|
||||
#if !defined(HAL_DISABLE_LOOP_DELAY) && !APM_BUILD_TYPE(APM_BUILD_Replay)
|
||||
if (!schedulerInstance.check_called_boost()) {
|
||||
hal.scheduler->delay_microseconds(50);
|
||||
}
|
||||
|
@ -30,8 +30,6 @@ PC13 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW HIGH
|
||||
|
||||
CAN_ORDER 1
|
||||
|
||||
define HAL_DISABLE_LOOP_DELAY
|
||||
|
||||
define HAL_NO_MONITOR_THREAD
|
||||
|
||||
# debugger support
|
||||
|
@ -130,3 +130,4 @@ define HAL_PERIPH_ENABLE_RANGEFINDER
|
||||
define AP_PERIPH_RANGEFINDER_PORT_DEFAULT -1
|
||||
|
||||
define HAL_RCIN_THREAD_ENABLED 1
|
||||
define HAL_SCHEDULER_LOOP_DELAY_ENABLED 1
|
||||
|
@ -54,8 +54,6 @@ define HAL_NO_TIMER_THREAD
|
||||
|
||||
define DMA_RESERVE_SIZE 0
|
||||
|
||||
define HAL_DISABLE_LOOP_DELAY
|
||||
|
||||
# enable CAN support
|
||||
PA11 CAN1_RX CAN1
|
||||
PA12 CAN1_TX CAN1
|
||||
|
@ -123,3 +123,4 @@ define HAL_PERIPH_GPS_PORT_DEFAULT 1
|
||||
|
||||
define HAL_SERIAL_ESC_COMM_ENABLED 1
|
||||
define HAL_RCIN_THREAD_ENABLED 1
|
||||
define HAL_SCHEDULER_LOOP_DELAY_ENABLED 1
|
||||
|
@ -54,8 +54,6 @@ define HAL_NO_TIMER_THREAD
|
||||
|
||||
define DMA_RESERVE_SIZE 0
|
||||
|
||||
define HAL_DISABLE_LOOP_DELAY
|
||||
|
||||
# enable CAN support
|
||||
PA11 CAN1_RX CAN1
|
||||
PA12 CAN1_TX CAN1
|
||||
|
@ -134,3 +134,4 @@ define HAL_PERIPH_GPS_PORT_DEFAULT 1
|
||||
|
||||
define HAL_SERIAL_ESC_COMM_ENABLED 1
|
||||
define HAL_RCIN_THREAD_ENABLED 1
|
||||
define HAL_SCHEDULER_LOOP_DELAY_ENABLED 1
|
||||
|
@ -35,7 +35,6 @@ define DMA_RESERVE_SIZE 0
|
||||
MAIN_STACK 0x800
|
||||
PROCESS_STACK 0x800
|
||||
|
||||
define HAL_DISABLE_LOOP_DELAY
|
||||
PA13 JTMS-SWDIO SWD
|
||||
PA14 JTCK-SWCLK SWD
|
||||
|
||||
|
@ -32,7 +32,6 @@ MAIN_STACK 0x300
|
||||
|
||||
# PROCESS_STACK controls stack for main thread
|
||||
PROCESS_STACK 0xA00
|
||||
define HAL_DISABLE_LOOP_DELAY
|
||||
define HAL_NO_MONITOR_THREAD
|
||||
|
||||
# we setup a small defaults.parm
|
||||
|
@ -33,6 +33,5 @@ define DMA_RESERVE_SIZE 0
|
||||
MAIN_STACK 0x800
|
||||
PROCESS_STACK 0x800
|
||||
|
||||
define HAL_DISABLE_LOOP_DELAY
|
||||
PA13 JTMS-SWDIO SWD
|
||||
PA14 JTCK-SWCLK SWD
|
||||
PA14 JTCK-SWCLK SWD
|
||||
|
@ -36,8 +36,6 @@ MAIN_STACK 0x300
|
||||
# PROCESS_STACK controls stack for main thread
|
||||
PROCESS_STACK 0xA00
|
||||
|
||||
define HAL_DISABLE_LOOP_DELAY
|
||||
|
||||
define HAL_NO_MONITOR_THREAD
|
||||
|
||||
# setup a small defaults.parm
|
||||
|
@ -59,8 +59,6 @@ define HAL_NO_TIMER_THREAD
|
||||
|
||||
define DMA_RESERVE_SIZE 0
|
||||
|
||||
define HAL_DISABLE_LOOP_DELAY
|
||||
|
||||
# enable CAN support
|
||||
PB8 CAN1_RX CAN1
|
||||
PB9 CAN1_TX CAN1
|
||||
|
@ -84,9 +84,6 @@ define HAL_USE_RTC FALSE
|
||||
|
||||
define DMA_RESERVE_SIZE 0
|
||||
|
||||
|
||||
define HAL_DISABLE_LOOP_DELAY
|
||||
|
||||
# enable CAN support
|
||||
PB8 CAN1_RX CAN1
|
||||
PB9 CAN1_TX CAN1
|
||||
|
@ -87,3 +87,4 @@ define STM32_ADC_USE_ADC2 FALSE
|
||||
define STM32_ADC_USE_ADC3 FALSE
|
||||
|
||||
define HAL_RCIN_THREAD_ENABLED 1
|
||||
define HAL_SCHEDULER_LOOP_DELAY_ENABLED 1
|
||||
|
@ -60,8 +60,6 @@ define HAL_NO_TIMER_THREAD
|
||||
|
||||
define DMA_RESERVE_SIZE 0
|
||||
|
||||
define HAL_DISABLE_LOOP_DELAY
|
||||
|
||||
# enable CAN support
|
||||
PB8 CAN1_RX CAN1
|
||||
PB9 CAN1_TX CAN1
|
||||
|
@ -76,8 +76,6 @@ define HAL_USE_RTC FALSE
|
||||
|
||||
define DMA_RESERVE_SIZE 0
|
||||
|
||||
define HAL_DISABLE_LOOP_DELAY
|
||||
|
||||
# enable CAN support
|
||||
PB8 CAN1_RX CAN1
|
||||
PB9 CAN1_TX CAN1
|
||||
|
@ -60,8 +60,6 @@ define HAL_NO_TIMER_THREAD
|
||||
|
||||
define DMA_RESERVE_SIZE 0
|
||||
|
||||
define HAL_DISABLE_LOOP_DELAY
|
||||
|
||||
# enable CAN support
|
||||
PB8 CAN1_RX CAN1
|
||||
PB9 CAN1_TX CAN1
|
||||
|
@ -114,9 +114,6 @@ define HAL_USE_RTC FALSE
|
||||
|
||||
define DMA_RESERVE_SIZE 0
|
||||
|
||||
|
||||
define HAL_DISABLE_LOOP_DELAY
|
||||
|
||||
# enable CAN support
|
||||
PB8 CAN1_RX CAN1
|
||||
PB9 CAN1_TX CAN1
|
||||
|
@ -54,8 +54,6 @@ define DMA_RESERVE_SIZE 0
|
||||
MAIN_STACK 0x800
|
||||
PROCESS_STACK 0x800
|
||||
|
||||
define HAL_DISABLE_LOOP_DELAY
|
||||
|
||||
# enable CAN support
|
||||
PB8 CAN1_RX CAN1
|
||||
PB9 CAN1_TX CAN1
|
||||
|
@ -93,8 +93,6 @@ MAIN_STACK 0x300
|
||||
# PROCESS_STACK controls stack for main thread
|
||||
PROCESS_STACK 0xA00
|
||||
|
||||
define HAL_DISABLE_LOOP_DELAY
|
||||
|
||||
# enable CAN support
|
||||
PB8 CAN1_RX CAN1
|
||||
PB9 CAN1_TX CAN1
|
||||
|
@ -54,8 +54,6 @@ define DMA_RESERVE_SIZE 0
|
||||
MAIN_STACK 0x800
|
||||
PROCESS_STACK 0x800
|
||||
|
||||
define HAL_DISABLE_LOOP_DELAY
|
||||
|
||||
# enable CAN support
|
||||
PB8 CAN1_RX CAN1
|
||||
PB9 CAN1_TX CAN1
|
||||
|
@ -96,8 +96,6 @@ MAIN_STACK 0x300
|
||||
# PROCESS_STACK controls stack for main thread
|
||||
PROCESS_STACK 0xA00
|
||||
|
||||
define HAL_DISABLE_LOOP_DELAY
|
||||
|
||||
# enable CAN support
|
||||
PB8 CAN1_RX CAN1
|
||||
PB9 CAN1_TX CAN1
|
||||
|
@ -37,8 +37,6 @@ define HAL_COMPASS_MAX_SENSORS 1
|
||||
|
||||
define HAL_NO_MONITOR_THREAD
|
||||
|
||||
define HAL_DISABLE_LOOP_DELAY
|
||||
|
||||
define HAL_USE_RTC FALSE
|
||||
|
||||
define HAL_BARO_ALLOW_INIT_NO_BARO
|
||||
|
@ -34,8 +34,6 @@ define HAL_COMPASS_MAX_SENSORS 1
|
||||
|
||||
define HAL_NO_MONITOR_THREAD
|
||||
|
||||
define HAL_DISABLE_LOOP_DELAY
|
||||
|
||||
define HAL_USE_RTC FALSE
|
||||
|
||||
define HAL_GCS_ENABLED 1
|
||||
|
@ -33,8 +33,6 @@ define HAL_COMPASS_MAX_SENSORS 1
|
||||
|
||||
define HAL_NO_MONITOR_THREAD
|
||||
|
||||
define HAL_DISABLE_LOOP_DELAY
|
||||
|
||||
define HAL_USE_RTC FALSE
|
||||
|
||||
define HAL_BARO_ALLOW_INIT_NO_BARO
|
||||
|
@ -72,12 +72,6 @@ define BOARD_PHY_ID MII_LAN8720_ID
|
||||
define BOARD_PHY_RMII
|
||||
define HAL_PERIPH_ENABLE_NETWORKING
|
||||
|
||||
# ---------------------------------------------------------------------------------------------
|
||||
# AP_Periph - boiler-plate configurations that all HW AP-Periph need
|
||||
# ---------------------------------------------------------------------------------------------
|
||||
#define HAL_NO_GPIO_IRQ
|
||||
define HAL_DISABLE_LOOP_DELAY
|
||||
|
||||
#################################
|
||||
# AP_Periph - configurations specific to this App
|
||||
#################################
|
||||
|
@ -24,7 +24,6 @@ define HAL_PERIPH_ENABLE_SERIAL_OPTIONS
|
||||
define AP_NETWORKING_BACKEND_PPP 1
|
||||
|
||||
define HAL_NO_MONITOR_THREAD
|
||||
define HAL_DISABLE_LOOP_DELAY
|
||||
|
||||
define HAL_USE_RTC FALSE
|
||||
|
||||
|
@ -56,8 +56,6 @@ define HAL_NO_TIMER_THREAD
|
||||
|
||||
define DMA_RESERVE_SIZE 0
|
||||
|
||||
define HAL_DISABLE_LOOP_DELAY
|
||||
|
||||
# enable CAN support
|
||||
PB8 CAN1_RX CAN1
|
||||
PB9 CAN1_TX CAN1
|
||||
|
@ -106,8 +106,6 @@ define HAL_NO_GPIO_IRQ
|
||||
|
||||
define DMA_RESERVE_SIZE 0
|
||||
|
||||
define HAL_DISABLE_LOOP_DELAY
|
||||
|
||||
# enable CAN support
|
||||
PB8 CAN1_RX CAN1
|
||||
PB9 CAN1_TX CAN1
|
||||
|
@ -52,8 +52,6 @@ define DMA_RESERVE_SIZE 0
|
||||
MAIN_STACK 0x800
|
||||
PROCESS_STACK 0x800
|
||||
|
||||
define HAL_DISABLE_LOOP_DELAY
|
||||
|
||||
# enable CAN support
|
||||
PB5 CAN2_RX CAN2
|
||||
PB6 CAN2_TX CAN2
|
||||
|
@ -100,8 +100,6 @@ MAIN_STACK 0x300
|
||||
# PROCESS_STACK controls stack for main thread
|
||||
PROCESS_STACK 0xA00
|
||||
|
||||
define HAL_DISABLE_LOOP_DELAY
|
||||
|
||||
# enable CAN support
|
||||
PB5 CAN2_RX CAN2
|
||||
PB6 CAN2_TX CAN2
|
||||
|
@ -135,3 +135,4 @@ define HAL_PERIPH_ENABLE_NOTIFY
|
||||
|
||||
define HAL_SERIAL_ESC_COMM_ENABLED 1
|
||||
define HAL_RCIN_THREAD_ENABLED 1
|
||||
define HAL_SCHEDULER_LOOP_DELAY_ENABLED 1
|
||||
|
@ -39,8 +39,6 @@ define DMA_RESERVE_SIZE 0
|
||||
MAIN_STACK 0x800
|
||||
PROCESS_STACK 0x800
|
||||
|
||||
define HAL_DISABLE_LOOP_DELAY
|
||||
|
||||
# enable CAN support
|
||||
PA11 CAN1_RX CAN1
|
||||
PA12 CAN1_TX CAN1
|
||||
|
@ -71,8 +71,6 @@ MAIN_STACK 0x300
|
||||
# PROCESS_STACK controls stack for main thread
|
||||
PROCESS_STACK 0xA00
|
||||
|
||||
define HAL_DISABLE_LOOP_DELAY
|
||||
|
||||
# enable CAN support
|
||||
PA11 CAN1_RX CAN1
|
||||
PA12 CAN1_TX CAN1
|
||||
|
@ -61,7 +61,6 @@ define DMA_RESERVE_SIZE 0
|
||||
|
||||
MAIN_STACK 0x800
|
||||
PROCESS_STACK 0x800
|
||||
define HAL_DISABLE_LOOP_DELAY
|
||||
|
||||
# enable CAN support
|
||||
PB8 CAN_RX CAN
|
||||
|
@ -88,8 +88,6 @@ MAIN_STACK 0x300
|
||||
# PROCESS_STACK controls stack for main thread
|
||||
PROCESS_STACK 0xA00
|
||||
|
||||
define HAL_DISABLE_LOOP_DELAY
|
||||
|
||||
# enable CAN support
|
||||
PB8 CAN_RX CAN
|
||||
PB9 CAN_TX CAN
|
||||
|
@ -59,8 +59,6 @@ define HAL_NO_TIMER_THREAD
|
||||
|
||||
define DMA_RESERVE_SIZE 0
|
||||
|
||||
define HAL_DISABLE_LOOP_DELAY
|
||||
|
||||
# enable CAN support
|
||||
|
||||
PA11 CAN1_RX CAN1
|
||||
|
@ -76,8 +76,6 @@ define HAL_USE_RTC FALSE
|
||||
|
||||
define DMA_RESERVE_SIZE 0
|
||||
|
||||
define HAL_DISABLE_LOOP_DELAY
|
||||
|
||||
# enable CAN support
|
||||
PA11 CAN1_RX CAN1
|
||||
PA12 CAN1_TX CAN1
|
||||
|
@ -59,8 +59,6 @@ define HAL_NO_TIMER_THREAD
|
||||
|
||||
define DMA_RESERVE_SIZE 0
|
||||
|
||||
define HAL_DISABLE_LOOP_DELAY
|
||||
|
||||
# enable CAN support
|
||||
|
||||
PA11 CAN1_RX CAN1
|
||||
|
@ -99,8 +99,6 @@ define HAL_USE_RTC FALSE
|
||||
|
||||
define DMA_RESERVE_SIZE 0
|
||||
|
||||
define HAL_DISABLE_LOOP_DELAY
|
||||
|
||||
# enable CAN support
|
||||
|
||||
PA11 CAN1_RX CAN1
|
||||
|
@ -58,8 +58,6 @@ define HAL_NO_TIMER_THREAD
|
||||
|
||||
define DMA_RESERVE_SIZE 0
|
||||
|
||||
define HAL_DISABLE_LOOP_DELAY
|
||||
|
||||
# enable CAN support
|
||||
|
||||
PA11 CAN1_RX CAN1
|
||||
|
@ -116,9 +116,6 @@ define HAL_USE_RTC FALSE
|
||||
|
||||
define DMA_RESERVE_SIZE 0
|
||||
|
||||
|
||||
define HAL_DISABLE_LOOP_DELAY
|
||||
|
||||
# enable CAN support
|
||||
|
||||
PA11 CAN1_RX CAN1
|
||||
|
@ -41,7 +41,6 @@ define HAL_PERIPH_ADSB_PORT_DEFAULT 3
|
||||
define HAL_PERIPH_ADSB_BAUD_DEFAULT 0
|
||||
|
||||
define HAL_NO_MONITOR_THREAD
|
||||
define HAL_DISABLE_LOOP_DELAY
|
||||
define HAL_USE_RTC FALSE
|
||||
|
||||
define AP_SCRIPTING_ENABLED 0
|
||||
|
@ -49,8 +49,6 @@ define DMA_RESERVE_SIZE 0
|
||||
MAIN_STACK 0x800
|
||||
PROCESS_STACK 0x800
|
||||
|
||||
define HAL_DISABLE_LOOP_DELAY
|
||||
|
||||
# Add CS pins to ensure they are high in bootloader
|
||||
PA4 MAG_CS CS
|
||||
PB2 SPARE_CS CS
|
||||
|
@ -38,8 +38,6 @@ MAIN_STACK 0x300
|
||||
# PROCESS_STACK controls stack for main thread
|
||||
PROCESS_STACK 0xA00
|
||||
|
||||
define HAL_DISABLE_LOOP_DELAY
|
||||
|
||||
define HAL_NO_MONITOR_THREAD
|
||||
|
||||
# we setup a small defaults.parm
|
||||
|
@ -45,8 +45,6 @@ define PORT_INT_REQUIRED_STACK 64
|
||||
|
||||
define DMA_RESERVE_SIZE 0
|
||||
|
||||
define HAL_DISABLE_LOOP_DELAY
|
||||
|
||||
# debugger support
|
||||
PA13 JTMS-SWDIO SWD
|
||||
PA14 JTCK-SWCLK SWD
|
||||
|
@ -65,8 +65,6 @@ define SERIAL_BUFFERS_SIZE 512
|
||||
|
||||
define DMA_RESERVE_SIZE 2048
|
||||
|
||||
define HAL_DISABLE_LOOP_DELAY
|
||||
|
||||
define AP_PARAM_MAX_EMBEDDED_PARAM 512
|
||||
|
||||
define HAL_USE_ADC TRUE
|
||||
|
@ -52,8 +52,6 @@ define DMA_RESERVE_SIZE 0
|
||||
MAIN_STACK 0x800
|
||||
PROCESS_STACK 0x800
|
||||
|
||||
define HAL_DISABLE_LOOP_DELAY
|
||||
|
||||
# enable CAN support
|
||||
PB8 CAN1_RX CAN1
|
||||
PB9 CAN1_TX CAN1
|
||||
|
@ -77,8 +77,6 @@ MAIN_STACK 0x300
|
||||
# PROCESS_STACK controls stack for main thread
|
||||
PROCESS_STACK 0xA00
|
||||
|
||||
define HAL_DISABLE_LOOP_DELAY
|
||||
|
||||
# enable CAN support
|
||||
PB8 CAN1_RX CAN1
|
||||
PB9 CAN1_TX CAN1
|
||||
|
@ -58,8 +58,6 @@ define DMA_RESERVE_SIZE 0
|
||||
MAIN_STACK 0x800
|
||||
PROCESS_STACK 0x800
|
||||
|
||||
define HAL_DISABLE_LOOP_DELAY
|
||||
|
||||
# enable CAN support
|
||||
PB8 CAN1_RX CAN1
|
||||
PB9 CAN1_TX CAN1
|
||||
|
@ -85,8 +85,6 @@ MAIN_STACK 0x300
|
||||
# PROCESS_STACK controls stack for main thread
|
||||
PROCESS_STACK 0xA00
|
||||
|
||||
define HAL_DISABLE_LOOP_DELAY
|
||||
|
||||
# enable CAN support
|
||||
PB8 CAN1_RX CAN1
|
||||
PB9 CAN1_TX CAN1
|
||||
|
@ -25,7 +25,6 @@ define HAL_PERIPH_ENABLE_SERIAL_OPTIONS
|
||||
define AP_NETWORKING_BACKEND_PPP 1
|
||||
|
||||
define HAL_NO_MONITOR_THREAD
|
||||
define HAL_DISABLE_LOOP_DELAY
|
||||
|
||||
define HAL_USE_RTC FALSE
|
||||
|
||||
|
@ -37,8 +37,6 @@ define HAL_COMPASS_MAX_SENSORS 1
|
||||
|
||||
define HAL_NO_MONITOR_THREAD
|
||||
|
||||
define HAL_DISABLE_LOOP_DELAY
|
||||
|
||||
define HAL_USE_RTC FALSE
|
||||
|
||||
define HAL_BARO_ALLOW_INIT_NO_BARO
|
||||
|
@ -34,7 +34,6 @@ define HAL_USE_RTC FALSE
|
||||
|
||||
define DMA_RESERVE_SIZE 0
|
||||
|
||||
define HAL_DISABLE_LOOP_DELAY
|
||||
define HAL_NO_MONITOR_THREAD
|
||||
|
||||
define HAL_DEVICE_THREAD_STACK 768
|
||||
|
@ -88,7 +88,6 @@ define HAL_NO_GPIO_IRQ
|
||||
define HAL_USE_RTC FALSE
|
||||
define DMA_RESERVE_SIZE 0
|
||||
define PERIPH_FW TRUE
|
||||
define HAL_DISABLE_LOOP_DELAY
|
||||
|
||||
# enable CAN support
|
||||
PA11 CAN1_RX CAN1
|
||||
|
@ -53,8 +53,6 @@ define HAL_USE_EMPTY_IO TRUE
|
||||
|
||||
define DMA_RESERVE_SIZE 0
|
||||
|
||||
define HAL_DISABLE_LOOP_DELAY
|
||||
|
||||
# enable CAN support
|
||||
PB8 CAN1_RX CAN1
|
||||
PB9 CAN1_TX CAN1
|
||||
|
@ -98,7 +98,6 @@ define HAL_NO_GPIO_IRQ
|
||||
# avoid RCIN thread to save memory
|
||||
define HAL_USE_RTC TRUE
|
||||
define DMA_RESERVE_SIZE 0
|
||||
define HAL_DISABLE_LOOP_DELAY
|
||||
define PERIPH_FW TRUE
|
||||
|
||||
# enable CAN support
|
||||
|
@ -50,8 +50,6 @@ define DMA_RESERVE_SIZE 0
|
||||
MAIN_STACK 0x800
|
||||
PROCESS_STACK 0x800
|
||||
|
||||
define HAL_DISABLE_LOOP_DELAY
|
||||
|
||||
# enable CAN support
|
||||
PA11 CAN1_RX CAN1
|
||||
PA12 CAN1_TX CAN1
|
||||
|
@ -83,8 +83,6 @@ MAIN_STACK 0x300
|
||||
# PROCESS_STACK controls stack for main thread
|
||||
PROCESS_STACK 0xA00
|
||||
|
||||
define HAL_DISABLE_LOOP_DELAY
|
||||
|
||||
# enable CAN support
|
||||
PA11 CAN1_RX CAN1
|
||||
PA12 CAN1_TX CAN1
|
||||
|
@ -58,7 +58,6 @@ define STM32_SERIAL_USE_USART3 FALSE
|
||||
define HAL_NO_GPIO_IRQ
|
||||
define HAL_USE_EMPTY_IO TRUE
|
||||
define DMA_RESERVE_SIZE 0
|
||||
define HAL_DISABLE_LOOP_DELAY
|
||||
|
||||
# avoid timer and RCIN threads to save memory
|
||||
define HAL_NO_TIMER_THREAD
|
||||
|
@ -147,3 +147,4 @@ PC6 USB_SEL OUTPUT PUSHPULL SPEED_LOW HIGH
|
||||
|
||||
define HAL_SERIAL_ESC_COMM_ENABLED 1
|
||||
define HAL_RCIN_THREAD_ENABLED 1
|
||||
define HAL_SCHEDULER_LOOP_DELAY_ENABLED 1
|
||||
|
@ -45,8 +45,6 @@ define DMA_RESERVE_SIZE 0
|
||||
MAIN_STACK 0x800
|
||||
PROCESS_STACK 0x800
|
||||
|
||||
define HAL_DISABLE_LOOP_DELAY
|
||||
|
||||
# Add CS pins to ensure they are high in bootloader
|
||||
PA8 BARO_CS CS
|
||||
|
||||
|
@ -36,7 +36,6 @@ MAIN_STACK 0x300
|
||||
PROCESS_STACK 0xA00
|
||||
|
||||
# save memory
|
||||
define HAL_DISABLE_LOOP_DELAY
|
||||
define HAL_GCS_ENABLED 0
|
||||
define HAL_NO_MONITOR_THREAD
|
||||
define HAL_NO_LOGGING
|
||||
|
@ -34,7 +34,6 @@ define HAL_NO_GPIO_IRQ
|
||||
define HAL_USE_EMPTY_IO TRUE
|
||||
define HAL_NO_TIMER_THREAD
|
||||
define DMA_RESERVE_SIZE 0
|
||||
define HAL_DISABLE_LOOP_DELAY
|
||||
define HAL_USE_SERIAL FALSE
|
||||
|
||||
# enable CAN support
|
||||
|
@ -68,7 +68,6 @@ define HAL_NO_GPIO_IRQ
|
||||
|
||||
define HAL_USE_RTC FALSE
|
||||
define DMA_RESERVE_SIZE 0
|
||||
define HAL_DISABLE_LOOP_DELAY
|
||||
define HAL_NO_MONITOR_THREAD
|
||||
|
||||
define HAL_DEVICE_THREAD_STACK 768
|
||||
|
@ -47,8 +47,6 @@ define DMA_RESERVE_SIZE 0
|
||||
MAIN_STACK 0x800
|
||||
PROCESS_STACK 0x800
|
||||
|
||||
define HAL_DISABLE_LOOP_DELAY
|
||||
|
||||
# Add CS pins to ensure they are high in bootloader
|
||||
PB12 RM3100_CS CS
|
||||
PA8 BARO_CS CS
|
||||
|
@ -36,7 +36,6 @@ MAIN_STACK 0x300
|
||||
PROCESS_STACK 0xA00
|
||||
|
||||
# save memory
|
||||
define HAL_DISABLE_LOOP_DELAY
|
||||
define HAL_NO_MONITOR_THREAD
|
||||
define HAL_USE_ADC FALSE
|
||||
|
||||
|
@ -47,8 +47,6 @@ define DMA_RESERVE_SIZE 0
|
||||
MAIN_STACK 0x800
|
||||
PROCESS_STACK 0x800
|
||||
|
||||
define HAL_DISABLE_LOOP_DELAY
|
||||
|
||||
# debugger support
|
||||
PA13 JTMS-SWDIO SWD
|
||||
PA14 JTCK-SWCLK SWD
|
||||
|
@ -36,7 +36,6 @@ MAIN_STACK 0x300
|
||||
PROCESS_STACK 0xA00
|
||||
|
||||
# save memory
|
||||
define HAL_DISABLE_LOOP_DELAY
|
||||
define HAL_NO_MONITOR_THREAD
|
||||
define HAL_USE_ADC FALSE
|
||||
|
||||
|
@ -47,8 +47,6 @@ define DMA_RESERVE_SIZE 0
|
||||
MAIN_STACK 0x800
|
||||
PROCESS_STACK 0x800
|
||||
|
||||
define HAL_DISABLE_LOOP_DELAY
|
||||
|
||||
# debugger support
|
||||
PA13 JTMS-SWDIO SWD
|
||||
PA14 JTCK-SWCLK SWD
|
||||
|
@ -36,7 +36,6 @@ MAIN_STACK 0x300
|
||||
PROCESS_STACK 0xA00
|
||||
|
||||
# save memory
|
||||
define HAL_DISABLE_LOOP_DELAY
|
||||
define HAL_NO_MONITOR_THREAD
|
||||
define HAL_USE_ADC FALSE
|
||||
|
||||
|
@ -80,7 +80,6 @@ define DMA_RESERVE_SIZE 0
|
||||
|
||||
MAIN_STACK 0x100
|
||||
PROCESS_STACK 0x600
|
||||
define HAL_DISABLE_LOOP_DELAY
|
||||
|
||||
define HAL_UART_MIN_TX_SIZE 256
|
||||
define HAL_UART_MIN_RX_SIZE 128
|
||||
|
@ -103,7 +103,6 @@ define DMA_RESERVE_SIZE 0
|
||||
|
||||
MAIN_STACK 0x200
|
||||
PROCESS_STACK 0xA00
|
||||
define HAL_DISABLE_LOOP_DELAY
|
||||
|
||||
define HAL_USE_I2C TRUE
|
||||
define STM32_I2C_USE_I2C1 TRUE
|
||||
|
@ -43,7 +43,6 @@ define DMA_RESERVE_SIZE 0
|
||||
|
||||
MAIN_STACK 0x800
|
||||
PROCESS_STACK 0x800
|
||||
define HAL_DISABLE_LOOP_DELAY
|
||||
|
||||
# enable CAN support
|
||||
PA11 CAN_RX CAN
|
||||
|
@ -78,7 +78,6 @@ MAIN_STACK 0x200
|
||||
|
||||
# PROCESS_STACK controls stack for main thread
|
||||
PROCESS_STACK 0xA00
|
||||
define HAL_DISABLE_LOOP_DELAY
|
||||
|
||||
# enable CAN support
|
||||
PA11 CAN_RX CAN
|
||||
|
@ -64,7 +64,6 @@ define DMA_RESERVE_SIZE 0
|
||||
|
||||
MAIN_STACK 0x800
|
||||
PROCESS_STACK 0x800
|
||||
define HAL_DISABLE_LOOP_DELAY
|
||||
|
||||
# enable CAN support
|
||||
PA11 CAN_RX CAN
|
||||
|
@ -55,7 +55,6 @@ MAIN_STACK 0x300
|
||||
|
||||
# PROCESS_STACK controls stack for main thread
|
||||
PROCESS_STACK 0xA00
|
||||
define HAL_DISABLE_LOOP_DELAY
|
||||
|
||||
# enable CAN support
|
||||
PA11 CAN_RX CAN
|
||||
|
@ -59,7 +59,6 @@ define DMA_RESERVE_SIZE 0
|
||||
|
||||
MAIN_STACK 0x800
|
||||
PROCESS_STACK 0x800
|
||||
define HAL_DISABLE_LOOP_DELAY
|
||||
|
||||
# enable CAN support
|
||||
PA11 CAN_RX CAN
|
||||
|
@ -77,7 +77,6 @@ MAIN_STACK 0x300
|
||||
|
||||
# PROCESS_STACK controls stack for main thread
|
||||
PROCESS_STACK 0xA00
|
||||
define HAL_DISABLE_LOOP_DELAY
|
||||
|
||||
# enable CAN support
|
||||
PA11 CAN_RX CAN
|
||||
|
@ -43,8 +43,6 @@ define HAL_USE_RTC FALSE
|
||||
|
||||
define DMA_RESERVE_SIZE 0
|
||||
|
||||
define HAL_DISABLE_LOOP_DELAY
|
||||
|
||||
define HAL_NO_MONITOR_THREAD
|
||||
|
||||
define HAL_DEVICE_THREAD_STACK 768
|
||||
|
@ -138,7 +138,6 @@ define PORT_INT_REQUIRED_STACK 64
|
||||
MAIN_STACK 0x180
|
||||
PROCESS_STACK 0x250
|
||||
|
||||
define HAL_DISABLE_LOOP_DELAY
|
||||
define AP_BOOTLOADER_FLASHING_ENABLED 0
|
||||
|
||||
define AP_RCPROTOCOL_BACKEND_DEFAULT_ENABLED 0
|
||||
|
@ -132,7 +132,6 @@ define HAL_DISABLE_ADC_DRIVER TRUE
|
||||
# AP_Periph - boiler-plate configurations that all HW AP-Periph need
|
||||
# ---------------------------------------------------------------------------------------------
|
||||
#define HAL_NO_GPIO_IRQ
|
||||
define HAL_DISABLE_LOOP_DELAY
|
||||
define HAL_PERIPH_SHOW_SERIAL_MANAGER_PARAMS
|
||||
|
||||
|
||||
|
@ -46,9 +46,6 @@ define HAL_USE_EMPTY_IO TRUE
|
||||
|
||||
define DMA_RESERVE_SIZE 0
|
||||
|
||||
|
||||
define HAL_DISABLE_LOOP_DELAY
|
||||
|
||||
# enable CAN support
|
||||
PA11 CAN1_RX CAN1
|
||||
PA12 CAN1_TX CAN1
|
||||
|
@ -77,8 +77,6 @@ PA10 USART1_RX USART1 SPEED_HIGH
|
||||
# stack for fast interrupts
|
||||
define PORT_INT_REQUIRED_STACK 64
|
||||
|
||||
define HAL_DISABLE_LOOP_DELAY
|
||||
|
||||
PA11 CAN1_RX CAN1
|
||||
PA12 CAN1_TX CAN1
|
||||
|
||||
|
@ -67,8 +67,6 @@ define HAL_NO_TIMER_THREAD
|
||||
|
||||
define DMA_RESERVE_SIZE 0
|
||||
|
||||
define HAL_DISABLE_LOOP_DELAY
|
||||
|
||||
# enable CAN support
|
||||
PA11 CAN1_RX CAN1
|
||||
PA12 CAN1_TX CAN1
|
||||
|
@ -57,8 +57,6 @@ define HAL_USE_RTC FALSE
|
||||
|
||||
#define DMA_RESERVE_SIZE 2048
|
||||
|
||||
define HAL_DISABLE_LOOP_DELAY
|
||||
|
||||
# enable CAN support
|
||||
PA11 CAN1_RX CAN1
|
||||
PA12 CAN1_TX CAN1
|
||||
|
@ -61,8 +61,6 @@ define HAL_NO_TIMER_THREAD
|
||||
|
||||
define DMA_RESERVE_SIZE 0
|
||||
|
||||
define HAL_DISABLE_LOOP_DELAY
|
||||
|
||||
# enable CAN support
|
||||
PA11 CAN1_RX CAN1
|
||||
PA12 CAN1_TX CAN1
|
||||
|
@ -95,8 +95,6 @@ define HAL_USE_RTC FALSE
|
||||
|
||||
define DMA_RESERVE_SIZE 0
|
||||
|
||||
define HAL_DISABLE_LOOP_DELAY
|
||||
|
||||
# enable CAN support
|
||||
PA11 CAN1_RX CAN1
|
||||
PA12 CAN1_TX CAN1
|
||||
|
@ -65,3 +65,7 @@
|
||||
#ifndef HAL_RCIN_THREAD_ENABLED
|
||||
#define HAL_RCIN_THREAD_ENABLED 0
|
||||
#endif
|
||||
|
||||
#ifndef HAL_SCHEDULER_LOOP_DELAY_ENABLED
|
||||
#define HAL_SCHEDULER_LOOP_DELAY_ENABLED 0
|
||||
#endif
|
||||
|
@ -325,6 +325,10 @@
|
||||
#define HAL_RCIN_THREAD_ENABLED 0
|
||||
#endif
|
||||
|
||||
#ifndef HAL_SCHEDULER_LOOP_DELAY_ENABLED
|
||||
#define HAL_SCHEDULER_LOOP_DELAY_ENABLED 0
|
||||
#endif
|
||||
|
||||
#ifndef HAL_WITH_ESC_TELEM
|
||||
#define HAL_WITH_ESC_TELEM 0
|
||||
#endif
|
||||
|
@ -80,6 +80,7 @@ define DISCRETE_RGB_BLUE_PIN 4
|
||||
define DISCRETE_RGB_POLARITY true
|
||||
|
||||
define HAL_RCIN_THREAD_ENABLED 1
|
||||
define HAL_SCHEDULER_LOOP_DELAY_ENABLED 1
|
||||
|
||||
# don't build on firmware.ardupilot.org
|
||||
AUTOBUILD_TARGETS None
|
||||
|
@ -125,3 +125,4 @@ AUTOBUILD_TARGETS None
|
||||
|
||||
define HAL_SERIAL_ESC_COMM_ENABLED 1
|
||||
define HAL_RCIN_THREAD_ENABLED 1
|
||||
define HAL_SCHEDULER_LOOP_DELAY_ENABLED 1
|
||||
|
Loading…
Reference in New Issue
Block a user