mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_ChibiOS: replace HAL_NO_RCIN_THREAD w/HAL_RCIN_THREAD_ENABLED
This commit is contained in:
parent
594c2466d8
commit
994c268644
|
@ -59,6 +59,10 @@ extern AP_IOMCU iomcu;
|
||||||
|
|
||||||
using namespace ChibiOS;
|
using namespace ChibiOS;
|
||||||
|
|
||||||
|
#ifndef HAL_RCIN_THREAD_ENABLED
|
||||||
|
#define HAL_RCIN_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);
|
||||||
|
@ -66,7 +70,7 @@ THD_WORKING_AREA(_timer_thread_wa, TIMER_THD_WA_SIZE);
|
||||||
#ifndef HAL_NO_RCOUT_THREAD
|
#ifndef HAL_NO_RCOUT_THREAD
|
||||||
THD_WORKING_AREA(_rcout_thread_wa, RCOUT_THD_WA_SIZE);
|
THD_WORKING_AREA(_rcout_thread_wa, RCOUT_THD_WA_SIZE);
|
||||||
#endif
|
#endif
|
||||||
#ifndef HAL_NO_RCIN_THREAD
|
#if HAL_RCIN_THREAD_ENABLED
|
||||||
THD_WORKING_AREA(_rcin_thread_wa, RCIN_THD_WA_SIZE);
|
THD_WORKING_AREA(_rcin_thread_wa, RCIN_THD_WA_SIZE);
|
||||||
#endif
|
#endif
|
||||||
#ifndef HAL_USE_EMPTY_IO
|
#ifndef HAL_USE_EMPTY_IO
|
||||||
|
@ -122,7 +126,7 @@ void Scheduler::init()
|
||||||
this); /* Thread parameter. */
|
this); /* Thread parameter. */
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifndef HAL_NO_RCIN_THREAD
|
#if HAL_RCIN_THREAD_ENABLED
|
||||||
// setup the RCIN thread - this will call tasks at 1kHz
|
// setup the RCIN thread - this will call tasks at 1kHz
|
||||||
_rcin_thread_ctx = chThdCreateStatic(_rcin_thread_wa,
|
_rcin_thread_ctx = chThdCreateStatic(_rcin_thread_wa,
|
||||||
sizeof(_rcin_thread_wa),
|
sizeof(_rcin_thread_wa),
|
||||||
|
|
|
@ -51,7 +51,6 @@ define HAL_USE_EMPTY_IO TRUE
|
||||||
|
|
||||||
# avoid timer and RCIN threads to save memory
|
# avoid timer and RCIN threads to save memory
|
||||||
define HAL_NO_TIMER_THREAD
|
define HAL_NO_TIMER_THREAD
|
||||||
define HAL_NO_RCIN_THREAD
|
|
||||||
|
|
||||||
define DMA_RESERVE_SIZE 0
|
define DMA_RESERVE_SIZE 0
|
||||||
|
|
||||||
|
|
|
@ -51,7 +51,6 @@ define HAL_USE_EMPTY_IO TRUE
|
||||||
|
|
||||||
# avoid timer and RCIN threads to save memory
|
# avoid timer and RCIN threads to save memory
|
||||||
define HAL_NO_TIMER_THREAD
|
define HAL_NO_TIMER_THREAD
|
||||||
define HAL_NO_RCIN_THREAD
|
|
||||||
|
|
||||||
define DMA_RESERVE_SIZE 0
|
define DMA_RESERVE_SIZE 0
|
||||||
|
|
||||||
|
|
|
@ -94,7 +94,6 @@ define HAL_USE_ADC FALSE
|
||||||
|
|
||||||
# disable unnecessary threads
|
# disable unnecessary threads
|
||||||
define HAL_NO_MONITOR_THREAD
|
define HAL_NO_MONITOR_THREAD
|
||||||
define HAL_NO_RCIN_THREAD
|
|
||||||
define HAL_NO_TIMER_THREAD
|
define HAL_NO_TIMER_THREAD
|
||||||
|
|
||||||
# enable LED
|
# enable LED
|
||||||
|
|
|
@ -55,7 +55,6 @@ define HAL_USE_EMPTY_IO TRUE
|
||||||
|
|
||||||
# avoid timer and RCIN threads to save memory
|
# avoid timer and RCIN threads to save memory
|
||||||
define HAL_NO_TIMER_THREAD
|
define HAL_NO_TIMER_THREAD
|
||||||
define HAL_NO_RCIN_THREAD
|
|
||||||
|
|
||||||
|
|
||||||
define DMA_RESERVE_SIZE 0
|
define DMA_RESERVE_SIZE 0
|
||||||
|
|
|
@ -80,9 +80,6 @@ define HAL_DISABLE_ADC_DRIVER TRUE
|
||||||
|
|
||||||
define HAL_NO_GPIO_IRQ
|
define HAL_NO_GPIO_IRQ
|
||||||
|
|
||||||
# avoid RCIN thread to save memory
|
|
||||||
define HAL_NO_RCIN_THREAD
|
|
||||||
|
|
||||||
define HAL_USE_RTC FALSE
|
define HAL_USE_RTC FALSE
|
||||||
|
|
||||||
define DMA_RESERVE_SIZE 0
|
define DMA_RESERVE_SIZE 0
|
||||||
|
|
|
@ -57,7 +57,6 @@ define HAL_USE_EMPTY_IO TRUE
|
||||||
|
|
||||||
# avoid timer and RCIN threads to save memory
|
# avoid timer and RCIN threads to save memory
|
||||||
define HAL_NO_TIMER_THREAD
|
define HAL_NO_TIMER_THREAD
|
||||||
define HAL_NO_RCIN_THREAD
|
|
||||||
|
|
||||||
define DMA_RESERVE_SIZE 0
|
define DMA_RESERVE_SIZE 0
|
||||||
|
|
||||||
|
|
|
@ -72,7 +72,6 @@ define HAL_DISABLE_ADC_DRIVER TRUE
|
||||||
define HAL_NO_GPIO_IRQ
|
define HAL_NO_GPIO_IRQ
|
||||||
|
|
||||||
# avoid RCIN thread to save memory
|
# avoid RCIN thread to save memory
|
||||||
define HAL_NO_RCIN_THREAD
|
|
||||||
define HAL_USE_RTC FALSE
|
define HAL_USE_RTC FALSE
|
||||||
|
|
||||||
define DMA_RESERVE_SIZE 0
|
define DMA_RESERVE_SIZE 0
|
||||||
|
|
|
@ -55,10 +55,8 @@ define STM32_SERIAL_USE_USART3 FALSE
|
||||||
define HAL_NO_GPIO_IRQ
|
define HAL_NO_GPIO_IRQ
|
||||||
define HAL_USE_EMPTY_IO TRUE
|
define HAL_USE_EMPTY_IO TRUE
|
||||||
|
|
||||||
# avoid timer and RCIN threads to save memory
|
# avoid timer thread to save memory
|
||||||
define HAL_NO_TIMER_THREAD
|
define HAL_NO_TIMER_THREAD
|
||||||
define HAL_NO_RCIN_THREAD
|
|
||||||
|
|
||||||
|
|
||||||
define DMA_RESERVE_SIZE 0
|
define DMA_RESERVE_SIZE 0
|
||||||
|
|
||||||
|
|
|
@ -110,9 +110,6 @@ define HAL_DISABLE_ADC_DRIVER TRUE
|
||||||
|
|
||||||
define HAL_NO_GPIO_IRQ
|
define HAL_NO_GPIO_IRQ
|
||||||
|
|
||||||
# avoid RCIN thread to save memory
|
|
||||||
define HAL_NO_RCIN_THREAD
|
|
||||||
|
|
||||||
define HAL_USE_RTC FALSE
|
define HAL_USE_RTC FALSE
|
||||||
|
|
||||||
define DMA_RESERVE_SIZE 0
|
define DMA_RESERVE_SIZE 0
|
||||||
|
|
|
@ -41,8 +41,6 @@ define HAL_DISABLE_LOOP_DELAY
|
||||||
|
|
||||||
define HAL_USE_RTC FALSE
|
define HAL_USE_RTC FALSE
|
||||||
|
|
||||||
define HAL_NO_RCIN_THREAD
|
|
||||||
|
|
||||||
define HAL_BARO_ALLOW_INIT_NO_BARO
|
define HAL_BARO_ALLOW_INIT_NO_BARO
|
||||||
|
|
||||||
define HAL_PERIPH_ENABLE_BATTERY
|
define HAL_PERIPH_ENABLE_BATTERY
|
||||||
|
|
|
@ -40,8 +40,6 @@ define HAL_USE_RTC FALSE
|
||||||
|
|
||||||
define HAL_GCS_ENABLED 1
|
define HAL_GCS_ENABLED 1
|
||||||
|
|
||||||
define HAL_NO_RCIN_THREAD
|
|
||||||
|
|
||||||
define HAL_BARO_ALLOW_INIT_NO_BARO
|
define HAL_BARO_ALLOW_INIT_NO_BARO
|
||||||
|
|
||||||
|
|
||||||
|
|
|
@ -37,8 +37,6 @@ define HAL_DISABLE_LOOP_DELAY
|
||||||
|
|
||||||
define HAL_USE_RTC FALSE
|
define HAL_USE_RTC FALSE
|
||||||
|
|
||||||
define HAL_NO_RCIN_THREAD
|
|
||||||
|
|
||||||
define HAL_BARO_ALLOW_INIT_NO_BARO
|
define HAL_BARO_ALLOW_INIT_NO_BARO
|
||||||
|
|
||||||
|
|
||||||
|
|
|
@ -75,7 +75,6 @@ define HAL_PERIPH_ENABLE_NETWORKING
|
||||||
# ---------------------------------------------------------------------------------------------
|
# ---------------------------------------------------------------------------------------------
|
||||||
# AP_Periph - boiler-plate configurations that all HW AP-Periph need
|
# AP_Periph - boiler-plate configurations that all HW AP-Periph need
|
||||||
# ---------------------------------------------------------------------------------------------
|
# ---------------------------------------------------------------------------------------------
|
||||||
define HAL_NO_RCIN_THREAD
|
|
||||||
#define HAL_NO_GPIO_IRQ
|
#define HAL_NO_GPIO_IRQ
|
||||||
define HAL_DISABLE_LOOP_DELAY
|
define HAL_DISABLE_LOOP_DELAY
|
||||||
|
|
||||||
|
|
|
@ -28,8 +28,6 @@ define HAL_DISABLE_LOOP_DELAY
|
||||||
|
|
||||||
define HAL_USE_RTC FALSE
|
define HAL_USE_RTC FALSE
|
||||||
|
|
||||||
define HAL_NO_RCIN_THREAD
|
|
||||||
|
|
||||||
# use amber LED
|
# use amber LED
|
||||||
define HAL_GPIO_PIN_LED HAL_GPIO_PIN_FMU_LED_AMBER
|
define HAL_GPIO_PIN_LED HAL_GPIO_PIN_FMU_LED_AMBER
|
||||||
|
|
||||||
|
|
|
@ -53,7 +53,6 @@ define HAL_USE_EMPTY_IO TRUE
|
||||||
|
|
||||||
# avoid timer and RCIN threads to save memory
|
# avoid timer and RCIN threads to save memory
|
||||||
define HAL_NO_TIMER_THREAD
|
define HAL_NO_TIMER_THREAD
|
||||||
define HAL_NO_RCIN_THREAD
|
|
||||||
|
|
||||||
define DMA_RESERVE_SIZE 0
|
define DMA_RESERVE_SIZE 0
|
||||||
|
|
||||||
|
|
|
@ -104,9 +104,6 @@ define HAL_DISABLE_ADC_DRIVER TRUE
|
||||||
|
|
||||||
define HAL_NO_GPIO_IRQ
|
define HAL_NO_GPIO_IRQ
|
||||||
|
|
||||||
# avoid RCIN thread to save memory
|
|
||||||
define HAL_NO_RCIN_THREAD
|
|
||||||
|
|
||||||
define DMA_RESERVE_SIZE 0
|
define DMA_RESERVE_SIZE 0
|
||||||
|
|
||||||
define HAL_DISABLE_LOOP_DELAY
|
define HAL_DISABLE_LOOP_DELAY
|
||||||
|
|
|
@ -61,8 +61,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
|
||||||
|
|
||||||
# avoid timer and RCIN threads to save memory
|
|
||||||
define HAL_NO_RCIN_THREAD
|
|
||||||
define HAL_NO_GPIO_IRQ
|
define HAL_NO_GPIO_IRQ
|
||||||
|
|
||||||
PB13 VBUS INPUT OPENDRAIN
|
PB13 VBUS INPUT OPENDRAIN
|
||||||
|
|
|
@ -61,8 +61,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
|
||||||
|
|
||||||
# avoid timer and RCIN threads to save memory
|
|
||||||
define HAL_NO_RCIN_THREAD
|
|
||||||
define HAL_NO_GPIO_IRQ
|
define HAL_NO_GPIO_IRQ
|
||||||
|
|
||||||
PB13 VBUS INPUT OPENDRAIN
|
PB13 VBUS INPUT OPENDRAIN
|
||||||
|
|
|
@ -103,7 +103,6 @@ define IO_THD_WA_SIZE 512
|
||||||
|
|
||||||
define AP_PARAM_MAX_EMBEDDED_PARAM 128
|
define AP_PARAM_MAX_EMBEDDED_PARAM 128
|
||||||
|
|
||||||
define HAL_NO_RCIN_THREAD
|
|
||||||
define HAL_NO_RCOUT_THREAD
|
define HAL_NO_RCOUT_THREAD
|
||||||
|
|
||||||
|
|
||||||
|
|
|
@ -56,8 +56,6 @@ define PORT_INT_REQUIRED_STACK 64
|
||||||
|
|
||||||
# avoid timer and RCIN threads to save memory
|
# avoid timer and RCIN threads to save memory
|
||||||
define HAL_NO_TIMER_THREAD
|
define HAL_NO_TIMER_THREAD
|
||||||
define HAL_NO_RCIN_THREAD
|
|
||||||
|
|
||||||
|
|
||||||
define DMA_RESERVE_SIZE 0
|
define DMA_RESERVE_SIZE 0
|
||||||
|
|
||||||
|
|
|
@ -74,9 +74,6 @@ define HAL_DISABLE_ADC_DRIVER TRUE
|
||||||
define HAL_NO_GPIO_IRQ
|
define HAL_NO_GPIO_IRQ
|
||||||
define SERIAL_BUFFERS_SIZE 512
|
define SERIAL_BUFFERS_SIZE 512
|
||||||
|
|
||||||
# avoid timer and RCIN threads to save memory
|
|
||||||
define HAL_NO_RCIN_THREAD
|
|
||||||
|
|
||||||
define HAL_USE_RTC FALSE
|
define HAL_USE_RTC FALSE
|
||||||
|
|
||||||
define DMA_RESERVE_SIZE 0
|
define DMA_RESERVE_SIZE 0
|
||||||
|
|
|
@ -54,9 +54,8 @@ define STM32_SERIAL_USE_USART3 FALSE
|
||||||
define HAL_NO_GPIO_IRQ
|
define HAL_NO_GPIO_IRQ
|
||||||
define HAL_USE_EMPTY_IO TRUE
|
define HAL_USE_EMPTY_IO TRUE
|
||||||
|
|
||||||
# avoid timer and RCIN threads to save memory
|
# avoid timer threads to save memory
|
||||||
define HAL_NO_TIMER_THREAD
|
define HAL_NO_TIMER_THREAD
|
||||||
define HAL_NO_RCIN_THREAD
|
|
||||||
|
|
||||||
define DMA_RESERVE_SIZE 0
|
define DMA_RESERVE_SIZE 0
|
||||||
|
|
||||||
|
|
|
@ -72,9 +72,6 @@ define HAL_DISABLE_ADC_DRIVER TRUE
|
||||||
|
|
||||||
define HAL_NO_GPIO_IRQ
|
define HAL_NO_GPIO_IRQ
|
||||||
|
|
||||||
# avoid RCIN thread to save memory
|
|
||||||
define HAL_NO_RCIN_THREAD
|
|
||||||
|
|
||||||
define HAL_USE_RTC FALSE
|
define HAL_USE_RTC FALSE
|
||||||
|
|
||||||
define DMA_RESERVE_SIZE 0
|
define DMA_RESERVE_SIZE 0
|
||||||
|
|
|
@ -54,9 +54,8 @@ define STM32_SERIAL_USE_USART3 FALSE
|
||||||
define HAL_NO_GPIO_IRQ
|
define HAL_NO_GPIO_IRQ
|
||||||
define HAL_USE_EMPTY_IO TRUE
|
define HAL_USE_EMPTY_IO TRUE
|
||||||
|
|
||||||
# avoid timer and RCIN threads to save memory
|
# avoid timer threads to save memory
|
||||||
define HAL_NO_TIMER_THREAD
|
define HAL_NO_TIMER_THREAD
|
||||||
define HAL_NO_RCIN_THREAD
|
|
||||||
|
|
||||||
define DMA_RESERVE_SIZE 0
|
define DMA_RESERVE_SIZE 0
|
||||||
|
|
||||||
|
|
|
@ -95,9 +95,6 @@ define HAL_DISABLE_ADC_DRIVER TRUE
|
||||||
|
|
||||||
define HAL_NO_GPIO_IRQ
|
define HAL_NO_GPIO_IRQ
|
||||||
|
|
||||||
# avoid RCIN thread to save memory
|
|
||||||
define HAL_NO_RCIN_THREAD
|
|
||||||
|
|
||||||
define HAL_USE_RTC FALSE
|
define HAL_USE_RTC FALSE
|
||||||
|
|
||||||
define DMA_RESERVE_SIZE 0
|
define DMA_RESERVE_SIZE 0
|
||||||
|
|
|
@ -55,8 +55,6 @@ define HAL_USE_EMPTY_IO TRUE
|
||||||
|
|
||||||
# avoid timer and RCIN threads to save memory
|
# avoid timer and RCIN threads to save memory
|
||||||
define HAL_NO_TIMER_THREAD
|
define HAL_NO_TIMER_THREAD
|
||||||
define HAL_NO_RCIN_THREAD
|
|
||||||
|
|
||||||
|
|
||||||
define DMA_RESERVE_SIZE 0
|
define DMA_RESERVE_SIZE 0
|
||||||
|
|
||||||
|
|
|
@ -112,9 +112,6 @@ define HAL_DISABLE_ADC_DRIVER TRUE
|
||||||
|
|
||||||
define HAL_NO_GPIO_IRQ
|
define HAL_NO_GPIO_IRQ
|
||||||
|
|
||||||
# avoid RCIN thread to save memory
|
|
||||||
define HAL_NO_RCIN_THREAD
|
|
||||||
|
|
||||||
define HAL_USE_RTC FALSE
|
define HAL_USE_RTC FALSE
|
||||||
|
|
||||||
define DMA_RESERVE_SIZE 0
|
define DMA_RESERVE_SIZE 0
|
||||||
|
|
|
@ -43,8 +43,6 @@ define HAL_PERIPH_ADSB_BAUD_DEFAULT 0
|
||||||
define HAL_NO_MONITOR_THREAD
|
define HAL_NO_MONITOR_THREAD
|
||||||
define HAL_DISABLE_LOOP_DELAY
|
define HAL_DISABLE_LOOP_DELAY
|
||||||
define HAL_USE_RTC FALSE
|
define HAL_USE_RTC FALSE
|
||||||
define HAL_NO_RCIN_THREAD
|
|
||||||
|
|
||||||
|
|
||||||
define AP_SCRIPTING_ENABLED 0
|
define AP_SCRIPTING_ENABLED 0
|
||||||
|
|
||||||
|
|
|
@ -14,7 +14,6 @@ define HAL_USE_ADC FALSE
|
||||||
|
|
||||||
# disable unnecessary threads
|
# disable unnecessary threads
|
||||||
define HAL_NO_MONITOR_THREAD
|
define HAL_NO_MONITOR_THREAD
|
||||||
define HAL_NO_RCIN_THREAD
|
|
||||||
define HAL_NO_RCOUT_THREAD
|
define HAL_NO_RCOUT_THREAD
|
||||||
define HAL_NO_TIMER_THREAD
|
define HAL_NO_TIMER_THREAD
|
||||||
|
|
||||||
|
|
|
@ -38,7 +38,6 @@ define HAL_USE_ADC FALSE
|
||||||
|
|
||||||
# disable unnecessary threads
|
# disable unnecessary threads
|
||||||
define HAL_NO_MONITOR_THREAD
|
define HAL_NO_MONITOR_THREAD
|
||||||
define HAL_NO_RCIN_THREAD
|
|
||||||
define HAL_NO_RCOUT_THREAD
|
define HAL_NO_RCOUT_THREAD
|
||||||
define HAL_NO_TIMER_THREAD
|
define HAL_NO_TIMER_THREAD
|
||||||
|
|
||||||
|
|
|
@ -29,8 +29,6 @@ define HAL_DISABLE_LOOP_DELAY
|
||||||
|
|
||||||
define HAL_USE_RTC FALSE
|
define HAL_USE_RTC FALSE
|
||||||
|
|
||||||
define HAL_NO_RCIN_THREAD
|
|
||||||
|
|
||||||
# use blue LED
|
# use blue LED
|
||||||
define HAL_GPIO_PIN_LED HAL_GPIO_PIN_LED_BLUE
|
define HAL_GPIO_PIN_LED HAL_GPIO_PIN_LED_BLUE
|
||||||
|
|
||||||
|
|
|
@ -41,8 +41,6 @@ define HAL_DISABLE_LOOP_DELAY
|
||||||
|
|
||||||
define HAL_USE_RTC FALSE
|
define HAL_USE_RTC FALSE
|
||||||
|
|
||||||
define HAL_NO_RCIN_THREAD
|
|
||||||
|
|
||||||
define HAL_BARO_ALLOW_INIT_NO_BARO
|
define HAL_BARO_ALLOW_INIT_NO_BARO
|
||||||
|
|
||||||
define HAL_USE_ADC TRUE
|
define HAL_USE_ADC TRUE
|
||||||
|
|
|
@ -30,9 +30,6 @@ STDOUT_BAUDRATE 57600
|
||||||
|
|
||||||
define HAL_NO_GPIO_IRQ
|
define HAL_NO_GPIO_IRQ
|
||||||
|
|
||||||
# avoid timer and RCIN threads to save memory
|
|
||||||
define HAL_NO_RCIN_THREAD
|
|
||||||
|
|
||||||
define HAL_USE_RTC FALSE
|
define HAL_USE_RTC FALSE
|
||||||
|
|
||||||
define DMA_RESERVE_SIZE 0
|
define DMA_RESERVE_SIZE 0
|
||||||
|
|
|
@ -85,7 +85,6 @@ PA0 VSENSE ADC1 SCALE(2)
|
||||||
define HAL_NO_GPIO_IRQ
|
define HAL_NO_GPIO_IRQ
|
||||||
|
|
||||||
# avoid RCIN thread to save memory
|
# avoid RCIN thread to save memory
|
||||||
define HAL_NO_RCIN_THREAD
|
|
||||||
define HAL_USE_RTC FALSE
|
define HAL_USE_RTC FALSE
|
||||||
define DMA_RESERVE_SIZE 0
|
define DMA_RESERVE_SIZE 0
|
||||||
define PERIPH_FW TRUE
|
define PERIPH_FW TRUE
|
||||||
|
|
|
@ -96,7 +96,6 @@ PA0 VSENSE ADC1 SCALE(2)
|
||||||
define HAL_NO_GPIO_IRQ
|
define HAL_NO_GPIO_IRQ
|
||||||
|
|
||||||
# avoid RCIN thread to save memory
|
# avoid RCIN thread to save memory
|
||||||
define HAL_NO_RCIN_THREAD
|
|
||||||
define HAL_USE_RTC TRUE
|
define HAL_USE_RTC TRUE
|
||||||
define DMA_RESERVE_SIZE 0
|
define DMA_RESERVE_SIZE 0
|
||||||
define HAL_DISABLE_LOOP_DELAY
|
define HAL_DISABLE_LOOP_DELAY
|
||||||
|
|
|
@ -62,7 +62,6 @@ define HAL_DISABLE_LOOP_DELAY
|
||||||
|
|
||||||
# avoid timer and RCIN threads to save memory
|
# avoid timer and RCIN threads to save memory
|
||||||
define HAL_NO_TIMER_THREAD
|
define HAL_NO_TIMER_THREAD
|
||||||
define HAL_NO_RCIN_THREAD
|
|
||||||
|
|
||||||
# enable CAN support
|
# enable CAN support
|
||||||
PB8 CAN1_RX CAN1
|
PB8 CAN1_RX CAN1
|
||||||
|
|
|
@ -41,7 +41,6 @@ define HAL_GCS_ENABLED 0
|
||||||
define HAL_NO_MONITOR_THREAD
|
define HAL_NO_MONITOR_THREAD
|
||||||
define HAL_NO_LOGGING
|
define HAL_NO_LOGGING
|
||||||
define HAL_USE_ADC FALSE
|
define HAL_USE_ADC FALSE
|
||||||
define HAL_NO_RCIN_THREAD
|
|
||||||
|
|
||||||
# we setup a small defaults.parm
|
# we setup a small defaults.parm
|
||||||
define AP_PARAM_MAX_EMBEDDED_PARAM 256
|
define AP_PARAM_MAX_EMBEDDED_PARAM 256
|
||||||
|
|
|
@ -33,7 +33,6 @@ PA14 JTCK-SWCLK SWD
|
||||||
define HAL_NO_GPIO_IRQ
|
define HAL_NO_GPIO_IRQ
|
||||||
define HAL_USE_EMPTY_IO TRUE
|
define HAL_USE_EMPTY_IO TRUE
|
||||||
define HAL_NO_TIMER_THREAD
|
define HAL_NO_TIMER_THREAD
|
||||||
define HAL_NO_RCIN_THREAD
|
|
||||||
define DMA_RESERVE_SIZE 0
|
define DMA_RESERVE_SIZE 0
|
||||||
define HAL_DISABLE_LOOP_DELAY
|
define HAL_DISABLE_LOOP_DELAY
|
||||||
define HAL_USE_SERIAL FALSE
|
define HAL_USE_SERIAL FALSE
|
||||||
|
|
|
@ -66,9 +66,6 @@ define STM32_ADC_USE_ADC1 FALSE
|
||||||
define HAL_DISABLE_ADC_DRIVER TRUE
|
define HAL_DISABLE_ADC_DRIVER TRUE
|
||||||
define HAL_NO_GPIO_IRQ
|
define HAL_NO_GPIO_IRQ
|
||||||
|
|
||||||
# avoid RCIN thread to save memory
|
|
||||||
define HAL_NO_RCIN_THREAD
|
|
||||||
|
|
||||||
define HAL_USE_RTC FALSE
|
define HAL_USE_RTC FALSE
|
||||||
define DMA_RESERVE_SIZE 0
|
define DMA_RESERVE_SIZE 0
|
||||||
define HAL_DISABLE_LOOP_DELAY
|
define HAL_DISABLE_LOOP_DELAY
|
||||||
|
|
|
@ -39,7 +39,6 @@ PROCESS_STACK 0xA00
|
||||||
define HAL_DISABLE_LOOP_DELAY
|
define HAL_DISABLE_LOOP_DELAY
|
||||||
define HAL_NO_MONITOR_THREAD
|
define HAL_NO_MONITOR_THREAD
|
||||||
define HAL_USE_ADC FALSE
|
define HAL_USE_ADC FALSE
|
||||||
define HAL_NO_RCIN_THREAD
|
|
||||||
|
|
||||||
# we setup a small defaults.parm
|
# we setup a small defaults.parm
|
||||||
define AP_PARAM_MAX_EMBEDDED_PARAM 256
|
define AP_PARAM_MAX_EMBEDDED_PARAM 256
|
||||||
|
|
|
@ -39,7 +39,6 @@ PROCESS_STACK 0xA00
|
||||||
define HAL_DISABLE_LOOP_DELAY
|
define HAL_DISABLE_LOOP_DELAY
|
||||||
define HAL_NO_MONITOR_THREAD
|
define HAL_NO_MONITOR_THREAD
|
||||||
define HAL_USE_ADC FALSE
|
define HAL_USE_ADC FALSE
|
||||||
define HAL_NO_RCIN_THREAD
|
|
||||||
|
|
||||||
# we setup a small defaults.parm
|
# we setup a small defaults.parm
|
||||||
define AP_PARAM_MAX_EMBEDDED_PARAM 256
|
define AP_PARAM_MAX_EMBEDDED_PARAM 256
|
||||||
|
|
|
@ -39,7 +39,6 @@ PROCESS_STACK 0xA00
|
||||||
define HAL_DISABLE_LOOP_DELAY
|
define HAL_DISABLE_LOOP_DELAY
|
||||||
define HAL_NO_MONITOR_THREAD
|
define HAL_NO_MONITOR_THREAD
|
||||||
define HAL_USE_ADC FALSE
|
define HAL_USE_ADC FALSE
|
||||||
define HAL_NO_RCIN_THREAD
|
|
||||||
|
|
||||||
# we setup a small defaults.parm
|
# we setup a small defaults.parm
|
||||||
define AP_PARAM_MAX_EMBEDDED_PARAM 256
|
define AP_PARAM_MAX_EMBEDDED_PARAM 256
|
||||||
|
|
|
@ -71,7 +71,6 @@ define PORT_INT_REQUIRED_STACK 64
|
||||||
|
|
||||||
# avoid timer and RCIN threads to save memory
|
# avoid timer and RCIN threads to save memory
|
||||||
define HAL_NO_TIMER_THREAD
|
define HAL_NO_TIMER_THREAD
|
||||||
define HAL_NO_RCIN_THREAD
|
|
||||||
|
|
||||||
#defined to turn off undef warnings
|
#defined to turn off undef warnings
|
||||||
define __FPU_PRESENT 0
|
define __FPU_PRESENT 0
|
||||||
|
|
|
@ -94,9 +94,6 @@ define CH_CFG_ST_TIMEDELTA 0
|
||||||
define SERIAL_BUFFERS_SIZE 512
|
define SERIAL_BUFFERS_SIZE 512
|
||||||
define PORT_INT_REQUIRED_STACK 64
|
define PORT_INT_REQUIRED_STACK 64
|
||||||
|
|
||||||
# avoid RCIN thread to save memory
|
|
||||||
define HAL_NO_RCIN_THREAD
|
|
||||||
|
|
||||||
#defined to turn off undef warnings
|
#defined to turn off undef warnings
|
||||||
define __FPU_PRESENT 0
|
define __FPU_PRESENT 0
|
||||||
|
|
||||||
|
|
|
@ -64,7 +64,6 @@ define PORT_INT_REQUIRED_STACK 64
|
||||||
# avoid timer and RCIN threads to save memory
|
# avoid timer and RCIN threads to save memory
|
||||||
define HAL_NO_TIMER_THREAD
|
define HAL_NO_TIMER_THREAD
|
||||||
define HAL_NO_RCOUT_THREAD
|
define HAL_NO_RCOUT_THREAD
|
||||||
define HAL_NO_RCIN_THREAD
|
|
||||||
|
|
||||||
#defined to turn off undef warnings
|
#defined to turn off undef warnings
|
||||||
define __FPU_PRESENT 0
|
define __FPU_PRESENT 0
|
||||||
|
|
|
@ -45,9 +45,6 @@ define HAL_NO_GPIO_IRQ
|
||||||
define SERIAL_BUFFERS_SIZE 512
|
define SERIAL_BUFFERS_SIZE 512
|
||||||
define PORT_INT_REQUIRED_STACK 64
|
define PORT_INT_REQUIRED_STACK 64
|
||||||
|
|
||||||
# avoid timer and RCIN threads to save memory
|
|
||||||
define HAL_NO_RCIN_THREAD
|
|
||||||
|
|
||||||
define HAL_USE_RTC FALSE
|
define HAL_USE_RTC FALSE
|
||||||
|
|
||||||
define DMA_RESERVE_SIZE 0
|
define DMA_RESERVE_SIZE 0
|
||||||
|
|
|
@ -65,8 +65,6 @@ define HAL_NO_GPIO_IRQ
|
||||||
define SERIAL_BUFFERS_SIZE 512
|
define SERIAL_BUFFERS_SIZE 512
|
||||||
define PORT_INT_REQUIRED_STACK 64
|
define PORT_INT_REQUIRED_STACK 64
|
||||||
|
|
||||||
# avoid timer and RCIN threads to save memory
|
|
||||||
define HAL_NO_RCIN_THREAD
|
|
||||||
define HAL_NO_RCOUT_THREAD
|
define HAL_NO_RCOUT_THREAD
|
||||||
|
|
||||||
define HAL_USE_RTC FALSE
|
define HAL_USE_RTC FALSE
|
||||||
|
|
|
@ -39,9 +39,6 @@ define PORT_INT_REQUIRED_STACK 64
|
||||||
#PA13 JTMS-SWDIO SWD
|
#PA13 JTMS-SWDIO SWD
|
||||||
#PA14 JTCK-SWCLK SWD
|
#PA14 JTCK-SWCLK SWD
|
||||||
|
|
||||||
# avoid timer and RCIN threads to save memory
|
|
||||||
define HAL_NO_RCIN_THREAD
|
|
||||||
|
|
||||||
define HAL_USE_RTC FALSE
|
define HAL_USE_RTC FALSE
|
||||||
|
|
||||||
define DMA_RESERVE_SIZE 0
|
define DMA_RESERVE_SIZE 0
|
||||||
|
|
|
@ -106,9 +106,8 @@ define SERIAL_BUFFERS_SIZE 32
|
||||||
define HAL_USE_EMPTY_IO TRUE
|
define HAL_USE_EMPTY_IO TRUE
|
||||||
define PORT_INT_REQUIRED_STACK 64
|
define PORT_INT_REQUIRED_STACK 64
|
||||||
|
|
||||||
# avoid timer and RCIN threads to save memory
|
# avoid timer threads to save memory
|
||||||
define HAL_NO_TIMER_THREAD
|
define HAL_NO_TIMER_THREAD
|
||||||
define HAL_NO_RCIN_THREAD
|
|
||||||
define HAL_NO_MONITOR_THREAD
|
define HAL_NO_MONITOR_THREAD
|
||||||
define HAL_NO_RCOUT_THREAD # also disables LED thread
|
define HAL_NO_RCOUT_THREAD # also disables LED thread
|
||||||
|
|
||||||
|
|
|
@ -131,7 +131,6 @@ define HAL_DISABLE_ADC_DRIVER TRUE
|
||||||
# ---------------------------------------------------------------------------------------------
|
# ---------------------------------------------------------------------------------------------
|
||||||
# AP_Periph - boiler-plate configurations that all HW AP-Periph need
|
# AP_Periph - boiler-plate configurations that all HW AP-Periph need
|
||||||
# ---------------------------------------------------------------------------------------------
|
# ---------------------------------------------------------------------------------------------
|
||||||
define HAL_NO_RCIN_THREAD
|
|
||||||
#define HAL_NO_GPIO_IRQ
|
#define HAL_NO_GPIO_IRQ
|
||||||
define HAL_DISABLE_LOOP_DELAY
|
define HAL_DISABLE_LOOP_DELAY
|
||||||
define HAL_PERIPH_SHOW_SERIAL_MANAGER_PARAMS
|
define HAL_PERIPH_SHOW_SERIAL_MANAGER_PARAMS
|
||||||
|
|
|
@ -64,7 +64,6 @@ define STM32_SERIAL_USE_USART3 FALSE
|
||||||
|
|
||||||
# avoid timer and RCIN threads to save memory
|
# avoid timer and RCIN threads to save memory
|
||||||
define HAL_NO_TIMER_THREAD
|
define HAL_NO_TIMER_THREAD
|
||||||
define HAL_NO_RCIN_THREAD
|
|
||||||
|
|
||||||
define DMA_RESERVE_SIZE 0
|
define DMA_RESERVE_SIZE 0
|
||||||
|
|
||||||
|
|
|
@ -53,9 +53,6 @@ define HAL_DISABLE_ADC_DRIVER TRUE
|
||||||
|
|
||||||
define HAL_NO_GPIO_IRQ
|
define HAL_NO_GPIO_IRQ
|
||||||
|
|
||||||
# avoid RCIN thread to save memory
|
|
||||||
define HAL_NO_RCIN_THREAD
|
|
||||||
|
|
||||||
define HAL_USE_RTC FALSE
|
define HAL_USE_RTC FALSE
|
||||||
|
|
||||||
#define DMA_RESERVE_SIZE 2048
|
#define DMA_RESERVE_SIZE 2048
|
||||||
|
|
|
@ -58,7 +58,6 @@ define HAL_USE_EMPTY_IO TRUE
|
||||||
|
|
||||||
# avoid timer and RCIN threads to save memory
|
# avoid timer and RCIN threads to save memory
|
||||||
define HAL_NO_TIMER_THREAD
|
define HAL_NO_TIMER_THREAD
|
||||||
define HAL_NO_RCIN_THREAD
|
|
||||||
|
|
||||||
define DMA_RESERVE_SIZE 0
|
define DMA_RESERVE_SIZE 0
|
||||||
|
|
||||||
|
|
|
@ -91,9 +91,6 @@ define HAL_DISABLE_ADC_DRIVER TRUE
|
||||||
|
|
||||||
define HAL_NO_GPIO_IRQ
|
define HAL_NO_GPIO_IRQ
|
||||||
|
|
||||||
# avoid RCIN thread to save memory
|
|
||||||
define HAL_NO_RCIN_THREAD
|
|
||||||
|
|
||||||
define HAL_USE_RTC FALSE
|
define HAL_USE_RTC FALSE
|
||||||
|
|
||||||
define DMA_RESERVE_SIZE 0
|
define DMA_RESERVE_SIZE 0
|
||||||
|
|
|
@ -1220,7 +1220,9 @@ class ChibiOSHWDef(object):
|
||||||
// avoid timer and RCIN threads to save memory
|
// avoid timer and RCIN threads to save memory
|
||||||
#define HAL_NO_TIMER_THREAD
|
#define HAL_NO_TIMER_THREAD
|
||||||
#define HAL_NO_RCOUT_THREAD
|
#define HAL_NO_RCOUT_THREAD
|
||||||
#define HAL_NO_RCIN_THREAD
|
#ifndef HAL_RCIN_THREAD_ENABLED
|
||||||
|
#define HAL_RCIN_THREAD_ENABLED 0
|
||||||
|
#endif
|
||||||
#ifndef AP_HAL_SHARED_DMA_ENABLED
|
#ifndef AP_HAL_SHARED_DMA_ENABLED
|
||||||
#define AP_HAL_SHARED_DMA_ENABLED 0
|
#define AP_HAL_SHARED_DMA_ENABLED 0
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -321,6 +321,10 @@
|
||||||
#define HAL_SERIAL_ESC_COMM_ENABLED 0
|
#define HAL_SERIAL_ESC_COMM_ENABLED 0
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#ifndef HAL_RCIN_THREAD_ENABLED
|
||||||
|
#define HAL_RCIN_THREAD_ENABLED 0
|
||||||
|
#endif
|
||||||
|
|
||||||
#ifndef HAL_WITH_ESC_TELEM
|
#ifndef HAL_WITH_ESC_TELEM
|
||||||
#define HAL_WITH_ESC_TELEM 0
|
#define HAL_WITH_ESC_TELEM 0
|
||||||
#endif
|
#endif
|
||||||
|
|
Loading…
Reference in New Issue