Browse Source

HAL_ChibiOS: fixed clock source for FDCAN

use selected source and add 80MHz limit, as per manual and latest STM32CubeMX tool
zr-v5.1
Andrew Tridgell 5 years ago
parent
commit
2c68ce1986
  1. 5
      libraries/AP_HAL_ChibiOS/CANFDIface.cpp

5
libraries/AP_HAL_ChibiOS/CANFDIface.cpp

@ -69,6 +69,8 @@ @@ -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 @@ -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;

Loading…
Cancel
Save