AP_HAL_ChibiOS: remove CAN thread management

This commit is contained in:
Francisco Ferreira 2018-02-27 23:59:47 +00:00
parent 0645a5b11a
commit 7278af05e0
No known key found for this signature in database
GPG Key ID: F63C20A6773E787E
4 changed files with 6 additions and 70 deletions

View File

@ -56,23 +56,4 @@ void CANManager::initialized(bool val)
initialized_ = val;
}
AP_UAVCAN *CANManager::get_UAVCAN(void)
{
return p_uavcan;
}
void CANManager::set_UAVCAN(AP_UAVCAN *uavcan)
{
p_uavcan = uavcan;
}
void CANManager::_timer_tick()
{
if (!initialized_) return;
if (p_uavcan != nullptr) {
p_uavcan->do_cyclic();
}
}
#endif //HAL_WITH_UAVCAN

View File

@ -21,7 +21,7 @@
#if HAL_WITH_UAVCAN
#define UAVCAN_STM32_LOG(fmt, ...) hal.console->printf("CANManager: " fmt "\n", ##__VA_ARGS__)
#define CAN_STM32_LOG(fmt, ...) hal.console->printf("CANManager: " fmt "\n", ##__VA_ARGS__)
#include <uavcan/uavcan.hpp>
#include <uavcan/time.hpp>
@ -30,12 +30,9 @@
#include <uavcan_stm32/clock.hpp>
#include <uavcan_stm32/can.hpp>
#include <AP_UAVCAN/AP_UAVCAN.h>
#define MAX_NUMBER_OF_CAN_INTERFACES 2
#define MAX_NUMBER_OF_CAN_DRIVERS 2
#define CAN_STM32_RX_QUEUE_SIZE 64
class AP_UAVCAN;
namespace ChibiOS {
/**
@ -67,12 +64,7 @@ public:
bool is_initialized() override;
void initialized(bool val) override;
AP_UAVCAN *get_UAVCAN(void) override;
void set_UAVCAN(AP_UAVCAN *uavcan) override;
void _timer_tick();
private:
AP_UAVCAN *p_uavcan;
bool initialized_;
uavcan_stm32::CanInitHelper<CAN_STM32_RX_QUEUE_SIZE> can_helper;
};

View File

@ -43,9 +43,6 @@ THD_WORKING_AREA(_timer_thread_wa, 2048);
THD_WORKING_AREA(_rcin_thread_wa, 512);
THD_WORKING_AREA(_io_thread_wa, 2048);
THD_WORKING_AREA(_storage_thread_wa, 2048);
#if HAL_WITH_UAVCAN
THD_WORKING_AREA(_uavcan_thread_wa, 4096);
#endif
Scheduler::Scheduler()
{
@ -62,14 +59,6 @@ void Scheduler::init()
_timer_thread, /* Thread function. */
this); /* Thread parameter. */
// setup the uavcan thread - this will call tasks at 1kHz
#if 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),
@ -286,24 +275,6 @@ void Scheduler::_timer_thread(void *arg)
hal.rcout->timer_tick();
}
}
#if HAL_WITH_UAVCAN
void Scheduler::_uavcan_thread(void *arg)
{
Scheduler *sched = (Scheduler *)arg;
chRegSetThreadName("apm_uavcan");
while (!sched->_hal_initialized) {
sched->delay_microseconds(20000);
}
while (true) {
sched->delay_microseconds(300);
for (int i = 0; i < MAX_NUMBER_OF_CAN_INTERFACES; i++) {
if (AP_UAVCAN::get_uavcan(i) != nullptr) {
CANManager::from(hal.can_mgr[i])->_timer_tick();
}
}
}
}
#endif
void Scheduler::_rcin_thread(void *arg)
{

View File

@ -43,12 +43,8 @@
#define APM_SPI_PRIORITY 181
#endif
#ifndef APM_UAVCAN_PRIORITY
#define APM_UAVCAN_PRIORITY 178
#endif
#ifndef APM_CAN_PRIORITY
#define APM_CAN_PRIORITY 177
#define APM_CAN_PRIORITY 178
#endif
#ifndef APM_I2C_PRIORITY
@ -96,14 +92,14 @@ public:
create a new thread
*/
bool thread_create(AP_HAL::MemberProc, const char *name, uint32_t stack_size, priority_base base, int8_t priority) override;
private:
bool _initialized;
volatile bool _hal_initialized;
AP_HAL::Proc _failsafe;
bool _called_boost;
bool _priority_boosted;
AP_HAL::MemberProc _timer_proc[CHIBIOS_SCHEDULER_MAX_TIMER_PROCS];
uint8_t _num_timer_procs;
@ -117,9 +113,7 @@ private:
thread_t* _rcin_thread_ctx;
thread_t* _io_thread_ctx;
thread_t* _storage_thread_ctx;
#if HAL_WITH_UAVCAN
thread_t* _uavcan_thread_ctx;
#endif
#if CH_CFG_USE_SEMAPHORES == TRUE
binary_semaphore_t _timer_semaphore;
binary_semaphore_t _io_semaphore;
@ -129,9 +123,7 @@ private:
static void _io_thread(void *arg);
static void _storage_thread(void *arg);
static void _uart_thread(void *arg);
#if HAL_WITH_UAVCAN
static void _uavcan_thread(void *arg);
#endif
void _run_timers();
void _run_io(void);
static void thread_create_trampoline(void *ctx);