mirror of https://github.com/ArduPilot/ardupilot
HAL_ChibiOS: switched G4 FDCAN clock to 80MHz
this requires main CPU clock at 160 MHz instead of 168 MHz
This commit is contained in:
parent
2d965684f6
commit
06a8aef998
|
@ -89,11 +89,7 @@ extern const AP_HAL::HAL& hal;
|
|||
|
||||
#define STR(x) #x
|
||||
#define XSTR(x) STR(x)
|
||||
#if defined(STM32H7)
|
||||
static_assert(STM32_FDCANCLK == 80U*1000U*1000U, "FDCAN clock must be 80MHz, got " XSTR(STM32_FDCANCLK));
|
||||
#else
|
||||
static_assert(STM32_FDCANCLK <= 80U*1000U*1000U, "FDCAN clock must be max 80MHz, got " XSTR(STM32_FDCANCLK));
|
||||
#endif
|
||||
|
||||
using namespace ChibiOS;
|
||||
|
||||
|
|
|
@ -89,10 +89,10 @@
|
|||
#define STM32_LSI_ENABLED FALSE
|
||||
#define STM32_LSE_ENABLED FALSE
|
||||
#define STM32_SW STM32_SW_PLLRCLK
|
||||
#define STM32_PLLN_VALUE 42
|
||||
#define STM32_PLLN_VALUE 40
|
||||
#define STM32_PLLPDIV_VALUE 0
|
||||
#define STM32_PLLP_VALUE 7
|
||||
#define STM32_PLLQ_VALUE 8
|
||||
#define STM32_PLLQ_VALUE 4
|
||||
#define STM32_PLLR_VALUE 2
|
||||
#define STM32_HPRE STM32_HPRE_DIV1
|
||||
#define STM32_PPRE1 STM32_PPRE1_DIV1
|
||||
|
@ -117,11 +117,7 @@
|
|||
#define STM32_LPTIM1SEL STM32_LPTIM1SEL_PCLK1
|
||||
#define STM32_SAI1SEL STM32_SAI1SEL_SYSCLK
|
||||
#define STM32_I2S23SEL STM32_I2S23SEL_SYSCLK
|
||||
#if STM32_HSECLK == 0U
|
||||
#define STM32_FDCANSEL STM32_FDCANSEL_PLLQCLK
|
||||
#else
|
||||
#define STM32_FDCANSEL STM32_FDCANSEL_HSE
|
||||
#endif
|
||||
#define STM32_CLK48SEL STM32_CLK48SEL_HSI48
|
||||
#define STM32_ADC12SEL STM32_ADC12SEL_PLLPCLK
|
||||
#define STM32_ADC345SEL STM32_ADC345SEL_PLLPCLK
|
||||
|
|
|
@ -20,7 +20,7 @@ mcu = {
|
|||
(0x10000000, 10, 2), # CCM
|
||||
],
|
||||
|
||||
'EXPECTED_CLOCK' : 168000000,
|
||||
'EXPECTED_CLOCK' : 160000000,
|
||||
|
||||
'DEFINES' : {
|
||||
'STM32G4' : '1',
|
||||
|
|
|
@ -20,7 +20,7 @@ mcu = {
|
|||
(0x10000000, 10, 2), # CCM
|
||||
],
|
||||
|
||||
'EXPECTED_CLOCK' : 168000000,
|
||||
'EXPECTED_CLOCK' : 160000000,
|
||||
|
||||
'DEFINES' : {
|
||||
'STM32G4' : '1',
|
||||
|
|
|
@ -20,7 +20,7 @@ mcu = {
|
|||
(0x10000000, 32, 2), # CCM
|
||||
],
|
||||
|
||||
'EXPECTED_CLOCK' : 168000000,
|
||||
'EXPECTED_CLOCK' : 160000000,
|
||||
|
||||
'DEFINES' : {
|
||||
'STM32G4' : '1',
|
||||
|
|
|
@ -20,7 +20,7 @@ mcu = {
|
|||
(0x10000000, 16, 2), # CCM
|
||||
],
|
||||
|
||||
'EXPECTED_CLOCK' : 168000000,
|
||||
'EXPECTED_CLOCK' : 160000000,
|
||||
|
||||
'DEFINES' : {
|
||||
'STM32G4' : '1',
|
||||
|
|
|
@ -33,6 +33,9 @@
|
|||
// we rely on systimestamp_t for 64 bit timestamps
|
||||
static_assert(sizeof(uint64_t) == sizeof(systimestamp_t), "unexpected systimestamp_t size");
|
||||
|
||||
#define STR(x) #x
|
||||
#define XSTR(x) STR(x)
|
||||
|
||||
#if CH_CFG_ST_RESOLUTION == 16
|
||||
static_assert(sizeof(systime_t) == 2, "expected 16 bit systime_t");
|
||||
#elif CH_CFG_ST_RESOLUTION == 32
|
||||
|
@ -42,9 +45,9 @@ static_assert(sizeof(systime_t) == sizeof(sysinterval_t), "expected systime_t sa
|
|||
|
||||
#if defined(HAL_EXPECTED_SYSCLOCK)
|
||||
#ifdef STM32_SYS_CK
|
||||
static_assert(HAL_EXPECTED_SYSCLOCK == STM32_SYS_CK, "unexpected STM32_SYS_CK value");
|
||||
static_assert(HAL_EXPECTED_SYSCLOCK == STM32_SYS_CK, "unexpected STM32_SYS_CK value got " XSTR(STM32_HCLK) " expected " XSTR(HAL_EXPECTED_SYSCLOCK));
|
||||
#elif defined(STM32_HCLK)
|
||||
static_assert(HAL_EXPECTED_SYSCLOCK == STM32_HCLK, "unexpected STM32_HCLK value");
|
||||
static_assert(HAL_EXPECTED_SYSCLOCK == STM32_HCLK, "unexpected STM32_HCLK value got " XSTR(STM32_HCLK) " expected " XSTR(HAL_EXPECTED_SYSCLOCK));
|
||||
#else
|
||||
#error "unknown system clock"
|
||||
#endif
|
||||
|
|
Loading…
Reference in New Issue