hwdef: change HAL_NO_MONITOR_THREAD out for HAL_MONITOR_THREAD_ENABLED
... and use a default value for peripherals
This commit is contained in:
parent
3a834e83c7
commit
90b2a2acaa
@ -64,6 +64,10 @@ using namespace ChibiOS;
|
|||||||
#define HAL_RCIN_THREAD_ENABLED 1
|
#define HAL_RCIN_THREAD_ENABLED 1
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#ifndef HAL_MONITOR_THREAD_ENABLED
|
||||||
|
#define HAL_MONITOR_THREAD_ENABLED 1
|
||||||
|
#endif
|
||||||
|
|
||||||
extern const AP_HAL::HAL& hal;
|
extern const AP_HAL::HAL& hal;
|
||||||
#ifndef HAL_NO_TIMER_THREAD
|
#ifndef HAL_NO_TIMER_THREAD
|
||||||
THD_WORKING_AREA(_timer_thread_wa, TIMER_THD_WA_SIZE);
|
THD_WORKING_AREA(_timer_thread_wa, TIMER_THD_WA_SIZE);
|
||||||
@ -80,7 +84,7 @@ THD_WORKING_AREA(_io_thread_wa, IO_THD_WA_SIZE);
|
|||||||
#ifndef HAL_USE_EMPTY_STORAGE
|
#ifndef HAL_USE_EMPTY_STORAGE
|
||||||
THD_WORKING_AREA(_storage_thread_wa, STORAGE_THD_WA_SIZE);
|
THD_WORKING_AREA(_storage_thread_wa, STORAGE_THD_WA_SIZE);
|
||||||
#endif
|
#endif
|
||||||
#ifndef HAL_NO_MONITOR_THREAD
|
#if HAL_MONITOR_THREAD_ENABLED
|
||||||
THD_WORKING_AREA(_monitor_thread_wa, MONITOR_THD_WA_SIZE);
|
THD_WORKING_AREA(_monitor_thread_wa, MONITOR_THD_WA_SIZE);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
@ -100,7 +104,7 @@ void Scheduler::init()
|
|||||||
chBSemObjectInit(&_timer_semaphore, false);
|
chBSemObjectInit(&_timer_semaphore, false);
|
||||||
chBSemObjectInit(&_io_semaphore, false);
|
chBSemObjectInit(&_io_semaphore, false);
|
||||||
|
|
||||||
#ifndef HAL_NO_MONITOR_THREAD
|
#if HAL_MONITOR_THREAD_ENABLED
|
||||||
// setup the monitor thread - this is used to detect software lockups
|
// setup the monitor thread - this is used to detect software lockups
|
||||||
_monitor_thread_ctx = chThdCreateStatic(_monitor_thread_wa,
|
_monitor_thread_ctx = chThdCreateStatic(_monitor_thread_wa,
|
||||||
sizeof(_monitor_thread_wa),
|
sizeof(_monitor_thread_wa),
|
||||||
@ -407,7 +411,7 @@ bool Scheduler::in_expected_delay(void) const
|
|||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
#ifndef HAL_NO_MONITOR_THREAD
|
#if HAL_MONITOR_THREAD_ENABLED
|
||||||
void Scheduler::_monitor_thread(void *arg)
|
void Scheduler::_monitor_thread(void *arg)
|
||||||
{
|
{
|
||||||
Scheduler *sched = (Scheduler *)arg;
|
Scheduler *sched = (Scheduler *)arg;
|
||||||
@ -513,7 +517,7 @@ void Scheduler::_monitor_thread(void *arg)
|
|||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
#endif // HAL_NO_MONITOR_THREAD
|
#endif // HAL_MONITOR_THREAD_ENABLED
|
||||||
|
|
||||||
void Scheduler::_rcin_thread(void *arg)
|
void Scheduler::_rcin_thread(void *arg)
|
||||||
{
|
{
|
||||||
|
@ -30,8 +30,6 @@ PC13 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW HIGH
|
|||||||
|
|
||||||
CAN_ORDER 1
|
CAN_ORDER 1
|
||||||
|
|
||||||
define HAL_NO_MONITOR_THREAD
|
|
||||||
|
|
||||||
# debugger support
|
# debugger support
|
||||||
PA13 JTMS-SWDIO SWD
|
PA13 JTMS-SWDIO SWD
|
||||||
PA14 JTCK-SWCLK SWD
|
PA14 JTCK-SWCLK SWD
|
||||||
|
@ -32,7 +32,6 @@ MAIN_STACK 0x300
|
|||||||
|
|
||||||
# PROCESS_STACK controls stack for main thread
|
# PROCESS_STACK controls stack for main thread
|
||||||
PROCESS_STACK 0xA00
|
PROCESS_STACK 0xA00
|
||||||
define HAL_NO_MONITOR_THREAD
|
|
||||||
|
|
||||||
# we setup a small defaults.parm
|
# we setup a small defaults.parm
|
||||||
define AP_PARAM_MAX_EMBEDDED_PARAM 512
|
define AP_PARAM_MAX_EMBEDDED_PARAM 512
|
||||||
@ -92,7 +91,6 @@ COMPASS QMC5883L I2C:0:0xd false ROTATION_YAW_180
|
|||||||
define HAL_USE_ADC FALSE
|
define HAL_USE_ADC FALSE
|
||||||
|
|
||||||
# disable unnecessary threads
|
# disable unnecessary threads
|
||||||
define HAL_NO_MONITOR_THREAD
|
|
||||||
define HAL_NO_TIMER_THREAD
|
define HAL_NO_TIMER_THREAD
|
||||||
|
|
||||||
# enable LED
|
# enable LED
|
||||||
|
@ -36,8 +36,6 @@ MAIN_STACK 0x300
|
|||||||
# PROCESS_STACK controls stack for main thread
|
# PROCESS_STACK controls stack for main thread
|
||||||
PROCESS_STACK 0xA00
|
PROCESS_STACK 0xA00
|
||||||
|
|
||||||
define HAL_NO_MONITOR_THREAD
|
|
||||||
|
|
||||||
# setup a small defaults.parm
|
# setup a small defaults.parm
|
||||||
define AP_PARAM_MAX_EMBEDDED_PARAM 512
|
define AP_PARAM_MAX_EMBEDDED_PARAM 512
|
||||||
|
|
||||||
|
@ -89,9 +89,6 @@ PB8 CAN1_RX CAN1
|
|||||||
PB9 CAN1_TX CAN1
|
PB9 CAN1_TX CAN1
|
||||||
PB2 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW
|
PB2 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW
|
||||||
|
|
||||||
define HAL_NO_MONITOR_THREAD
|
|
||||||
|
|
||||||
|
|
||||||
define HAL_DEVICE_THREAD_STACK 768
|
define HAL_DEVICE_THREAD_STACK 768
|
||||||
|
|
||||||
define AP_PARAM_MAX_EMBEDDED_PARAM 0
|
define AP_PARAM_MAX_EMBEDDED_PARAM 0
|
||||||
|
@ -90,8 +90,6 @@ PA4 RTK_RESET_N OUTPUT HIGH
|
|||||||
# PPS
|
# PPS
|
||||||
PA7 PPS INPUT PULLUP
|
PA7 PPS INPUT PULLUP
|
||||||
|
|
||||||
define HAL_NO_MONITOR_THREAD
|
|
||||||
|
|
||||||
define HAL_DEVICE_THREAD_STACK 768
|
define HAL_DEVICE_THREAD_STACK 768
|
||||||
|
|
||||||
# we setup a small defaults.parm
|
# we setup a small defaults.parm
|
||||||
|
@ -119,10 +119,6 @@ PB8 CAN1_RX CAN1
|
|||||||
PB9 CAN1_TX CAN1
|
PB9 CAN1_TX CAN1
|
||||||
PB5 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW
|
PB5 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW
|
||||||
|
|
||||||
|
|
||||||
define HAL_NO_MONITOR_THREAD
|
|
||||||
|
|
||||||
|
|
||||||
define HAL_DEVICE_THREAD_STACK 768
|
define HAL_DEVICE_THREAD_STACK 768
|
||||||
|
|
||||||
# we setup a small defaults.parm
|
# we setup a small defaults.parm
|
||||||
|
@ -109,7 +109,6 @@ PB1 VSENSE4 ADC1 SCALE(1)
|
|||||||
define AP_STATS_ENABLED 1
|
define AP_STATS_ENABLED 1
|
||||||
|
|
||||||
define HAL_NO_GCS
|
define HAL_NO_GCS
|
||||||
define HAL_NO_MONITOR_THREAD
|
|
||||||
|
|
||||||
define AP_PARAM_MAX_EMBEDDED_PARAM 512
|
define AP_PARAM_MAX_EMBEDDED_PARAM 512
|
||||||
|
|
||||||
|
@ -112,7 +112,6 @@ PB1 VSENSE4 ADC1 SCALE(1)
|
|||||||
define AP_STATS_ENABLED 1
|
define AP_STATS_ENABLED 1
|
||||||
|
|
||||||
define HAL_NO_GCS
|
define HAL_NO_GCS
|
||||||
define HAL_NO_MONITOR_THREAD
|
|
||||||
|
|
||||||
define AP_PARAM_MAX_EMBEDDED_PARAM 512
|
define AP_PARAM_MAX_EMBEDDED_PARAM 512
|
||||||
|
|
||||||
|
@ -35,8 +35,6 @@ define GPS_MAX_RECEIVERS 1
|
|||||||
define GPS_MAX_INSTANCES 1
|
define GPS_MAX_INSTANCES 1
|
||||||
define HAL_COMPASS_MAX_SENSORS 1
|
define HAL_COMPASS_MAX_SENSORS 1
|
||||||
|
|
||||||
define HAL_NO_MONITOR_THREAD
|
|
||||||
|
|
||||||
define HAL_USE_RTC FALSE
|
define HAL_USE_RTC FALSE
|
||||||
|
|
||||||
define HAL_BARO_ALLOW_INIT_NO_BARO
|
define HAL_BARO_ALLOW_INIT_NO_BARO
|
||||||
|
@ -32,8 +32,6 @@ define GPS_MAX_RECEIVERS 1
|
|||||||
define GPS_MAX_INSTANCES 1
|
define GPS_MAX_INSTANCES 1
|
||||||
define HAL_COMPASS_MAX_SENSORS 1
|
define HAL_COMPASS_MAX_SENSORS 1
|
||||||
|
|
||||||
define HAL_NO_MONITOR_THREAD
|
|
||||||
|
|
||||||
define HAL_USE_RTC FALSE
|
define HAL_USE_RTC FALSE
|
||||||
|
|
||||||
define HAL_GCS_ENABLED 1
|
define HAL_GCS_ENABLED 1
|
||||||
|
@ -31,8 +31,6 @@ define GPS_MAX_RECEIVERS 1
|
|||||||
define GPS_MAX_INSTANCES 1
|
define GPS_MAX_INSTANCES 1
|
||||||
define HAL_COMPASS_MAX_SENSORS 1
|
define HAL_COMPASS_MAX_SENSORS 1
|
||||||
|
|
||||||
define HAL_NO_MONITOR_THREAD
|
|
||||||
|
|
||||||
define HAL_USE_RTC FALSE
|
define HAL_USE_RTC FALSE
|
||||||
|
|
||||||
define HAL_BARO_ALLOW_INIT_NO_BARO
|
define HAL_BARO_ALLOW_INIT_NO_BARO
|
||||||
|
@ -23,8 +23,6 @@ define HAL_PERIPH_ENABLE_SERIAL_OPTIONS
|
|||||||
|
|
||||||
define AP_NETWORKING_BACKEND_PPP 1
|
define AP_NETWORKING_BACKEND_PPP 1
|
||||||
|
|
||||||
define HAL_NO_MONITOR_THREAD
|
|
||||||
|
|
||||||
define HAL_USE_RTC FALSE
|
define HAL_USE_RTC FALSE
|
||||||
|
|
||||||
# use amber LED
|
# use amber LED
|
||||||
|
@ -110,9 +110,6 @@ define DMA_RESERVE_SIZE 0
|
|||||||
PB8 CAN1_RX CAN1
|
PB8 CAN1_RX CAN1
|
||||||
PB9 CAN1_TX CAN1
|
PB9 CAN1_TX CAN1
|
||||||
|
|
||||||
|
|
||||||
define HAL_NO_MONITOR_THREAD
|
|
||||||
|
|
||||||
define HAL_DEVICE_THREAD_STACK 768
|
define HAL_DEVICE_THREAD_STACK 768
|
||||||
|
|
||||||
# we setup a small defaults.parm
|
# we setup a small defaults.parm
|
||||||
|
@ -130,10 +130,6 @@ define HAL_UART_MIN_RX_SIZE 128
|
|||||||
|
|
||||||
define HAL_UART_STACK_SIZE 0x200
|
define HAL_UART_STACK_SIZE 0x200
|
||||||
|
|
||||||
|
|
||||||
define HAL_NO_MONITOR_THREAD
|
|
||||||
|
|
||||||
|
|
||||||
define HAL_DEVICE_THREAD_STACK 0x200
|
define HAL_DEVICE_THREAD_STACK 0x200
|
||||||
define STORAGE_THD_WA_SIZE 512
|
define STORAGE_THD_WA_SIZE 512
|
||||||
define IO_THD_WA_SIZE 512
|
define IO_THD_WA_SIZE 512
|
||||||
|
@ -45,8 +45,6 @@ STM32_VDD 330U
|
|||||||
PB8 LED_SCK OUTPUT LOW
|
PB8 LED_SCK OUTPUT LOW
|
||||||
PB9 LED_DI OUTPUT HIGH
|
PB9 LED_DI OUTPUT HIGH
|
||||||
|
|
||||||
define HAL_NO_MONITOR_THREAD
|
|
||||||
|
|
||||||
PA13 JTMS-SWDIO SWD
|
PA13 JTMS-SWDIO SWD
|
||||||
PA14 JTCK-SWCLK SWD
|
PA14 JTCK-SWCLK SWD
|
||||||
|
|
||||||
|
@ -45,8 +45,6 @@ STM32_VDD 330U
|
|||||||
PB8 LED_SCK OUTPUT LOW
|
PB8 LED_SCK OUTPUT LOW
|
||||||
PB9 LED_DI OUTPUT HIGH
|
PB9 LED_DI OUTPUT HIGH
|
||||||
|
|
||||||
define HAL_NO_MONITOR_THREAD
|
|
||||||
|
|
||||||
PA13 JTMS-SWDIO SWD
|
PA13 JTMS-SWDIO SWD
|
||||||
PA14 JTCK-SWCLK SWD
|
PA14 JTCK-SWCLK SWD
|
||||||
|
|
||||||
|
@ -92,9 +92,6 @@ define HAL_USE_ADC FALSE
|
|||||||
define STM32_ADC_USE_ADC1 FALSE
|
define STM32_ADC_USE_ADC1 FALSE
|
||||||
define HAL_DISABLE_ADC_DRIVER TRUE
|
define HAL_DISABLE_ADC_DRIVER TRUE
|
||||||
|
|
||||||
define HAL_NO_MONITOR_THREAD
|
|
||||||
|
|
||||||
|
|
||||||
define HAL_DEVICE_THREAD_STACK 0x200
|
define HAL_DEVICE_THREAD_STACK 0x200
|
||||||
define STORAGE_THD_WA_SIZE 512
|
define STORAGE_THD_WA_SIZE 512
|
||||||
define IO_THD_WA_SIZE 512
|
define IO_THD_WA_SIZE 512
|
||||||
|
@ -101,10 +101,6 @@ define HAL_UART_MIN_RX_SIZE 128
|
|||||||
|
|
||||||
define HAL_UART_STACK_SIZE 0x200
|
define HAL_UART_STACK_SIZE 0x200
|
||||||
|
|
||||||
|
|
||||||
define HAL_NO_MONITOR_THREAD
|
|
||||||
|
|
||||||
|
|
||||||
# only one I2C bus
|
# only one I2C bus
|
||||||
I2C_ORDER I2C1
|
I2C_ORDER I2C1
|
||||||
|
|
||||||
|
@ -81,8 +81,6 @@ PA11 CAN1_RX CAN1
|
|||||||
PA12 CAN1_TX CAN1
|
PA12 CAN1_TX CAN1
|
||||||
PC13 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW
|
PC13 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW
|
||||||
|
|
||||||
define HAL_NO_MONITOR_THREAD
|
|
||||||
|
|
||||||
define HAL_DEVICE_THREAD_STACK 768
|
define HAL_DEVICE_THREAD_STACK 768
|
||||||
|
|
||||||
# we setup a small defaults.parm
|
# we setup a small defaults.parm
|
||||||
|
@ -109,8 +109,6 @@ PB12 CAN2_RX CAN2
|
|||||||
PB13 CAN2_TX CAN2
|
PB13 CAN2_TX CAN2
|
||||||
PB14 GPIO_CAN2_SILENT OUTPUT PUSHPULL SPEED_LOW LOW
|
PB14 GPIO_CAN2_SILENT OUTPUT PUSHPULL SPEED_LOW LOW
|
||||||
|
|
||||||
define HAL_NO_MONITOR_THREAD
|
|
||||||
|
|
||||||
define HAL_DEVICE_THREAD_STACK 768
|
define HAL_DEVICE_THREAD_STACK 768
|
||||||
|
|
||||||
# we setup a small defaults.parm
|
# we setup a small defaults.parm
|
||||||
|
@ -126,10 +126,6 @@ PB12 CAN2_RX CAN2
|
|||||||
PB13 CAN2_TX CAN2
|
PB13 CAN2_TX CAN2
|
||||||
PA4 GPIO_CAN2_SILENT OUTPUT PUSHPULL SPEED_LOW LOW
|
PA4 GPIO_CAN2_SILENT OUTPUT PUSHPULL SPEED_LOW LOW
|
||||||
|
|
||||||
|
|
||||||
define HAL_NO_MONITOR_THREAD
|
|
||||||
|
|
||||||
|
|
||||||
define HAL_DEVICE_THREAD_STACK 768
|
define HAL_DEVICE_THREAD_STACK 768
|
||||||
|
|
||||||
# we setup a small defaults.parm
|
# we setup a small defaults.parm
|
||||||
|
@ -40,7 +40,6 @@ define HAL_PERIPH_ADSB_PORT_DEFAULT 3
|
|||||||
# default ADSB off by setting 0 baudrate
|
# default ADSB off by setting 0 baudrate
|
||||||
define HAL_PERIPH_ADSB_BAUD_DEFAULT 0
|
define HAL_PERIPH_ADSB_BAUD_DEFAULT 0
|
||||||
|
|
||||||
define HAL_NO_MONITOR_THREAD
|
|
||||||
define HAL_USE_RTC FALSE
|
define HAL_USE_RTC FALSE
|
||||||
|
|
||||||
define AP_SCRIPTING_ENABLED 0
|
define AP_SCRIPTING_ENABLED 0
|
||||||
|
@ -13,7 +13,6 @@ SPIDEV INA23X SPI1 DEVID1 SPARE_CS MODE1 10*MHZ 10*MHZ
|
|||||||
define HAL_USE_ADC FALSE
|
define HAL_USE_ADC FALSE
|
||||||
|
|
||||||
# disable unnecessary threads
|
# disable unnecessary threads
|
||||||
define HAL_NO_MONITOR_THREAD
|
|
||||||
define HAL_NO_RCOUT_THREAD
|
define HAL_NO_RCOUT_THREAD
|
||||||
define HAL_NO_TIMER_THREAD
|
define HAL_NO_TIMER_THREAD
|
||||||
|
|
||||||
|
@ -37,7 +37,6 @@ PB11 USART3_RX USART3 SPEED_HIGH
|
|||||||
define HAL_USE_ADC FALSE
|
define HAL_USE_ADC FALSE
|
||||||
|
|
||||||
# disable unnecessary threads
|
# disable unnecessary threads
|
||||||
define HAL_NO_MONITOR_THREAD
|
|
||||||
define HAL_NO_RCOUT_THREAD
|
define HAL_NO_RCOUT_THREAD
|
||||||
define HAL_NO_TIMER_THREAD
|
define HAL_NO_TIMER_THREAD
|
||||||
undef HAL_RCIN_THREAD_ENABLED
|
undef HAL_RCIN_THREAD_ENABLED
|
||||||
|
@ -38,8 +38,6 @@ MAIN_STACK 0x300
|
|||||||
# PROCESS_STACK controls stack for main thread
|
# PROCESS_STACK controls stack for main thread
|
||||||
PROCESS_STACK 0xA00
|
PROCESS_STACK 0xA00
|
||||||
|
|
||||||
define HAL_NO_MONITOR_THREAD
|
|
||||||
|
|
||||||
# we setup a small defaults.parm
|
# we setup a small defaults.parm
|
||||||
define AP_PARAM_MAX_EMBEDDED_PARAM 512
|
define AP_PARAM_MAX_EMBEDDED_PARAM 512
|
||||||
|
|
||||||
|
@ -87,9 +87,6 @@ define HAL_USE_ADC TRUE
|
|||||||
define STM32_ADC_USE_ADC1 TRUE
|
define STM32_ADC_USE_ADC1 TRUE
|
||||||
PA4 VSENSE ADC1 SCALE(2)
|
PA4 VSENSE ADC1 SCALE(2)
|
||||||
|
|
||||||
define HAL_NO_MONITOR_THREAD
|
|
||||||
|
|
||||||
|
|
||||||
define AP_PARAM_MAX_EMBEDDED_PARAM 512
|
define AP_PARAM_MAX_EMBEDDED_PARAM 512
|
||||||
|
|
||||||
define HAL_PERIPH_ENABLE_GPS
|
define HAL_PERIPH_ENABLE_GPS
|
||||||
|
@ -95,8 +95,6 @@ define HAL_USE_ADC TRUE
|
|||||||
define STM32_ADC_USE_ADC1 TRUE
|
define STM32_ADC_USE_ADC1 TRUE
|
||||||
PA4 VSENSE ADC1 SCALE(2)
|
PA4 VSENSE ADC1 SCALE(2)
|
||||||
|
|
||||||
define HAL_NO_MONITOR_THREAD
|
|
||||||
|
|
||||||
define AP_PARAM_MAX_EMBEDDED_PARAM 512
|
define AP_PARAM_MAX_EMBEDDED_PARAM 512
|
||||||
|
|
||||||
define HAL_PERIPH_ENABLE_GPS
|
define HAL_PERIPH_ENABLE_GPS
|
||||||
|
@ -24,8 +24,6 @@ define HAL_PERIPH_ENABLE_SERIAL_OPTIONS
|
|||||||
|
|
||||||
define AP_NETWORKING_BACKEND_PPP 1
|
define AP_NETWORKING_BACKEND_PPP 1
|
||||||
|
|
||||||
define HAL_NO_MONITOR_THREAD
|
|
||||||
|
|
||||||
define HAL_USE_RTC FALSE
|
define HAL_USE_RTC FALSE
|
||||||
|
|
||||||
# use blue LED
|
# use blue LED
|
||||||
|
@ -35,8 +35,6 @@ define GPS_MAX_RECEIVERS 1
|
|||||||
define GPS_MAX_INSTANCES 1
|
define GPS_MAX_INSTANCES 1
|
||||||
define HAL_COMPASS_MAX_SENSORS 1
|
define HAL_COMPASS_MAX_SENSORS 1
|
||||||
|
|
||||||
define HAL_NO_MONITOR_THREAD
|
|
||||||
|
|
||||||
define HAL_USE_RTC FALSE
|
define HAL_USE_RTC FALSE
|
||||||
|
|
||||||
define HAL_BARO_ALLOW_INIT_NO_BARO
|
define HAL_BARO_ALLOW_INIT_NO_BARO
|
||||||
|
@ -34,8 +34,6 @@ define HAL_USE_RTC FALSE
|
|||||||
|
|
||||||
define DMA_RESERVE_SIZE 0
|
define DMA_RESERVE_SIZE 0
|
||||||
|
|
||||||
define HAL_NO_MONITOR_THREAD
|
|
||||||
|
|
||||||
define HAL_DEVICE_THREAD_STACK 768
|
define HAL_DEVICE_THREAD_STACK 768
|
||||||
|
|
||||||
# we setup a small defaults.parm
|
# we setup a small defaults.parm
|
||||||
|
@ -95,7 +95,6 @@ PA12 CAN1_TX CAN1
|
|||||||
# use DNA
|
# use DNA
|
||||||
define HAL_CAN_DEFAULT_NODE_ID 0
|
define HAL_CAN_DEFAULT_NODE_ID 0
|
||||||
|
|
||||||
define HAL_NO_MONITOR_THREAD
|
|
||||||
define HAL_DEVICE_THREAD_STACK 768
|
define HAL_DEVICE_THREAD_STACK 768
|
||||||
|
|
||||||
# disable dual GPS and GPS blending to save flash space
|
# disable dual GPS and GPS blending to save flash space
|
||||||
|
@ -104,7 +104,6 @@ PB8 CAN1_RX CAN1
|
|||||||
PB9 CAN1_TX CAN1
|
PB9 CAN1_TX CAN1
|
||||||
PC1 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW
|
PC1 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW
|
||||||
|
|
||||||
define HAL_NO_MONITOR_THREAD
|
|
||||||
define HAL_DEVICE_THREAD_STACK 768
|
define HAL_DEVICE_THREAD_STACK 768
|
||||||
|
|
||||||
# we setup a small defaults.parm
|
# we setup a small defaults.parm
|
||||||
|
@ -92,7 +92,6 @@ define HAL_USE_ADC TRUE
|
|||||||
define STM32_ADC_USE_ADC1 TRUE
|
define STM32_ADC_USE_ADC1 TRUE
|
||||||
PA0 VDD_5V_SENS ADC1 SCALE(2)
|
PA0 VDD_5V_SENS ADC1 SCALE(2)
|
||||||
|
|
||||||
define HAL_NO_MONITOR_THREAD
|
|
||||||
define AP_PARAM_MAX_EMBEDDED_PARAM 512
|
define AP_PARAM_MAX_EMBEDDED_PARAM 512
|
||||||
|
|
||||||
define HAL_PERIPH_ENABLE_MAG
|
define HAL_PERIPH_ENABLE_MAG
|
||||||
|
@ -37,7 +37,6 @@ PROCESS_STACK 0xA00
|
|||||||
|
|
||||||
# save memory
|
# save memory
|
||||||
define HAL_GCS_ENABLED 0
|
define HAL_GCS_ENABLED 0
|
||||||
define HAL_NO_MONITOR_THREAD
|
|
||||||
define HAL_NO_LOGGING
|
define HAL_NO_LOGGING
|
||||||
define HAL_USE_ADC FALSE
|
define HAL_USE_ADC FALSE
|
||||||
|
|
||||||
|
@ -68,7 +68,6 @@ define HAL_NO_GPIO_IRQ
|
|||||||
|
|
||||||
define HAL_USE_RTC FALSE
|
define HAL_USE_RTC FALSE
|
||||||
define DMA_RESERVE_SIZE 0
|
define DMA_RESERVE_SIZE 0
|
||||||
define HAL_NO_MONITOR_THREAD
|
|
||||||
|
|
||||||
define HAL_DEVICE_THREAD_STACK 768
|
define HAL_DEVICE_THREAD_STACK 768
|
||||||
|
|
||||||
|
@ -36,7 +36,6 @@ MAIN_STACK 0x300
|
|||||||
PROCESS_STACK 0xA00
|
PROCESS_STACK 0xA00
|
||||||
|
|
||||||
# save memory
|
# save memory
|
||||||
define HAL_NO_MONITOR_THREAD
|
|
||||||
define HAL_USE_ADC FALSE
|
define HAL_USE_ADC FALSE
|
||||||
|
|
||||||
# we setup a small defaults.parm
|
# we setup a small defaults.parm
|
||||||
|
@ -36,7 +36,6 @@ MAIN_STACK 0x300
|
|||||||
PROCESS_STACK 0xA00
|
PROCESS_STACK 0xA00
|
||||||
|
|
||||||
# save memory
|
# save memory
|
||||||
define HAL_NO_MONITOR_THREAD
|
|
||||||
define HAL_USE_ADC FALSE
|
define HAL_USE_ADC FALSE
|
||||||
|
|
||||||
# we setup a small defaults.parm
|
# we setup a small defaults.parm
|
||||||
|
@ -36,7 +36,6 @@ MAIN_STACK 0x300
|
|||||||
PROCESS_STACK 0xA00
|
PROCESS_STACK 0xA00
|
||||||
|
|
||||||
# save memory
|
# save memory
|
||||||
define HAL_NO_MONITOR_THREAD
|
|
||||||
define HAL_USE_ADC FALSE
|
define HAL_USE_ADC FALSE
|
||||||
|
|
||||||
# we setup a small defaults.parm
|
# we setup a small defaults.parm
|
||||||
|
@ -87,8 +87,6 @@ define HAL_UART_MIN_RX_SIZE 128
|
|||||||
define HAL_UART_STACK_SIZE 256
|
define HAL_UART_STACK_SIZE 256
|
||||||
define STORAGE_THD_WA_SIZE 512
|
define STORAGE_THD_WA_SIZE 512
|
||||||
|
|
||||||
define HAL_NO_MONITOR_THREAD
|
|
||||||
|
|
||||||
define HAL_DEVICE_THREAD_STACK 768
|
define HAL_DEVICE_THREAD_STACK 768
|
||||||
|
|
||||||
define AP_PARAM_MAX_EMBEDDED_PARAM 0
|
define AP_PARAM_MAX_EMBEDDED_PARAM 0
|
||||||
|
@ -130,9 +130,6 @@ BARO MS56XX SPI:ms5611
|
|||||||
|
|
||||||
define HAL_BARO_ALLOW_INIT_NO_BARO
|
define HAL_BARO_ALLOW_INIT_NO_BARO
|
||||||
|
|
||||||
|
|
||||||
define HAL_NO_MONITOR_THREAD
|
|
||||||
|
|
||||||
define HAL_PERIPH_ENABLE_GPS
|
define HAL_PERIPH_ENABLE_GPS
|
||||||
define HAL_PERIPH_ENABLE_MAG
|
define HAL_PERIPH_ENABLE_MAG
|
||||||
define HAL_PERIPH_ENABLE_BARO
|
define HAL_PERIPH_ENABLE_BARO
|
||||||
|
@ -98,9 +98,6 @@ define HAL_UART_STACK_SIZE 256
|
|||||||
define STORAGE_THD_WA_SIZE 300
|
define STORAGE_THD_WA_SIZE 300
|
||||||
define IO_THD_WA_SIZE 300
|
define IO_THD_WA_SIZE 300
|
||||||
|
|
||||||
define HAL_NO_MONITOR_THREAD
|
|
||||||
|
|
||||||
|
|
||||||
# only one I2C bus
|
# only one I2C bus
|
||||||
I2C_ORDER I2C1
|
I2C_ORDER I2C1
|
||||||
|
|
||||||
|
@ -43,8 +43,6 @@ define HAL_USE_RTC FALSE
|
|||||||
|
|
||||||
define DMA_RESERVE_SIZE 0
|
define DMA_RESERVE_SIZE 0
|
||||||
|
|
||||||
define HAL_NO_MONITOR_THREAD
|
|
||||||
|
|
||||||
define HAL_DEVICE_THREAD_STACK 768
|
define HAL_DEVICE_THREAD_STACK 768
|
||||||
|
|
||||||
# we setup a small defaults.parm
|
# we setup a small defaults.parm
|
||||||
|
@ -108,7 +108,6 @@ define PORT_INT_REQUIRED_STACK 64
|
|||||||
|
|
||||||
# avoid timer threads to save memory
|
# avoid timer threads to save memory
|
||||||
define HAL_NO_TIMER_THREAD
|
define HAL_NO_TIMER_THREAD
|
||||||
define HAL_NO_MONITOR_THREAD
|
|
||||||
define HAL_NO_RCOUT_THREAD # also disables LED thread
|
define HAL_NO_RCOUT_THREAD # also disables LED thread
|
||||||
|
|
||||||
define AP_HAL_SHARED_DMA_ENABLED 0
|
define AP_HAL_SHARED_DMA_ENABLED 0
|
||||||
|
@ -80,8 +80,6 @@ define PORT_INT_REQUIRED_STACK 64
|
|||||||
PA11 CAN1_RX CAN1
|
PA11 CAN1_RX CAN1
|
||||||
PA12 CAN1_TX CAN1
|
PA12 CAN1_TX CAN1
|
||||||
|
|
||||||
define HAL_NO_MONITOR_THREAD
|
|
||||||
|
|
||||||
define AP_PARAM_MAX_EMBEDDED_PARAM 512
|
define AP_PARAM_MAX_EMBEDDED_PARAM 512
|
||||||
|
|
||||||
# keep ROMFS uncompressed as we don't have enough RAM
|
# keep ROMFS uncompressed as we don't have enough RAM
|
||||||
|
@ -100,8 +100,6 @@ PA11 CAN1_RX CAN1
|
|||||||
PA12 CAN1_TX CAN1
|
PA12 CAN1_TX CAN1
|
||||||
PA15 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW
|
PA15 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW
|
||||||
|
|
||||||
define HAL_NO_MONITOR_THREAD
|
|
||||||
|
|
||||||
define HAL_DEVICE_THREAD_STACK 768
|
define HAL_DEVICE_THREAD_STACK 768
|
||||||
|
|
||||||
# we setup a small defaults.parm
|
# we setup a small defaults.parm
|
||||||
|
@ -325,6 +325,10 @@
|
|||||||
#define HAL_RCIN_THREAD_ENABLED 0
|
#define HAL_RCIN_THREAD_ENABLED 0
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#ifndef HAL_MONITOR_THREAD_ENABLED
|
||||||
|
#define HAL_MONITOR_THREAD_ENABLED 0
|
||||||
|
#endif
|
||||||
|
|
||||||
#ifndef HAL_SCHEDULER_LOOP_DELAY_ENABLED
|
#ifndef HAL_SCHEDULER_LOOP_DELAY_ENABLED
|
||||||
#define HAL_SCHEDULER_LOOP_DELAY_ENABLED 0
|
#define HAL_SCHEDULER_LOOP_DELAY_ENABLED 0
|
||||||
#endif
|
#endif
|
||||||
|
Loading…
Reference in New Issue
Block a user