|
|
|
@ -25,6 +25,7 @@
@@ -25,6 +25,7 @@
|
|
|
|
|
#include <AP_HAL_ChibiOS/Storage.h> |
|
|
|
|
#include <AP_HAL_ChibiOS/RCOutput.h> |
|
|
|
|
#include <AP_HAL_ChibiOS/RCInput.h> |
|
|
|
|
#include <AP_HAL_ChibiOS/CAN.h> |
|
|
|
|
|
|
|
|
|
#include <AP_Scheduler/AP_Scheduler.h> |
|
|
|
|
#include <AP_BoardConfig/AP_BoardConfig.h> |
|
|
|
@ -37,7 +38,9 @@ THD_WORKING_AREA(_rcin_thread_wa, 512);
@@ -37,7 +38,9 @@ THD_WORKING_AREA(_rcin_thread_wa, 512);
|
|
|
|
|
THD_WORKING_AREA(_io_thread_wa, 2048); |
|
|
|
|
THD_WORKING_AREA(_storage_thread_wa, 2048); |
|
|
|
|
THD_WORKING_AREA(_uart_thread_wa, 2048); |
|
|
|
|
|
|
|
|
|
#ifdef HAL_WITH_UAVCAN |
|
|
|
|
THD_WORKING_AREA(_uavcan_thread_wa, 2048); |
|
|
|
|
#endif |
|
|
|
|
#if HAL_WITH_IO_MCU |
|
|
|
|
extern ChibiOS::UARTDriver uart_io; |
|
|
|
|
#endif |
|
|
|
@ -54,6 +57,14 @@ void Scheduler::init()
@@ -54,6 +57,14 @@ void Scheduler::init()
|
|
|
|
|
_timer_thread, /* Thread function. */ |
|
|
|
|
this); /* Thread parameter. */ |
|
|
|
|
|
|
|
|
|
// setup the timer thread - this will call tasks at 1kHz
|
|
|
|
|
#ifdef HAL_WITH_UAVCAN |
|
|
|
|
_uavcan_thread_ctx = chThdCreateStatic(_uavcan_thread_wa, |
|
|
|
|
sizeof(_uavcan_thread_wa), |
|
|
|
|
APM_UAVCAN_PRIORITY, /* Initial priority. */ |
|
|
|
|
_uavcan_thread, /* Thread function. */ |
|
|
|
|
this); /* Thread parameter. */ |
|
|
|
|
#endif |
|
|
|
|
// setup the RCIN thread - this will call tasks at 1kHz
|
|
|
|
|
_rcin_thread_ctx = chThdCreateStatic(_rcin_thread_wa, |
|
|
|
|
sizeof(_rcin_thread_wa), |
|
|
|
@ -264,6 +275,24 @@ void Scheduler::_timer_thread(void *arg)
@@ -264,6 +275,24 @@ void Scheduler::_timer_thread(void *arg)
|
|
|
|
|
hal.rcout->timer_tick(); |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
#if HAL_WITH_UAVCAN |
|
|
|
|
void Scheduler::_uavcan_thread(void *arg) |
|
|
|
|
{ |
|
|
|
|
Scheduler *sched = (Scheduler *)arg; |
|
|
|
|
sched->_rcin_thread_ctx->name = "apm_uavcan"; |
|
|
|
|
while (!sched->_hal_initialized) { |
|
|
|
|
sched->delay_microseconds(20000); |
|
|
|
|
} |
|
|
|
|
while (true) { |
|
|
|
|
sched->delay_microseconds(1000); |
|
|
|
|
for (int i = 0; i < MAX_NUMBER_OF_CAN_INTERFACES; i++) { |
|
|
|
|
if(hal.can_mgr[i] != nullptr) { |
|
|
|
|
CANManager::from(hal.can_mgr[i])->_timer_tick(); |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
#endif |
|
|
|
|
|
|
|
|
|
void Scheduler::_rcin_thread(void *arg) |
|
|
|
|
{ |
|
|
|
|