diff --git a/libraries/AP_HAL_ChibiOS/CAN.cpp b/libraries/AP_HAL_ChibiOS/CAN.cpp index 2cca664a17..3d516da640 100644 --- a/libraries/AP_HAL_ChibiOS/CAN.cpp +++ b/libraries/AP_HAL_ChibiOS/CAN.cpp @@ -43,11 +43,7 @@ uavcan::MonotonicTime clock::getMonotonic() bool CANManager::begin(uint32_t bitrate, uint8_t can_number) { - if (can_helper.init(bitrate, CanIface::OperatingMode::NormalMode, can_number) == 0) { - bitrate_ = bitrate; - initialized_ = true; - } - return initialized_; + return (can_helper.init(bitrate, CanIface::OperatingMode::NormalMode, can_number) == 0); } bool CANManager::is_initialized() diff --git a/libraries/AP_HAL_ChibiOS/CAN.h b/libraries/AP_HAL_ChibiOS/CAN.h index 7f69839850..6fe243e424 100644 --- a/libraries/AP_HAL_ChibiOS/CAN.h +++ b/libraries/AP_HAL_ChibiOS/CAN.h @@ -74,7 +74,6 @@ public: private: AP_UAVCAN *p_uavcan; bool initialized_; - uint32_t bitrate_; uavcan_stm32::CanInitHelper can_helper; };