HAL_ChibiOS: fixed fmuv4 build

This commit is contained in:
Andrew Tridgell 2018-02-02 21:17:58 +11:00
parent 9acacba53b
commit 6b187b393a
1 changed files with 2 additions and 2 deletions

View File

@ -38,7 +38,7 @@ THD_WORKING_AREA(_rcin_thread_wa, 512);
THD_WORKING_AREA(_io_thread_wa, 2048); THD_WORKING_AREA(_io_thread_wa, 2048);
THD_WORKING_AREA(_storage_thread_wa, 2048); THD_WORKING_AREA(_storage_thread_wa, 2048);
THD_WORKING_AREA(_uart_thread_wa, 2048); THD_WORKING_AREA(_uart_thread_wa, 2048);
#ifdef HAL_WITH_UAVCAN #if HAL_WITH_UAVCAN
THD_WORKING_AREA(_uavcan_thread_wa, 4096); THD_WORKING_AREA(_uavcan_thread_wa, 4096);
#endif #endif
#if HAL_WITH_IO_MCU #if HAL_WITH_IO_MCU
@ -58,7 +58,7 @@ void Scheduler::init()
this); /* Thread parameter. */ this); /* Thread parameter. */
// setup the timer thread - this will call tasks at 1kHz // setup the timer thread - this will call tasks at 1kHz
#ifdef HAL_WITH_UAVCAN #if HAL_WITH_UAVCAN
_uavcan_thread_ctx = chThdCreateStatic(_uavcan_thread_wa, _uavcan_thread_ctx = chThdCreateStatic(_uavcan_thread_wa,
sizeof(_uavcan_thread_wa), sizeof(_uavcan_thread_wa),
APM_UAVCAN_PRIORITY, /* Initial priority. */ APM_UAVCAN_PRIORITY, /* Initial priority. */