AP_HAL_PX4: remove CAN thread management

This commit is contained in:
Francisco Ferreira 2018-02-28 00:01:13 +00:00
parent 1d7f3e48a4
commit 68ada13f28
No known key found for this signature in database
GPG Key ID: F63C20A6773E787E
4 changed files with 1 additions and 89 deletions

View File

@ -35,8 +35,6 @@
extern const AP_HAL::HAL& hal; extern const AP_HAL::HAL& hal;
#include <AP_UAVCAN/AP_UAVCAN.h>
extern "C" { extern "C" {
static int can1_irq(const int irq, void*); static int can1_irq(const int irq, void*);
#if CAN_STM32_NUM_IFACES > 1 #if CAN_STM32_NUM_IFACES > 1
@ -826,7 +824,7 @@ int32_t PX4CAN::tx_pending()
PX4CANManager::PX4CANManager() : PX4CANManager::PX4CANManager() :
AP_HAL::CANManager(this), update_event_(*this), if0_(bxcan::Can[0], nullptr, 0, CAN_STM32_RX_QUEUE_SIZE), if1_( AP_HAL::CANManager(this), update_event_(*this), if0_(bxcan::Can[0], nullptr, 0, CAN_STM32_RX_QUEUE_SIZE), if1_(
bxcan::Can[1], nullptr, 1, CAN_STM32_RX_QUEUE_SIZE), initialized_(false), p_uavcan(nullptr) bxcan::Can[1], nullptr, 1, CAN_STM32_RX_QUEUE_SIZE), initialized_(false)
{ {
uavcan::StaticAssert<(CAN_STM32_RX_QUEUE_SIZE <= PX4CAN::MaxRxQueueCapacity)>::check(); uavcan::StaticAssert<(CAN_STM32_RX_QUEUE_SIZE <= PX4CAN::MaxRxQueueCapacity)>::check();
@ -1076,16 +1074,6 @@ void PX4CANManager::initialized(bool val)
initialized_ = val; initialized_ = val;
} }
AP_UAVCAN *PX4CANManager::get_UAVCAN(void)
{
return p_uavcan;
}
void PX4CANManager::set_UAVCAN(AP_UAVCAN *uavcan)
{
p_uavcan = uavcan;
}
/* /*
* Interrupt handlers * Interrupt handlers
*/ */

View File

@ -271,8 +271,6 @@ class PX4CANManager: public AP_HAL::CANManager, public uavcan::ICanDriver {
uint8_t _ifaces_num; uint8_t _ifaces_num;
uint8_t _ifaces_out_to_in[CAN_STM32_NUM_IFACES]; uint8_t _ifaces_out_to_in[CAN_STM32_NUM_IFACES];
AP_UAVCAN *p_uavcan;
public: public:
PX4CANManager(); PX4CANManager();
@ -310,8 +308,5 @@ public:
bool is_initialized() override; bool is_initialized() override;
void initialized(bool val) override; void initialized(bool val) override;
AP_UAVCAN *get_UAVCAN(void) override;
void set_UAVCAN(AP_UAVCAN *uavcan) override;
}; };
} }

View File

@ -24,11 +24,6 @@
#include <AP_Scheduler/AP_Scheduler.h> #include <AP_Scheduler/AP_Scheduler.h>
#include <AP_BoardConfig/AP_BoardConfig.h> #include <AP_BoardConfig/AP_BoardConfig.h>
#if HAL_WITH_UAVCAN
#include "CAN.h"
#include <AP_UAVCAN/AP_UAVCAN.h>
#endif
using namespace PX4; using namespace PX4;
extern const AP_HAL::HAL& hal; extern const AP_HAL::HAL& hal;
@ -90,33 +85,6 @@ void PX4Scheduler::init()
pthread_create(&_storage_thread_ctx, &thread_attr, &PX4Scheduler::_storage_thread, this); pthread_create(&_storage_thread_ctx, &thread_attr, &PX4Scheduler::_storage_thread, this);
} }
void PX4Scheduler::create_uavcan_thread()
{
#if HAL_WITH_UAVCAN
pthread_attr_t thread_attr;
struct sched_param param;
//the UAVCAN thread runs at medium priority
pthread_attr_init(&thread_attr);
pthread_attr_setstacksize(&thread_attr, 8192);
param.sched_priority = APM_CAN_PRIORITY;
(void) pthread_attr_setschedparam(&thread_attr, &param);
pthread_attr_setschedpolicy(&thread_attr, SCHED_FIFO);
for (uint8_t i = 0; i < MAX_NUMBER_OF_CAN_DRIVERS; i++) {
if (AP_UAVCAN::get_uavcan(i) == nullptr) {
continue;
}
_uavcan_thread_arg *arg = new _uavcan_thread_arg;
arg->sched = this;
arg->uavcan_number = i;
pthread_create(&_uavcan_thread_ctx, &thread_attr, &PX4Scheduler::_uavcan_thread, arg);
}
#endif
}
/** /**
delay for a specified number of microseconds using a semaphore wait delay for a specified number of microseconds using a semaphore wait
*/ */
@ -379,36 +347,6 @@ void *PX4Scheduler::_storage_thread(void *arg)
return nullptr; return nullptr;
} }
#if HAL_WITH_UAVCAN
void *PX4Scheduler::_uavcan_thread(void *arg)
{
PX4Scheduler *sched = ((_uavcan_thread_arg *) arg)->sched;
uint8_t uavcan_number = ((_uavcan_thread_arg *) arg)->uavcan_number;
char name[15];
snprintf(name, sizeof(name), "apm_uavcan:%u", uavcan_number);
pthread_setname_np(pthread_self(), name);
while (!sched->_hal_initialized) {
poll(nullptr, 0, 1);
}
while (!_px4_thread_should_exit) {
if (((PX4CANManager *)hal.can_mgr[uavcan_number])->is_initialized()) {
if (((PX4CANManager *)hal.can_mgr[uavcan_number])->get_UAVCAN() != nullptr) {
(((PX4CANManager *)hal.can_mgr[uavcan_number])->get_UAVCAN())->do_cyclic();
} else {
sched->delay_microseconds_semaphore(10000);
}
} else {
sched->delay_microseconds_semaphore(10000);
}
}
return nullptr;
}
#endif
bool PX4Scheduler::in_main_thread() const bool PX4Scheduler::in_main_thread() const
{ {
return getpid() == _main_task_pid; return getpid() == _main_task_pid;

View File

@ -60,8 +60,6 @@ public:
void system_initialized(); void system_initialized();
void hal_initialized() { _hal_initialized = true; } void hal_initialized() { _hal_initialized = true; }
void create_uavcan_thread() override;
/* /*
disable interrupts and return a context that can be used to disable interrupts and return a context that can be used to
restore the interrupt state. This can be used to protect restore the interrupt state. This can be used to protect
@ -99,18 +97,11 @@ private:
pthread_t _io_thread_ctx; pthread_t _io_thread_ctx;
pthread_t _storage_thread_ctx; pthread_t _storage_thread_ctx;
pthread_t _uart_thread_ctx; pthread_t _uart_thread_ctx;
pthread_t _uavcan_thread_ctx;
struct _uavcan_thread_arg {
PX4Scheduler *sched;
uint8_t uavcan_number;
};
static void *_timer_thread(void *arg); static void *_timer_thread(void *arg);
static void *_io_thread(void *arg); static void *_io_thread(void *arg);
static void *_storage_thread(void *arg); static void *_storage_thread(void *arg);
static void *_uart_thread(void *arg); static void *_uart_thread(void *arg);
static void *_uavcan_thread(void *arg);
void _run_timers(); void _run_timers();
void _run_io(void); void _run_io(void);