AP_HAL_Linux: remove CAN thread management

Also fix comment
This commit is contained in:
Francisco Ferreira 2018-02-27 23:59:47 +00:00
parent 7278af05e0
commit 1d7f3e48a4
No known key found for this signature in database
GPG Key ID: F63C20A6773E787E
3 changed files with 1 additions and 45 deletions

View File

@ -31,8 +31,6 @@
#include "CAN.h"
#include <AP_UAVCAN/AP_UAVCAN.h>
#include <unistd.h>
#include <fcntl.h>
@ -461,17 +459,6 @@ void CANManager::IfaceWrapper::updateDownStatusFromPollResult(const pollfd& pfd)
}
}
void CANManager::_timer_tick()
{
if (!_initialized) return;
if (p_uavcan != nullptr) {
p_uavcan->do_cyclic();
} else {
hal.console->printf("p_uavcan is nullptr");
}
}
bool CANManager::begin(uint32_t bitrate, uint8_t can_number)
{
if (init(can_number) >= 0) {
@ -490,16 +477,6 @@ 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;
}
CAN* CANManager::getIface(uint8_t iface_index)
{
return (iface_index >= _ifaces.size()) ? nullptr : _ifaces[iface_index].get();

View File

@ -180,8 +180,6 @@ public:
CANManager() : AP_HAL::CANManager(this) { _ifaces.reserve(uavcan::MaxCanIfaces); }
~CANManager() { }
void _timer_tick();
//These methods belong to AP_HAL::CANManager
virtual bool begin(uint32_t bitrate, uint8_t can_number) override;
@ -189,12 +187,7 @@ public:
virtual void initialized(bool val);
virtual bool is_initialized();
AP_UAVCAN *p_uavcan;
virtual AP_UAVCAN *get_UAVCAN(void) override;
virtual void set_UAVCAN(AP_UAVCAN *uavcan) override;
//These methods belong to ICanDriver (which is an ancestor of AP_HAL::CANManager)
//These methods belong to ICanDriver
virtual CAN* getIface(uint8_t iface_index) override;

View File

@ -19,10 +19,6 @@
#include "UARTDriver.h"
#include "Util.h"
#if HAL_WITH_UAVCAN
#include "CAN.h"
#endif
using namespace Linux;
extern const AP_HAL::HAL& hal;
@ -222,16 +218,6 @@ void Scheduler::_timer_task()
}
_in_timer_proc = false;
#if HAL_WITH_UAVCAN
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
for (i = 0; i < MAX_NUMBER_OF_CAN_INTERFACES; i++) {
if(hal.can_mgr[i] != nullptr) {
CANManager::from(hal.can_mgr[i])->_timer_tick();
}
}
#endif
#endif
}
void Scheduler::_run_io(void)