Bulk format

This commit is contained in:
Ben V. Brown
2020-10-13 19:04:16 +11:00
parent 03afdcdf20
commit 2e4168be73
15 changed files with 730 additions and 810 deletions

View File

@@ -21,16 +21,15 @@ uint16_t totalPWM; //htim2.Init.Period, the full PWM cycle
static bool fastPWM;
//2 second filter (ADC is PID_TIM_HZ Hz)
history<uint16_t, PID_TIM_HZ> rawTempFilter = {{0}, 0, 0};
void resetWatchdog()
{
history<uint16_t, PID_TIM_HZ> rawTempFilter = { { 0 }, 0, 0 };
void resetWatchdog() {
HAL_IWDG_Refresh(&hiwdg);
}
#ifdef TEMP_NTC
//Lookup table for the NTC
//Stored as ADCReading,Temp in degC
static const uint16_t NTCHandleLookup[] = {
//ADC Reading , Temp in C
//ADC Reading , Temp in C
29189, 0, //
29014, 1, //
28832, 2, //
@@ -92,21 +91,18 @@ static const uint16_t NTCHandleLookup[] = {
// 11874, 58, //
// 11580, 59, //
// 11292, 60, //
};
};
#endif
uint16_t getHandleTemperature()
{
uint16_t getHandleTemperature() {
#ifdef TEMP_NTC
//TS80P uses 100k NTC resistors instead
//NTCG104EF104FT1X from TDK
//For now not doing interpolation
int32_t result = getADC(0);
for (uint32_t i = 0; i < (sizeof(NTCHandleLookup) / (2 * sizeof(uint16_t)));
i++)
{
if (result > NTCHandleLookup[(i * 2) + 0])
{
i++) {
if (result > NTCHandleLookup[(i * 2) + 0]) {
return NTCHandleLookup[(i * 2) + 1] * 10;
}
}
@@ -130,8 +126,7 @@ uint16_t getHandleTemperature()
#endif
}
uint16_t getTipInstantTemperature()
{
uint16_t getTipInstantTemperature() {
uint16_t sum = 0; // 12 bit readings * 8 -> 15 bits
uint16_t readings[8];
//Looking to reject the highest outlier readings.
@@ -146,29 +141,23 @@ uint16_t getTipInstantTemperature()
readings[6] = hadc2.Instance->JDR3;
readings[7] = hadc2.Instance->JDR4;
for (int i = 0; i < 8; i++)
{
for (int i = 0; i < 8; i++) {
sum += readings[i];
}
return sum; // 8x over sample
}
uint16_t getTipRawTemp(uint8_t refresh)
{
if (refresh)
{
uint16_t getTipRawTemp(uint8_t refresh) {
if (refresh) {
uint16_t lastSample = getTipInstantTemperature();
rawTempFilter.update(lastSample);
return lastSample;
}
else
{
} else {
return rawTempFilter.average();
}
}
uint16_t getInputVoltageX10(uint16_t divisor, uint8_t sample)
{
uint16_t getInputVoltageX10(uint16_t divisor, uint8_t sample) {
// ADC maximum is 32767 == 3.3V at input == 28.05V at VIN
// Therefore we can divide down from there
// Multiplying ADC max by 4 for additional calibration options,
@@ -182,14 +171,12 @@ uint16_t getInputVoltageX10(uint16_t divisor, uint8_t sample)
static uint8_t preFillneeded = 10;
static uint32_t samples[BATTFILTERDEPTH];
static uint8_t index = 0;
if (preFillneeded)
{
if (preFillneeded) {
for (uint8_t i = 0; i < BATTFILTERDEPTH; i++)
samples[i] = getADC(1);
preFillneeded--;
}
if (sample)
{
if (sample) {
samples[index] = getADC(1);
index = (index + 1) % BATTFILTERDEPTH;
}
@@ -199,23 +186,20 @@ uint16_t getInputVoltageX10(uint16_t divisor, uint8_t sample)
sum += samples[i];
sum /= BATTFILTERDEPTH;
if (divisor == 0)
{
if (divisor == 0) {
divisor = 1;
}
return sum * 4 / divisor;
}
void setTipPWM(uint8_t pulse)
{
void setTipPWM(uint8_t pulse) {
PWMSafetyTimer = 10; // This is decremented in the handler for PWM so that the tip pwm is
// disabled if the PID task is not scheduled often enough.
pendingPWM = pulse;
}
static void switchToFastPWM(void)
{
static void switchToFastPWM(void) {
fastPWM = true;
totalPWM = powerPWM + tempMeasureTicks * 2;
htim2.Instance->ARR = totalPWM;
@@ -225,8 +209,7 @@ static void switchToFastPWM(void)
htim2.Instance->PSC = 2000;
}
static void switchToSlowPWM(void)
{
static void switchToSlowPWM(void) {
fastPWM = false;
totalPWM = powerPWM + tempMeasureTicks;
htim2.Instance->ARR = totalPWM;
@@ -236,16 +219,12 @@ static void switchToSlowPWM(void)
htim2.Instance->PSC = 4000;
}
bool tryBetterPWM(uint8_t pwm)
{
if (fastPWM && pwm == powerPWM)
{
bool tryBetterPWM(uint8_t pwm) {
if (fastPWM && pwm == powerPWM) {
// maximum power for fast PWM reached, need to go slower to get more
switchToSlowPWM();
return true;
}
else if (!fastPWM && pwm < 230)
{
} else if (!fastPWM && pwm < 230) {
// 254 in fast PWM mode gives the same power as 239 in slow
// allow for some reasonable hysteresis by switching only when it goes
// below 230 (equivalent to 245 in fast mode)
@@ -258,11 +237,9 @@ bool tryBetterPWM(uint8_t pwm)
// These are called by the HAL after the corresponding events from the system
// timers.
void HAL_TIM_PeriodElapsedCallback(TIM_HandleTypeDef *htim)
{
void HAL_TIM_PeriodElapsedCallback(TIM_HandleTypeDef *htim) {
// Period has elapsed
if (htim->Instance == TIM2)
{
if (htim->Instance == TIM2) {
// we want to turn on the output again
PWMSafetyTimer--;
// We decrement this safety value so that lockups in the
@@ -271,32 +248,24 @@ void HAL_TIM_PeriodElapsedCallback(TIM_HandleTypeDef *htim)
// While we could assume this could never happen, its a small price for
// increased safety
htim2.Instance->CCR4 = pendingPWM;
if (htim2.Instance->CCR4 && PWMSafetyTimer)
{
if (htim2.Instance->CCR4 && PWMSafetyTimer) {
HAL_TIM_PWM_Start(&htim3, TIM_CHANNEL_1);
}
else
{
} else {
HAL_TIM_PWM_Stop(&htim3, TIM_CHANNEL_1);
}
}
else if (htim->Instance == TIM1)
{
} else if (htim->Instance == TIM1) {
// STM uses this for internal functions as a counter for timeouts
HAL_IncTick();
}
}
void HAL_TIM_PWM_PulseFinishedCallback(TIM_HandleTypeDef *htim)
{
void HAL_TIM_PWM_PulseFinishedCallback(TIM_HandleTypeDef *htim) {
// This was a when the PWM for the output has timed out
if (htim->Channel == HAL_TIM_ACTIVE_CHANNEL_4)
{
if (htim->Channel == HAL_TIM_ACTIVE_CHANNEL_4) {
HAL_TIM_PWM_Stop(&htim3, TIM_CHANNEL_1);
}
}
void unstick_I2C()
{
void unstick_I2C() {
GPIO_InitTypeDef GPIO_InitStruct;
int timeout = 100;
int timeout_cnt = 0;
@@ -320,8 +289,7 @@ void unstick_I2C()
HAL_GPIO_Init(SDA_GPIO_Port, &GPIO_InitStruct);
HAL_GPIO_WritePin(SDA_GPIO_Port, SDA_Pin, GPIO_PIN_SET);
while (GPIO_PIN_SET != HAL_GPIO_ReadPin(SDA_GPIO_Port, SDA_Pin))
{
while (GPIO_PIN_SET != HAL_GPIO_ReadPin(SDA_GPIO_Port, SDA_Pin)) {
//Move clock to release I2C
HAL_GPIO_WritePin(SCL_GPIO_Port, SCL_Pin, GPIO_PIN_RESET);
asm("nop");
@@ -366,26 +334,23 @@ void unstick_I2C()
HAL_I2C_Init(&hi2c1);
}
uint8_t getButtonA()
{
return HAL_GPIO_ReadPin(KEY_A_GPIO_Port, KEY_A_Pin) == GPIO_PIN_RESET ? 1 : 0;
uint8_t getButtonA() {
return HAL_GPIO_ReadPin(KEY_A_GPIO_Port, KEY_A_Pin) == GPIO_PIN_RESET ?
1 : 0;
}
uint8_t getButtonB()
{
return HAL_GPIO_ReadPin(KEY_B_GPIO_Port, KEY_B_Pin) == GPIO_PIN_RESET ? 1 : 0;
uint8_t getButtonB() {
return HAL_GPIO_ReadPin(KEY_B_GPIO_Port, KEY_B_Pin) == GPIO_PIN_RESET ?
1 : 0;
}
void BSPInit(void)
{
void BSPInit(void) {
switchToFastPWM();
}
void reboot()
{
void reboot() {
NVIC_SystemReset();
}
void delay_ms(uint16_t count)
{
void delay_ms(uint16_t count) {
HAL_Delay(count);
}

View File

@@ -17,11 +17,13 @@ void FRToSI2C::CpltCallback() {
}
}
bool FRToSI2C::Mem_Read(uint16_t DevAddress, uint16_t MemAddress, uint8_t *pData, uint16_t Size) {
bool FRToSI2C::Mem_Read(uint16_t DevAddress, uint16_t MemAddress,
uint8_t *pData, uint16_t Size) {
if (!lock())
return false;
if (HAL_I2C_Mem_Read(&hi2c1, DevAddress, MemAddress, I2C_MEMADD_SIZE_8BIT, pData, Size, 500) != HAL_OK) {
if (HAL_I2C_Mem_Read(&hi2c1, DevAddress, MemAddress, I2C_MEMADD_SIZE_8BIT,
pData, Size, 500) != HAL_OK) {
I2C_Unstick();
unlock();
@@ -40,11 +42,13 @@ uint8_t FRToSI2C::I2C_RegisterRead(uint8_t add, uint8_t reg) {
Mem_Read(add, reg, tx_data, 1);
return tx_data[0];
}
bool FRToSI2C::Mem_Write(uint16_t DevAddress, uint16_t MemAddress, uint8_t *pData, uint16_t Size) {
bool FRToSI2C::Mem_Write(uint16_t DevAddress, uint16_t MemAddress,
uint8_t *pData, uint16_t Size) {
if (!lock())
return false;
if (HAL_I2C_Mem_Write(&hi2c1, DevAddress, MemAddress, I2C_MEMADD_SIZE_8BIT, pData, Size, 500) != HAL_OK) {
if (HAL_I2C_Mem_Write(&hi2c1, DevAddress, MemAddress, I2C_MEMADD_SIZE_8BIT,
pData, Size, 500) != HAL_OK) {
I2C_Unstick();
unlock();
@@ -58,7 +62,8 @@ bool FRToSI2C::Mem_Write(uint16_t DevAddress, uint16_t MemAddress, uint8_t *pDat
bool FRToSI2C::Transmit(uint16_t DevAddress, uint8_t *pData, uint16_t Size) {
if (!lock())
return false;
if (HAL_I2C_Master_Transmit_DMA(&hi2c1, DevAddress, pData, Size) != HAL_OK) {
if (HAL_I2C_Master_Transmit_DMA(&hi2c1, DevAddress, pData, Size)
!= HAL_OK) {
I2C_Unstick();
unlock();
return false;
@@ -70,7 +75,8 @@ bool FRToSI2C::probe(uint16_t DevAddress) {
if (!lock())
return false;
uint8_t buffer[1];
bool worked = HAL_I2C_Mem_Read(&hi2c1, DevAddress, 0x0F, I2C_MEMADD_SIZE_8BIT, buffer, 1, 1000) == HAL_OK;
bool worked = HAL_I2C_Mem_Read(&hi2c1, DevAddress, 0x0F,
I2C_MEMADD_SIZE_8BIT, buffer, 1, 1000) == HAL_OK;
unlock();
return worked;
}
@@ -87,9 +93,11 @@ bool FRToSI2C::lock() {
return xSemaphoreTake(I2CSemaphore, (TickType_t)50) == pdTRUE;
}
bool FRToSI2C::writeRegistersBulk(const uint8_t address, const I2C_REG *registers, const uint8_t registersLength) {
bool FRToSI2C::writeRegistersBulk(const uint8_t address,
const I2C_REG *registers, const uint8_t registersLength) {
for (int index = 0; index < registersLength; index++) {
if (!I2C_RegisterWrite(address, registers[index].reg, registers[index].val)) {
if (!I2C_RegisterWrite(address, registers[index].reg,
registers[index].val)) {
return false;
}
if (registers[index].pause_ms)

View File

@@ -44,6 +44,6 @@ void HAL_I2C_MemRxCpltCallback(I2C_HandleTypeDef *hi2c __unused) {
}
void HAL_GPIO_EXTI_Callback(uint16_t GPIO_Pin) {
(void)GPIO_Pin;
(void) GPIO_Pin;
InterruptHandler::irqCallback();
}

View File

@@ -66,7 +66,9 @@ void QC_Post_Probe_En() {
HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
}
uint8_t QC_DM_PulledDown() { return HAL_GPIO_ReadPin(GPIOA, GPIO_PIN_11) == GPIO_PIN_RESET ? 1 : 0; }
uint8_t QC_DM_PulledDown() {
return HAL_GPIO_ReadPin(GPIOA, GPIO_PIN_11) == GPIO_PIN_RESET ? 1 : 0;
}
#endif
void QC_resync() {
#ifdef POW_QC

View File

@@ -22,6 +22,4 @@
#endif
#endif /* BSP_MINIWARE_SOFTWARE_I2C_H_ */

View File

@@ -17,7 +17,7 @@ uint8_t flash_save_buffer(const uint8_t *buffer, const uint16_t length) {
pEraseInit.TypeErase = FLASH_TYPEERASE_PAGES;
pEraseInit.Banks = FLASH_BANK_1;
pEraseInit.NbPages = 1;
pEraseInit.PageAddress = (uint32_t)settings_page;
pEraseInit.PageAddress = (uint32_t) settings_page;
uint32_t failingAddress = 0;
resetWatchdog();
__HAL_FLASH_CLEAR_FLAG(
@@ -33,8 +33,8 @@ uint8_t flash_save_buffer(const uint8_t *buffer, const uint16_t length) {
HAL_FLASH_Unlock();
for (uint8_t i = 0; i < (length / 2); i++) {
resetWatchdog();
HAL_FLASH_Program(FLASH_TYPEPROGRAM_HALFWORD, (uint32_t)&settings_page[i],
data[i]);
HAL_FLASH_Program(FLASH_TYPEPROGRAM_HALFWORD,
(uint32_t) &settings_page[i], data[i]);
}
HAL_FLASH_Lock();
return 1;

View File

@@ -82,12 +82,12 @@ void fusb_send_message(const union pd_msg *msg) {
FUSB_FIFO_TX_SOP1,
FUSB_FIFO_TX_SOP1,
FUSB_FIFO_TX_SOP2,
FUSB_FIFO_TX_PACKSYM};
FUSB_FIFO_TX_PACKSYM };
static const uint8_t eop_seq[4] = {
FUSB_FIFO_TX_JAM_CRC,
FUSB_FIFO_TX_EOP,
FUSB_FIFO_TX_TXOFF,
FUSB_FIFO_TX_TXON};
FUSB_FIFO_TX_TXON };
/* Take the I2C2 mutex now so there can't be a race condition on sop_seq */
/* Get the length of the message: a two-octet header plus NUMOBJ four-octet

View File

@@ -15,8 +15,7 @@ static uint8_t logo_page[1024] __attribute__ ((section (".logo_page")));
uint8_t showBootLogoIfavailable() {
// Do not show logo data if signature is not found.
if (LOGO_HEADER_VALUE
!= *(reinterpret_cast<const uint32_t*>(logo_page))) {
if (LOGO_HEADER_VALUE != *(reinterpret_cast<const uint32_t*>(logo_page))) {
return 0;
}

View File

@@ -34,16 +34,16 @@
#include "task.h"
/* For backward compatibility, ensure configKERNEL_INTERRUPT_PRIORITY is
defined. The value should also ensure backward compatibility.
FreeRTOS.org versions prior to V4.4.0 did not include this definition. */
defined. The value should also ensure backward compatibility.
FreeRTOS.org versions prior to V4.4.0 did not include this definition. */
#ifndef configKERNEL_INTERRUPT_PRIORITY
#define configKERNEL_INTERRUPT_PRIORITY 255
#define configKERNEL_INTERRUPT_PRIORITY 255
#endif
#ifndef configSYSTICK_CLOCK_HZ
#define configSYSTICK_CLOCK_HZ configCPU_CLOCK_HZ
/* Ensure the SysTick is clocked at the same frequency as the core. */
#define portNVIC_SYSTICK_CLK_BIT ( 1UL << 2UL )
#define configSYSTICK_CLOCK_HZ configCPU_CLOCK_HZ
/* Ensure the SysTick is clocked at the same frequency as the core. */
#define portNVIC_SYSTICK_CLK_BIT ( 1UL << 2UL )
#else
/* The way the SysTick is clocked is not modified in case it is not the same
as the core. */
@@ -85,21 +85,21 @@ FreeRTOS.org versions prior to V4.4.0 did not include this definition. */
#define portMAX_24_BIT_NUMBER ( 0xffffffUL )
/* A fiddle factor to estimate the number of SysTick counts that would have
occurred while the SysTick counter is stopped during tickless idle
calculations. */
occurred while the SysTick counter is stopped during tickless idle
calculations. */
#define portMISSED_COUNTS_FACTOR ( 45UL )
/* For strict compliance with the Cortex-M spec the task start address should
have bit-0 clear, as it is loaded into the PC on exit from an ISR. */
have bit-0 clear, as it is loaded into the PC on exit from an ISR. */
#define portSTART_ADDRESS_MASK ( ( StackType_t ) 0xfffffffeUL )
/* Let the user override the pre-loading of the initial LR with the address of
prvTaskExitError() in case it messes up unwinding of the stack in the
debugger. */
prvTaskExitError() in case it messes up unwinding of the stack in the
debugger. */
#ifdef configTASK_RETURN_ADDRESS
#define portTASK_RETURN_ADDRESS configTASK_RETURN_ADDRESS
#else
#define portTASK_RETURN_ADDRESS prvTaskExitError
#define portTASK_RETURN_ADDRESS prvTaskExitError
#endif
/*
@@ -107,29 +107,29 @@ debugger. */
* file is weak to allow application writers to change the timer used to
* generate the tick interrupt.
*/
void vPortSetupTimerInterrupt( void );
void vPortSetupTimerInterrupt(void);
/*
* Exception handlers.
*/
void xPortPendSVHandler( void ) __attribute__ (( naked ));
void xPortSysTickHandler( void );
void vPortSVCHandler( void ) __attribute__ (( naked ));
void xPortPendSVHandler(void) __attribute__ (( naked ));
void xPortSysTickHandler(void);
void vPortSVCHandler(void) __attribute__ (( naked ));
/*
* Start first task is a separate function so it can be tested in isolation.
*/
static void prvPortStartFirstTask( void ) __attribute__ (( naked ));
static void prvPortStartFirstTask(void) __attribute__ (( naked ));
/*
* Used to catch tasks that attempt to return from their implementing function.
*/
static void prvTaskExitError( void );
static void prvTaskExitError(void);
/*-----------------------------------------------------------*/
/* Each task maintains its own interrupt status in the critical nesting
variable. */
variable. */
static UBaseType_t uxCriticalNesting = 0xaaaaaaaa;
/*
@@ -161,9 +161,10 @@ static UBaseType_t uxCriticalNesting = 0xaaaaaaaa;
* a priority above configMAX_SYSCALL_INTERRUPT_PRIORITY.
*/
#if( configASSERT_DEFINED == 1 )
static uint8_t ucMaxSysCallPriority = 0;
static uint32_t ulMaxPRIGROUPValue = 0;
static const volatile uint8_t * const pcInterruptPriorityRegisters = ( const volatile uint8_t * const ) portNVIC_IP_REGISTERS_OFFSET_16;
static uint8_t ucMaxSysCallPriority = 0;
static uint32_t ulMaxPRIGROUPValue = 0;
static const volatile uint8_t *const pcInterruptPriorityRegisters =
(const volatile uint8_t* const ) portNVIC_IP_REGISTERS_OFFSET_16;
#endif /* configASSERT_DEFINED */
/*-----------------------------------------------------------*/
@@ -171,27 +172,26 @@ static UBaseType_t uxCriticalNesting = 0xaaaaaaaa;
/*
* See header file for description.
*/
StackType_t *pxPortInitialiseStack( StackType_t *pxTopOfStack, TaskFunction_t pxCode, void *pvParameters )
{
StackType_t* pxPortInitialiseStack(StackType_t *pxTopOfStack,
TaskFunction_t pxCode, void *pvParameters) {
/* Simulate the stack frame as it would be created by a context switch
interrupt. */
pxTopOfStack--; /* Offset added to account for the way the MCU uses the stack on entry/exit of interrupts. */
*pxTopOfStack = portINITIAL_XPSR; /* xPSR */
pxTopOfStack--;
*pxTopOfStack = ( ( StackType_t ) pxCode ) & portSTART_ADDRESS_MASK; /* PC */
*pxTopOfStack = ((StackType_t) pxCode) & portSTART_ADDRESS_MASK; /* PC */
pxTopOfStack--;
*pxTopOfStack = ( StackType_t ) portTASK_RETURN_ADDRESS; /* LR */
*pxTopOfStack = (StackType_t) portTASK_RETURN_ADDRESS; /* LR */
pxTopOfStack -= 5; /* R12, R3, R2 and R1. */
*pxTopOfStack = ( StackType_t ) pvParameters; /* R0 */
*pxTopOfStack = (StackType_t) pvParameters; /* R0 */
pxTopOfStack -= 8; /* R11, R10, R9, R8, R7, R6, R5 and R4. */
return pxTopOfStack;
}
/*-----------------------------------------------------------*/
static void prvTaskExitError( void )
{
volatile uint32_t ulDummy = 0UL;
static void prvTaskExitError(void) {
volatile uint32_t ulDummy = 0UL;
/* A function that implements a task must not exit or attempt to return to
its caller as there is nothing to return to. If a task wants to exit it
@@ -199,10 +199,9 @@ volatile uint32_t ulDummy = 0UL;
Artificially force an assert() to be triggered if configASSERT() is
defined, then stop here so application writers can catch the error. */
configASSERT( uxCriticalNesting == ~0UL );
configASSERT(uxCriticalNesting == ~0UL);
portDISABLE_INTERRUPTS();
while( ulDummy == 0 )
{
while (ulDummy == 0) {
/* This file calls prvTaskExitError() after the scheduler has been
started to remove a compiler warning about the function being defined
but never called. ulDummy is used purely to quieten other warnings
@@ -214,8 +213,7 @@ volatile uint32_t ulDummy = 0UL;
}
/*-----------------------------------------------------------*/
void vPortSVCHandler( void )
{
void vPortSVCHandler(void) {
__asm volatile (
" ldr r3, pxCurrentTCBConst2 \n" /* Restore the context. */
" ldr r1, [r3] \n" /* Use pxCurrentTCBConst to get the pxCurrentTCB address. */
@@ -234,8 +232,7 @@ void vPortSVCHandler( void )
}
/*-----------------------------------------------------------*/
static void prvPortStartFirstTask( void )
{
static void prvPortStartFirstTask(void) {
__asm volatile(
" ldr r0, =0xE000ED08 \n" /* Use the NVIC offset register to locate the stack. */
" ldr r0, [r0] \n"
@@ -254,16 +251,17 @@ static void prvPortStartFirstTask( void )
/*
* See header file for description.
*/
BaseType_t xPortStartScheduler( void )
{
BaseType_t xPortStartScheduler(void) {
/* configMAX_SYSCALL_INTERRUPT_PRIORITY must not be set to 0.
See http://www.FreeRTOS.org/RTOS-Cortex-M3-M4.html */
configASSERT( configMAX_SYSCALL_INTERRUPT_PRIORITY );
configASSERT(configMAX_SYSCALL_INTERRUPT_PRIORITY);
#if( configASSERT_DEFINED == 1 )
#if( configASSERT_DEFINED == 1 )
{
volatile uint32_t ulOriginalPriority;
volatile uint8_t * const pucFirstUserPriorityRegister = ( volatile uint8_t * const ) ( portNVIC_IP_REGISTERS_OFFSET_16 + portFIRST_USER_INTERRUPT_NUMBER );
volatile uint8_t *const pucFirstUserPriorityRegister =
(volatile uint8_t* const ) ( portNVIC_IP_REGISTERS_OFFSET_16
+ portFIRST_USER_INTERRUPT_NUMBER);
volatile uint8_t ucMaxPriorityValue;
/* Determine the maximum priority from which ISR safe FreeRTOS API
@@ -282,18 +280,18 @@ BaseType_t xPortStartScheduler( void )
ucMaxPriorityValue = *pucFirstUserPriorityRegister;
/* Use the same mask on the maximum system call priority. */
ucMaxSysCallPriority = configMAX_SYSCALL_INTERRUPT_PRIORITY & ucMaxPriorityValue;
ucMaxSysCallPriority = configMAX_SYSCALL_INTERRUPT_PRIORITY
& ucMaxPriorityValue;
/* Calculate the maximum acceptable priority group value for the number
of bits read back. */
ulMaxPRIGROUPValue = portMAX_PRIGROUP_BITS;
while( ( ucMaxPriorityValue & portTOP_BIT_OF_BYTE ) == portTOP_BIT_OF_BYTE )
{
while ((ucMaxPriorityValue & portTOP_BIT_OF_BYTE) == portTOP_BIT_OF_BYTE) {
ulMaxPRIGROUPValue--;
ucMaxPriorityValue <<= ( uint8_t ) 0x01;
ucMaxPriorityValue <<= (uint8_t) 0x01;
}
#ifdef __NVIC_PRIO_BITS
#ifdef __NVIC_PRIO_BITS
{
/* Check the CMSIS configuration that defines the number of
priority bits matches the number of priority bits actually queried
@@ -302,7 +300,7 @@ BaseType_t xPortStartScheduler( void )
}
#endif
#ifdef configPRIO_BITS
#ifdef configPRIO_BITS
{
/* Check the FreeRTOS configuration that defines the number of
priority bits matches the number of priority bits actually queried
@@ -320,7 +318,7 @@ BaseType_t xPortStartScheduler( void )
value. */
*pucFirstUserPriorityRegister = ulOriginalPriority;
}
#endif /* conifgASSERT_DEFINED */
#endif /* conifgASSERT_DEFINED */
/* Make PendSV and SysTick the lowest priority interrupts. */
portNVIC_SYSPRI2_REG |= portNVIC_PENDSV_PRI;
@@ -350,16 +348,14 @@ BaseType_t xPortStartScheduler( void )
}
/*-----------------------------------------------------------*/
void vPortEndScheduler( void )
{
void vPortEndScheduler(void) {
/* Not implemented in ports where there is nothing to return to.
Artificially force an assert. */
configASSERT( uxCriticalNesting == 1000UL );
configASSERT(uxCriticalNesting == 1000UL);
}
/*-----------------------------------------------------------*/
void vPortEnterCritical( void )
{
void vPortEnterCritical(void) {
portDISABLE_INTERRUPTS();
uxCriticalNesting++;
@@ -368,26 +364,22 @@ void vPortEnterCritical( void )
functions that end in "FromISR" can be used in an interrupt. Only assert if
the critical nesting count is 1 to protect against recursive calls if the
assert function also uses a critical section. */
if( uxCriticalNesting == 1 )
{
configASSERT( ( portNVIC_INT_CTRL_REG & portVECTACTIVE_MASK ) == 0 );
if (uxCriticalNesting == 1) {
configASSERT(( portNVIC_INT_CTRL_REG & portVECTACTIVE_MASK) == 0);
}
}
/*-----------------------------------------------------------*/
void vPortExitCritical( void )
{
configASSERT( uxCriticalNesting );
void vPortExitCritical(void) {
configASSERT(uxCriticalNesting);
uxCriticalNesting--;
if( uxCriticalNesting == 0 )
{
if (uxCriticalNesting == 0) {
portENABLE_INTERRUPTS();
}
}
/*-----------------------------------------------------------*/
void xPortPendSVHandler( void )
{
void xPortPendSVHandler(void) {
/* This is a naked function. */
__asm volatile
@@ -423,8 +415,7 @@ void xPortPendSVHandler( void )
}
/*-----------------------------------------------------------*/
void xPortSysTickHandler( void )
{
void xPortSysTickHandler(void) {
/* The SysTick runs at the lowest interrupt priority, so when this interrupt
executes all interrupts must be unmasked. There is therefore no need to
save and then restore the interrupt mask value as its value is already
@@ -432,8 +423,7 @@ void xPortSysTickHandler( void )
portDISABLE_INTERRUPTS();
{
/* Increment the RTOS tick. */
if( xTaskIncrementTick() != pdFALSE )
{
if (xTaskIncrementTick() != pdFALSE) {
/* A context switch is required. Context switching is performed in
the PendSV interrupt. Pend the PendSV interrupt. */
portNVIC_INT_CTRL_REG = portNVIC_PENDSVSET_BIT;
@@ -614,10 +604,9 @@ void xPortSysTickHandler( void )
* Setup the systick timer to generate the tick interrupts at the required
* frequency.
*/
__attribute__(( weak )) void vPortSetupTimerInterrupt( void )
{
__attribute__(( weak )) void vPortSetupTimerInterrupt(void) {
/* Calculate the constants required to configure the tick interrupt. */
#if( configUSE_TICKLESS_IDLE == 1 )
#if( configUSE_TICKLESS_IDLE == 1 )
{
ulTimerCountsForOneTick = ( configSYSTICK_CLOCK_HZ / configTICK_RATE_HZ );
xMaximumPossibleSuppressedTicks = portMAX_24_BIT_NUMBER / ulTimerCountsForOneTick;
@@ -630,15 +619,16 @@ __attribute__(( weak )) void vPortSetupTimerInterrupt( void )
portNVIC_SYSTICK_CURRENT_VALUE_REG = 0UL;
/* Configure SysTick to interrupt at the requested rate. */
portNVIC_SYSTICK_LOAD_REG = ( configSYSTICK_CLOCK_HZ / configTICK_RATE_HZ ) - 1UL;
portNVIC_SYSTICK_CTRL_REG = ( portNVIC_SYSTICK_CLK_BIT | portNVIC_SYSTICK_INT_BIT | portNVIC_SYSTICK_ENABLE_BIT );
portNVIC_SYSTICK_LOAD_REG = ( configSYSTICK_CLOCK_HZ / configTICK_RATE_HZ)
- 1UL;
portNVIC_SYSTICK_CTRL_REG = ( portNVIC_SYSTICK_CLK_BIT
| portNVIC_SYSTICK_INT_BIT | portNVIC_SYSTICK_ENABLE_BIT);
}
/*-----------------------------------------------------------*/
#if( configASSERT_DEFINED == 1 )
void vPortValidateInterruptPriority( void )
{
void vPortValidateInterruptPriority(void) {
uint32_t ulCurrentInterrupt;
uint8_t ucCurrentPriority;
@@ -646,10 +636,9 @@ __attribute__(( weak )) void vPortSetupTimerInterrupt( void )
__asm volatile( "mrs %0, ipsr" : "=r"( ulCurrentInterrupt ) :: "memory" );
/* Is the interrupt number a user defined interrupt? */
if( ulCurrentInterrupt >= portFIRST_USER_INTERRUPT_NUMBER )
{
if (ulCurrentInterrupt >= portFIRST_USER_INTERRUPT_NUMBER) {
/* Look up the interrupt's priority. */
ucCurrentPriority = pcInterruptPriorityRegisters[ ulCurrentInterrupt ];
ucCurrentPriority = pcInterruptPriorityRegisters[ulCurrentInterrupt];
/* The following assertion will fail if a service routine (ISR) for
an interrupt that has been assigned a priority above
@@ -674,7 +663,7 @@ __attribute__(( weak )) void vPortSetupTimerInterrupt( void )
The following links provide detailed information:
http://www.freertos.org/RTOS-Cortex-M3-M4.html
http://www.freertos.org/FAQHelp.html */
configASSERT( ucCurrentPriority >= ucMaxSysCallPriority );
configASSERT(ucCurrentPriority >= ucMaxSysCallPriority);
}
/* Priority grouping: The interrupt controller (NVIC) allows the bits
@@ -690,28 +679,9 @@ __attribute__(( weak )) void vPortSetupTimerInterrupt( void )
scheduler. Note however that some vendor specific peripheral libraries
assume a non-zero priority group setting, in which cases using a value
of zero will result in unpredictable behaviour. */
configASSERT( ( portAIRCR_REG & portPRIORITY_GROUP_MASK ) <= ulMaxPRIGROUPValue );
}
configASSERT(
( portAIRCR_REG & portPRIORITY_GROUP_MASK) <= ulMaxPRIGROUPValue);
}
#endif /* configASSERT_DEFINED */

View File

@@ -25,7 +25,6 @@
* 1 tab == 4 spaces!
*/
#ifndef PORTMACRO_H
#define PORTMACRO_H
@@ -60,12 +59,12 @@ typedef unsigned long UBaseType_t;
typedef uint16_t TickType_t;
#define portMAX_DELAY ( TickType_t ) 0xffff
#else
typedef uint32_t TickType_t;
#define portMAX_DELAY ( TickType_t ) 0xffffffffUL
typedef uint32_t TickType_t;
#define portMAX_DELAY ( TickType_t ) 0xffffffffUL
/* 32-bit tick type on a 32-bit architecture, so reads of the tick count do
/* 32-bit tick type on a 32-bit architecture, so reads of the tick count do
not need to be guarded with a critical section. */
#define portTICK_TYPE_IS_ATOMIC 1
#define portTICK_TYPE_IS_ATOMIC 1
#endif
/*-----------------------------------------------------------*/
@@ -94,8 +93,8 @@ typedef unsigned long UBaseType_t;
/*-----------------------------------------------------------*/
/* Critical section management. */
extern void vPortEnterCritical( void );
extern void vPortExitCritical( void );
extern void vPortEnterCritical(void);
extern void vPortExitCritical(void);
#define portSET_INTERRUPT_MASK_FROM_ISR() ulPortRaiseBASEPRI()
#define portCLEAR_INTERRUPT_MASK_FROM_ISR(x) vPortSetBASEPRI(x)
#define portDISABLE_INTERRUPTS() vPortRaiseBASEPRI()
@@ -106,55 +105,55 @@ extern void vPortExitCritical( void );
/*-----------------------------------------------------------*/
/* Task function macros as described on the FreeRTOS.org WEB site. These are
not necessary for to use this port. They are defined so the common demo files
(which build with all the ports) will build. */
not necessary for to use this port. They are defined so the common demo files
(which build with all the ports) will build. */
#define portTASK_FUNCTION_PROTO( vFunction, pvParameters ) void vFunction( void *pvParameters )
#define portTASK_FUNCTION( vFunction, pvParameters ) void vFunction( void *pvParameters )
/*-----------------------------------------------------------*/
/* Tickless idle/low power functionality. */
#ifndef portSUPPRESS_TICKS_AND_SLEEP
extern void vPortSuppressTicksAndSleep( TickType_t xExpectedIdleTime );
#define portSUPPRESS_TICKS_AND_SLEEP( xExpectedIdleTime ) vPortSuppressTicksAndSleep( xExpectedIdleTime )
extern void vPortSuppressTicksAndSleep(TickType_t xExpectedIdleTime);
#define portSUPPRESS_TICKS_AND_SLEEP( xExpectedIdleTime ) vPortSuppressTicksAndSleep( xExpectedIdleTime )
#endif
/*-----------------------------------------------------------*/
/* Architecture specific optimisations. */
#ifndef configUSE_PORT_OPTIMISED_TASK_SELECTION
#define configUSE_PORT_OPTIMISED_TASK_SELECTION 1
#define configUSE_PORT_OPTIMISED_TASK_SELECTION 1
#endif
#if configUSE_PORT_OPTIMISED_TASK_SELECTION == 1
/* Generic helper function. */
__attribute__( ( always_inline ) ) static inline uint8_t ucPortCountLeadingZeros( uint32_t ulBitmap )
{
/* Generic helper function. */
__attribute__( ( always_inline ) ) static inline uint8_t ucPortCountLeadingZeros(
uint32_t ulBitmap) {
uint8_t ucReturn;
__asm volatile ( "clz %0, %1" : "=r" ( ucReturn ) : "r" ( ulBitmap ) : "memory" );
return ucReturn;
}
}
/* Check the configuration. */
#if( configMAX_PRIORITIES > 32 )
#error configUSE_PORT_OPTIMISED_TASK_SELECTION can only be set to 1 when configMAX_PRIORITIES is less than or equal to 32. It is very rare that a system requires more than 10 to 15 difference priorities as tasks that share a priority will time slice.
#endif
/* Check the configuration. */
#if( configMAX_PRIORITIES > 32 )
#error configUSE_PORT_OPTIMISED_TASK_SELECTION can only be set to 1 when configMAX_PRIORITIES is less than or equal to 32. It is very rare that a system requires more than 10 to 15 difference priorities as tasks that share a priority will time slice.
#endif
/* Store/clear the ready priorities in a bit map. */
#define portRECORD_READY_PRIORITY( uxPriority, uxReadyPriorities ) ( uxReadyPriorities ) |= ( 1UL << ( uxPriority ) )
#define portRESET_READY_PRIORITY( uxPriority, uxReadyPriorities ) ( uxReadyPriorities ) &= ~( 1UL << ( uxPriority ) )
/* Store/clear the ready priorities in a bit map. */
#define portRECORD_READY_PRIORITY( uxPriority, uxReadyPriorities ) ( uxReadyPriorities ) |= ( 1UL << ( uxPriority ) )
#define portRESET_READY_PRIORITY( uxPriority, uxReadyPriorities ) ( uxReadyPriorities ) &= ~( 1UL << ( uxPriority ) )
/*-----------------------------------------------------------*/
/*-----------------------------------------------------------*/
#define portGET_HIGHEST_PRIORITY( uxTopPriority, uxReadyPriorities ) uxTopPriority = ( 31UL - ( uint32_t ) ucPortCountLeadingZeros( ( uxReadyPriorities ) ) )
#define portGET_HIGHEST_PRIORITY( uxTopPriority, uxReadyPriorities ) uxTopPriority = ( 31UL - ( uint32_t ) ucPortCountLeadingZeros( ( uxReadyPriorities ) ) )
#endif /* configUSE_PORT_OPTIMISED_TASK_SELECTION */
/*-----------------------------------------------------------*/
#ifdef configASSERT
void vPortValidateInterruptPriority( void );
#define portASSERT_IF_INTERRUPT_PRIORITY_INVALID() vPortValidateInterruptPriority()
void vPortValidateInterruptPriority( void );
#define portASSERT_IF_INTERRUPT_PRIORITY_INVALID() vPortValidateInterruptPriority()
#endif
/* portNOP() is not required by this port. */
@@ -163,25 +162,21 @@ not necessary for to use this port. They are defined so the common demo files
#define portINLINE __inline
#ifndef portFORCE_INLINE
#define portFORCE_INLINE inline __attribute__(( always_inline))
#define portFORCE_INLINE inline __attribute__(( always_inline))
#endif
/*-----------------------------------------------------------*/
portFORCE_INLINE static BaseType_t xPortIsInsideInterrupt( void )
{
uint32_t ulCurrentInterrupt;
BaseType_t xReturn;
portFORCE_INLINE static BaseType_t xPortIsInsideInterrupt(void) {
uint32_t ulCurrentInterrupt;
BaseType_t xReturn;
/* Obtain the number of the currently executing interrupt. */
__asm volatile( "mrs %0, ipsr" : "=r"( ulCurrentInterrupt ) :: "memory" );
if( ulCurrentInterrupt == 0 )
{
if (ulCurrentInterrupt == 0) {
xReturn = pdFALSE;
}
else
{
} else {
xReturn = pdTRUE;
}
@@ -190,33 +185,31 @@ BaseType_t xReturn;
/*-----------------------------------------------------------*/
portFORCE_INLINE static void vPortRaiseBASEPRI( void )
{
uint32_t ulNewBASEPRI;
portFORCE_INLINE static void vPortRaiseBASEPRI(void) {
uint32_t ulNewBASEPRI;
__asm volatile
(
" mov %0, %1 \n" \
" msr basepri, %0 \n" \
" isb \n" \
" dsb \n" \
" mov %0, %1 \n"
" msr basepri, %0 \n"
" isb \n"
" dsb \n"
:"=r" (ulNewBASEPRI) : "i" ( configMAX_SYSCALL_INTERRUPT_PRIORITY ) : "memory"
);
}
/*-----------------------------------------------------------*/
portFORCE_INLINE static uint32_t ulPortRaiseBASEPRI( void )
{
uint32_t ulOriginalBASEPRI, ulNewBASEPRI;
portFORCE_INLINE static uint32_t ulPortRaiseBASEPRI(void) {
uint32_t ulOriginalBASEPRI, ulNewBASEPRI;
__asm volatile
(
" mrs %0, basepri \n" \
" mov %1, %2 \n" \
" msr basepri, %1 \n" \
" isb \n" \
" dsb \n" \
" mrs %0, basepri \n"
" mov %1, %2 \n"
" msr basepri, %1 \n"
" isb \n"
" dsb \n"
:"=r" (ulOriginalBASEPRI), "=r" (ulNewBASEPRI) : "i" ( configMAX_SYSCALL_INTERRUPT_PRIORITY ) : "memory"
);
@@ -226,8 +219,7 @@ uint32_t ulOriginalBASEPRI, ulNewBASEPRI;
}
/*-----------------------------------------------------------*/
portFORCE_INLINE static void vPortSetBASEPRI( uint32_t ulNewMaskValue )
{
portFORCE_INLINE static void vPortSetBASEPRI(uint32_t ulNewMaskValue) {
__asm volatile
(
" msr basepri, %0 " :: "r" ( ulNewMaskValue ) : "memory"

View File

@@ -26,10 +26,9 @@ void HAL_MspInit(void) {
/* SysTick_IRQn interrupt configuration */
HAL_NVIC_SetPriority(SysTick_IRQn, 15, 0);
}
void HAL_ADC_MspInit(ADC_HandleTypeDef* hadc) {
void HAL_ADC_MspInit(ADC_HandleTypeDef *hadc) {
GPIO_InitTypeDef GPIO_InitStruct;
if (hadc->Instance == ADC1) {
@@ -72,7 +71,7 @@ void HAL_ADC_MspInit(ADC_HandleTypeDef* hadc) {
}
void HAL_I2C_MspInit(I2C_HandleTypeDef* hi2c) {
void HAL_I2C_MspInit(I2C_HandleTypeDef *hi2c) {
GPIO_InitTypeDef GPIO_InitStruct;
/**I2C1 GPIO Configuration
@@ -123,7 +122,7 @@ void HAL_I2C_MspInit(I2C_HandleTypeDef* hi2c) {
}
void HAL_TIM_Base_MspInit(TIM_HandleTypeDef* htim_base) {
void HAL_TIM_Base_MspInit(TIM_HandleTypeDef *htim_base) {
if (htim_base->Instance == TIM3) {
/* Peripheral clock enable */
__HAL_RCC_TIM3_CLK_ENABLE()

View File

@@ -75,15 +75,14 @@ uint32_t uwIncrementState = 0;
* @param TickPriority: Tick interrupt priorty.
* @retval HAL status
*/
HAL_StatusTypeDef HAL_InitTick(uint32_t TickPriority)
{
HAL_StatusTypeDef HAL_InitTick(uint32_t TickPriority) {
RCC_ClkInitTypeDef clkconfig;
uint32_t uwTimclock = 0;
uint32_t uwPrescalerValue = 0;
uint32_t pFLatency;
/*Configure the TIM1 IRQ priority */
HAL_NVIC_SetPriority(TIM1_UP_IRQn, TickPriority ,0);
HAL_NVIC_SetPriority(TIM1_UP_IRQn, TickPriority, 0);
/* Enable the TIM1 global Interrupt */
HAL_NVIC_EnableIRQ(TIM1_UP_IRQn);
@@ -113,8 +112,7 @@ HAL_StatusTypeDef HAL_InitTick(uint32_t TickPriority)
htim1.Init.Prescaler = uwPrescalerValue;
htim1.Init.ClockDivision = 0;
htim1.Init.CounterMode = TIM_COUNTERMODE_UP;
if(HAL_TIM_Base_Init(&htim1) == HAL_OK)
{
if (HAL_TIM_Base_Init(&htim1) == HAL_OK) {
/* Start the TIM time Base generation in interrupt mode */
return HAL_TIM_Base_Start_IT(&htim1);
}
@@ -129,8 +127,7 @@ HAL_StatusTypeDef HAL_InitTick(uint32_t TickPriority)
* @param None
* @retval None
*/
void HAL_SuspendTick(void)
{
void HAL_SuspendTick(void) {
/* Disable TIM1 update Interrupt */
__HAL_TIM_DISABLE_IT(&htim1, TIM_IT_UPDATE);
}
@@ -141,8 +138,7 @@ void HAL_SuspendTick(void)
* @param None
* @retval None
*/
void HAL_ResumeTick(void)
{
void HAL_ResumeTick(void) {
/* Enable TIM1 Update interrupt */
__HAL_TIM_ENABLE_IT(&htim1, TIM_IT_UPDATE);
}

View File

@@ -82,6 +82,6 @@ void DMA1_Channel6_IRQHandler(void) {
void DMA1_Channel7_IRQHandler(void) {
HAL_DMA_IRQHandler(&hdma_i2c1_rx);
}
void EXTI9_5_IRQHandler(void){
void EXTI9_5_IRQHandler(void) {
HAL_GPIO_EXTI_IRQHandler(GPIO_PIN_9);
}

View File

@@ -19,17 +19,17 @@
#endif
/*******************************************************************************
* Clock Definitions
*******************************************************************************/
* Clock Definitions
*******************************************************************************/
#if defined(STM32F100xB) ||defined(STM32F100xE)
uint32_t SystemCoreClock = 24000000U; /*!< System Clock Frequency (Core Clock) */
#else /*!< HSI Selected as System Clock source */
uint32_t SystemCoreClock = 64000000U; /*!< System Clock Frequency (Core Clock) */
uint32_t SystemCoreClock = 64000000U; /*!< System Clock Frequency (Core Clock) */
#endif
const uint8_t AHBPrescTable[16U] = {0, 0, 0, 0, 0, 0, 0, 0, 1, 2, 3, 4, 6, 7, 8, 9};
const uint8_t APBPrescTable[8U] = {0, 0, 0, 0, 1, 2, 3, 4};
const uint8_t AHBPrescTable[16U] = { 0, 0, 0, 0, 0, 0, 0, 0, 1, 2, 3, 4, 6, 7,
8, 9 };
const uint8_t APBPrescTable[8U] = { 0, 0, 0, 0, 1, 2, 3, 4 };
/**
* @brief Setup the microcontroller system
@@ -39,8 +39,7 @@ const uint8_t APBPrescTable[8U] = {0, 0, 0, 0, 1, 2, 3, 4};
* @param None
* @retval None
*/
void SystemInit (void)
{
void SystemInit(void) {
/* Reset the RCC clock configuration to the default reset state(for debug purpose) */
/* Set HSION bit */
RCC->CR |= 0x00000001U;
@@ -129,8 +128,7 @@ void SystemInit (void)
* @param None
* @retval None
*/
void SystemCoreClockUpdate (void)
{
void SystemCoreClockUpdate(void) {
uint32_t tmp = 0U, pllmull = 0U, pllsource = 0U;
#if defined(STM32F105xC) || defined(STM32F107xC)
@@ -144,8 +142,7 @@ void SystemCoreClockUpdate (void)
/* Get SYSCLK source -------------------------------------------------------*/
tmp = RCC->CFGR & RCC_CFGR_SWS;
switch (tmp)
{
switch (tmp) {
case 0x00U: /* HSI used as system clock */
SystemCoreClock = HSI_VALUE;
break;
@@ -159,30 +156,24 @@ void SystemCoreClockUpdate (void)
pllsource = RCC->CFGR & RCC_CFGR_PLLSRC;
#if !defined(STM32F105xC) && !defined(STM32F107xC)
pllmull = ( pllmull >> 18U) + 2U;
pllmull = (pllmull >> 18U) + 2U;
if (pllsource == 0x00U)
{
if (pllsource == 0x00U) {
/* HSI oscillator clock divided by 2 selected as PLL clock entry */
SystemCoreClock = (HSI_VALUE >> 1U) * pllmull;
}
else
{
#if defined(STM32F100xB) || defined(STM32F100xE)
} else {
#if defined(STM32F100xB) || defined(STM32F100xE)
prediv1factor = (RCC->CFGR2 & RCC_CFGR2_PREDIV1) + 1U;
/* HSE oscillator clock selected as PREDIV1 clock entry */
SystemCoreClock = (HSE_VALUE / prediv1factor) * pllmull;
#else
/* HSE selected as PLL clock entry */
if ((RCC->CFGR & RCC_CFGR_PLLXTPRE) != (uint32_t)RESET)
{/* HSE oscillator clock divided by 2 */
if ((RCC->CFGR & RCC_CFGR_PLLXTPRE) != (uint32_t) RESET) {/* HSE oscillator clock divided by 2 */
SystemCoreClock = (HSE_VALUE >> 1U) * pllmull;
}
else
{
} else {
SystemCoreClock = HSE_VALUE * pllmull;
}
#endif
#endif
}
#else
pllmull = pllmull >> 18U;