AP_HAL_Linux: CAN: Rename CANDriver -> CANManager

This commit is contained in:
Nikita Tomilov 2017-12-28 12:05:53 +03:00 committed by Tom Pittenger
parent d0fc481202
commit 43bfcbc8e2
4 changed files with 19 additions and 19 deletions

View File

@ -168,7 +168,7 @@ void AP_BoardConfig_CAN::linux_setup_canbus(void) {
if (drv_num != 0 && drv_num <= MAX_NUMBER_OF_CAN_DRIVERS) { if (drv_num != 0 && drv_num <= MAX_NUMBER_OF_CAN_DRIVERS) {
if (hal.can_mgr[drv_num - 1] == nullptr) { if (hal.can_mgr[drv_num - 1] == nullptr) {
const_cast <AP_HAL::HAL&> (hal).can_mgr[drv_num - 1] = new Linux::CANDriver; const_cast <AP_HAL::HAL&> (hal).can_mgr[drv_num - 1] = new Linux::CANManager;
} }
if (hal.can_mgr[drv_num - 1] != nullptr) { if (hal.can_mgr[drv_num - 1] != nullptr) {

View File

@ -428,7 +428,7 @@ bool CAN::_checkHWFilters(const can_frame& frame) const
} }
} }
void CANDriver::IfaceWrapper::updateDownStatusFromPollResult(const pollfd& pfd) void CANManager::IfaceWrapper::updateDownStatusFromPollResult(const pollfd& pfd)
{ {
if (!_down&& (pfd.revents & POLLERR)) { if (!_down&& (pfd.revents & POLLERR)) {
int error = 0; int error = 0;
@ -441,7 +441,7 @@ void CANDriver::IfaceWrapper::updateDownStatusFromPollResult(const pollfd& pfd)
} }
} }
void CANDriver::_timer_tick() void CANManager::_timer_tick()
{ {
if (!_initialized) return; if (!_initialized) return;
@ -452,7 +452,7 @@ void CANDriver::_timer_tick()
} }
} }
bool CANDriver::begin(uint32_t bitrate, uint8_t can_number) bool CANManager::begin(uint32_t bitrate, uint8_t can_number)
{ {
if (init(can_number) >= 0) { if (init(can_number) >= 0) {
_initialized = true; _initialized = true;
@ -476,32 +476,32 @@ bool CANDriver::begin(uint32_t bitrate, uint8_t can_number)
return false; return false;
} }
bool CANDriver::is_initialized() bool CANManager::is_initialized()
{ {
return _initialized; return _initialized;
} }
void CANDriver::initialized(bool val) void CANManager::initialized(bool val)
{ {
_initialized = val; _initialized = val;
} }
AP_UAVCAN *CANDriver::get_UAVCAN(void) AP_UAVCAN *CANManager::get_UAVCAN(void)
{ {
return p_uavcan; return p_uavcan;
} }
void CANDriver::set_UAVCAN(AP_UAVCAN *uavcan) void CANManager::set_UAVCAN(AP_UAVCAN *uavcan)
{ {
p_uavcan = uavcan; p_uavcan = uavcan;
} }
CAN* CANDriver::getIface(uint8_t iface_index) CAN* CANManager::getIface(uint8_t iface_index)
{ {
return (iface_index >= _ifaces.size()) ? nullptr : _ifaces[iface_index].get(); return (iface_index >= _ifaces.size()) ? nullptr : _ifaces[iface_index].get();
} }
int CANDriver::init(uint8_t can_number) int CANManager::init(uint8_t can_number)
{ {
int res = -1; int res = -1;
char iface_name[16]; char iface_name[16];
@ -509,13 +509,13 @@ int CANDriver::init(uint8_t can_number)
res = addIface(iface_name); res = addIface(iface_name);
if (res < 0) { if (res < 0) {
hal.console->printf("CANDriver: init %s failed\n", iface_name); hal.console->printf("CANManager: init %s failed\n", iface_name);
} }
return res; return res;
} }
int16_t CANDriver::select(uavcan::CanSelectMasks& inout_masks, int16_t CANManager::select(uavcan::CanSelectMasks& inout_masks,
const uavcan::CanFrame* (&)[uavcan::MaxCanIfaces], const uavcan::CanFrame* (&)[uavcan::MaxCanIfaces],
uavcan::MonotonicTime blocking_deadline) uavcan::MonotonicTime blocking_deadline)
{ {
@ -590,7 +590,7 @@ int16_t CANDriver::select(uavcan::CanSelectMasks& inout_masks,
return _ifaces.size(); return _ifaces.size();
} }
int CANDriver::addIface(const std::string& iface_name) int CANManager::addIface(const std::string& iface_name)
{ {
if (_ifaces.size() >= uavcan::MaxCanIfaces) { if (_ifaces.size() >= uavcan::MaxCanIfaces) {
return -1; return -1;

View File

@ -175,15 +175,15 @@ private:
std::vector<can_filter> _hw_filters_container; std::vector<can_filter> _hw_filters_container;
}; };
class CANDriver: public AP_HAL::CANManager { class CANManager: public AP_HAL::CANManager {
public: public:
static CANDriver *from(AP_HAL::CANManager *can) static CANManager *from(AP_HAL::CANManager *can)
{ {
return static_cast<CANDriver*>(can); return static_cast<CANManager*>(can);
} }
CANDriver() { _ifaces.reserve(uavcan::MaxCanIfaces); } CANManager() { _ifaces.reserve(uavcan::MaxCanIfaces); }
~CANDriver() { } ~CANManager() { }
void _timer_tick(); void _timer_tick();

View File

@ -280,7 +280,7 @@ void Scheduler::_timer_task()
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX #if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
for (i = 0; i < MAX_NUMBER_OF_CAN_INTERFACES; i++) { for (i = 0; i < MAX_NUMBER_OF_CAN_INTERFACES; i++) {
if(hal.can_mgr[i] != nullptr) { if(hal.can_mgr[i] != nullptr) {
CANDriver::from(hal.can_mgr[i])->_timer_tick(); CANManager::from(hal.can_mgr[i])->_timer_tick();
} }
} }
#endif #endif