From 2c68ce19869287cbdd0785754cd64d4b007fc83a Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 24 Apr 2020 09:31:20 +1000 Subject: [PATCH] HAL_ChibiOS: fixed clock source for FDCAN use selected source and add 80MHz limit, as per manual and latest STM32CubeMX tool --- libraries/AP_HAL_ChibiOS/CANFDIface.cpp | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/libraries/AP_HAL_ChibiOS/CANFDIface.cpp b/libraries/AP_HAL_ChibiOS/CANFDIface.cpp index 00a2c58b5f..57d426b46d 100644 --- a/libraries/AP_HAL_ChibiOS/CANFDIface.cpp +++ b/libraries/AP_HAL_ChibiOS/CANFDIface.cpp @@ -69,6 +69,8 @@ extern const AP_HAL::HAL& hal; +static_assert(STM32_FDCANCLK <= 80U*1000U*1000U, "FDCAN clock must be max 80MHz"); + namespace ChibiOS_CAN { namespace @@ -200,7 +202,8 @@ int CanIface::computeTimings(const uavcan::uint32_t target_bitrate, Timings& out /* * Hardware configuration */ - const uavcan::uint32_t pclk = STM32_PLL1_Q_CK; + const uavcan::uint32_t pclk = STM32_FDCANCLK; + static const int MaxBS1 = 16; static const int MaxBS2 = 8;