mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
AP_HAL_ChibiOS: fix CAN manager initialization
This commit is contained in:
parent
458b7ea0b8
commit
e1bf89f32d
@ -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()
|
||||
|
@ -74,7 +74,6 @@ public:
|
||||
private:
|
||||
AP_UAVCAN *p_uavcan;
|
||||
bool initialized_;
|
||||
uint32_t bitrate_;
|
||||
uavcan_stm32::CanInitHelper<CAN_STM32_RX_QUEUE_SIZE> can_helper;
|
||||
};
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user