This commit is contained in:
Rene Hopf 2018-01-06 23:33:34 +01:00
parent cd5718e151
commit 61aff94a26
8 changed files with 399 additions and 400 deletions

27
.clang-format Normal file
View File

@ -0,0 +1,27 @@
---
BasedOnStyle: LLVM
AccessModifierOffset: '2'
AlignAfterOpenBracket: Align
AlignConsecutiveAssignments: 'true'
AlignOperands: 'false'
AlignTrailingComments: 'true'
SortIncludes: 'false'
ColumnLimit: '0'
IndentCaseLabels: 'true'
IndentWidth: '2'
KeepEmptyLinesAtTheStartOfBlocks: 'false'
MaxEmptyLinesToKeep: '2'
SpaceAfterCStyleCast: 'false'
SpaceBeforeAssignmentOperators: 'true'
SpaceBeforeParens: Never
SpaceInEmptyParentheses: 'false'
SpacesBeforeTrailingComments: '2'
SpacesInAngles: 'false'
SpacesInCStyleCastParentheses: 'false'
SpacesInContainerLiterals: 'false'
SpacesInParentheses: 'false'
SpacesInSquareBrackets: 'false'
TabWidth: '2'
UseTab: Never
...

View File

@ -37,7 +37,7 @@
#define __STM32F1xx_HAL_CONF_H
#ifdef __cplusplus
extern "C" {
extern "C" {
#endif
/* Exported types ------------------------------------------------------------*/
@ -96,12 +96,12 @@
* This value is used by the RCC HAL module to compute the system frequency
* (when HSE is used as system clock source, directly or through the PLL).
*/
#if !defined (HSE_VALUE)
#define HSE_VALUE ((uint32_t)8000000) /*!< Value of the External oscillator in Hz */
#if !defined(HSE_VALUE)
#define HSE_VALUE ((uint32_t)8000000) /*!< Value of the External oscillator in Hz */
#endif /* HSE_VALUE */
#if !defined (HSE_STARTUP_TIMEOUT)
#define HSE_STARTUP_TIMEOUT ((uint32_t)100) /*!< Time out for HSE start up, in ms */
#if !defined(HSE_STARTUP_TIMEOUT)
#define HSE_STARTUP_TIMEOUT ((uint32_t)100) /*!< Time out for HSE start up, in ms */
#endif /* HSE_STARTUP_TIMEOUT */
/**
@ -109,29 +109,29 @@
* This value is used by the RCC HAL module to compute the system frequency
* (when HSI is used as system clock source, directly or through the PLL).
*/
#if !defined (HSI_VALUE)
#define HSI_VALUE ((uint32_t)8000000) /*!< Value of the Internal oscillator in Hz*/
#if !defined(HSI_VALUE)
#define HSI_VALUE ((uint32_t)8000000) /*!< Value of the Internal oscillator in Hz*/
#endif /* HSI_VALUE */
/**
* @brief Internal Low Speed oscillator (LSI) value.
*/
#if !defined (LSI_VALUE)
#define LSI_VALUE 40000U /*!< LSI Typical Value in Hz */
#endif /* LSI_VALUE */ /*!< Value of the Internal Low Speed oscillator in Hz
The real value may vary depending on the variations
#if !defined(LSI_VALUE)
#define LSI_VALUE 40000U /*!< LSI Typical Value in Hz */
#endif /* LSI_VALUE */ /*!< Value of the Internal Low Speed oscillator in Hz \
The real value may vary depending on the variations \
in voltage and temperature. */
/**
* @brief External Low Speed oscillator (LSE) value.
* This value is used by the UART, RTC HAL module to compute the system frequency
*/
#if !defined (LSE_VALUE)
#define LSE_VALUE ((uint32_t)32768) /*!< Value of the External oscillator in Hz*/
#if !defined(LSE_VALUE)
#define LSE_VALUE ((uint32_t)32768) /*!< Value of the External oscillator in Hz*/
#endif /* LSE_VALUE */
#if !defined (LSE_STARTUP_TIMEOUT)
#define LSE_STARTUP_TIMEOUT ((uint32_t)5000) /*!< Time out for LSE start up, in ms */
#if !defined(LSE_STARTUP_TIMEOUT)
#define LSE_STARTUP_TIMEOUT ((uint32_t)5000) /*!< Time out for LSE start up, in ms */
#endif /* LSE_STARTUP_TIMEOUT */
/* Tip: To avoid modifying this file each time you need to use different HSE,
@ -215,127 +215,127 @@
*/
#ifdef HAL_RCC_MODULE_ENABLED
#include "stm32f1xx_hal_rcc.h"
#include "stm32f1xx_hal_rcc.h"
#endif /* HAL_RCC_MODULE_ENABLED */
#ifdef HAL_GPIO_MODULE_ENABLED
#include "stm32f1xx_hal_gpio.h"
#include "stm32f1xx_hal_gpio.h"
#endif /* HAL_GPIO_MODULE_ENABLED */
#ifdef HAL_DMA_MODULE_ENABLED
#include "stm32f1xx_hal_dma.h"
#include "stm32f1xx_hal_dma.h"
#endif /* HAL_DMA_MODULE_ENABLED */
#ifdef HAL_ETH_MODULE_ENABLED
#include "stm32f1xx_hal_eth.h"
#include "stm32f1xx_hal_eth.h"
#endif /* HAL_ETH_MODULE_ENABLED */
#ifdef HAL_CAN_MODULE_ENABLED
#include "stm32f1xx_hal_can.h"
#include "stm32f1xx_hal_can.h"
#endif /* HAL_CAN_MODULE_ENABLED */
#ifdef HAL_CEC_MODULE_ENABLED
#include "stm32f1xx_hal_cec.h"
#include "stm32f1xx_hal_cec.h"
#endif /* HAL_CEC_MODULE_ENABLED */
#ifdef HAL_CORTEX_MODULE_ENABLED
#include "stm32f1xx_hal_cortex.h"
#include "stm32f1xx_hal_cortex.h"
#endif /* HAL_CORTEX_MODULE_ENABLED */
#ifdef HAL_ADC_MODULE_ENABLED
#include "stm32f1xx_hal_adc.h"
#include "stm32f1xx_hal_adc.h"
#endif /* HAL_ADC_MODULE_ENABLED */
#ifdef HAL_CRC_MODULE_ENABLED
#include "stm32f1xx_hal_crc.h"
#include "stm32f1xx_hal_crc.h"
#endif /* HAL_CRC_MODULE_ENABLED */
#ifdef HAL_DAC_MODULE_ENABLED
#include "stm32f1xx_hal_dac.h"
#include "stm32f1xx_hal_dac.h"
#endif /* HAL_DAC_MODULE_ENABLED */
#ifdef HAL_FLASH_MODULE_ENABLED
#include "stm32f1xx_hal_flash.h"
#include "stm32f1xx_hal_flash.h"
#endif /* HAL_FLASH_MODULE_ENABLED */
#ifdef HAL_SRAM_MODULE_ENABLED
#include "stm32f1xx_hal_sram.h"
#include "stm32f1xx_hal_sram.h"
#endif /* HAL_SRAM_MODULE_ENABLED */
#ifdef HAL_NOR_MODULE_ENABLED
#include "stm32f1xx_hal_nor.h"
#include "stm32f1xx_hal_nor.h"
#endif /* HAL_NOR_MODULE_ENABLED */
#ifdef HAL_I2C_MODULE_ENABLED
#include "stm32f1xx_hal_i2c.h"
#include "stm32f1xx_hal_i2c.h"
#endif /* HAL_I2C_MODULE_ENABLED */
#ifdef HAL_I2S_MODULE_ENABLED
#include "stm32f1xx_hal_i2s.h"
#include "stm32f1xx_hal_i2s.h"
#endif /* HAL_I2S_MODULE_ENABLED */
#ifdef HAL_IWDG_MODULE_ENABLED
#include "stm32f1xx_hal_iwdg.h"
#include "stm32f1xx_hal_iwdg.h"
#endif /* HAL_IWDG_MODULE_ENABLED */
#ifdef HAL_PWR_MODULE_ENABLED
#include "stm32f1xx_hal_pwr.h"
#include "stm32f1xx_hal_pwr.h"
#endif /* HAL_PWR_MODULE_ENABLED */
#ifdef HAL_RTC_MODULE_ENABLED
#include "stm32f1xx_hal_rtc.h"
#include "stm32f1xx_hal_rtc.h"
#endif /* HAL_RTC_MODULE_ENABLED */
#ifdef HAL_PCCARD_MODULE_ENABLED
#include "stm32f1xx_hal_pccard.h"
#include "stm32f1xx_hal_pccard.h"
#endif /* HAL_PCCARD_MODULE_ENABLED */
#ifdef HAL_SD_MODULE_ENABLED
#include "stm32f1xx_hal_sd.h"
#include "stm32f1xx_hal_sd.h"
#endif /* HAL_SD_MODULE_ENABLED */
#ifdef HAL_MMC_MODULE_ENABLED
#include "stm32f1xx_hal_mmc.h"
#include "stm32f1xx_hal_mmc.h"
#endif /* HAL_MMC_MODULE_ENABLED */
#ifdef HAL_NAND_MODULE_ENABLED
#include "stm32f1xx_hal_nand.h"
#include "stm32f1xx_hal_nand.h"
#endif /* HAL_NAND_MODULE_ENABLED */
#ifdef HAL_SPI_MODULE_ENABLED
#include "stm32f1xx_hal_spi.h"
#include "stm32f1xx_hal_spi.h"
#endif /* HAL_SPI_MODULE_ENABLED */
#ifdef HAL_TIM_MODULE_ENABLED
#include "stm32f1xx_hal_tim.h"
#include "stm32f1xx_hal_tim.h"
#endif /* HAL_TIM_MODULE_ENABLED */
#ifdef HAL_UART_MODULE_ENABLED
#include "stm32f1xx_hal_uart.h"
#include "stm32f1xx_hal_uart.h"
#endif /* HAL_UART_MODULE_ENABLED */
#ifdef HAL_USART_MODULE_ENABLED
#include "stm32f1xx_hal_usart.h"
#include "stm32f1xx_hal_usart.h"
#endif /* HAL_USART_MODULE_ENABLED */
#ifdef HAL_IRDA_MODULE_ENABLED
#include "stm32f1xx_hal_irda.h"
#include "stm32f1xx_hal_irda.h"
#endif /* HAL_IRDA_MODULE_ENABLED */
#ifdef HAL_SMARTCARD_MODULE_ENABLED
#include "stm32f1xx_hal_smartcard.h"
#include "stm32f1xx_hal_smartcard.h"
#endif /* HAL_SMARTCARD_MODULE_ENABLED */
#ifdef HAL_WWDG_MODULE_ENABLED
#include "stm32f1xx_hal_wwdg.h"
#include "stm32f1xx_hal_wwdg.h"
#endif /* HAL_WWDG_MODULE_ENABLED */
#ifdef HAL_PCD_MODULE_ENABLED
#include "stm32f1xx_hal_pcd.h"
#include "stm32f1xx_hal_pcd.h"
#endif /* HAL_PCD_MODULE_ENABLED */
#ifdef HAL_HCD_MODULE_ENABLED
#include "stm32f1xx_hal_hcd.h"
#include "stm32f1xx_hal_hcd.h"
#endif /* HAL_HCD_MODULE_ENABLED */
@ -349,11 +349,11 @@
* If expr is true, it returns no value.
* @retval None
*/
#define assert_param(expr) ((expr) ? (void)0U : assert_failed((uint8_t *)__FILE__, __LINE__))
#define assert_param(expr) ((expr) ? (void)0U : assert_failed((uint8_t *)__FILE__, __LINE__))
/* Exported functions ------------------------------------------------------- */
void assert_failed(uint8_t* file, uint32_t line);
void assert_failed(uint8_t *file, uint32_t line);
#else
#define assert_param(expr) ((void)0U)
#define assert_param(expr) ((void)0U)
#endif /* USE_FULL_ASSERT */
#ifdef __cplusplus

View File

@ -36,7 +36,7 @@
#define __STM32F1xx_IT_H
#ifdef __cplusplus
extern "C" {
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/

View File

@ -149,6 +149,8 @@ $(BUILD_DIR)/%.bin: $(BUILD_DIR)/%.elf | $(BUILD_DIR)
$(BUILD_DIR):
mkdir $@
format:
find Src/ Inc/ -iname '*.h' -o -iname '*.c' | xargs clang-format -i
#######################################
# clean up
#######################################

View File

@ -48,8 +48,8 @@ const uint8_t hall_to_pos[8] = {
0,
};
inline void block(int pwm, int pos, int* u, int* v, int* w){
switch(pos){
inline void block(int pwm, int pos, int *u, int *v, int *w) {
switch(pos) {
case 0:
*u = 0;
*v = pwm;
@ -94,9 +94,9 @@ volatile int vel = 0;
volatile uint8_t uart_buf[10];
void DMA1_Channel1_IRQHandler(){
void DMA1_Channel1_IRQHandler() {
DMA1->IFCR = DMA_IFCR_CTCIF1;
HAL_GPIO_WritePin(LED_PORT, LED_PIN, 1);
/*
uart_buf[0] = 0xff;
uart_buf[1] = adc_buffer.r_dc1 - 1850 + 127;
@ -117,17 +117,15 @@ void DMA1_Channel1_IRQHandler(){
}
*/
if(adc_buffer.l_dc2 > 1950){
if(adc_buffer.l_dc2 > 1950) {
LEFT_TIM->BDTR &= ~TIM_BDTR_MOE;
HAL_GPIO_WritePin(LED_PORT, LED_PIN, 1);
}else{
} else {
LEFT_TIM->BDTR |= TIM_BDTR_MOE;
HAL_GPIO_WritePin(LED_PORT, LED_PIN, 0);
}
if(adc_buffer.r_dc1 > 1950){
if(adc_buffer.r_dc1 > 1950) {
RIGHT_TIM->BDTR &= ~TIM_BDTR_MOE;
}else{
} else {
RIGHT_TIM->BDTR |= TIM_BDTR_MOE;
}
@ -139,13 +137,13 @@ void DMA1_Channel1_IRQHandler(){
int vr = 0;
int wr = 0;
uint8_t hall_ul = HAL_GPIO_ReadPin(LEFT_HALL_U_PORT, LEFT_HALL_U_PIN);
uint8_t hall_vl = HAL_GPIO_ReadPin(LEFT_HALL_V_PORT, LEFT_HALL_V_PIN);
uint8_t hall_wl = HAL_GPIO_ReadPin(LEFT_HALL_W_PORT, LEFT_HALL_W_PIN);
uint8_t hall_ul = !(LEFT_HALL_U_PORT->IDR & LEFT_HALL_U_PIN);
uint8_t hall_vl = !(LEFT_HALL_V_PORT->IDR & LEFT_HALL_V_PIN);
uint8_t hall_wl = !(LEFT_HALL_W_PORT->IDR & LEFT_HALL_W_PIN);
uint8_t hall_ur = HAL_GPIO_ReadPin(RIGHT_HALL_U_PORT, RIGHT_HALL_U_PIN);
uint8_t hall_vr = HAL_GPIO_ReadPin(RIGHT_HALL_V_PORT, RIGHT_HALL_V_PIN);
uint8_t hall_wr = HAL_GPIO_ReadPin(RIGHT_HALL_W_PORT, RIGHT_HALL_W_PIN);
uint8_t hall_ur = !(RIGHT_HALL_U_PORT->IDR & RIGHT_HALL_U_PIN);
uint8_t hall_vr = !(RIGHT_HALL_V_PORT->IDR & RIGHT_HALL_V_PIN);
uint8_t hall_wr = !(RIGHT_HALL_W_PORT->IDR & RIGHT_HALL_W_PIN);
uint8_t halll = hall_ul * 1 + hall_vl * 2 + hall_wl * 4;
posl = hall_to_pos[halll];
@ -178,7 +176,6 @@ void DMA1_Channel1_IRQHandler(){
block(pwml, posl, &ul, &vl, &wl);
block(pwmr, posr, &ur, &vr, &wr);
LEFT_TIM->LEFT_TIM_U = CLAMP(ul + pwm_res / 2, 0, pwm_res);
LEFT_TIM->LEFT_TIM_V = CLAMP(vl + pwm_res / 2, 0, pwm_res);
LEFT_TIM->LEFT_TIM_W = CLAMP(wl + pwm_res / 2, 0, pwm_res);
@ -186,13 +183,12 @@ void DMA1_Channel1_IRQHandler(){
RIGHT_TIM->RIGHT_TIM_U = CLAMP(ur + pwm_res / 2, 0, pwm_res);
RIGHT_TIM->RIGHT_TIM_V = CLAMP(vr + pwm_res / 2, 0, pwm_res);
RIGHT_TIM->RIGHT_TIM_W = CLAMP(wr + pwm_res / 2, 0, pwm_res);
HAL_GPIO_WritePin(LED_PORT, LED_PIN, 0);
}
int milli_vel_error_sum = 0;
int main(void)
{
int main(void) {
HAL_Init();
__HAL_RCC_AFIO_CLK_ENABLE();
HAL_NVIC_SetPriorityGrouping(NVIC_PRIORITYGROUP_4);
@ -226,8 +222,7 @@ int main(void)
HAL_ADC_Start(&hadc1);
HAL_ADC_Start(&hadc2);
while (1)
{
while(1) {
HAL_Delay(0);
// int milli_cur = 3000;
// int milli_volt = milli_cur * MILLI_R / 1000;// + vel * MILLI_PSI * 141;
@ -252,9 +247,7 @@ int main(void)
/** System Clock Configuration
*/
void SystemClock_Config(void)
{
void SystemClock_Config(void) {
RCC_OscInitTypeDef RCC_OscInitStruct;
RCC_ClkInitTypeDef RCC_ClkInitStruct;
RCC_PeriphCLKInitTypeDef PeriphClkInit;
@ -271,8 +264,7 @@ void SystemClock_Config(void)
/**Initializes the CPU, AHB and APB busses clocks
*/
RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_HCLK|RCC_CLOCKTYPE_SYSCLK
|RCC_CLOCKTYPE_PCLK1|RCC_CLOCKTYPE_PCLK2;
RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_HCLK | RCC_CLOCKTYPE_SYSCLK | RCC_CLOCKTYPE_PCLK1 | RCC_CLOCKTYPE_PCLK2;
RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK;
RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1;
RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV2;
@ -286,7 +278,7 @@ void SystemClock_Config(void)
/**Configure the Systick interrupt time
*/
HAL_SYSTICK_Config(HAL_RCC_GetHCLKFreq()/1000);
HAL_SYSTICK_Config(HAL_RCC_GetHCLKFreq() / 1000);
/**Configure the Systick
*/

View File

@ -18,6 +18,22 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
/*
tim1 master, enable -> trgo
tim8, gated slave mode, trgo by tim1 trgo. overflow -> trgo
adc1,adc2 triggered by tim8 trgo
adc 1,2 dual mode
ADC1 ADC2
R_Blau PC4 CH14 R_Gelb PC5 CH15
L_Grün PA0 CH01 L_Blau PC3 CH13
R_DC PC1 CH11 L_DC PC0 CH10
BAT PC2 CH12 L_TX PA2 CH02
BAT PC2 CH12 L_RX PA3 CH03
pb10 usart3 dma1 channel2/3
*/
#include "defines.h"
TIM_HandleTypeDef htim_right;
@ -26,7 +42,7 @@ ADC_HandleTypeDef hadc1;
ADC_HandleTypeDef hadc2;
volatile adc_buf_t adc_buffer;
void UART_Init(){
void UART_Init() {
__HAL_RCC_USART3_CLK_ENABLE();
__HAL_RCC_DMA1_CLK_ENABLE();
@ -41,7 +57,7 @@ void UART_Init(){
huart3.Init.OverSampling = UART_OVERSAMPLING_16;
HAL_UART_Init(&huart3);
USART3->CR3 |= USART_CR3_DMAT;// | USART_CR3_DMAR | USART_CR3_OVRDIS;
USART3->CR3 |= USART_CR3_DMAT; // | USART_CR3_DMAR | USART_CR3_OVRDIS;
GPIO_InitTypeDef GPIO_InitStruct;
GPIO_InitStruct.Pin = GPIO_PIN_10;
@ -51,17 +67,14 @@ void UART_Init(){
HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);
DMA1_Channel2->CCR = 0;
DMA1_Channel2->CPAR = (uint32_t)&(USART3->DR);
DMA1_Channel2->CPAR = (uint32_t) & (USART3->DR);
DMA1_Channel2->CNDTR = 0;
DMA1_Channel2->CCR = DMA_CCR_MINC | DMA_CCR_DIR;
DMA1->IFCR = DMA_IFCR_CTCIF2 | DMA_IFCR_CHTIF2 | DMA_IFCR_CGIF2;
}
void MX_GPIO_Init(void)
{
void MX_GPIO_Init(void) {
GPIO_InitTypeDef GPIO_InitStruct;
/* GPIO Ports Clock Enable */
@ -169,7 +182,7 @@ void MX_GPIO_Init(void)
HAL_GPIO_Init(RIGHT_TIM_WL_PORT, &GPIO_InitStruct);
}
void MX_TIM_Init(void){
void MX_TIM_Init(void) {
__HAL_RCC_TIM1_CLK_ENABLE();
__HAL_RCC_TIM8_CLK_ENABLE();
@ -267,8 +280,7 @@ void MX_TIM_Init(void){
__HAL_TIM_ENABLE(&htim_right);
}
void MX_ADC1_Init(void)
{
void MX_ADC1_Init(void) {
ADC_MultiModeTypeDef multimode;
ADC_ChannelConfTypeDef sConfig;
@ -322,7 +334,7 @@ void MX_ADC1_Init(void)
DMA1_Channel1->CCR = 0;
DMA1_Channel1->CNDTR = 5;
DMA1_Channel1->CPAR = (uint32_t)&(ADC1->DR);
DMA1_Channel1->CPAR = (uint32_t) & (ADC1->DR);
DMA1_Channel1->CMAR = (uint32_t)&adc_buffer;
DMA1_Channel1->CCR = DMA_CCR_MSIZE_1 | DMA_CCR_PSIZE_1 | DMA_CCR_MINC | DMA_CCR_CIRC | DMA_CCR_TCIE;
DMA1_Channel1->CCR |= DMA_CCR_EN;
@ -332,8 +344,7 @@ void MX_ADC1_Init(void)
}
/* ADC2 init function */
void MX_ADC2_Init(void)
{
void MX_ADC2_Init(void) {
ADC_ChannelConfTypeDef sConfig;
__HAL_RCC_ADC2_CLK_ENABLE();

View File

@ -49,8 +49,7 @@
/**
* @brief This function handles Non maskable interrupt.
*/
void NMI_Handler(void)
{
void NMI_Handler(void) {
/* USER CODE BEGIN NonMaskableInt_IRQn 0 */
/* USER CODE END NonMaskableInt_IRQn 0 */
@ -62,13 +61,11 @@ void NMI_Handler(void)
/**
* @brief This function handles Hard fault interrupt.
*/
void HardFault_Handler(void)
{
void HardFault_Handler(void) {
/* USER CODE BEGIN HardFault_IRQn 0 */
/* USER CODE END HardFault_IRQn 0 */
while (1)
{
while(1) {
}
/* USER CODE BEGIN HardFault_IRQn 1 */
@ -78,13 +75,11 @@ void HardFault_Handler(void)
/**
* @brief This function handles Memory management fault.
*/
void MemManage_Handler(void)
{
void MemManage_Handler(void) {
/* USER CODE BEGIN MemoryManagement_IRQn 0 */
/* USER CODE END MemoryManagement_IRQn 0 */
while (1)
{
while(1) {
}
/* USER CODE BEGIN MemoryManagement_IRQn 1 */
@ -94,13 +89,11 @@ void MemManage_Handler(void)
/**
* @brief This function handles Prefetch fault, memory access fault.
*/
void BusFault_Handler(void)
{
void BusFault_Handler(void) {
/* USER CODE BEGIN BusFault_IRQn 0 */
/* USER CODE END BusFault_IRQn 0 */
while (1)
{
while(1) {
}
/* USER CODE BEGIN BusFault_IRQn 1 */
@ -110,13 +103,11 @@ void BusFault_Handler(void)
/**
* @brief This function handles Undefined instruction or illegal state.
*/
void UsageFault_Handler(void)
{
void UsageFault_Handler(void) {
/* USER CODE BEGIN UsageFault_IRQn 0 */
/* USER CODE END UsageFault_IRQn 0 */
while (1)
{
while(1) {
}
/* USER CODE BEGIN UsageFault_IRQn 1 */
@ -126,8 +117,7 @@ void UsageFault_Handler(void)
/**
* @brief This function handles System service call via SWI instruction.
*/
void SVC_Handler(void)
{
void SVC_Handler(void) {
/* USER CODE BEGIN SVCall_IRQn 0 */
/* USER CODE END SVCall_IRQn 0 */
@ -139,8 +129,7 @@ void SVC_Handler(void)
/**
* @brief This function handles Debug monitor.
*/
void DebugMon_Handler(void)
{
void DebugMon_Handler(void) {
/* USER CODE BEGIN DebugMonitor_IRQn 0 */
/* USER CODE END DebugMonitor_IRQn 0 */
@ -152,8 +141,7 @@ void DebugMon_Handler(void)
/**
* @brief This function handles Pendable request for system service.
*/
void PendSV_Handler(void)
{
void PendSV_Handler(void) {
/* USER CODE BEGIN PendSV_IRQn 0 */
/* USER CODE END PendSV_IRQn 0 */
@ -165,8 +153,7 @@ void PendSV_Handler(void)
/**
* @brief This function handles System tick timer.
*/
void SysTick_Handler(void)
{
void SysTick_Handler(void) {
/* USER CODE BEGIN SysTick_IRQn 0 */
/* USER CODE END SysTick_IRQn 0 */
@ -185,7 +172,6 @@ void SysTick_Handler(void)
/******************************************************************************/
/* USER CODE BEGIN 1 */
/* USER CODE END 1 */

View File

@ -92,13 +92,13 @@
* @{
*/
#if !defined (HSE_VALUE)
#define HSE_VALUE 8000000U /*!< Default value of the External oscillator in Hz.
#if !defined(HSE_VALUE)
#define HSE_VALUE 8000000U /*!< Default value of the External oscillator in Hz. \
This value can be provided and adapted by the user application. */
#endif /* HSE_VALUE */
#if !defined (HSI_VALUE)
#define HSI_VALUE 8000000U /*!< Default value of the Internal oscillator in Hz.
#if !defined(HSI_VALUE)
#define HSI_VALUE 8000000U /*!< Default value of the Internal oscillator in Hz. \
This value can be provided and adapted by the user application. */
#endif /* HSI_VALUE */
@ -110,7 +110,7 @@
/*!< Uncomment the following line if you need to relocate your vector Table in
Internal SRAM. */
/* #define VECT_TAB_SRAM */
#define VECT_TAB_OFFSET 0x00000000U /*!< Vector Table base offset field.
#define VECT_TAB_OFFSET 0x00000000U /*!< Vector Table base offset field. \
This value must be a multiple of 0x200. */
@ -133,10 +133,10 @@
/*******************************************************************************
* Clock Definitions
*******************************************************************************/
#if defined(STM32F100xB) ||defined(STM32F100xE)
uint32_t SystemCoreClock = 24000000U; /*!< System Clock Frequency (Core Clock) */
#if defined(STM32F100xB) || defined(STM32F100xE)
uint32_t SystemCoreClock = 24000000U; /*!< System Clock Frequency (Core Clock) */
#else /*!< HSI Selected as System Clock source */
uint32_t SystemCoreClock = 72000000U; /*!< System Clock Frequency (Core Clock) */
uint32_t SystemCoreClock = 72000000U; /*!< 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};
@ -152,7 +152,7 @@ const uint8_t APBPrescTable[8U] = {0, 0, 0, 0, 1, 2, 3, 4};
#if defined(STM32F100xE) || defined(STM32F101xE) || defined(STM32F101xG) || defined(STM32F103xE) || defined(STM32F103xG)
#ifdef DATA_IN_ExtSRAM
static void SystemInit_ExtMemCtl(void);
static void SystemInit_ExtMemCtl(void);
#endif /* DATA_IN_ExtSRAM */
#endif /* STM32F100xE || STM32F101xE || STM32F101xG || STM32F103xE || STM32F103xG */
@ -172,13 +172,12 @@ 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;
/* Reset SW, HPRE, PPRE1, PPRE2, ADCPRE and MCO bits */
/* Reset SW, HPRE, PPRE1, PPRE2, ADCPRE and MCO bits */
#if !defined(STM32F105xC) && !defined(STM32F107xC)
RCC->CFGR &= 0xF8FF0000U;
#else
@ -215,9 +214,9 @@ void SystemInit (void)
#endif /* STM32F105xC */
#if defined(STM32F100xE) || defined(STM32F101xE) || defined(STM32F101xG) || defined(STM32F103xE) || defined(STM32F103xG)
#ifdef DATA_IN_ExtSRAM
#ifdef DATA_IN_ExtSRAM
SystemInit_ExtMemCtl();
#endif /* DATA_IN_ExtSRAM */
#endif /* DATA_IN_ExtSRAM */
#endif
#ifdef VECT_TAB_SRAM
@ -262,8 +261,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)
@ -277,8 +275,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;
@ -292,62 +289,47 @@ 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
#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;
if (pllmull != 0x0DU)
{
if(pllmull != 0x0DU) {
pllmull += 2U;
}
else
{ /* PLL multiplication factor = PLL input clock * 6.5 */
} else { /* PLL multiplication factor = PLL input clock * 6.5 */
pllmull = 13U / 2U;
}
if (pllsource == 0x00U)
{
if(pllsource == 0x00U) {
/* HSI oscillator clock divided by 2 selected as PLL clock entry */
SystemCoreClock = (HSI_VALUE >> 1U) * pllmull;
}
else
{/* PREDIV1 selected as PLL clock entry */
} else { /* PREDIV1 selected as PLL clock entry */
/* Get PREDIV1 clock source and division factor */
prediv1source = RCC->CFGR2 & RCC_CFGR2_PREDIV1SRC;
prediv1factor = (RCC->CFGR2 & RCC_CFGR2_PREDIV1) + 1U;
if (prediv1source == 0U)
{
if(prediv1source == 0U) {
/* HSE oscillator clock selected as PREDIV1 clock entry */
SystemCoreClock = (HSE_VALUE / prediv1factor) * pllmull;
}
else
{/* PLL2 clock selected as PREDIV1 clock entry */
} else { /* PLL2 clock selected as PREDIV1 clock entry */
/* Get PREDIV2 division factor and PLL2 multiplication factor */
prediv2factor = ((RCC->CFGR2 & RCC_CFGR2_PREDIV2) >> 4U) + 1U;
@ -387,8 +369,7 @@ void SystemCoreClockUpdate (void)
* @param None
* @retval None
*/
void SystemInit_ExtMemCtl(void)
{
void SystemInit_ExtMemCtl(void) {
__IO uint32_t tmpreg;
/*!< FSMC Bank1 NOR/SRAM3 is used for the STM3210E-EVAL, if another Bank is
required, then adjust the Register Addresses */
@ -407,11 +388,11 @@ void SystemInit_ExtMemCtl(void)
(void)(tmpreg);
/* --------------- SRAM Data lines, NOE and NWE configuration ---------------*/
/*---------------- SRAM Address lines configuration -------------------------*/
/*---------------- NOE and NWE configuration --------------------------------*/
/*---------------- NE3 configuration ----------------------------------------*/
/*---------------- NBL0, NBL1 configuration ---------------------------------*/
/* --------------- SRAM Data lines, NOE and NWE configuration ---------------*/
/*---------------- SRAM Address lines configuration -------------------------*/
/*---------------- NOE and NWE configuration --------------------------------*/
/*---------------- NE3 configuration ----------------------------------------*/
/*---------------- NBL0, NBL1 configuration ---------------------------------*/
GPIOD->CRL = 0x44BB44BBU;
GPIOD->CRH = 0xBBBBBBBBU;
@ -425,8 +406,8 @@ void SystemInit_ExtMemCtl(void)
GPIOG->CRL = 0x44BBBBBBU;
GPIOG->CRH = 0x444B4B44U;
/*---------------- FSMC Configuration ---------------------------------------*/
/*---------------- Enable FSMC Bank1_SRAM Bank ------------------------------*/
/*---------------- FSMC Configuration ---------------------------------------*/
/*---------------- Enable FSMC Bank1_SRAM Bank ------------------------------*/
FSMC_Bank1->BTCR[4U] = 0x00001091U;
FSMC_Bank1->BTCR[5U] = 0x00110212U;