diff --git a/libraries/AP_BoardConfig/AP_BoardConfig_CAN.cpp b/libraries/AP_BoardConfig/AP_BoardConfig_CAN.cpp index 26566fe203..c85f86a44e 100644 --- a/libraries/AP_BoardConfig/AP_BoardConfig_CAN.cpp +++ b/libraries/AP_BoardConfig/AP_BoardConfig_CAN.cpp @@ -168,7 +168,7 @@ void AP_BoardConfig_CAN::linux_setup_canbus(void) { if (drv_num != 0 && drv_num <= MAX_NUMBER_OF_CAN_DRIVERS) { if (hal.can_mgr[drv_num - 1] == nullptr) { - const_cast (hal).can_mgr[drv_num - 1] = new Linux::CANDriver; + const_cast (hal).can_mgr[drv_num - 1] = new Linux::CANManager; } if (hal.can_mgr[drv_num - 1] != nullptr) { diff --git a/libraries/AP_HAL_Linux/CAN.cpp b/libraries/AP_HAL_Linux/CAN.cpp index 05ec08072d..2293f9c816 100644 --- a/libraries/AP_HAL_Linux/CAN.cpp +++ b/libraries/AP_HAL_Linux/CAN.cpp @@ -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)) { 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; @@ -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) { _initialized = true; @@ -476,32 +476,32 @@ bool CANDriver::begin(uint32_t bitrate, uint8_t can_number) return false; } -bool CANDriver::is_initialized() +bool CANManager::is_initialized() { return _initialized; } -void CANDriver::initialized(bool val) +void CANManager::initialized(bool val) { _initialized = val; } -AP_UAVCAN *CANDriver::get_UAVCAN(void) +AP_UAVCAN *CANManager::get_UAVCAN(void) { return p_uavcan; } -void CANDriver::set_UAVCAN(AP_UAVCAN *uavcan) +void CANManager::set_UAVCAN(AP_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(); } -int CANDriver::init(uint8_t can_number) +int CANManager::init(uint8_t can_number) { int res = -1; char iface_name[16]; @@ -509,13 +509,13 @@ int CANDriver::init(uint8_t can_number) res = addIface(iface_name); 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; } -int16_t CANDriver::select(uavcan::CanSelectMasks& inout_masks, +int16_t CANManager::select(uavcan::CanSelectMasks& inout_masks, const uavcan::CanFrame* (&)[uavcan::MaxCanIfaces], uavcan::MonotonicTime blocking_deadline) { @@ -590,7 +590,7 @@ int16_t CANDriver::select(uavcan::CanSelectMasks& inout_masks, return _ifaces.size(); } -int CANDriver::addIface(const std::string& iface_name) +int CANManager::addIface(const std::string& iface_name) { if (_ifaces.size() >= uavcan::MaxCanIfaces) { return -1; diff --git a/libraries/AP_HAL_Linux/CAN.h b/libraries/AP_HAL_Linux/CAN.h index 1a0bba38ba..d652de4fb8 100644 --- a/libraries/AP_HAL_Linux/CAN.h +++ b/libraries/AP_HAL_Linux/CAN.h @@ -175,15 +175,15 @@ private: std::vector _hw_filters_container; }; -class CANDriver: public AP_HAL::CANManager { +class CANManager: public AP_HAL::CANManager { public: - static CANDriver *from(AP_HAL::CANManager *can) + static CANManager *from(AP_HAL::CANManager *can) { - return static_cast(can); + return static_cast(can); } - CANDriver() { _ifaces.reserve(uavcan::MaxCanIfaces); } - ~CANDriver() { } + CANManager() { _ifaces.reserve(uavcan::MaxCanIfaces); } + ~CANManager() { } void _timer_tick(); diff --git a/libraries/AP_HAL_Linux/Scheduler.cpp b/libraries/AP_HAL_Linux/Scheduler.cpp index 89f73b866a..16a2135d46 100644 --- a/libraries/AP_HAL_Linux/Scheduler.cpp +++ b/libraries/AP_HAL_Linux/Scheduler.cpp @@ -280,7 +280,7 @@ void Scheduler::_timer_task() #if CONFIG_HAL_BOARD == HAL_BOARD_LINUX for (i = 0; i < MAX_NUMBER_OF_CAN_INTERFACES; i++) { if(hal.can_mgr[i] != nullptr) { - CANDriver::from(hal.can_mgr[i])->_timer_tick(); + CANManager::from(hal.can_mgr[i])->_timer_tick(); } } #endif