├── src ├── ego.c ├── knock.c ├── ignition.c ├── injection.c ├── ego.h ├── knock.h ├── pwm.c ├── cmsis_boot │ ├── stm32f4xx.h │ ├── system_stm32f4xx.h │ ├── stm32f4xx_conf.h │ ├── startup │ │ └── startup_stm32f4xx.c │ └── system_stm32f4xx.c ├── ignition.h ├── injection.h ├── idle.h ├── hardware.h ├── ecu.h ├── sensors.h ├── main.c ├── pwm.h ├── pid.h ├── mathext.h ├── idle.c ├── pid.c ├── actuators.h ├── actuators.c ├── mathext.c ├── config.h └── cmsis │ ├── core_cmFunc.h │ ├── core_cmInstr.h │ ├── core_cm4_simd.h │ └── core_cm4.h ├── .gitignore └── README.md /src/ego.c: -------------------------------------------------------------------------------- 1 | #include "ego.h" 2 | -------------------------------------------------------------------------------- /.gitignore: -------------------------------------------------------------------------------- 1 | /bin 2 | *.coproj 3 | -------------------------------------------------------------------------------- /src/knock.c: -------------------------------------------------------------------------------- 1 | #include "knock.h" 2 | -------------------------------------------------------------------------------- /src/ignition.c: -------------------------------------------------------------------------------- 1 | #include "ignition.h" 2 | -------------------------------------------------------------------------------- /src/injection.c: -------------------------------------------------------------------------------- 1 | #include "injection.h" 2 | -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- 1 | Open source ECU firmware based on STM32 MCU. 2 | -------------------------------------------------------------------------------- /src/ego.h: -------------------------------------------------------------------------------- 1 | #ifndef _EGO_H 2 | #define _EGO_H 3 | 4 | #include 5 | 6 | #endif 7 | -------------------------------------------------------------------------------- /src/knock.h: -------------------------------------------------------------------------------- 1 | #ifndef _KNOCK_H 2 | #define _KNOCK_H 3 | 4 | #include 5 | 6 | #endif 7 | -------------------------------------------------------------------------------- /src/pwm.c: -------------------------------------------------------------------------------- 1 | #include "pwm.h" 2 | 3 | void pwm_set_duty(uint8_t ch, uint16_t duty) 4 | { 5 | 6 | } 7 | -------------------------------------------------------------------------------- /src/cmsis_boot/stm32f4xx.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/openecu/stm32-firmware/HEAD/src/cmsis_boot/stm32f4xx.h -------------------------------------------------------------------------------- /src/ignition.h: -------------------------------------------------------------------------------- 1 | #ifndef _IGNITION_H 2 | #define _IGNITION_H 3 | 4 | #include 5 | 6 | #endif 7 | -------------------------------------------------------------------------------- /src/injection.h: -------------------------------------------------------------------------------- 1 | #ifndef _INJECTION_H 2 | #define _INJECTION_H 3 | 4 | #include 5 | 6 | #endif 7 | -------------------------------------------------------------------------------- /src/idle.h: -------------------------------------------------------------------------------- 1 | #ifndef _IDLE_H 2 | #define _IDLE_H 3 | 4 | #include 5 | 6 | void idle_init(void); 7 | 8 | #endif 9 | -------------------------------------------------------------------------------- /src/hardware.h: -------------------------------------------------------------------------------- 1 | #ifndef _HARDWARE_H 2 | #define _HARDWARE_H 3 | 4 | #include "pwm.h" 5 | 6 | #define PWM_IDLE PWM_CH0 7 | #define PWM_EVAP PWM_CH1 8 | #define PWM_EGO_HEATER PWM_CH2 9 | 10 | #endif 11 | -------------------------------------------------------------------------------- /src/ecu.h: -------------------------------------------------------------------------------- 1 | #ifndef _ECU_H 2 | #define _ECU_H 3 | 4 | #include "config.h" 5 | #include "sensors.h" 6 | 7 | typedef struct 8 | { 9 | config_t config; 10 | sensors_t sensors; 11 | } ecu_t; 12 | 13 | ecu_t ecu; 14 | 15 | #endif 16 | -------------------------------------------------------------------------------- /src/sensors.h: -------------------------------------------------------------------------------- 1 | #ifndef _SENSORS_H 2 | #define _SENSORS_H 3 | 4 | typedef struct 5 | { 6 | uint16_t rpm; 7 | uint16_t map; 8 | uint16_t maf; 9 | int8_t ect; 10 | int8_t iat; 11 | uint8_t ego; 12 | } sensors_t; 13 | 14 | #endif 15 | -------------------------------------------------------------------------------- /src/main.c: -------------------------------------------------------------------------------- 1 | #include 2 | #include "ecu.h" 3 | #include "actuators.h" 4 | 5 | extern ecu_t ecu; 6 | 7 | int main(void) 8 | { 9 | actuators_init(); 10 | 11 | for (;;) 12 | { 13 | cooling_fan(); 14 | water_pump(); 15 | aux(); 16 | } 17 | } 18 | -------------------------------------------------------------------------------- /src/pwm.h: -------------------------------------------------------------------------------- 1 | #ifndef _PWM_H 2 | #define _PWM_H 3 | 4 | #include 5 | 6 | #define PWM_CH0 0 7 | #define PWM_CH1 1 8 | #define PWM_CH2 2 9 | #define PWM_CH3 3 10 | #define PWM_CH4 4 11 | #define PWM_CH5 5 12 | #define PWM_CH6 6 13 | #define PWM_CH7 7 14 | 15 | void pwm_set_duty(uint8_t ch, uint16_t duty); 16 | 17 | #endif 18 | -------------------------------------------------------------------------------- /src/pid.h: -------------------------------------------------------------------------------- 1 | #ifndef _PID_H 2 | #define _PID_H 3 | 4 | #include 5 | #include "config.h" 6 | 7 | typedef struct 8 | { 9 | pid_config_t *config; 10 | int16_t target; 11 | int16_t error; 12 | int32_t integral; 13 | } pid_t; 14 | 15 | void pid_init(pid_t *pid, pid_config_t *config); 16 | 17 | void pid_set_target(pid_t *pid, int16_t target); 18 | 19 | int16_t pid_do(pid_t *pid, int16_t current); 20 | 21 | #endif 22 | -------------------------------------------------------------------------------- /src/mathext.h: -------------------------------------------------------------------------------- 1 | #ifndef _MATHEXT_H 2 | #define _MATHEXT_H 3 | 4 | #include 5 | 6 | int16_t linear_interp(int16_t x, int16_t y0, int16_t y1, int16_t x0, int16_t x1); 7 | 8 | int16_t bilinear_interp( 9 | int16_t x, int16_t y, 10 | int16_t z0, int16_t z1, int16_t z2, int16_t z3, 11 | int16_t x0, int16_t x1, 12 | int16_t y0, int16_t y1 13 | ); 14 | 15 | uint8_t table_index(int16_t *value, int16_t values[], uint8_t size); 16 | 17 | int16_t table1d_lookup(int16_t x, uint8_t nx, int16_t vx[], int16_t *data); 18 | 19 | int16_t table2d_lookup( 20 | int16_t x, int16_t y, 21 | uint8_t nx, uint8_t ny, 22 | int16_t vx[], int16_t vy[], 23 | int16_t **data 24 | ); 25 | 26 | #endif 27 | -------------------------------------------------------------------------------- /src/idle.c: -------------------------------------------------------------------------------- 1 | #include "idle.h" 2 | #include "ecu.h" 3 | #include "pid.h" 4 | #include "pwm.h" 5 | #include "hardware.h" 6 | #include "mathext.h" 7 | 8 | extern ecu_t ecu; 9 | pid_t idle_pid; 10 | 11 | void idle_init(void) 12 | { 13 | pid_init(&idle_pid, &ecu.config.idle_pid_config); 14 | } 15 | 16 | void idle_control(void) 17 | { 18 | uint16_t target_rpm; 19 | int16_t duty; 20 | 21 | target_rpm = table1d_lookup( 22 | ecu.sensors.ect, IDLE_TEMP_SCALE_SIZE, 23 | (int16_t*)ecu.config.idle_temp_scale, (int16_t*)ecu.config.idle_rpm 24 | ); 25 | pid_set_target(&idle_pid, target_rpm); 26 | duty = pid_do(&idle_pid, ecu.sensors.rpm); 27 | pwm_set_duty(PWM_IDLE, (512 + (duty >> 6))); 28 | } 29 | -------------------------------------------------------------------------------- /src/pid.c: -------------------------------------------------------------------------------- 1 | #include "pid.h" 2 | 3 | void pid_init(pid_t *pid, pid_config_t *config) 4 | { 5 | pid->config = config; 6 | pid->integral = 0; 7 | } 8 | 9 | void pid_set_target(pid_t *pid, int16_t target) 10 | { 11 | pid->target = target; 12 | } 13 | 14 | int16_t pid_do(pid_t *pid, int16_t current) 15 | { 16 | int16_t result, error, diff; 17 | int32_t integral; 18 | 19 | error = current - pid->target; 20 | diff = error - pid->error; 21 | integral = pid->integral + error; 22 | 23 | if (integral > pid->config->integral_max) 24 | { 25 | integral = pid->config->integral_max; 26 | } 27 | else if (integral < -pid->config->integral_max) 28 | { 29 | integral = -pid->config->integral_max; 30 | } 31 | 32 | pid->integral = integral; 33 | 34 | result = (error * pid->config->kp / 256) 35 | + (integral * pid->config->ki / 256) 36 | + (diff * pid->config->kd / 256); 37 | 38 | return result; 39 | } 40 | -------------------------------------------------------------------------------- /src/actuators.h: -------------------------------------------------------------------------------- 1 | #ifndef _ACTUATORS_H 2 | #define _ACTUATORS_H 3 | 4 | #include 5 | #include 6 | 7 | /* Actuators */ 8 | 9 | #define ECU_RELAY_PIN 0 10 | #define CE_LAMP_PIN 1 11 | #define FUEL_PUMP_PIN 2 12 | #define COOLING_FAN_PIN 3 13 | #define WATER_PUMP_PIN 4 14 | 15 | #define ACTUATORS_GPIO GPIOA 16 | #define ACTUATORS_PORT_MASK ((1 << ECU_RELAY_PIN) \ 17 | | (1 << CE_LAMP_PIN) \ 18 | | (1 << FUEL_PUMP_PIN) \ 19 | | (1 << COOLING_FAN_PIN) \ 20 | | (1 << WATER_PUMP_PIN)) 21 | 22 | #define ACTUATORS_OFF() ACTUATORS_GPIO->ODR &= ~ACTUATORS_PORT_MASK 23 | 24 | #define ACTUATOR_ON(name) ACTUATORS_GPIO->ODR |= (1 << name##_PIN) 25 | #define ACTUATOR_OFF(name) ACTUATORS_GPIO->ODR &= ~(1 << name##_PIN) 26 | 27 | void actuators_init(void); 28 | 29 | static inline void ecu_relay_on(void) 30 | { 31 | ACTUATOR_ON(ECU_RELAY); 32 | } 33 | 34 | static inline void ecu_relay_off(void) 35 | { 36 | ACTUATOR_OFF(ECU_RELAY); 37 | } 38 | 39 | static inline void fuel_pump_relay_on(void) 40 | { 41 | ACTUATOR_ON(FUEL_PUMP); 42 | } 43 | 44 | static inline void fuel_pump_relay_off(void) 45 | { 46 | ACTUATOR_OFF(FUEL_PUMP); 47 | } 48 | 49 | static inline void ce_lamp_on(void) 50 | { 51 | ACTUATOR_ON(CE_LAMP); 52 | } 53 | 54 | static inline void ce_lamp_off(void) 55 | { 56 | ACTUATOR_OFF(CE_LAMP); 57 | } 58 | 59 | void cooling_fan(void); 60 | 61 | void water_pump(void); 62 | 63 | /* Auxiliary outputs */ 64 | #define AUX_GPIO GPIOA 65 | #define AUX_PORT_OFFSET 8 66 | #define AUX_PORT_MASK (0xFF << AUX_PORT_OFFSET) 67 | 68 | #define AUX_OFF() AUX_GPIO->ODR &= ~(1 << AUX_PORT_OFFSET); 69 | 70 | #define AUX_CH_ON(num) AUX_GPIO->ODR |= (1 << (num + AUX_PORT_OFFSET)) 71 | #define AUX_CH_OFF(num) AUX_GPIO->ODR &= ~(1 << (num + AUX_PORT_OFFSET)) 72 | 73 | void aux(void); 74 | 75 | #endif 76 | -------------------------------------------------------------------------------- /src/actuators.c: -------------------------------------------------------------------------------- 1 | #include "actuators.h" 2 | #include "ecu.h" 3 | 4 | extern ecu_t ecu; 5 | 6 | void actuators_init(void) 7 | { 8 | ACTUATORS_OFF(); 9 | AUX_OFF(); 10 | } 11 | 12 | void cooling_fan(void) 13 | { 14 | if (ecu.sensors.ect >= ecu.config.cooling_fan_temp) 15 | { 16 | ACTUATOR_ON(COOLING_FAN); 17 | } 18 | else if (ecu.sensors.ect < (ecu.config.cooling_fan_temp - ecu.config.cooling_fan_temp_hyst)) 19 | { 20 | ACTUATOR_OFF(COOLING_FAN); 21 | } 22 | } 23 | 24 | void water_pump(void) 25 | { 26 | if (ecu.sensors.ect >= ecu.config.water_pump_temp) 27 | { 28 | ACTUATOR_ON(WATER_PUMP); 29 | } 30 | else if (ecu.sensors.ect < (ecu.config.water_pump_temp - ecu.config.water_pump_temp_hyst)) 31 | { 32 | ACTUATOR_OFF(WATER_PUMP); 33 | } 34 | } 35 | 36 | void aux(void) 37 | { 38 | uint8_t i; 39 | aux_config_t *aux; 40 | 41 | for (i = 0; i < AUX_COUNT; i++) 42 | { 43 | aux = &ecu.config.aux[i]; 44 | 45 | if (!(aux->flags & AUX_FLAG_EN)) 46 | { 47 | AUX_CH_OFF(i); 48 | } 49 | else 50 | { 51 | if ( 52 | (ecu.sensors.rpm >= aux->rpm_on) 53 | && (ecu.sensors.ect >= aux->ect_on) 54 | ) 55 | { 56 | if ((aux->flags & AUX_FLAG_INV)) 57 | { 58 | AUX_CH_OFF(i); 59 | } 60 | else 61 | { 62 | AUX_CH_ON(i); 63 | } 64 | } 65 | else if ( 66 | (ecu.sensors.rpm <= aux->rpm_off) 67 | && (ecu.sensors.ect <= aux->ect_off) 68 | ) 69 | { 70 | if ((aux->flags & AUX_FLAG_INV)) 71 | { 72 | AUX_CH_ON(i); 73 | } 74 | else 75 | { 76 | AUX_CH_OFF(i); 77 | } 78 | } 79 | } 80 | } 81 | } 82 | -------------------------------------------------------------------------------- /src/mathext.c: -------------------------------------------------------------------------------- 1 | #include "mathext.h" 2 | 3 | int16_t linear_interp(int16_t x, int16_t y0, int16_t y1, int16_t x0, int16_t x1) 4 | { 5 | return (y0 + (int32_t)((y1 - y0) * (x - x0)) / (x1 - x0)); 6 | } 7 | 8 | int16_t bilinear_interp( 9 | int16_t x, int16_t y, 10 | int16_t z0, int16_t z1, int16_t z2, int16_t z3, 11 | int16_t x0, int16_t x1, int16_t y0, int16_t y1 12 | ) 13 | { 14 | int16_t z12, z03; 15 | 16 | z12 = z1 + (int32_t)((z2 - z1) * (x - x0)) / (x1 - x0); 17 | z03 = z0 + (int32_t)((z3 - z0) * (x - x0)) / (x1 - x0); 18 | 19 | return (z03 + (uint32_t)((z12 - z03) * (y - y0)) / (y1 - y0)); 20 | } 21 | 22 | uint8_t table_index(int16_t *value, int16_t values[], uint8_t size) 23 | { 24 | uint8_t index, last_index; 25 | 26 | last_index = size - 1; 27 | 28 | if ((*value) <= values[0]) 29 | { 30 | (*value) = values[0]; 31 | 32 | return 0; 33 | } 34 | else if ((*value) >= values[last_index]) 35 | { 36 | (*value) = values[last_index]; 37 | 38 | return (last_index - 1); 39 | } 40 | 41 | for (index = 1; index < size; index++) 42 | { 43 | if ((*value) < values[index]) 44 | { 45 | break; 46 | } 47 | } 48 | 49 | return (index - 1); 50 | } 51 | 52 | int16_t table1d_lookup(int16_t x, uint8_t nx, int16_t vx[], int16_t *data) 53 | { 54 | uint8_t ix; 55 | int16_t _x; 56 | 57 | _x = x; 58 | ix = table_index(&_x, vx, nx); 59 | 60 | return linear_interp(_x, data[ix], data[ix + 1], vx[ix], vx[ix + 1]); 61 | } 62 | 63 | int16_t table2d_lookup( 64 | int16_t x, int16_t y, 65 | uint8_t nx, uint8_t ny, 66 | int16_t vx[], int16_t vy[], 67 | int16_t **data 68 | ) 69 | { 70 | uint8_t ix, iy; 71 | int16_t _x, _y; 72 | 73 | _x = x; 74 | _y = y; 75 | ix = table_index(&_x, vx, nx); 76 | iy = table_index(&_y, vy, ny); 77 | 78 | return bilinear_interp( 79 | _x, _y, 80 | data[iy][ix], data[iy + 1][ix], data[iy + 1][ix + 1], data[iy][ix + 1], 81 | vx[ix], vx[ix + 1], vy[iy], vy[iy + 1] 82 | ); 83 | } 84 | -------------------------------------------------------------------------------- /src/cmsis_boot/system_stm32f4xx.h: -------------------------------------------------------------------------------- 1 | /** 2 | ****************************************************************************** 3 | * @file system_stm32f4xx.h 4 | * @author MCD Application Team 5 | * @version V1.0.0 6 | * @date 30-September-2011 7 | * @brief CMSIS Cortex-M4 Device System Source File for STM32F4xx devices. 8 | ****************************************************************************** 9 | * @attention 10 | * 11 | * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS 12 | * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE 13 | * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY 14 | * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING 15 | * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE 16 | * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. 17 | * 18 | *

© COPYRIGHT 2011 STMicroelectronics

19 | ****************************************************************************** 20 | */ 21 | 22 | /** @addtogroup CMSIS 23 | * @{ 24 | */ 25 | 26 | /** @addtogroup stm32f4xx_system 27 | * @{ 28 | */ 29 | 30 | /** 31 | * @brief Define to prevent recursive inclusion 32 | */ 33 | #ifndef __SYSTEM_STM32F4XX_H 34 | #define __SYSTEM_STM32F4XX_H 35 | 36 | #ifdef __cplusplus 37 | extern "C" { 38 | #endif 39 | 40 | /** @addtogroup STM32F4xx_System_Includes 41 | * @{ 42 | */ 43 | 44 | /** 45 | * @} 46 | */ 47 | 48 | 49 | /** @addtogroup STM32F4xx_System_Exported_types 50 | * @{ 51 | */ 52 | 53 | extern uint32_t SystemCoreClock; /*!< System Clock Frequency (Core Clock) */ 54 | 55 | 56 | /** 57 | * @} 58 | */ 59 | 60 | /** @addtogroup STM32F4xx_System_Exported_Constants 61 | * @{ 62 | */ 63 | 64 | /** 65 | * @} 66 | */ 67 | 68 | /** @addtogroup STM32F4xx_System_Exported_Macros 69 | * @{ 70 | */ 71 | 72 | /** 73 | * @} 74 | */ 75 | 76 | /** @addtogroup STM32F4xx_System_Exported_Functions 77 | * @{ 78 | */ 79 | 80 | extern void SystemInit(void); 81 | extern void SystemCoreClockUpdate(void); 82 | /** 83 | * @} 84 | */ 85 | 86 | #ifdef __cplusplus 87 | } 88 | #endif 89 | 90 | #endif /*__SYSTEM_STM32F4XX_H */ 91 | 92 | /** 93 | * @} 94 | */ 95 | 96 | /** 97 | * @} 98 | */ 99 | /******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ 100 | -------------------------------------------------------------------------------- /src/cmsis_boot/stm32f4xx_conf.h: -------------------------------------------------------------------------------- 1 | /** 2 | ****************************************************************************** 3 | * @file Project/STM32F4xx_StdPeriph_Templates/stm32f4xx_conf.h 4 | * @author MCD Application Team 5 | * @version V1.0.0 6 | * @date 30-September-2011 7 | * @brief Library configuration file. 8 | ****************************************************************************** 9 | * @attention 10 | * 11 | * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS 12 | * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE 13 | * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY 14 | * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING 15 | * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE 16 | * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. 17 | * 18 | *

© COPYRIGHT 2011 STMicroelectronics

19 | ****************************************************************************** 20 | */ 21 | 22 | /* Define to prevent recursive inclusion -------------------------------------*/ 23 | #ifndef __STM32F4xx_CONF_H 24 | #define __STM32F4xx_CONF_H 25 | 26 | /* Includes ------------------------------------------------------------------*/ 27 | /* Uncomment the line below to enable peripheral header file inclusion */ 28 | /*#include "stm32f4xx_adc.h" 29 | #include "stm32f4xx_can.h" 30 | #include "stm32f4xx_crc.h" 31 | #include "stm32f4xx_cryp.h" 32 | #include "stm32f4xx_dac.h" 33 | #include "stm32f4xx_dbgmcu.h" 34 | #include "stm32f4xx_dcmi.h" 35 | #include "stm32f4xx_dma.h" 36 | #include "stm32f4xx_exti.h" 37 | #include "stm32f4xx_flash.h" 38 | #include "stm32f4xx_fsmc.h" 39 | #include "stm32f4xx_hash.h" 40 | #include "stm32f4xx_gpio.h" 41 | #include "stm32f4xx_i2c.h" 42 | #include "stm32f4xx_iwdg.h" 43 | #include "stm32f4xx_pwr.h" 44 | #include "stm32f4xx_rcc.h" 45 | #include "stm32f4xx_rng.h" 46 | #include "stm32f4xx_rtc.h" 47 | #include "stm32f4xx_sdio.h" 48 | #include "stm32f4xx_spi.h" 49 | #include "stm32f4xx_syscfg.h" 50 | #include "stm32f4xx_tim.h" 51 | #include "stm32f4xx_usart.h" 52 | #include "stm32f4xx_wwdg.h" 53 | #include "misc.h"*/ 54 | /* High level functions for NVIC and SysTick (add-on to CMSIS functions) */ 55 | 56 | /* Exported types ------------------------------------------------------------*/ 57 | /* Exported constants --------------------------------------------------------*/ 58 | 59 | /* If an external clock source is used, then the value of the following define 60 | should be set to the value of the external clock source, else, if no external 61 | clock is used, keep this define commented */ 62 | /*#define I2S_EXTERNAL_CLOCK_VAL 12288000 */ /* Value of the external clock in Hz */ 63 | 64 | 65 | /* Uncomment the line below to expanse the "assert_param" macro in the 66 | Standard Peripheral Library drivers code */ 67 | /* #define USE_FULL_ASSERT 1 */ 68 | 69 | /* Exported macro ------------------------------------------------------------*/ 70 | #ifdef USE_FULL_ASSERT 71 | 72 | /** 73 | * @brief The assert_param macro is used for function's parameters check. 74 | * @param expr: If expr is false, it calls assert_failed function 75 | * which reports the name of the source file and the source 76 | * line number of the call that failed. 77 | * If expr is true, it returns no value. 78 | * @retval None 79 | */ 80 | #define assert_param(expr) ((expr) ? (void)0 : assert_failed((uint8_t *)__FILE__, __LINE__)) 81 | /* Exported functions ------------------------------------------------------- */ 82 | void assert_failed(uint8_t* file, uint32_t line); 83 | #else 84 | #define assert_param(expr) ((void)0) 85 | #endif /* USE_FULL_ASSERT */ 86 | 87 | #endif /* __STM32F4xx_CONF_H */ 88 | 89 | /******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ 90 | -------------------------------------------------------------------------------- /src/config.h: -------------------------------------------------------------------------------- 1 | #ifndef _CONFIG_H 2 | #define _CONFIG_H 3 | 4 | /* Cranking */ 5 | #define CRANK_TEMP_SCALE_SIZE 8 6 | 7 | /* Afterstart and Warm-Up */ 8 | #define AFTERSTART_TEMP_SCALE_SIZE 8 9 | #define WARMUP_TEMP_SCALE_SIZE 8 10 | 11 | /* Idling */ 12 | #define IDLE_TEMP_SCALE_SIZE 8 13 | #define IDLE_RPM_SCALE_SIZE 8 14 | 15 | /* Auxiliary outputs */ 16 | #define AUX_COUNT 8 17 | #define AUX_FLAG_EN 0x01 18 | #define AUX_FLAG_INV 0x02 19 | 20 | /* Injectors */ 21 | #define INJ_COUNT 8 22 | #define INJ_VOLTAGE_SCALE_SIZE 8 23 | #define INJ_RPM_SCALE_SIZE 8 24 | 25 | /* Ignition channels */ 26 | #define IGN_COUNT 8 27 | #define IGN_VOLTAGE_SCALE_SIZE 8 28 | 29 | /* Tables */ 30 | #define TABLE_AFR_RPM_SCALE_SIZE 16 31 | #define TABLE_AFR_LOAD_SCALE_SIZE 16 32 | #define TABLE_IGN_RPM_SCALE_SIZE 16 33 | #define TABLE_IGN_LOAD_SCALE_SIZE 16 34 | #define TABLE_VE_RPM_SCALE_SIZE 16 35 | #define TABLE_VE_LOAD_SCALE_SIZE 16 36 | 37 | /* Sensors */ 38 | #define TPS_FLAG_INV 0x01 39 | 40 | typedef struct 41 | { 42 | // Proportional gain 43 | uint8_t kp; 44 | // Integral gain 45 | uint8_t ki; 46 | // Differential gain 47 | uint8_t kd; 48 | // Maximum integral sum 49 | uint32_t integral_max; 50 | } pid_config_t; 51 | 52 | typedef struct 53 | { 54 | // Flags 55 | // Bit 0 : AUX_FLAG_EN enable output 56 | // Bit 1 : AUX_FLAG_INV invert output 57 | uint8_t flags; 58 | // RPM on/off 59 | uint16_t rpm_on; 60 | uint16_t rpm_off; 61 | // Coolant temp on/off 62 | int8_t ect_on; 63 | int8_t ect_off; 64 | } aux_config_t; 65 | 66 | typedef struct 67 | { 68 | // Multiplier 69 | uint16_t multiplier; 70 | } inj_config_t; 71 | 72 | typedef struct 73 | { 74 | /* Cranking */ 75 | // Cranking threshold RPM 76 | uint16_t crank_thres_rpm; 77 | // Engine coolant temp scale 78 | int8_t crank_temp_scale[CRANK_TEMP_SCALE_SIZE]; 79 | // Injector pulse width vs coolant temp 80 | uint16_t crank_pw[CRANK_TEMP_SCALE_SIZE]; 81 | // Enrichment vs coolant temp 82 | //int16_t crank_enrich[CRANK_TEMP_SCALE_SIZE]; 83 | // Ignition timing advance vs coolant temp 84 | int8_t crank_ign_adv[CRANK_TEMP_SCALE_SIZE]; 85 | 86 | /* Afterstart and Warm-Up */ 87 | // Afterstart enrichment vs coolant temp 88 | int16_t afterstart_enrich[AFTERSTART_TEMP_SCALE_SIZE]; 89 | // Afterstart enrichment decay vs coolant temp 90 | uint16_t afterstart_enrich_decay[AFTERSTART_TEMP_SCALE_SIZE]; 91 | // Warm-Up enrichment vs coolant temp 92 | int16_t warmup_enrich[WARMUP_TEMP_SCALE_SIZE]; 93 | 94 | /* Idling */ 95 | // Coolant temp scale 96 | int8_t idle_temp_scale[IDLE_TEMP_SCALE_SIZE]; 97 | // RPM scale 98 | uint16_t idle_rpm_scale[IDLE_RPM_SCALE_SIZE]; 99 | // Target RPM vs coolant temp 100 | uint16_t idle_rpm[IDLE_TEMP_SCALE_SIZE]; 101 | // Ignition timing advance vs RPM 102 | int8_t idle_ign_adv[IDLE_RPM_SCALE_SIZE]; 103 | // Valve PID config 104 | pid_config_t idle_pid_config; 105 | 106 | /* Fuel pump */ 107 | // Fuel pump duration after ignition switch on 108 | uint16_t fuel_pump_on_time; 109 | // Fuel pump duration after ignition switch off 110 | uint16_t fuel_pump_off_time; 111 | 112 | /* Water cooling */ 113 | // Cooling fan switch temp 114 | int8_t cooling_fan_temp; 115 | // Cooling fan temp hysteresis 116 | uint8_t cooling_fan_temp_hyst; 117 | // Water pump fan start temp 118 | int8_t water_pump_temp; 119 | // Water pump temp hysteresis 120 | uint8_t water_pump_temp_hyst; 121 | 122 | /* Auxiliary outputs */ 123 | aux_config_t aux[AUX_COUNT]; 124 | 125 | /* Injectors */ 126 | // Battery voltage scale 127 | uint8_t inj_voltage_scale[INJ_VOLTAGE_SCALE_SIZE]; 128 | // Deadtime vs battery voltage 129 | uint16_t inj_deadtime[INJ_VOLTAGE_SCALE_SIZE]; 130 | // Injection start phase vs RPM 131 | uint16_t inj_start_phase[INJ_RPM_SCALE_SIZE]; 132 | // Individual injector config 133 | inj_config_t inj[INJ_COUNT]; 134 | 135 | /* Ignition */ 136 | uint8_t ign_min_adv; 137 | uint8_t ign_max_adv; 138 | uint8_t ign_adv_step; 139 | // Dwell time vs battery voltage 140 | uint16_t ign_dwell[IGN_VOLTAGE_SCALE_SIZE]; 141 | 142 | /* AFR table */ 143 | // RPM scale 144 | uint16_t table_afr_rpm_scale[TABLE_AFR_RPM_SCALE_SIZE]; 145 | // Load scale 146 | uint16_t table_afr_load_scale[TABLE_AFR_LOAD_SCALE_SIZE]; 147 | // Table 148 | int16_t table_afr[TABLE_AFR_RPM_SCALE_SIZE][TABLE_AFR_LOAD_SCALE_SIZE]; 149 | 150 | /* Ignition timing advance table */ 151 | // RPM scale 152 | uint16_t table_ign_rpm_scale[TABLE_ING_RPM_SCALE_SIZE]; 153 | // Load scale 154 | uint16_t table_ign_load_scale[TABLE_IGN_LOAD_SCALE_SIZE]; 155 | // Ignition timing advance 156 | int16_t table_ign[TABLE_IGN_RPM_SCALE_SIZE][TABLE_IGN_LOAD_SCALE_SIZE]; 157 | 158 | /* Volumetric efficiency table */ 159 | // RPM scale 160 | uint16_t table_ve_rpm_scale[TABLE_VE_RPM_SCALE_SIZE]; 161 | // Load scale 162 | uint16_t table_ve_load_scale[TABLE_VE_LOAD_SCALE_SIZE]; 163 | // Volumetric efficiency 164 | int16_t table_ve[TABLE_VE_RPM_SCALE_SIZE][TABLE_VE_LOAD_SCALE_SIZE]; 165 | 166 | /* Sensor */ 167 | // TP 168 | // 0 : TPS_FLAG_INV inverse voltage 169 | uint8_t tps_flags; 170 | uint16_t tps_min_voltage; 171 | uint16_t tps_max_voltage; 172 | // MAF 173 | // MAP 174 | int16_t maps_factor; 175 | int16_t maps_offset; 176 | uint16_t maps_min_voltage; 177 | uint16_t maps_max_voltage; 178 | // IAT 179 | // ECT 180 | 181 | } config_t; 182 | 183 | #endif 184 | -------------------------------------------------------------------------------- /src/cmsis/core_cmFunc.h: -------------------------------------------------------------------------------- 1 | /**************************************************************************//** 2 | * @file core_cmFunc.h 3 | * @brief CMSIS Cortex-M Core Function Access Header File 4 | * @version V2.10 5 | * @date 26. July 2011 6 | * 7 | * @note 8 | * Copyright (C) 2009-2011 ARM Limited. All rights reserved. 9 | * 10 | * @par 11 | * ARM Limited (ARM) is supplying this software for use with Cortex-M 12 | * processor based microcontrollers. This file can be freely distributed 13 | * within development tools that are supporting such ARM based processors. 14 | * 15 | * @par 16 | * THIS SOFTWARE IS PROVIDED "AS IS". NO WARRANTIES, WHETHER EXPRESS, IMPLIED 17 | * OR STATUTORY, INCLUDING, BUT NOT LIMITED TO, IMPLIED WARRANTIES OF 18 | * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE APPLY TO THIS SOFTWARE. 19 | * ARM SHALL NOT, IN ANY CIRCUMSTANCES, BE LIABLE FOR SPECIAL, INCIDENTAL, OR 20 | * CONSEQUENTIAL DAMAGES, FOR ANY REASON WHATSOEVER. 21 | * 22 | ******************************************************************************/ 23 | 24 | #ifndef __CORE_CMFUNC_H 25 | #define __CORE_CMFUNC_H 26 | 27 | 28 | /* ########################### Core Function Access ########################### */ 29 | /** \ingroup CMSIS_Core_FunctionInterface 30 | \defgroup CMSIS_Core_RegAccFunctions CMSIS Core Register Access Functions 31 | @{ 32 | */ 33 | 34 | #if defined ( __CC_ARM ) /*------------------RealView Compiler -----------------*/ 35 | /* ARM armcc specific functions */ 36 | 37 | #if (__ARMCC_VERSION < 400677) 38 | #error "Please use ARM Compiler Toolchain V4.0.677 or later!" 39 | #endif 40 | 41 | /* intrinsic void __enable_irq(); */ 42 | /* intrinsic void __disable_irq(); */ 43 | 44 | /** \brief Get Control Register 45 | 46 | This function returns the content of the Control Register. 47 | 48 | \return Control Register value 49 | */ 50 | static __INLINE uint32_t __get_CONTROL(void) 51 | { 52 | register uint32_t __regControl __ASM("control"); 53 | return(__regControl); 54 | } 55 | 56 | 57 | /** \brief Set Control Register 58 | 59 | This function writes the given value to the Control Register. 60 | 61 | \param [in] control Control Register value to set 62 | */ 63 | static __INLINE void __set_CONTROL(uint32_t control) 64 | { 65 | register uint32_t __regControl __ASM("control"); 66 | __regControl = control; 67 | } 68 | 69 | 70 | /** \brief Get ISPR Register 71 | 72 | This function returns the content of the ISPR Register. 73 | 74 | \return ISPR Register value 75 | */ 76 | static __INLINE uint32_t __get_IPSR(void) 77 | { 78 | register uint32_t __regIPSR __ASM("ipsr"); 79 | return(__regIPSR); 80 | } 81 | 82 | 83 | /** \brief Get APSR Register 84 | 85 | This function returns the content of the APSR Register. 86 | 87 | \return APSR Register value 88 | */ 89 | static __INLINE uint32_t __get_APSR(void) 90 | { 91 | register uint32_t __regAPSR __ASM("apsr"); 92 | return(__regAPSR); 93 | } 94 | 95 | 96 | /** \brief Get xPSR Register 97 | 98 | This function returns the content of the xPSR Register. 99 | 100 | \return xPSR Register value 101 | */ 102 | static __INLINE uint32_t __get_xPSR(void) 103 | { 104 | register uint32_t __regXPSR __ASM("xpsr"); 105 | return(__regXPSR); 106 | } 107 | 108 | 109 | /** \brief Get Process Stack Pointer 110 | 111 | This function returns the current value of the Process Stack Pointer (PSP). 112 | 113 | \return PSP Register value 114 | */ 115 | static __INLINE uint32_t __get_PSP(void) 116 | { 117 | register uint32_t __regProcessStackPointer __ASM("psp"); 118 | return(__regProcessStackPointer); 119 | } 120 | 121 | 122 | /** \brief Set Process Stack Pointer 123 | 124 | This function assigns the given value to the Process Stack Pointer (PSP). 125 | 126 | \param [in] topOfProcStack Process Stack Pointer value to set 127 | */ 128 | static __INLINE void __set_PSP(uint32_t topOfProcStack) 129 | { 130 | register uint32_t __regProcessStackPointer __ASM("psp"); 131 | __regProcessStackPointer = topOfProcStack; 132 | } 133 | 134 | 135 | /** \brief Get Main Stack Pointer 136 | 137 | This function returns the current value of the Main Stack Pointer (MSP). 138 | 139 | \return MSP Register value 140 | */ 141 | static __INLINE uint32_t __get_MSP(void) 142 | { 143 | register uint32_t __regMainStackPointer __ASM("msp"); 144 | return(__regMainStackPointer); 145 | } 146 | 147 | 148 | /** \brief Set Main Stack Pointer 149 | 150 | This function assigns the given value to the Main Stack Pointer (MSP). 151 | 152 | \param [in] topOfMainStack Main Stack Pointer value to set 153 | */ 154 | static __INLINE void __set_MSP(uint32_t topOfMainStack) 155 | { 156 | register uint32_t __regMainStackPointer __ASM("msp"); 157 | __regMainStackPointer = topOfMainStack; 158 | } 159 | 160 | 161 | /** \brief Get Priority Mask 162 | 163 | This function returns the current state of the priority mask bit from the Priority Mask Register. 164 | 165 | \return Priority Mask value 166 | */ 167 | static __INLINE uint32_t __get_PRIMASK(void) 168 | { 169 | register uint32_t __regPriMask __ASM("primask"); 170 | return(__regPriMask); 171 | } 172 | 173 | 174 | /** \brief Set Priority Mask 175 | 176 | This function assigns the given value to the Priority Mask Register. 177 | 178 | \param [in] priMask Priority Mask 179 | */ 180 | static __INLINE void __set_PRIMASK(uint32_t priMask) 181 | { 182 | register uint32_t __regPriMask __ASM("primask"); 183 | __regPriMask = (priMask); 184 | } 185 | 186 | 187 | #if (__CORTEX_M >= 0x03) 188 | 189 | /** \brief Enable FIQ 190 | 191 | This function enables FIQ interrupts by clearing the F-bit in the CPSR. 192 | Can only be executed in Privileged modes. 193 | */ 194 | #define __enable_fault_irq __enable_fiq 195 | 196 | 197 | /** \brief Disable FIQ 198 | 199 | This function disables FIQ interrupts by setting the F-bit in the CPSR. 200 | Can only be executed in Privileged modes. 201 | */ 202 | #define __disable_fault_irq __disable_fiq 203 | 204 | 205 | /** \brief Get Base Priority 206 | 207 | This function returns the current value of the Base Priority register. 208 | 209 | \return Base Priority register value 210 | */ 211 | static __INLINE uint32_t __get_BASEPRI(void) 212 | { 213 | register uint32_t __regBasePri __ASM("basepri"); 214 | return(__regBasePri); 215 | } 216 | 217 | 218 | /** \brief Set Base Priority 219 | 220 | This function assigns the given value to the Base Priority register. 221 | 222 | \param [in] basePri Base Priority value to set 223 | */ 224 | static __INLINE void __set_BASEPRI(uint32_t basePri) 225 | { 226 | register uint32_t __regBasePri __ASM("basepri"); 227 | __regBasePri = (basePri & 0xff); 228 | } 229 | 230 | 231 | /** \brief Get Fault Mask 232 | 233 | This function returns the current value of the Fault Mask register. 234 | 235 | \return Fault Mask register value 236 | */ 237 | static __INLINE uint32_t __get_FAULTMASK(void) 238 | { 239 | register uint32_t __regFaultMask __ASM("faultmask"); 240 | return(__regFaultMask); 241 | } 242 | 243 | 244 | /** \brief Set Fault Mask 245 | 246 | This function assigns the given value to the Fault Mask register. 247 | 248 | \param [in] faultMask Fault Mask value to set 249 | */ 250 | static __INLINE void __set_FAULTMASK(uint32_t faultMask) 251 | { 252 | register uint32_t __regFaultMask __ASM("faultmask"); 253 | __regFaultMask = (faultMask & (uint32_t)1); 254 | } 255 | 256 | #endif /* (__CORTEX_M >= 0x03) */ 257 | 258 | 259 | #if (__CORTEX_M == 0x04) 260 | 261 | /** \brief Get FPSCR 262 | 263 | This function returns the current value of the Floating Point Status/Control register. 264 | 265 | \return Floating Point Status/Control register value 266 | */ 267 | static __INLINE uint32_t __get_FPSCR(void) 268 | { 269 | #if (__FPU_PRESENT == 1) && (__FPU_USED == 1) 270 | register uint32_t __regfpscr __ASM("fpscr"); 271 | return(__regfpscr); 272 | #else 273 | return(0); 274 | #endif 275 | } 276 | 277 | 278 | /** \brief Set FPSCR 279 | 280 | This function assigns the given value to the Floating Point Status/Control register. 281 | 282 | \param [in] fpscr Floating Point Status/Control value to set 283 | */ 284 | static __INLINE void __set_FPSCR(uint32_t fpscr) 285 | { 286 | #if (__FPU_PRESENT == 1) && (__FPU_USED == 1) 287 | register uint32_t __regfpscr __ASM("fpscr"); 288 | __regfpscr = (fpscr); 289 | #endif 290 | } 291 | 292 | #endif /* (__CORTEX_M == 0x04) */ 293 | 294 | 295 | #elif defined ( __ICCARM__ ) /*------------------ ICC Compiler -------------------*/ 296 | /* IAR iccarm specific functions */ 297 | 298 | #include 299 | 300 | #elif defined ( __GNUC__ ) /*------------------ GNU Compiler ---------------------*/ 301 | /* GNU gcc specific functions */ 302 | 303 | /** \brief Enable IRQ Interrupts 304 | 305 | This function enables IRQ interrupts by clearing the I-bit in the CPSR. 306 | Can only be executed in Privileged modes. 307 | */ 308 | __attribute__( ( always_inline ) ) static __INLINE void __enable_irq(void) 309 | { 310 | __ASM volatile ("cpsie i"); 311 | } 312 | 313 | 314 | /** \brief Disable IRQ Interrupts 315 | 316 | This function disables IRQ interrupts by setting the I-bit in the CPSR. 317 | Can only be executed in Privileged modes. 318 | */ 319 | __attribute__( ( always_inline ) ) static __INLINE void __disable_irq(void) 320 | { 321 | __ASM volatile ("cpsid i"); 322 | } 323 | 324 | 325 | /** \brief Get Control Register 326 | 327 | This function returns the content of the Control Register. 328 | 329 | \return Control Register value 330 | */ 331 | __attribute__( ( always_inline ) ) static __INLINE uint32_t __get_CONTROL(void) 332 | { 333 | uint32_t result; 334 | 335 | __ASM volatile ("MRS %0, control" : "=r" (result) ); 336 | return(result); 337 | } 338 | 339 | 340 | /** \brief Set Control Register 341 | 342 | This function writes the given value to the Control Register. 343 | 344 | \param [in] control Control Register value to set 345 | */ 346 | __attribute__( ( always_inline ) ) static __INLINE void __set_CONTROL(uint32_t control) 347 | { 348 | __ASM volatile ("MSR control, %0" : : "r" (control) ); 349 | } 350 | 351 | 352 | /** \brief Get ISPR Register 353 | 354 | This function returns the content of the ISPR Register. 355 | 356 | \return ISPR Register value 357 | */ 358 | __attribute__( ( always_inline ) ) static __INLINE uint32_t __get_IPSR(void) 359 | { 360 | uint32_t result; 361 | 362 | __ASM volatile ("MRS %0, ipsr" : "=r" (result) ); 363 | return(result); 364 | } 365 | 366 | 367 | /** \brief Get APSR Register 368 | 369 | This function returns the content of the APSR Register. 370 | 371 | \return APSR Register value 372 | */ 373 | __attribute__( ( always_inline ) ) static __INLINE uint32_t __get_APSR(void) 374 | { 375 | uint32_t result; 376 | 377 | __ASM volatile ("MRS %0, apsr" : "=r" (result) ); 378 | return(result); 379 | } 380 | 381 | 382 | /** \brief Get xPSR Register 383 | 384 | This function returns the content of the xPSR Register. 385 | 386 | \return xPSR Register value 387 | */ 388 | __attribute__( ( always_inline ) ) static __INLINE uint32_t __get_xPSR(void) 389 | { 390 | uint32_t result; 391 | 392 | __ASM volatile ("MRS %0, xpsr" : "=r" (result) ); 393 | return(result); 394 | } 395 | 396 | 397 | /** \brief Get Process Stack Pointer 398 | 399 | This function returns the current value of the Process Stack Pointer (PSP). 400 | 401 | \return PSP Register value 402 | */ 403 | __attribute__( ( always_inline ) ) static __INLINE uint32_t __get_PSP(void) 404 | { 405 | register uint32_t result; 406 | 407 | __ASM volatile ("MRS %0, psp\n" : "=r" (result) ); 408 | return(result); 409 | } 410 | 411 | 412 | /** \brief Set Process Stack Pointer 413 | 414 | This function assigns the given value to the Process Stack Pointer (PSP). 415 | 416 | \param [in] topOfProcStack Process Stack Pointer value to set 417 | */ 418 | __attribute__( ( always_inline ) ) static __INLINE void __set_PSP(uint32_t topOfProcStack) 419 | { 420 | __ASM volatile ("MSR psp, %0\n" : : "r" (topOfProcStack) ); 421 | } 422 | 423 | 424 | /** \brief Get Main Stack Pointer 425 | 426 | This function returns the current value of the Main Stack Pointer (MSP). 427 | 428 | \return MSP Register value 429 | */ 430 | __attribute__( ( always_inline ) ) static __INLINE uint32_t __get_MSP(void) 431 | { 432 | register uint32_t result; 433 | 434 | __ASM volatile ("MRS %0, msp\n" : "=r" (result) ); 435 | return(result); 436 | } 437 | 438 | 439 | /** \brief Set Main Stack Pointer 440 | 441 | This function assigns the given value to the Main Stack Pointer (MSP). 442 | 443 | \param [in] topOfMainStack Main Stack Pointer value to set 444 | */ 445 | __attribute__( ( always_inline ) ) static __INLINE void __set_MSP(uint32_t topOfMainStack) 446 | { 447 | __ASM volatile ("MSR msp, %0\n" : : "r" (topOfMainStack) ); 448 | } 449 | 450 | 451 | /** \brief Get Priority Mask 452 | 453 | This function returns the current state of the priority mask bit from the Priority Mask Register. 454 | 455 | \return Priority Mask value 456 | */ 457 | __attribute__( ( always_inline ) ) static __INLINE uint32_t __get_PRIMASK(void) 458 | { 459 | uint32_t result; 460 | 461 | __ASM volatile ("MRS %0, primask" : "=r" (result) ); 462 | return(result); 463 | } 464 | 465 | 466 | /** \brief Set Priority Mask 467 | 468 | This function assigns the given value to the Priority Mask Register. 469 | 470 | \param [in] priMask Priority Mask 471 | */ 472 | __attribute__( ( always_inline ) ) static __INLINE void __set_PRIMASK(uint32_t priMask) 473 | { 474 | __ASM volatile ("MSR primask, %0" : : "r" (priMask) ); 475 | } 476 | 477 | 478 | #if (__CORTEX_M >= 0x03) 479 | 480 | /** \brief Enable FIQ 481 | 482 | This function enables FIQ interrupts by clearing the F-bit in the CPSR. 483 | Can only be executed in Privileged modes. 484 | */ 485 | __attribute__( ( always_inline ) ) static __INLINE void __enable_fault_irq(void) 486 | { 487 | __ASM volatile ("cpsie f"); 488 | } 489 | 490 | 491 | /** \brief Disable FIQ 492 | 493 | This function disables FIQ interrupts by setting the F-bit in the CPSR. 494 | Can only be executed in Privileged modes. 495 | */ 496 | __attribute__( ( always_inline ) ) static __INLINE void __disable_fault_irq(void) 497 | { 498 | __ASM volatile ("cpsid f"); 499 | } 500 | 501 | 502 | /** \brief Get Base Priority 503 | 504 | This function returns the current value of the Base Priority register. 505 | 506 | \return Base Priority register value 507 | */ 508 | __attribute__( ( always_inline ) ) static __INLINE uint32_t __get_BASEPRI(void) 509 | { 510 | uint32_t result; 511 | 512 | __ASM volatile ("MRS %0, basepri_max" : "=r" (result) ); 513 | return(result); 514 | } 515 | 516 | 517 | /** \brief Set Base Priority 518 | 519 | This function assigns the given value to the Base Priority register. 520 | 521 | \param [in] basePri Base Priority value to set 522 | */ 523 | __attribute__( ( always_inline ) ) static __INLINE void __set_BASEPRI(uint32_t value) 524 | { 525 | __ASM volatile ("MSR basepri, %0" : : "r" (value) ); 526 | } 527 | 528 | 529 | /** \brief Get Fault Mask 530 | 531 | This function returns the current value of the Fault Mask register. 532 | 533 | \return Fault Mask register value 534 | */ 535 | __attribute__( ( always_inline ) ) static __INLINE uint32_t __get_FAULTMASK(void) 536 | { 537 | uint32_t result; 538 | 539 | __ASM volatile ("MRS %0, faultmask" : "=r" (result) ); 540 | return(result); 541 | } 542 | 543 | 544 | /** \brief Set Fault Mask 545 | 546 | This function assigns the given value to the Fault Mask register. 547 | 548 | \param [in] faultMask Fault Mask value to set 549 | */ 550 | __attribute__( ( always_inline ) ) static __INLINE void __set_FAULTMASK(uint32_t faultMask) 551 | { 552 | __ASM volatile ("MSR faultmask, %0" : : "r" (faultMask) ); 553 | } 554 | 555 | #endif /* (__CORTEX_M >= 0x03) */ 556 | 557 | 558 | #if (__CORTEX_M == 0x04) 559 | 560 | /** \brief Get FPSCR 561 | 562 | This function returns the current value of the Floating Point Status/Control register. 563 | 564 | \return Floating Point Status/Control register value 565 | */ 566 | __attribute__( ( always_inline ) ) static __INLINE uint32_t __get_FPSCR(void) 567 | { 568 | #if (__FPU_PRESENT == 1) && (__FPU_USED == 1) 569 | uint32_t result; 570 | 571 | __ASM volatile ("VMRS %0, fpscr" : "=r" (result) ); 572 | return(result); 573 | #else 574 | return(0); 575 | #endif 576 | } 577 | 578 | 579 | /** \brief Set FPSCR 580 | 581 | This function assigns the given value to the Floating Point Status/Control register. 582 | 583 | \param [in] fpscr Floating Point Status/Control value to set 584 | */ 585 | __attribute__( ( always_inline ) ) static __INLINE void __set_FPSCR(uint32_t fpscr) 586 | { 587 | #if (__FPU_PRESENT == 1) && (__FPU_USED == 1) 588 | __ASM volatile ("VMSR fpscr, %0" : : "r" (fpscr) ); 589 | #endif 590 | } 591 | 592 | #endif /* (__CORTEX_M == 0x04) */ 593 | 594 | 595 | #elif defined ( __TASKING__ ) /*------------------ TASKING Compiler --------------*/ 596 | /* TASKING carm specific functions */ 597 | 598 | /* 599 | * The CMSIS functions have been implemented as intrinsics in the compiler. 600 | * Please use "carm -?i" to get an up to date list of all instrinsics, 601 | * Including the CMSIS ones. 602 | */ 603 | 604 | #endif 605 | 606 | /*@} end of CMSIS_Core_RegAccFunctions */ 607 | 608 | 609 | #endif /* __CORE_CMFUNC_H */ 610 | -------------------------------------------------------------------------------- /src/cmsis/core_cmInstr.h: -------------------------------------------------------------------------------- 1 | /**************************************************************************//** 2 | * @file core_cmInstr.h 3 | * @brief CMSIS Cortex-M Core Instruction Access Header File 4 | * @version V2.10 5 | * @date 19. July 2011 6 | * 7 | * @note 8 | * Copyright (C) 2009-2011 ARM Limited. All rights reserved. 9 | * 10 | * @par 11 | * ARM Limited (ARM) is supplying this software for use with Cortex-M 12 | * processor based microcontrollers. This file can be freely distributed 13 | * within development tools that are supporting such ARM based processors. 14 | * 15 | * @par 16 | * THIS SOFTWARE IS PROVIDED "AS IS". NO WARRANTIES, WHETHER EXPRESS, IMPLIED 17 | * OR STATUTORY, INCLUDING, BUT NOT LIMITED TO, IMPLIED WARRANTIES OF 18 | * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE APPLY TO THIS SOFTWARE. 19 | * ARM SHALL NOT, IN ANY CIRCUMSTANCES, BE LIABLE FOR SPECIAL, INCIDENTAL, OR 20 | * CONSEQUENTIAL DAMAGES, FOR ANY REASON WHATSOEVER. 21 | * 22 | ******************************************************************************/ 23 | 24 | #ifndef __CORE_CMINSTR_H 25 | #define __CORE_CMINSTR_H 26 | 27 | 28 | /* ########################## Core Instruction Access ######################### */ 29 | /** \defgroup CMSIS_Core_InstructionInterface CMSIS Core Instruction Interface 30 | Access to dedicated instructions 31 | @{ 32 | */ 33 | 34 | #if defined ( __CC_ARM ) /*------------------RealView Compiler -----------------*/ 35 | /* ARM armcc specific functions */ 36 | 37 | #if (__ARMCC_VERSION < 400677) 38 | #error "Please use ARM Compiler Toolchain V4.0.677 or later!" 39 | #endif 40 | 41 | 42 | /** \brief No Operation 43 | 44 | No Operation does nothing. This instruction can be used for code alignment purposes. 45 | */ 46 | #define __NOP __nop 47 | 48 | 49 | /** \brief Wait For Interrupt 50 | 51 | Wait For Interrupt is a hint instruction that suspends execution 52 | until one of a number of events occurs. 53 | */ 54 | #define __WFI __wfi 55 | 56 | 57 | /** \brief Wait For Event 58 | 59 | Wait For Event is a hint instruction that permits the processor to enter 60 | a low-power state until one of a number of events occurs. 61 | */ 62 | #define __WFE __wfe 63 | 64 | 65 | /** \brief Send Event 66 | 67 | Send Event is a hint instruction. It causes an event to be signaled to the CPU. 68 | */ 69 | #define __SEV __sev 70 | 71 | 72 | /** \brief Instruction Synchronization Barrier 73 | 74 | Instruction Synchronization Barrier flushes the pipeline in the processor, 75 | so that all instructions following the ISB are fetched from cache or 76 | memory, after the instruction has been completed. 77 | */ 78 | #define __ISB() __isb(0xF) 79 | 80 | 81 | /** \brief Data Synchronization Barrier 82 | 83 | This function acts as a special kind of Data Memory Barrier. 84 | It completes when all explicit memory accesses before this instruction complete. 85 | */ 86 | #define __DSB() __dsb(0xF) 87 | 88 | 89 | /** \brief Data Memory Barrier 90 | 91 | This function ensures the apparent order of the explicit memory operations before 92 | and after the instruction, without ensuring their completion. 93 | */ 94 | #define __DMB() __dmb(0xF) 95 | 96 | 97 | /** \brief Reverse byte order (32 bit) 98 | 99 | This function reverses the byte order in integer value. 100 | 101 | \param [in] value Value to reverse 102 | \return Reversed value 103 | */ 104 | #define __REV __rev 105 | 106 | 107 | /** \brief Reverse byte order (16 bit) 108 | 109 | This function reverses the byte order in two unsigned short values. 110 | 111 | \param [in] value Value to reverse 112 | \return Reversed value 113 | */ 114 | static __INLINE __ASM uint32_t __REV16(uint32_t value) 115 | { 116 | rev16 r0, r0 117 | bx lr 118 | } 119 | 120 | 121 | /** \brief Reverse byte order in signed short value 122 | 123 | This function reverses the byte order in a signed short value with sign extension to integer. 124 | 125 | \param [in] value Value to reverse 126 | \return Reversed value 127 | */ 128 | static __INLINE __ASM int32_t __REVSH(int32_t value) 129 | { 130 | revsh r0, r0 131 | bx lr 132 | } 133 | 134 | 135 | #if (__CORTEX_M >= 0x03) 136 | 137 | /** \brief Reverse bit order of value 138 | 139 | This function reverses the bit order of the given value. 140 | 141 | \param [in] value Value to reverse 142 | \return Reversed value 143 | */ 144 | #define __RBIT __rbit 145 | 146 | 147 | /** \brief LDR Exclusive (8 bit) 148 | 149 | This function performs a exclusive LDR command for 8 bit value. 150 | 151 | \param [in] ptr Pointer to data 152 | \return value of type uint8_t at (*ptr) 153 | */ 154 | #define __LDREXB(ptr) ((uint8_t ) __ldrex(ptr)) 155 | 156 | 157 | /** \brief LDR Exclusive (16 bit) 158 | 159 | This function performs a exclusive LDR command for 16 bit values. 160 | 161 | \param [in] ptr Pointer to data 162 | \return value of type uint16_t at (*ptr) 163 | */ 164 | #define __LDREXH(ptr) ((uint16_t) __ldrex(ptr)) 165 | 166 | 167 | /** \brief LDR Exclusive (32 bit) 168 | 169 | This function performs a exclusive LDR command for 32 bit values. 170 | 171 | \param [in] ptr Pointer to data 172 | \return value of type uint32_t at (*ptr) 173 | */ 174 | #define __LDREXW(ptr) ((uint32_t ) __ldrex(ptr)) 175 | 176 | 177 | /** \brief STR Exclusive (8 bit) 178 | 179 | This function performs a exclusive STR command for 8 bit values. 180 | 181 | \param [in] value Value to store 182 | \param [in] ptr Pointer to location 183 | \return 0 Function succeeded 184 | \return 1 Function failed 185 | */ 186 | #define __STREXB(value, ptr) __strex(value, ptr) 187 | 188 | 189 | /** \brief STR Exclusive (16 bit) 190 | 191 | This function performs a exclusive STR command for 16 bit values. 192 | 193 | \param [in] value Value to store 194 | \param [in] ptr Pointer to location 195 | \return 0 Function succeeded 196 | \return 1 Function failed 197 | */ 198 | #define __STREXH(value, ptr) __strex(value, ptr) 199 | 200 | 201 | /** \brief STR Exclusive (32 bit) 202 | 203 | This function performs a exclusive STR command for 32 bit values. 204 | 205 | \param [in] value Value to store 206 | \param [in] ptr Pointer to location 207 | \return 0 Function succeeded 208 | \return 1 Function failed 209 | */ 210 | #define __STREXW(value, ptr) __strex(value, ptr) 211 | 212 | 213 | /** \brief Remove the exclusive lock 214 | 215 | This function removes the exclusive lock which is created by LDREX. 216 | 217 | */ 218 | #define __CLREX __clrex 219 | 220 | 221 | /** \brief Signed Saturate 222 | 223 | This function saturates a signed value. 224 | 225 | \param [in] value Value to be saturated 226 | \param [in] sat Bit position to saturate to (1..32) 227 | \return Saturated value 228 | */ 229 | #define __SSAT __ssat 230 | 231 | 232 | /** \brief Unsigned Saturate 233 | 234 | This function saturates an unsigned value. 235 | 236 | \param [in] value Value to be saturated 237 | \param [in] sat Bit position to saturate to (0..31) 238 | \return Saturated value 239 | */ 240 | #define __USAT __usat 241 | 242 | 243 | /** \brief Count leading zeros 244 | 245 | This function counts the number of leading zeros of a data value. 246 | 247 | \param [in] value Value to count the leading zeros 248 | \return number of leading zeros in value 249 | */ 250 | #define __CLZ __clz 251 | 252 | #endif /* (__CORTEX_M >= 0x03) */ 253 | 254 | 255 | 256 | #elif defined ( __ICCARM__ ) /*------------------ ICC Compiler -------------------*/ 257 | /* IAR iccarm specific functions */ 258 | 259 | #include 260 | 261 | 262 | #elif defined ( __GNUC__ ) /*------------------ GNU Compiler ---------------------*/ 263 | /* GNU gcc specific functions */ 264 | 265 | /** \brief No Operation 266 | 267 | No Operation does nothing. This instruction can be used for code alignment purposes. 268 | */ 269 | __attribute__( ( always_inline ) ) static __INLINE void __NOP(void) 270 | { 271 | __ASM volatile ("nop"); 272 | } 273 | 274 | 275 | /** \brief Wait For Interrupt 276 | 277 | Wait For Interrupt is a hint instruction that suspends execution 278 | until one of a number of events occurs. 279 | */ 280 | __attribute__( ( always_inline ) ) static __INLINE void __WFI(void) 281 | { 282 | __ASM volatile ("wfi"); 283 | } 284 | 285 | 286 | /** \brief Wait For Event 287 | 288 | Wait For Event is a hint instruction that permits the processor to enter 289 | a low-power state until one of a number of events occurs. 290 | */ 291 | __attribute__( ( always_inline ) ) static __INLINE void __WFE(void) 292 | { 293 | __ASM volatile ("wfe"); 294 | } 295 | 296 | 297 | /** \brief Send Event 298 | 299 | Send Event is a hint instruction. It causes an event to be signaled to the CPU. 300 | */ 301 | __attribute__( ( always_inline ) ) static __INLINE void __SEV(void) 302 | { 303 | __ASM volatile ("sev"); 304 | } 305 | 306 | 307 | /** \brief Instruction Synchronization Barrier 308 | 309 | Instruction Synchronization Barrier flushes the pipeline in the processor, 310 | so that all instructions following the ISB are fetched from cache or 311 | memory, after the instruction has been completed. 312 | */ 313 | __attribute__( ( always_inline ) ) static __INLINE void __ISB(void) 314 | { 315 | __ASM volatile ("isb"); 316 | } 317 | 318 | 319 | /** \brief Data Synchronization Barrier 320 | 321 | This function acts as a special kind of Data Memory Barrier. 322 | It completes when all explicit memory accesses before this instruction complete. 323 | */ 324 | __attribute__( ( always_inline ) ) static __INLINE void __DSB(void) 325 | { 326 | __ASM volatile ("dsb"); 327 | } 328 | 329 | 330 | /** \brief Data Memory Barrier 331 | 332 | This function ensures the apparent order of the explicit memory operations before 333 | and after the instruction, without ensuring their completion. 334 | */ 335 | __attribute__( ( always_inline ) ) static __INLINE void __DMB(void) 336 | { 337 | __ASM volatile ("dmb"); 338 | } 339 | 340 | 341 | /** \brief Reverse byte order (32 bit) 342 | 343 | This function reverses the byte order in integer value. 344 | 345 | \param [in] value Value to reverse 346 | \return Reversed value 347 | */ 348 | __attribute__( ( always_inline ) ) static __INLINE uint32_t __REV(uint32_t value) 349 | { 350 | uint32_t result; 351 | 352 | __ASM volatile ("rev %0, %1" : "=r" (result) : "r" (value) ); 353 | return(result); 354 | } 355 | 356 | 357 | /** \brief Reverse byte order (16 bit) 358 | 359 | This function reverses the byte order in two unsigned short values. 360 | 361 | \param [in] value Value to reverse 362 | \return Reversed value 363 | */ 364 | __attribute__( ( always_inline ) ) static __INLINE uint32_t __REV16(uint32_t value) 365 | { 366 | uint32_t result; 367 | 368 | __ASM volatile ("rev16 %0, %1" : "=r" (result) : "r" (value) ); 369 | return(result); 370 | } 371 | 372 | 373 | /** \brief Reverse byte order in signed short value 374 | 375 | This function reverses the byte order in a signed short value with sign extension to integer. 376 | 377 | \param [in] value Value to reverse 378 | \return Reversed value 379 | */ 380 | __attribute__( ( always_inline ) ) static __INLINE int32_t __REVSH(int32_t value) 381 | { 382 | uint32_t result; 383 | 384 | __ASM volatile ("revsh %0, %1" : "=r" (result) : "r" (value) ); 385 | return(result); 386 | } 387 | 388 | 389 | #if (__CORTEX_M >= 0x03) 390 | 391 | /** \brief Reverse bit order of value 392 | 393 | This function reverses the bit order of the given value. 394 | 395 | \param [in] value Value to reverse 396 | \return Reversed value 397 | */ 398 | __attribute__( ( always_inline ) ) static __INLINE uint32_t __RBIT(uint32_t value) 399 | { 400 | uint32_t result; 401 | 402 | __ASM volatile ("rbit %0, %1" : "=r" (result) : "r" (value) ); 403 | return(result); 404 | } 405 | 406 | 407 | /** \brief LDR Exclusive (8 bit) 408 | 409 | This function performs a exclusive LDR command for 8 bit value. 410 | 411 | \param [in] ptr Pointer to data 412 | \return value of type uint8_t at (*ptr) 413 | */ 414 | __attribute__( ( always_inline ) ) static __INLINE uint8_t __LDREXB(volatile uint8_t *addr) 415 | { 416 | uint8_t result; 417 | 418 | __ASM volatile ("ldrexb %0, [%1]" : "=r" (result) : "r" (addr) ); 419 | return(result); 420 | } 421 | 422 | 423 | /** \brief LDR Exclusive (16 bit) 424 | 425 | This function performs a exclusive LDR command for 16 bit values. 426 | 427 | \param [in] ptr Pointer to data 428 | \return value of type uint16_t at (*ptr) 429 | */ 430 | __attribute__( ( always_inline ) ) static __INLINE uint16_t __LDREXH(volatile uint16_t *addr) 431 | { 432 | uint16_t result; 433 | 434 | __ASM volatile ("ldrexh %0, [%1]" : "=r" (result) : "r" (addr) ); 435 | return(result); 436 | } 437 | 438 | 439 | /** \brief LDR Exclusive (32 bit) 440 | 441 | This function performs a exclusive LDR command for 32 bit values. 442 | 443 | \param [in] ptr Pointer to data 444 | \return value of type uint32_t at (*ptr) 445 | */ 446 | __attribute__( ( always_inline ) ) static __INLINE uint32_t __LDREXW(volatile uint32_t *addr) 447 | { 448 | uint32_t result; 449 | 450 | __ASM volatile ("ldrex %0, [%1]" : "=r" (result) : "r" (addr) ); 451 | return(result); 452 | } 453 | 454 | 455 | /** \brief STR Exclusive (8 bit) 456 | 457 | This function performs a exclusive STR command for 8 bit values. 458 | 459 | \param [in] value Value to store 460 | \param [in] ptr Pointer to location 461 | \return 0 Function succeeded 462 | \return 1 Function failed 463 | */ 464 | __attribute__( ( always_inline ) ) static __INLINE uint32_t __STREXB(uint8_t value, volatile uint8_t *addr) 465 | { 466 | uint32_t result; 467 | 468 | __ASM volatile ("strexb %0, %2, [%1]" : "=r" (result) : "r" (addr), "r" (value) ); 469 | return(result); 470 | } 471 | 472 | 473 | /** \brief STR Exclusive (16 bit) 474 | 475 | This function performs a exclusive STR command for 16 bit values. 476 | 477 | \param [in] value Value to store 478 | \param [in] ptr Pointer to location 479 | \return 0 Function succeeded 480 | \return 1 Function failed 481 | */ 482 | __attribute__( ( always_inline ) ) static __INLINE uint32_t __STREXH(uint16_t value, volatile uint16_t *addr) 483 | { 484 | uint32_t result; 485 | 486 | __ASM volatile ("strexh %0, %2, [%1]" : "=r" (result) : "r" (addr), "r" (value) ); 487 | return(result); 488 | } 489 | 490 | 491 | /** \brief STR Exclusive (32 bit) 492 | 493 | This function performs a exclusive STR command for 32 bit values. 494 | 495 | \param [in] value Value to store 496 | \param [in] ptr Pointer to location 497 | \return 0 Function succeeded 498 | \return 1 Function failed 499 | */ 500 | __attribute__( ( always_inline ) ) static __INLINE uint32_t __STREXW(uint32_t value, volatile uint32_t *addr) 501 | { 502 | uint32_t result; 503 | 504 | __ASM volatile ("strex %0, %2, [%1]" : "=r" (result) : "r" (addr), "r" (value) ); 505 | return(result); 506 | } 507 | 508 | 509 | /** \brief Remove the exclusive lock 510 | 511 | This function removes the exclusive lock which is created by LDREX. 512 | 513 | */ 514 | __attribute__( ( always_inline ) ) static __INLINE void __CLREX(void) 515 | { 516 | __ASM volatile ("clrex"); 517 | } 518 | 519 | 520 | /** \brief Signed Saturate 521 | 522 | This function saturates a signed value. 523 | 524 | \param [in] value Value to be saturated 525 | \param [in] sat Bit position to saturate to (1..32) 526 | \return Saturated value 527 | */ 528 | #define __SSAT(ARG1,ARG2) \ 529 | ({ \ 530 | uint32_t __RES, __ARG1 = (ARG1); \ 531 | __ASM ("ssat %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \ 532 | __RES; \ 533 | }) 534 | 535 | 536 | /** \brief Unsigned Saturate 537 | 538 | This function saturates an unsigned value. 539 | 540 | \param [in] value Value to be saturated 541 | \param [in] sat Bit position to saturate to (0..31) 542 | \return Saturated value 543 | */ 544 | #define __USAT(ARG1,ARG2) \ 545 | ({ \ 546 | uint32_t __RES, __ARG1 = (ARG1); \ 547 | __ASM ("usat %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \ 548 | __RES; \ 549 | }) 550 | 551 | 552 | /** \brief Count leading zeros 553 | 554 | This function counts the number of leading zeros of a data value. 555 | 556 | \param [in] value Value to count the leading zeros 557 | \return number of leading zeros in value 558 | */ 559 | __attribute__( ( always_inline ) ) static __INLINE uint8_t __CLZ(uint32_t value) 560 | { 561 | uint8_t result; 562 | 563 | __ASM volatile ("clz %0, %1" : "=r" (result) : "r" (value) ); 564 | return(result); 565 | } 566 | 567 | #endif /* (__CORTEX_M >= 0x03) */ 568 | 569 | 570 | 571 | 572 | #elif defined ( __TASKING__ ) /*------------------ TASKING Compiler --------------*/ 573 | /* TASKING carm specific functions */ 574 | 575 | /* 576 | * The CMSIS functions have been implemented as intrinsics in the compiler. 577 | * Please use "carm -?i" to get an up to date list of all intrinsics, 578 | * Including the CMSIS ones. 579 | */ 580 | 581 | #endif 582 | 583 | /*@}*/ /* end of group CMSIS_Core_InstructionInterface */ 584 | 585 | #endif /* __CORE_CMINSTR_H */ 586 | -------------------------------------------------------------------------------- /src/cmsis_boot/startup/startup_stm32f4xx.c: -------------------------------------------------------------------------------- 1 | /** 2 | ****************************************************************************** 3 | * @file startup_stm32f4xx.s 4 | * @author Coocox 5 | * @version V1.0 6 | * @date 03/05/2012 7 | * @brief STM32F4xx Devices vector table for RIDE7 toolchain. 8 | * This module performs: 9 | * - Set the initial SP 10 | * - Set the initial PC == Reset_Handler, 11 | * - Set the vector table entries with the exceptions ISR address 12 | * - Configure the clock system and the external SRAM mounted on 13 | * STM324xG-EVAL board to be used as data memory (optional, 14 | * to be enabled by user) 15 | * - Branches to main in the C library (which eventually 16 | * calls main()). 17 | * After Reset the Cortex-M4 processor is in Thread mode, 18 | * priority is Privileged, and the Stack is set to Main. 19 | ****************************************************************************** 20 | */ 21 | 22 | 23 | /*----------Stack Configuration-----------------------------------------------*/ 24 | #define STACK_SIZE 0x00000200 /*!< Stack size (in Words) */ 25 | __attribute__ ((section(".co_stack"))) 26 | unsigned long pulStack[STACK_SIZE]; 27 | 28 | 29 | /*----------Macro definition--------------------------------------------------*/ 30 | #define WEAK __attribute__ ((weak)) 31 | 32 | 33 | 34 | /*----------Declaration of the default fault handlers-------------------------*/ 35 | /* System exception vector handler */ 36 | void WEAK Reset_Handler(void); 37 | void WEAK NMI_Handler(void); 38 | void WEAK HardFault_Handler(void); 39 | void WEAK MemManage_Handler(void); 40 | void WEAK BusFault_Handler(void); 41 | void WEAK UsageFault_Handler(void); 42 | void WEAK SVC_Handler(void); 43 | void WEAK DebugMon_Handler(void); 44 | void WEAK PendSV_Handler(void); 45 | void WEAK SysTick_Handler(void); 46 | 47 | void WEAK WWDG_IRQHandler(void); 48 | void WEAK PVD_IRQHandler(void); 49 | void WEAK TAMP_STAMP_IRQHandler(void); 50 | void WEAK RTC_WKUP_IRQHandler(void); 51 | void WEAK FLASH_IRQHandler(void); 52 | void WEAK RCC_IRQHandler(void); 53 | void WEAK EXTI0_IRQHandler(void); 54 | void WEAK EXTI1_IRQHandler(void); 55 | void WEAK EXTI2_IRQHandler(void); 56 | void WEAK EXTI3_IRQHandler(void); 57 | void WEAK EXTI4_IRQHandler(void); 58 | void WEAK DMA1_Stream0_IRQHandler(void); 59 | void WEAK DMA1_Stream1_IRQHandler(void); 60 | void WEAK DMA1_Stream2_IRQHandler(void); 61 | void WEAK DMA1_Stream3_IRQHandler(void); 62 | void WEAK DMA1_Stream4_IRQHandler(void); 63 | void WEAK DMA1_Stream5_IRQHandler(void); 64 | void WEAK DMA1_Stream6_IRQHandler(void); 65 | void WEAK ADC_IRQHandler(void); 66 | void WEAK CAN1_TX_IRQHandler(void); 67 | void WEAK CAN1_RX0_IRQHandler(void); 68 | void WEAK CAN1_RX1_IRQHandler(void); 69 | void WEAK CAN1_SCE_IRQHandler(void); 70 | void WEAK EXTI9_5_IRQHandler(void); 71 | void WEAK TIM1_BRK_TIM9_IRQHandler(void); 72 | void WEAK TIM1_UP_TIM10_IRQHandler(void); 73 | void WEAK TIM1_TRG_COM_TIM11_IRQHandler(void); 74 | void WEAK TIM1_CC_IRQHandler(void); 75 | void WEAK TIM2_IRQHandler(void); 76 | void WEAK TIM3_IRQHandler(void); 77 | void WEAK TIM4_IRQHandler(void); 78 | void WEAK I2C1_EV_IRQHandler(void); 79 | void WEAK I2C1_ER_IRQHandler(void); 80 | void WEAK I2C2_EV_IRQHandler(void); 81 | void WEAK I2C2_ER_IRQHandler(void); 82 | void WEAK SPI1_IRQHandler(void); 83 | void WEAK SPI2_IRQHandler(void); 84 | void WEAK USART1_IRQHandler(void); 85 | void WEAK USART2_IRQHandler(void); 86 | void WEAK USART3_IRQHandler(void); 87 | void WEAK EXTI15_10_IRQHandler(void); 88 | void WEAK RTC_Alarm_IRQHandler(void); 89 | void WEAK OTG_FS_WKUP_IRQHandler(void); 90 | void WEAK TIM8_BRK_TIM12_IRQHandler(void); 91 | void WEAK TIM8_UP_TIM13_IRQHandler(void); 92 | void WEAK TIM8_TRG_COM_TIM14_IRQHandler(void); 93 | void WEAK TIM8_CC_IRQHandler(void); 94 | void WEAK DMA1_Stream7_IRQHandler(void); 95 | void WEAK FSMC_IRQHandler(void); 96 | void WEAK SDIO_IRQHandler(void); 97 | void WEAK TIM5_IRQHandler(void); 98 | void WEAK SPI3_IRQHandler(void); 99 | void WEAK UART4_IRQHandler(void); 100 | void WEAK UART5_IRQHandler(void); 101 | void WEAK TIM6_DAC_IRQHandler(void); 102 | void WEAK TIM7_IRQHandler(void); 103 | void WEAK DMA2_Stream0_IRQHandler(void); 104 | void WEAK DMA2_Stream1_IRQHandler(void); 105 | void WEAK DMA2_Stream2_IRQHandler(void); 106 | void WEAK DMA2_Stream3_IRQHandler(void); 107 | void WEAK DMA2_Stream4_IRQHandler(void); 108 | void WEAK ETH_IRQHandler(void); 109 | void WEAK ETH_WKUP_IRQHandler(void); 110 | void WEAK CAN2_TX_IRQHandler(void); 111 | void WEAK CAN2_RX0_IRQHandler(void); 112 | void WEAK CAN2_RX1_IRQHandler(void); 113 | void WEAK CAN2_SCE_IRQHandler(void); 114 | void WEAK OTG_FS_IRQHandler(void); 115 | void WEAK DMA2_Stream5_IRQHandler(void); 116 | void WEAK DMA2_Stream6_IRQHandler(void); 117 | void WEAK DMA2_Stream7_IRQHandler(void); 118 | void WEAK USART6_IRQHandler(void); 119 | void WEAK I2C3_EV_IRQHandler(void); 120 | void WEAK I2C3_ER_IRQHandler(void); 121 | void WEAK OTG_HS_EP1_OUT_IRQHandler(void); 122 | void WEAK OTG_HS_EP1_IN_IRQHandler(void); 123 | void WEAK OTG_HS_WKUP_IRQHandler(void); 124 | void WEAK OTG_HS_IRQHandler(void); 125 | void WEAK DCMI_IRQHandler(void); 126 | void WEAK CRYP_IRQHandler(void); 127 | void WEAK HASH_RNG_IRQHandler(void); 128 | void WEAK FPU_IRQHandler(void); 129 | 130 | /*----------Symbols defined in linker script----------------------------------*/ 131 | extern unsigned long _sidata; /*!< Start address for the initialization 132 | values of the .data section. */ 133 | extern unsigned long _sdata; /*!< Start address for the .data section */ 134 | extern unsigned long _edata; /*!< End address for the .data section */ 135 | extern unsigned long _sbss; /*!< Start address for the .bss section */ 136 | extern unsigned long _ebss; /*!< End address for the .bss section */ 137 | extern void _eram; /*!< End address for ram */ 138 | 139 | 140 | /*----------Function prototypes-----------------------------------------------*/ 141 | extern int main(void); /*!< The entry point for the application. */ 142 | //extern void SystemInit(void); /*!< Setup the microcontroller system(CMSIS) */ 143 | void Default_Reset_Handler(void); /*!< Default reset handler */ 144 | static void Default_Handler(void); /*!< Default exception handler */ 145 | 146 | 147 | /** 148 | *@brief The minimal vector table for a Cortex M3. Note that the proper constructs 149 | * must be placed on this to ensure that it ends up at physical address 150 | * 0x00000000. 151 | */ 152 | __attribute__ ((section(".isr_vector"))) 153 | void (* const g_pfnVectors[])(void) = 154 | { 155 | /*----------Core Exceptions------------------------------------------------ */ 156 | (void *)&pulStack[STACK_SIZE-1], /*!< The initial stack pointer */ 157 | Reset_Handler, /*!< Reset Handler */ 158 | NMI_Handler, /*!< NMI Handler */ 159 | HardFault_Handler, /*!< Hard Fault Handler */ 160 | MemManage_Handler, /*!< MPU Fault Handler */ 161 | BusFault_Handler, /*!< Bus Fault Handler */ 162 | UsageFault_Handler, /*!< Usage Fault Handler */ 163 | 0,0,0,0, /*!< Reserved */ 164 | SVC_Handler, /*!< SVCall Handler */ 165 | DebugMon_Handler, /*!< Debug Monitor Handler */ 166 | 0, /*!< Reserved */ 167 | PendSV_Handler, /*!< PendSV Handler */ 168 | SysTick_Handler, /*!< SysTick Handler */ 169 | 170 | /*----------External Exceptions---------------------------------------------*/ 171 | WWDG_IRQHandler, /*!< 0: Window WatchDog */ 172 | PVD_IRQHandler, /*!< 1: PVD through EXTI Line detection */ 173 | TAMP_STAMP_IRQHandler, /*!< 2: Tamper and TimeStamps through the EXTI line*/ 174 | RTC_WKUP_IRQHandler, /*!< 3: RTC Wakeup through the EXTI line */ 175 | FLASH_IRQHandler, /*!< 4: FLASH */ 176 | RCC_IRQHandler , /*!< 5: RCC */ 177 | EXTI0_IRQHandler, /*!< 6: EXTI Line0 */ 178 | EXTI1_IRQHandler, /*!< 7: EXTI Line1 */ 179 | EXTI2_IRQHandler, /*!< 8: EXTI Line2 */ 180 | EXTI3_IRQHandler, /*!< 9: EXTI Line3 */ 181 | EXTI4_IRQHandler, /*!< 10: EXTI Line4 */ 182 | DMA1_Stream0_IRQHandler, /*!< 11: DMA1 Stream 0 */ 183 | DMA1_Stream1_IRQHandler, /*!< 12: DMA1 Stream 1 */ 184 | DMA1_Stream2_IRQHandler, /*!< 13: DMA1 Stream 2 */ 185 | DMA1_Stream3_IRQHandler, /*!< 14: DMA1 Stream 3 */ 186 | DMA1_Stream4_IRQHandler, /*!< 15: DMA1 Stream 4 */ 187 | DMA1_Stream5_IRQHandler, /*!< 16: DMA1 Stream 5 */ 188 | DMA1_Stream6_IRQHandler, /*!< 17: DMA1 Stream 6 */ 189 | ADC_IRQHandler, /*!< 18: ADC1, ADC2 and ADC3s */ 190 | CAN1_TX_IRQHandler, /*!< 19: CAN1 TX */ 191 | CAN1_RX0_IRQHandler, /*!< 20: CAN1 RX0 */ 192 | CAN1_RX1_IRQHandler, /*!< 21: CAN1 RX1 */ 193 | CAN1_SCE_IRQHandler, /*!< 22: CAN1 SCE */ 194 | EXTI9_5_IRQHandler, /*!< 23: External Line[9:5]s */ 195 | TIM1_BRK_TIM9_IRQHandler, /*!< 24: TIM1 Break and TIM9 */ 196 | TIM1_UP_TIM10_IRQHandler, /*!< 25: TIM1 Update and TIM10 */ 197 | TIM1_TRG_COM_TIM11_IRQHandler,/*!< 26: TIM1 Trigger and Commutation and TIM11*/ 198 | TIM1_CC_IRQHandler, /*!< 27: TIM1 Capture Compare */ 199 | TIM2_IRQHandler, /*!< 28: TIM2 */ 200 | TIM3_IRQHandler, /*!< 29: TIM3 */ 201 | TIM4_IRQHandler, /*!< 30: TIM4 */ 202 | I2C1_EV_IRQHandler, /*!< 31: I2C1 Event */ 203 | I2C1_ER_IRQHandler, /*!< 32: I2C1 Error */ 204 | I2C2_EV_IRQHandler, /*!< 33: I2C2 Event */ 205 | I2C2_ER_IRQHandler, /*!< 34: I2C2 Error */ 206 | SPI1_IRQHandler, /*!< 35: SPI1 */ 207 | SPI2_IRQHandler, /*!< 36: SPI2 */ 208 | USART1_IRQHandler, /*!< 37: USART1 */ 209 | USART2_IRQHandler, /*!< 38: USART2 */ 210 | USART3_IRQHandler, /*!< 39: USART3 */ 211 | EXTI15_10_IRQHandler, /*!< 40: External Line[15:10]s */ 212 | RTC_Alarm_IRQHandler, /*!< 41: RTC Alarm (A and B) through EXTI Line */ 213 | OTG_FS_WKUP_IRQHandler, /*!< 42: USB OTG FS Wakeup through EXTI line */ 214 | TIM8_BRK_TIM12_IRQHandler, /*!< 43: TIM8 Break and TIM12 */ 215 | TIM8_UP_TIM13_IRQHandler, /*!< 44: TIM8 Update and TIM13 */ 216 | TIM8_TRG_COM_TIM14_IRQHandler,/*!< 45:TIM8 Trigger and Commutation and TIM14*/ 217 | TIM8_CC_IRQHandler, /*!< 46: TIM8 Capture Compare */ 218 | DMA1_Stream7_IRQHandler, /*!< 47: DMA1 Stream7 */ 219 | FSMC_IRQHandler, /*!< 48: FSMC */ 220 | SDIO_IRQHandler, /*!< 49: SDIO */ 221 | TIM5_IRQHandler, /*!< 50: TIM5 */ 222 | SPI3_IRQHandler, /*!< 51: SPI3 */ 223 | UART4_IRQHandler, /*!< 52: UART4 */ 224 | UART5_IRQHandler, /*!< 53: UART5 */ 225 | TIM6_DAC_IRQHandler, /*!< 54: TIM6 and DAC1&2 underrun errors */ 226 | TIM7_IRQHandler, /*!< 55: TIM7 */ 227 | DMA2_Stream0_IRQHandler, /*!< 56: DMA2 Stream 0 */ 228 | DMA2_Stream1_IRQHandler, /*!< 57: DMA2 Stream 1 */ 229 | DMA2_Stream2_IRQHandler, /*!< 58: DMA2 Stream 2 */ 230 | DMA2_Stream3_IRQHandler, /*!< 59: DMA2 Stream 3 */ 231 | DMA2_Stream4_IRQHandler, /*!< 60: DMA2 Stream 4 */ 232 | ETH_IRQHandler, /*!< 61: Ethernet */ 233 | ETH_WKUP_IRQHandler, /*!< 62: Ethernet Wakeup through EXTI line */ 234 | CAN2_TX_IRQHandler, /*!< 63: CAN2 TX */ 235 | CAN2_RX0_IRQHandler, /*!< 64: CAN2 RX0 */ 236 | CAN2_RX1_IRQHandler, /*!< 65: CAN2 RX1 */ 237 | CAN2_SCE_IRQHandler, /*!< 66: CAN2 SCE */ 238 | OTG_FS_IRQHandler, /*!< 67: USB OTG FS */ 239 | DMA2_Stream5_IRQHandler, /*!< 68: DMA2 Stream 5 */ 240 | DMA2_Stream6_IRQHandler, /*!< 69: DMA2 Stream 6 */ 241 | DMA2_Stream7_IRQHandler, /*!< 70: DMA2 Stream 7 */ 242 | USART6_IRQHandler, /*!< 71: USART6 */ 243 | I2C3_EV_IRQHandler, /*!< 72: I2C3 event */ 244 | I2C3_ER_IRQHandler, /*!< 73: I2C3 error */ 245 | OTG_HS_EP1_OUT_IRQHandler, /*!< 74: USB OTG HS End Point 1 Out */ 246 | OTG_HS_EP1_IN_IRQHandler, /*!< 75: USB OTG HS End Point 1 In */ 247 | OTG_HS_WKUP_IRQHandler, /*!< 76: USB OTG HS Wakeup through EXTI */ 248 | OTG_HS_IRQHandler, /*!< 77: USB OTG HS */ 249 | DCMI_IRQHandler, /*!< 53: DCMI */ 250 | CRYP_IRQHandler, /*!< 53: CRYP crypto */ 251 | HASH_RNG_IRQHandler, /*!< 53: Hash and Rng */ 252 | FPU_IRQHandler /*!< 53: FPU */ 253 | 254 | }; 255 | 256 | 257 | /** 258 | * @brief This is the code that gets called when the processor first 259 | * starts execution following a reset event. Only the absolutely 260 | * necessary set is performed, after which the application 261 | * supplied main() routine is called. 262 | * @param None 263 | * @retval None 264 | */ 265 | void Default_Reset_Handler(void) 266 | { 267 | /* Initialize data and bss */ 268 | unsigned long *pulSrc, *pulDest; 269 | 270 | /* Copy the data segment initializers from flash to SRAM */ 271 | pulSrc = &_sidata; 272 | 273 | for(pulDest = &_sdata; pulDest < &_edata; ) 274 | { 275 | *(pulDest++) = *(pulSrc++); 276 | } 277 | 278 | /* Zero fill the bss segment. This is done with inline assembly since this 279 | will clear the value of pulDest if it is not kept in a register. */ 280 | __asm(" ldr r0, =_sbss\n" 281 | " ldr r1, =_ebss\n" 282 | " mov r2, #0\n" 283 | " .thumb_func\n" 284 | "zero_loop:\n" 285 | " cmp r0, r1\n" 286 | " it lt\n" 287 | " strlt r2, [r0], #4\n" 288 | " blt zero_loop"); 289 | #ifdef __FPU_USED 290 | /* Enable FPU.*/ 291 | __asm(" LDR.W R0, =0xE000ED88\n" 292 | " LDR R1, [R0]\n" 293 | " ORR R1, R1, #(0xF << 20)\n" 294 | " STR R1, [R0]"); 295 | #endif 296 | 297 | /* Call the application's entry point.*/ 298 | main(); 299 | } 300 | 301 | 302 | /** 303 | *@brief Provide weak aliases for each Exception handler to the Default_Handler. 304 | * As they are weak aliases, any function with the same name will override 305 | * this definition. 306 | */ 307 | #pragma weak Reset_Handler = Default_Reset_Handler 308 | #pragma weak NMI_Handler = Default_Handler 309 | #pragma weak HardFault_Handler = Default_Handler 310 | #pragma weak MemManage_Handler = Default_Handler 311 | #pragma weak BusFault_Handler = Default_Handler 312 | #pragma weak UsageFault_Handler = Default_Handler 313 | #pragma weak SVC_Handler = Default_Handler 314 | #pragma weak DebugMon_Handler = Default_Handler 315 | #pragma weak PendSV_Handler = Default_Handler 316 | #pragma weak SysTick_Handler = Default_Handler 317 | 318 | #pragma weak WWDG_IRQHandler = Default_Handler 319 | #pragma weak PVD_IRQHandler = Default_Handler 320 | #pragma weak TAMP_STAMP_IRQHandler = Default_Handler 321 | #pragma weak RTC_WKUP_IRQHandler = Default_Handler 322 | #pragma weak FLASH_IRQHandler = Default_Handler 323 | #pragma weak RCC_IRQHandler = Default_Handler 324 | #pragma weak EXTI0_IRQHandler = Default_Handler 325 | #pragma weak EXTI1_IRQHandler = Default_Handler 326 | #pragma weak EXTI2_IRQHandler = Default_Handler 327 | #pragma weak EXTI3_IRQHandler = Default_Handler 328 | #pragma weak EXTI4_IRQHandler = Default_Handler 329 | #pragma weak DMA1_Stream0_IRQHandler = Default_Handler 330 | #pragma weak DMA1_Stream1_IRQHandler = Default_Handler 331 | #pragma weak DMA1_Stream2_IRQHandler = Default_Handler 332 | #pragma weak DMA1_Stream3_IRQHandler = Default_Handler 333 | #pragma weak DMA1_Stream4_IRQHandler = Default_Handler 334 | #pragma weak DMA1_Stream5_IRQHandler = Default_Handler 335 | #pragma weak DMA1_Stream6_IRQHandler = Default_Handler 336 | #pragma weak ADC_IRQHandler = Default_Handler 337 | #pragma weak CAN1_TX_IRQHandler = Default_Handler 338 | #pragma weak CAN1_RX0_IRQHandler = Default_Handler 339 | #pragma weak CAN1_RX1_IRQHandler = Default_Handler 340 | #pragma weak CAN1_SCE_IRQHandler = Default_Handler 341 | #pragma weak EXTI9_5_IRQHandler = Default_Handler 342 | #pragma weak TIM1_BRK_TIM9_IRQHandler = Default_Handler 343 | #pragma weak TIM1_UP_TIM10_IRQHandler = Default_Handler 344 | #pragma weak TIM1_TRG_COM_TIM11_IRQHandler = Default_Handler 345 | #pragma weak TIM1_CC_IRQHandler = Default_Handler 346 | #pragma weak TIM2_IRQHandler = Default_Handler 347 | #pragma weak TIM3_IRQHandler = Default_Handler 348 | #pragma weak TIM4_IRQHandler = Default_Handler 349 | #pragma weak I2C1_EV_IRQHandler = Default_Handler 350 | #pragma weak I2C1_ER_IRQHandler = Default_Handler 351 | #pragma weak I2C2_EV_IRQHandler = Default_Handler 352 | #pragma weak I2C2_ER_IRQHandler = Default_Handler 353 | #pragma weak SPI1_IRQHandler = Default_Handler 354 | #pragma weak SPI2_IRQHandler = Default_Handler 355 | #pragma weak USART1_IRQHandler = Default_Handler 356 | #pragma weak USART2_IRQHandler = Default_Handler 357 | #pragma weak USART3_IRQHandler = Default_Handler 358 | #pragma weak EXTI15_10_IRQHandler = Default_Handler 359 | #pragma weak RTC_Alarm_IRQHandler = Default_Handler 360 | #pragma weak OTG_FS_WKUP_IRQHandler = Default_Handler 361 | #pragma weak TIM8_BRK_TIM12_IRQHandler = Default_Handler 362 | #pragma weak TIM8_UP_TIM13_IRQHandler = Default_Handler 363 | #pragma weak TIM8_TRG_COM_TIM14_IRQHandler = Default_Handler 364 | #pragma weak TIM8_CC_IRQHandler = Default_Handler 365 | #pragma weak DMA1_Stream7_IRQHandler = Default_Handler 366 | #pragma weak FSMC_IRQHandler = Default_Handler 367 | #pragma weak SDIO_IRQHandler = Default_Handler 368 | #pragma weak TIM5_IRQHandler = Default_Handler 369 | #pragma weak SPI3_IRQHandler = Default_Handler 370 | #pragma weak UART4_IRQHandler = Default_Handler 371 | #pragma weak UART5_IRQHandler = Default_Handler 372 | #pragma weak TIM6_DAC_IRQHandler = Default_Handler 373 | #pragma weak TIM7_IRQHandler = Default_Handler 374 | #pragma weak DMA2_Stream0_IRQHandler = Default_Handler 375 | #pragma weak DMA2_Stream1_IRQHandler = Default_Handler 376 | #pragma weak DMA2_Stream2_IRQHandler = Default_Handler 377 | #pragma weak DMA2_Stream3_IRQHandler = Default_Handler 378 | #pragma weak DMA2_Stream4_IRQHandler = Default_Handler 379 | #pragma weak ETH_IRQHandler = Default_Handler 380 | #pragma weak ETH_WKUP_IRQHandler = Default_Handler 381 | #pragma weak CAN2_TX_IRQHandler = Default_Handler 382 | #pragma weak CAN2_RX0_IRQHandler = Default_Handler 383 | #pragma weak CAN2_RX1_IRQHandler = Default_Handler 384 | #pragma weak CAN2_SCE_IRQHandler = Default_Handler 385 | #pragma weak OTG_FS_IRQHandler = Default_Handler 386 | #pragma weak DMA2_Stream5_IRQHandler = Default_Handler 387 | #pragma weak DMA2_Stream6_IRQHandler = Default_Handler 388 | #pragma weak DMA2_Stream7_IRQHandler = Default_Handler 389 | #pragma weak USART6_IRQHandler = Default_Handler 390 | #pragma weak I2C3_EV_IRQHandler = Default_Handler 391 | #pragma weak I2C3_ER_IRQHandler = Default_Handler 392 | #pragma weak OTG_HS_EP1_OUT_IRQHandler = Default_Handler 393 | #pragma weak OTG_HS_EP1_IN_IRQHandler = Default_Handler 394 | #pragma weak OTG_HS_WKUP_IRQHandler = Default_Handler 395 | #pragma weak OTG_HS_IRQHandler = Default_Handler 396 | #pragma weak DCMI_IRQHandler = Default_Handler 397 | #pragma weak CRYP_IRQHandler = Default_Handler 398 | #pragma weak HASH_RNG_IRQHandler = Default_Handler 399 | #pragma weak FPU_IRQHandler = Default_Handler 400 | 401 | /** 402 | * @brief This is the code that gets called when the processor receives an 403 | * unexpected interrupt. This simply enters an infinite loop, 404 | * preserving the system state for examination by a debugger. 405 | * @param None 406 | * @retval None 407 | */ 408 | static void Default_Handler(void) 409 | { 410 | /* Go into an infinite loop. */ 411 | while (1) 412 | { 413 | } 414 | } 415 | 416 | /*********************** (C) COPYRIGHT 2009 Coocox ************END OF FILE*****/ 417 | -------------------------------------------------------------------------------- /src/cmsis_boot/system_stm32f4xx.c: -------------------------------------------------------------------------------- 1 | /** 2 | ****************************************************************************** 3 | * @file system_stm32f4xx.c 4 | * @author MCD Application Team 5 | * @version V1.0.0 6 | * @date 30-September-2011 7 | * @brief CMSIS Cortex-M4 Device Peripheral Access Layer System Source File. 8 | * This file contains the system clock configuration for STM32F4xx devices, 9 | * and is generated by the clock configuration tool 10 | * stm32f4xx_Clock_Configuration_V1.0.0.xls 11 | * 12 | * 1. This file provides two functions and one global variable to be called from 13 | * user application: 14 | * - SystemInit(): Setups the system clock (System clock source, PLL Multiplier 15 | * and Divider factors, AHB/APBx prescalers and Flash settings), 16 | * depending on the configuration made in the clock xls tool. 17 | * This function is called at startup just after reset and 18 | * before branch to main program. This call is made inside 19 | * the "startup_stm32f4xx.s" file. 20 | * 21 | * - SystemCoreClock variable: Contains the core clock (HCLK), it can be used 22 | * by the user application to setup the SysTick 23 | * timer or configure other parameters. 24 | * 25 | * - SystemCoreClockUpdate(): Updates the variable SystemCoreClock and must 26 | * be called whenever the core clock is changed 27 | * during program execution. 28 | * 29 | * 2. After each device reset the HSI (16 MHz) is used as system clock source. 30 | * Then SystemInit() function is called, in "startup_stm32f4xx.s" file, to 31 | * configure the system clock before to branch to main program. 32 | * 33 | * 3. If the system clock source selected by user fails to startup, the SystemInit() 34 | * function will do nothing and HSI still used as system clock source. User can 35 | * add some code to deal with this issue inside the SetSysClock() function. 36 | * 37 | * 4. The default value of HSE crystal is set to 25MHz, refer to "HSE_VALUE" define 38 | * in "stm32f4xx.h" file. When HSE is used as system clock source, directly or 39 | * through PLL, and you are using different crystal you have to adapt the HSE 40 | * value to your own configuration. 41 | * 42 | * 5. This file configures the system clock as follows: 43 | *============================================================================= 44 | *============================================================================= 45 | * Supported STM32F4xx device revision | Rev A 46 | *----------------------------------------------------------------------------- 47 | * System Clock source | PLL (HSE) 48 | *----------------------------------------------------------------------------- 49 | * SYSCLK(Hz) | 168000000 50 | *----------------------------------------------------------------------------- 51 | * HCLK(Hz) | 168000000 52 | *----------------------------------------------------------------------------- 53 | * AHB Prescaler | 1 54 | *----------------------------------------------------------------------------- 55 | * APB1 Prescaler | 4 56 | *----------------------------------------------------------------------------- 57 | * APB2 Prescaler | 2 58 | *----------------------------------------------------------------------------- 59 | * HSE Frequency(Hz) | 25000000 60 | *----------------------------------------------------------------------------- 61 | * PLL_M | 25 62 | *----------------------------------------------------------------------------- 63 | * PLL_N | 336 64 | *----------------------------------------------------------------------------- 65 | * PLL_P | 2 66 | *----------------------------------------------------------------------------- 67 | * PLL_Q | 7 68 | *----------------------------------------------------------------------------- 69 | * PLLI2S_N | NA 70 | *----------------------------------------------------------------------------- 71 | * PLLI2S_R | NA 72 | *----------------------------------------------------------------------------- 73 | * I2S input clock | NA 74 | *----------------------------------------------------------------------------- 75 | * VDD(V) | 3.3 76 | *----------------------------------------------------------------------------- 77 | * Main regulator output voltage | Scale1 mode 78 | *----------------------------------------------------------------------------- 79 | * Flash Latency(WS) | 5 80 | *----------------------------------------------------------------------------- 81 | * Prefetch Buffer | OFF 82 | *----------------------------------------------------------------------------- 83 | * Instruction cache | ON 84 | *----------------------------------------------------------------------------- 85 | * Data cache | ON 86 | *----------------------------------------------------------------------------- 87 | * Require 48MHz for USB OTG FS, | Enabled 88 | * SDIO and RNG clock | 89 | *----------------------------------------------------------------------------- 90 | *============================================================================= 91 | ****************************************************************************** 92 | * @attention 93 | * 94 | * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS 95 | * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE 96 | * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY 97 | * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING 98 | * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE 99 | * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. 100 | * 101 | *

© COPYRIGHT 2011 STMicroelectronics

102 | ****************************************************************************** 103 | */ 104 | 105 | /** @addtogroup CMSIS 106 | * @{ 107 | */ 108 | 109 | /** @addtogroup stm32f4xx_system 110 | * @{ 111 | */ 112 | 113 | /** @addtogroup STM32F4xx_System_Private_Includes 114 | * @{ 115 | */ 116 | 117 | #include "stm32f4xx.h" 118 | 119 | /** 120 | * @} 121 | */ 122 | 123 | /** @addtogroup STM32F4xx_System_Private_TypesDefinitions 124 | * @{ 125 | */ 126 | 127 | /** 128 | * @} 129 | */ 130 | 131 | /** @addtogroup STM32F4xx_System_Private_Defines 132 | * @{ 133 | */ 134 | 135 | /************************* Miscellaneous Configuration ************************/ 136 | /*!< Uncomment the following line if you need to use external SRAM mounted 137 | on STM324xG_EVAL board as data memory */ 138 | /* #define DATA_IN_ExtSRAM */ 139 | 140 | /*!< Uncomment the following line if you need to relocate your vector Table in 141 | Internal SRAM. */ 142 | /* #define VECT_TAB_SRAM */ 143 | #define VECT_TAB_OFFSET 0x00 /*!< Vector Table base offset field. 144 | This value must be a multiple of 0x200. */ 145 | /******************************************************************************/ 146 | 147 | /************************* PLL Parameters *************************************/ 148 | /* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLL_M) * PLL_N */ 149 | #define PLL_M 25 150 | #define PLL_N 336 151 | 152 | /* SYSCLK = PLL_VCO / PLL_P */ 153 | #define PLL_P 2 154 | 155 | /* USB OTG FS, SDIO and RNG Clock = PLL_VCO / PLLQ */ 156 | #define PLL_Q 7 157 | 158 | /******************************************************************************/ 159 | 160 | /** 161 | * @} 162 | */ 163 | 164 | /** @addtogroup STM32F4xx_System_Private_Macros 165 | * @{ 166 | */ 167 | 168 | /** 169 | * @} 170 | */ 171 | 172 | /** @addtogroup STM32F4xx_System_Private_Variables 173 | * @{ 174 | */ 175 | 176 | uint32_t SystemCoreClock = 168000000; 177 | 178 | __I uint8_t AHBPrescTable[16] = {0, 0, 0, 0, 0, 0, 0, 0, 1, 2, 3, 4, 6, 7, 8, 9}; 179 | 180 | /** 181 | * @} 182 | */ 183 | 184 | /** @addtogroup STM32F4xx_System_Private_FunctionPrototypes 185 | * @{ 186 | */ 187 | 188 | static void SetSysClock(void); 189 | #ifdef DATA_IN_ExtSRAM 190 | static void SystemInit_ExtMemCtl(void); 191 | #endif /* DATA_IN_ExtSRAM */ 192 | 193 | /** 194 | * @} 195 | */ 196 | 197 | /** @addtogroup STM32F4xx_System_Private_Functions 198 | * @{ 199 | */ 200 | 201 | /** 202 | * @brief Setup the microcontroller system 203 | * Initialize the Embedded Flash Interface, the PLL and update the 204 | * SystemFrequency variable. 205 | * @param None 206 | * @retval None 207 | */ 208 | void SystemInit(void) 209 | { 210 | /* FPU settings ------------------------------------------------------------*/ 211 | #if (__FPU_PRESENT == 1) && (__FPU_USED == 1) 212 | SCB->CPACR |= ((3UL << 10*2)|(3UL << 11*2)); /* set CP10 and CP11 Full Access */ 213 | #endif 214 | 215 | /* Reset the RCC clock configuration to the default reset state ------------*/ 216 | /* Set HSION bit */ 217 | RCC->CR |= (uint32_t)0x00000001; 218 | 219 | /* Reset CFGR register */ 220 | RCC->CFGR = 0x00000000; 221 | 222 | /* Reset HSEON, CSSON and PLLON bits */ 223 | RCC->CR &= (uint32_t)0xFEF6FFFF; 224 | 225 | /* Reset PLLCFGR register */ 226 | RCC->PLLCFGR = 0x24003010; 227 | 228 | /* Reset HSEBYP bit */ 229 | RCC->CR &= (uint32_t)0xFFFBFFFF; 230 | 231 | /* Disable all interrupts */ 232 | RCC->CIR = 0x00000000; 233 | 234 | #ifdef DATA_IN_ExtSRAM 235 | SystemInit_ExtMemCtl(); 236 | #endif /* DATA_IN_ExtSRAM */ 237 | 238 | /* Configure the System clock source, PLL Multiplier and Divider factors, 239 | AHB/APBx prescalers and Flash settings ----------------------------------*/ 240 | SetSysClock(); 241 | 242 | /* Configure the Vector Table location add offset address ------------------*/ 243 | #ifdef VECT_TAB_SRAM 244 | SCB->VTOR = SRAM_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal SRAM */ 245 | #else 246 | SCB->VTOR = FLASH_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal FLASH */ 247 | #endif 248 | } 249 | 250 | /** 251 | * @brief Update SystemCoreClock variable according to Clock Register Values. 252 | * The SystemCoreClock variable contains the core clock (HCLK), it can 253 | * be used by the user application to setup the SysTick timer or configure 254 | * other parameters. 255 | * 256 | * @note Each time the core clock (HCLK) changes, this function must be called 257 | * to update SystemCoreClock variable value. Otherwise, any configuration 258 | * based on this variable will be incorrect. 259 | * 260 | * @note - The system frequency computed by this function is not the real 261 | * frequency in the chip. It is calculated based on the predefined 262 | * constant and the selected clock source: 263 | * 264 | * - If SYSCLK source is HSI, SystemCoreClock will contain the HSI_VALUE(*) 265 | * 266 | * - If SYSCLK source is HSE, SystemCoreClock will contain the HSE_VALUE(**) 267 | * 268 | * - If SYSCLK source is PLL, SystemCoreClock will contain the HSE_VALUE(**) 269 | * or HSI_VALUE(*) multiplied/divided by the PLL factors. 270 | * 271 | * (*) HSI_VALUE is a constant defined in stm32f4xx.h file (default value 272 | * 16 MHz) but the real value may vary depending on the variations 273 | * in voltage and temperature. 274 | * 275 | * (**) HSE_VALUE is a constant defined in stm32f4xx.h file (default value 276 | * 25 MHz), user has to ensure that HSE_VALUE is same as the real 277 | * frequency of the crystal used. Otherwise, this function may 278 | * have wrong result. 279 | * 280 | * - The result of this function could be not correct when using fractional 281 | * value for HSE crystal. 282 | * 283 | * @param None 284 | * @retval None 285 | */ 286 | void SystemCoreClockUpdate(void) 287 | { 288 | uint32_t tmp = 0, pllvco = 0, pllp = 2, pllsource = 0, pllm = 2; 289 | 290 | /* Get SYSCLK source -------------------------------------------------------*/ 291 | tmp = RCC->CFGR & RCC_CFGR_SWS; 292 | 293 | switch (tmp) 294 | { 295 | case 0x00: /* HSI used as system clock source */ 296 | SystemCoreClock = HSI_VALUE; 297 | break; 298 | case 0x04: /* HSE used as system clock source */ 299 | SystemCoreClock = HSE_VALUE; 300 | break; 301 | case 0x08: /* PLL used as system clock source */ 302 | 303 | /* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLL_M) * PLL_N 304 | SYSCLK = PLL_VCO / PLL_P 305 | */ 306 | pllsource = (RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) >> 22; 307 | pllm = RCC->PLLCFGR & RCC_PLLCFGR_PLLM; 308 | 309 | if (pllsource != 0) 310 | { 311 | /* HSE used as PLL clock source */ 312 | pllvco = (HSE_VALUE / pllm) * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6); 313 | } 314 | else 315 | { 316 | /* HSI used as PLL clock source */ 317 | pllvco = (HSI_VALUE / pllm) * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6); 318 | } 319 | 320 | pllp = (((RCC->PLLCFGR & RCC_PLLCFGR_PLLP) >>16) + 1 ) *2; 321 | SystemCoreClock = pllvco/pllp; 322 | break; 323 | default: 324 | SystemCoreClock = HSI_VALUE; 325 | break; 326 | } 327 | /* Compute HCLK frequency --------------------------------------------------*/ 328 | /* Get HCLK prescaler */ 329 | tmp = AHBPrescTable[((RCC->CFGR & RCC_CFGR_HPRE) >> 4)]; 330 | /* HCLK frequency */ 331 | SystemCoreClock >>= tmp; 332 | } 333 | 334 | /** 335 | * @brief Configures the System clock source, PLL Multiplier and Divider factors, 336 | * AHB/APBx prescalers and Flash settings 337 | * @Note This function should be called only once the RCC clock configuration 338 | * is reset to the default reset state (done in SystemInit() function). 339 | * @param None 340 | * @retval None 341 | */ 342 | static void SetSysClock(void) 343 | { 344 | /******************************************************************************/ 345 | /* PLL (clocked by HSE) used as System clock source */ 346 | /******************************************************************************/ 347 | __IO uint32_t StartUpCounter = 0, HSEStatus = 0; 348 | 349 | /* Enable HSE */ 350 | RCC->CR |= ((uint32_t)RCC_CR_HSEON); 351 | 352 | /* Wait till HSE is ready and if Time out is reached exit */ 353 | do 354 | { 355 | HSEStatus = RCC->CR & RCC_CR_HSERDY; 356 | StartUpCounter++; 357 | } while((HSEStatus == 0) && (StartUpCounter != HSE_STARTUP_TIMEOUT)); 358 | 359 | if ((RCC->CR & RCC_CR_HSERDY) != RESET) 360 | { 361 | HSEStatus = (uint32_t)0x01; 362 | } 363 | else 364 | { 365 | HSEStatus = (uint32_t)0x00; 366 | } 367 | 368 | if (HSEStatus == (uint32_t)0x01) 369 | { 370 | /* Select regulator voltage output Scale 1 mode, System frequency up to 168 MHz */ 371 | RCC->APB1ENR |= RCC_APB1ENR_PWREN; 372 | PWR->CR |= PWR_CR_VOS; 373 | 374 | /* HCLK = SYSCLK / 1*/ 375 | RCC->CFGR |= RCC_CFGR_HPRE_DIV1; 376 | 377 | /* PCLK2 = HCLK / 2*/ 378 | RCC->CFGR |= RCC_CFGR_PPRE2_DIV2; 379 | 380 | /* PCLK1 = HCLK / 4*/ 381 | RCC->CFGR |= RCC_CFGR_PPRE1_DIV4; 382 | 383 | /* Configure the main PLL */ 384 | RCC->PLLCFGR = PLL_M | (PLL_N << 6) | (((PLL_P >> 1) -1) << 16) | 385 | (RCC_PLLCFGR_PLLSRC_HSE) | (PLL_Q << 24); 386 | 387 | /* Enable the main PLL */ 388 | RCC->CR |= RCC_CR_PLLON; 389 | 390 | /* Wait till the main PLL is ready */ 391 | while((RCC->CR & RCC_CR_PLLRDY) == 0) 392 | { 393 | } 394 | 395 | /* Configure Flash prefetch, Instruction cache, Data cache and wait state */ 396 | FLASH->ACR = FLASH_ACR_ICEN |FLASH_ACR_DCEN |FLASH_ACR_LATENCY_5WS; 397 | 398 | /* Select the main PLL as system clock source */ 399 | RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_SW)); 400 | RCC->CFGR |= RCC_CFGR_SW_PLL; 401 | 402 | /* Wait till the main PLL is used as system clock source */ 403 | while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS ) != RCC_CFGR_SWS_PLL); 404 | { 405 | } 406 | } 407 | else 408 | { /* If HSE fails to start-up, the application will have wrong clock 409 | configuration. User can add here some code to deal with this error */ 410 | } 411 | 412 | } 413 | 414 | /** 415 | * @brief Setup the external memory controller. Called in startup_stm32f4xx.s 416 | * before jump to __main 417 | * @param None 418 | * @retval None 419 | */ 420 | #ifdef DATA_IN_ExtSRAM 421 | /** 422 | * @brief Setup the external memory controller. 423 | * Called in startup_stm32f4xx.s before jump to main. 424 | * This function configures the external SRAM mounted on STM324xG_EVAL board 425 | * This SRAM will be used as program data memory (including heap and stack). 426 | * @param None 427 | * @retval None 428 | */ 429 | void SystemInit_ExtMemCtl(void) 430 | { 431 | /*-- GPIOs Configuration -----------------------------------------------------*/ 432 | /* 433 | +-------------------+--------------------+------------------+------------------+ 434 | + SRAM pins assignment + 435 | +-------------------+--------------------+------------------+------------------+ 436 | | PD0 <-> FSMC_D2 | PE0 <-> FSMC_NBL0 | PF0 <-> FSMC_A0 | PG0 <-> FSMC_A10 | 437 | | PD1 <-> FSMC_D3 | PE1 <-> FSMC_NBL1 | PF1 <-> FSMC_A1 | PG1 <-> FSMC_A11 | 438 | | PD4 <-> FSMC_NOE | PE3 <-> FSMC_A19 | PF2 <-> FSMC_A2 | PG2 <-> FSMC_A12 | 439 | | PD5 <-> FSMC_NWE | PE4 <-> FSMC_A20 | PF3 <-> FSMC_A3 | PG3 <-> FSMC_A13 | 440 | | PD8 <-> FSMC_D13 | PE7 <-> FSMC_D4 | PF4 <-> FSMC_A4 | PG4 <-> FSMC_A14 | 441 | | PD9 <-> FSMC_D14 | PE8 <-> FSMC_D5 | PF5 <-> FSMC_A5 | PG5 <-> FSMC_A15 | 442 | | PD10 <-> FSMC_D15 | PE9 <-> FSMC_D6 | PF12 <-> FSMC_A6 | PG9 <-> FSMC_NE2 | 443 | | PD11 <-> FSMC_A16 | PE10 <-> FSMC_D7 | PF13 <-> FSMC_A7 |------------------+ 444 | | PD12 <-> FSMC_A17 | PE11 <-> FSMC_D8 | PF14 <-> FSMC_A8 | 445 | | PD13 <-> FSMC_A18 | PE12 <-> FSMC_D9 | PF15 <-> FSMC_A9 | 446 | | PD14 <-> FSMC_D0 | PE13 <-> FSMC_D10 |------------------+ 447 | | PD15 <-> FSMC_D1 | PE14 <-> FSMC_D11 | 448 | | | PE15 <-> FSMC_D12 | 449 | +-------------------+--------------------+ 450 | */ 451 | /* Enable GPIOD, GPIOE, GPIOF and GPIOG interface clock */ 452 | RCC->AHB1ENR = 0x00000078; 453 | 454 | /* Connect PDx pins to FSMC Alternate function */ 455 | GPIOD->AFR[0] = 0x00cc00cc; 456 | GPIOD->AFR[1] = 0xcc0ccccc; 457 | /* Configure PDx pins in Alternate function mode */ 458 | GPIOD->MODER = 0xaaaa0a0a; 459 | /* Configure PDx pins speed to 100 MHz */ 460 | GPIOD->OSPEEDR = 0xffff0f0f; 461 | /* Configure PDx pins Output type to push-pull */ 462 | GPIOD->OTYPER = 0x00000000; 463 | /* No pull-up, pull-down for PDx pins */ 464 | GPIOD->PUPDR = 0x00000000; 465 | 466 | /* Connect PEx pins to FSMC Alternate function */ 467 | GPIOE->AFR[0] = 0xc00cc0cc; 468 | GPIOE->AFR[1] = 0xcccccccc; 469 | /* Configure PEx pins in Alternate function mode */ 470 | GPIOE->MODER = 0xaaaa828a; 471 | /* Configure PEx pins speed to 100 MHz */ 472 | GPIOE->OSPEEDR = 0xffffc3cf; 473 | /* Configure PEx pins Output type to push-pull */ 474 | GPIOE->OTYPER = 0x00000000; 475 | /* No pull-up, pull-down for PEx pins */ 476 | GPIOE->PUPDR = 0x00000000; 477 | 478 | /* Connect PFx pins to FSMC Alternate function */ 479 | GPIOF->AFR[0] = 0x00cccccc; 480 | GPIOF->AFR[1] = 0xcccc0000; 481 | /* Configure PFx pins in Alternate function mode */ 482 | GPIOF->MODER = 0xaa000aaa; 483 | /* Configure PFx pins speed to 100 MHz */ 484 | GPIOF->OSPEEDR = 0xff000fff; 485 | /* Configure PFx pins Output type to push-pull */ 486 | GPIOF->OTYPER = 0x00000000; 487 | /* No pull-up, pull-down for PFx pins */ 488 | GPIOF->PUPDR = 0x00000000; 489 | 490 | /* Connect PGx pins to FSMC Alternate function */ 491 | GPIOG->AFR[0] = 0x00cccccc; 492 | GPIOG->AFR[1] = 0x000000c0; 493 | /* Configure PGx pins in Alternate function mode */ 494 | GPIOG->MODER = 0x00080aaa; 495 | /* Configure PGx pins speed to 100 MHz */ 496 | GPIOG->OSPEEDR = 0x000c0fff; 497 | /* Configure PGx pins Output type to push-pull */ 498 | GPIOG->OTYPER = 0x00000000; 499 | /* No pull-up, pull-down for PGx pins */ 500 | GPIOG->PUPDR = 0x00000000; 501 | 502 | /*-- FSMC Configuration ------------------------------------------------------*/ 503 | /* Enable the FSMC interface clock */ 504 | RCC->AHB3ENR = 0x00000001; 505 | 506 | /* Configure and enable Bank1_SRAM2 */ 507 | FSMC_Bank1->BTCR[2] = 0x00001015; 508 | FSMC_Bank1->BTCR[3] = 0x00010603; 509 | FSMC_Bank1E->BWTR[2] = 0x0fffffff; 510 | /* 511 | Bank1_SRAM2 is configured as follow: 512 | 513 | p.FSMC_AddressSetupTime = 3; 514 | p.FSMC_AddressHoldTime = 0; 515 | p.FSMC_DataSetupTime = 6; 516 | p.FSMC_BusTurnAroundDuration = 1; 517 | p.FSMC_CLKDivision = 0; 518 | p.FSMC_DataLatency = 0; 519 | p.FSMC_AccessMode = FSMC_AccessMode_A; 520 | 521 | FSMC_NORSRAMInitStructure.FSMC_Bank = FSMC_Bank1_NORSRAM2; 522 | FSMC_NORSRAMInitStructure.FSMC_DataAddressMux = FSMC_DataAddressMux_Disable; 523 | FSMC_NORSRAMInitStructure.FSMC_MemoryType = FSMC_MemoryType_PSRAM; 524 | FSMC_NORSRAMInitStructure.FSMC_MemoryDataWidth = FSMC_MemoryDataWidth_16b; 525 | FSMC_NORSRAMInitStructure.FSMC_BurstAccessMode = FSMC_BurstAccessMode_Disable; 526 | FSMC_NORSRAMInitStructure.FSMC_AsynchronousWait = FSMC_AsynchronousWait_Disable; 527 | FSMC_NORSRAMInitStructure.FSMC_WaitSignalPolarity = FSMC_WaitSignalPolarity_Low; 528 | FSMC_NORSRAMInitStructure.FSMC_WrapMode = FSMC_WrapMode_Disable; 529 | FSMC_NORSRAMInitStructure.FSMC_WaitSignalActive = FSMC_WaitSignalActive_BeforeWaitState; 530 | FSMC_NORSRAMInitStructure.FSMC_WriteOperation = FSMC_WriteOperation_Enable; 531 | FSMC_NORSRAMInitStructure.FSMC_WaitSignal = FSMC_WaitSignal_Disable; 532 | FSMC_NORSRAMInitStructure.FSMC_ExtendedMode = FSMC_ExtendedMode_Disable; 533 | FSMC_NORSRAMInitStructure.FSMC_WriteBurst = FSMC_WriteBurst_Disable; 534 | FSMC_NORSRAMInitStructure.FSMC_ReadWriteTimingStruct = &p; 535 | FSMC_NORSRAMInitStructure.FSMC_WriteTimingStruct = &p; 536 | */ 537 | 538 | } 539 | #endif /* DATA_IN_ExtSRAM */ 540 | 541 | 542 | /** 543 | * @} 544 | */ 545 | 546 | /** 547 | * @} 548 | */ 549 | 550 | /** 551 | * @} 552 | */ 553 | /******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ 554 | -------------------------------------------------------------------------------- /src/cmsis/core_cm4_simd.h: -------------------------------------------------------------------------------- 1 | /**************************************************************************//** 2 | * @file core_cm4_simd.h 3 | * @brief CMSIS Cortex-M4 SIMD Header File 4 | * @version V2.10 5 | * @date 19. July 2011 6 | * 7 | * @note 8 | * Copyright (C) 2010-2011 ARM Limited. All rights reserved. 9 | * 10 | * @par 11 | * ARM Limited (ARM) is supplying this software for use with Cortex-M 12 | * processor based microcontrollers. This file can be freely distributed 13 | * within development tools that are supporting such ARM based processors. 14 | * 15 | * @par 16 | * THIS SOFTWARE IS PROVIDED "AS IS". NO WARRANTIES, WHETHER EXPRESS, IMPLIED 17 | * OR STATUTORY, INCLUDING, BUT NOT LIMITED TO, IMPLIED WARRANTIES OF 18 | * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE APPLY TO THIS SOFTWARE. 19 | * ARM SHALL NOT, IN ANY CIRCUMSTANCES, BE LIABLE FOR SPECIAL, INCIDENTAL, OR 20 | * CONSEQUENTIAL DAMAGES, FOR ANY REASON WHATSOEVER. 21 | * 22 | ******************************************************************************/ 23 | 24 | #ifdef __cplusplus 25 | extern "C" { 26 | #endif 27 | 28 | #ifndef __CORE_CM4_SIMD_H 29 | #define __CORE_CM4_SIMD_H 30 | 31 | 32 | /******************************************************************************* 33 | * Hardware Abstraction Layer 34 | ******************************************************************************/ 35 | 36 | 37 | /* ################### Compiler specific Intrinsics ########################### */ 38 | /** \defgroup CMSIS_SIMD_intrinsics CMSIS SIMD Intrinsics 39 | Access to dedicated SIMD instructions 40 | @{ 41 | */ 42 | 43 | #if defined ( __CC_ARM ) /*------------------RealView Compiler -----------------*/ 44 | /* ARM armcc specific functions */ 45 | 46 | /*------ CM4 SOMD Intrinsics -----------------------------------------------------*/ 47 | #define __SADD8 __sadd8 48 | #define __QADD8 __qadd8 49 | #define __SHADD8 __shadd8 50 | #define __UADD8 __uadd8 51 | #define __UQADD8 __uqadd8 52 | #define __UHADD8 __uhadd8 53 | #define __SSUB8 __ssub8 54 | #define __QSUB8 __qsub8 55 | #define __SHSUB8 __shsub8 56 | #define __USUB8 __usub8 57 | #define __UQSUB8 __uqsub8 58 | #define __UHSUB8 __uhsub8 59 | #define __SADD16 __sadd16 60 | #define __QADD16 __qadd16 61 | #define __SHADD16 __shadd16 62 | #define __UADD16 __uadd16 63 | #define __UQADD16 __uqadd16 64 | #define __UHADD16 __uhadd16 65 | #define __SSUB16 __ssub16 66 | #define __QSUB16 __qsub16 67 | #define __SHSUB16 __shsub16 68 | #define __USUB16 __usub16 69 | #define __UQSUB16 __uqsub16 70 | #define __UHSUB16 __uhsub16 71 | #define __SASX __sasx 72 | #define __QASX __qasx 73 | #define __SHASX __shasx 74 | #define __UASX __uasx 75 | #define __UQASX __uqasx 76 | #define __UHASX __uhasx 77 | #define __SSAX __ssax 78 | #define __QSAX __qsax 79 | #define __SHSAX __shsax 80 | #define __USAX __usax 81 | #define __UQSAX __uqsax 82 | #define __UHSAX __uhsax 83 | #define __USAD8 __usad8 84 | #define __USADA8 __usada8 85 | #define __SSAT16 __ssat16 86 | #define __USAT16 __usat16 87 | #define __UXTB16 __uxtb16 88 | #define __UXTAB16 __uxtab16 89 | #define __SXTB16 __sxtb16 90 | #define __SXTAB16 __sxtab16 91 | #define __SMUAD __smuad 92 | #define __SMUADX __smuadx 93 | #define __SMLAD __smlad 94 | #define __SMLADX __smladx 95 | #define __SMLALD __smlald 96 | #define __SMLALDX __smlaldx 97 | #define __SMUSD __smusd 98 | #define __SMUSDX __smusdx 99 | #define __SMLSD __smlsd 100 | #define __SMLSDX __smlsdx 101 | #define __SMLSLD __smlsld 102 | #define __SMLSLDX __smlsldx 103 | #define __SEL __sel 104 | #define __QADD __qadd 105 | #define __QSUB __qsub 106 | 107 | #define __PKHBT(ARG1,ARG2,ARG3) ( ((((uint32_t)(ARG1)) ) & 0x0000FFFFUL) | \ 108 | ((((uint32_t)(ARG2)) << (ARG3)) & 0xFFFF0000UL) ) 109 | 110 | #define __PKHTB(ARG1,ARG2,ARG3) ( ((((uint32_t)(ARG1)) ) & 0xFFFF0000UL) | \ 111 | ((((uint32_t)(ARG2)) >> (ARG3)) & 0x0000FFFFUL) ) 112 | 113 | 114 | /*-- End CM4 SIMD Intrinsics -----------------------------------------------------*/ 115 | 116 | 117 | 118 | #elif defined ( __ICCARM__ ) /*------------------ ICC Compiler -------------------*/ 119 | /* IAR iccarm specific functions */ 120 | 121 | #include 122 | 123 | /*------ CM4 SIMDDSP Intrinsics -----------------------------------------------------*/ 124 | /* intrinsic __SADD8 see intrinsics.h */ 125 | /* intrinsic __QADD8 see intrinsics.h */ 126 | /* intrinsic __SHADD8 see intrinsics.h */ 127 | /* intrinsic __UADD8 see intrinsics.h */ 128 | /* intrinsic __UQADD8 see intrinsics.h */ 129 | /* intrinsic __UHADD8 see intrinsics.h */ 130 | /* intrinsic __SSUB8 see intrinsics.h */ 131 | /* intrinsic __QSUB8 see intrinsics.h */ 132 | /* intrinsic __SHSUB8 see intrinsics.h */ 133 | /* intrinsic __USUB8 see intrinsics.h */ 134 | /* intrinsic __UQSUB8 see intrinsics.h */ 135 | /* intrinsic __UHSUB8 see intrinsics.h */ 136 | /* intrinsic __SADD16 see intrinsics.h */ 137 | /* intrinsic __QADD16 see intrinsics.h */ 138 | /* intrinsic __SHADD16 see intrinsics.h */ 139 | /* intrinsic __UADD16 see intrinsics.h */ 140 | /* intrinsic __UQADD16 see intrinsics.h */ 141 | /* intrinsic __UHADD16 see intrinsics.h */ 142 | /* intrinsic __SSUB16 see intrinsics.h */ 143 | /* intrinsic __QSUB16 see intrinsics.h */ 144 | /* intrinsic __SHSUB16 see intrinsics.h */ 145 | /* intrinsic __USUB16 see intrinsics.h */ 146 | /* intrinsic __UQSUB16 see intrinsics.h */ 147 | /* intrinsic __UHSUB16 see intrinsics.h */ 148 | /* intrinsic __SASX see intrinsics.h */ 149 | /* intrinsic __QASX see intrinsics.h */ 150 | /* intrinsic __SHASX see intrinsics.h */ 151 | /* intrinsic __UASX see intrinsics.h */ 152 | /* intrinsic __UQASX see intrinsics.h */ 153 | /* intrinsic __UHASX see intrinsics.h */ 154 | /* intrinsic __SSAX see intrinsics.h */ 155 | /* intrinsic __QSAX see intrinsics.h */ 156 | /* intrinsic __SHSAX see intrinsics.h */ 157 | /* intrinsic __USAX see intrinsics.h */ 158 | /* intrinsic __UQSAX see intrinsics.h */ 159 | /* intrinsic __UHSAX see intrinsics.h */ 160 | /* intrinsic __USAD8 see intrinsics.h */ 161 | /* intrinsic __USADA8 see intrinsics.h */ 162 | /* intrinsic __SSAT16 see intrinsics.h */ 163 | /* intrinsic __USAT16 see intrinsics.h */ 164 | /* intrinsic __UXTB16 see intrinsics.h */ 165 | /* intrinsic __SXTB16 see intrinsics.h */ 166 | /* intrinsic __UXTAB16 see intrinsics.h */ 167 | /* intrinsic __SXTAB16 see intrinsics.h */ 168 | /* intrinsic __SMUAD see intrinsics.h */ 169 | /* intrinsic __SMUADX see intrinsics.h */ 170 | /* intrinsic __SMLAD see intrinsics.h */ 171 | /* intrinsic __SMLADX see intrinsics.h */ 172 | /* intrinsic __SMLALD see intrinsics.h */ 173 | /* intrinsic __SMLALDX see intrinsics.h */ 174 | /* intrinsic __SMUSD see intrinsics.h */ 175 | /* intrinsic __SMUSDX see intrinsics.h */ 176 | /* intrinsic __SMLSD see intrinsics.h */ 177 | /* intrinsic __SMLSDX see intrinsics.h */ 178 | /* intrinsic __SMLSLD see intrinsics.h */ 179 | /* intrinsic __SMLSLDX see intrinsics.h */ 180 | /* intrinsic __SEL see intrinsics.h */ 181 | /* intrinsic __QADD see intrinsics.h */ 182 | /* intrinsic __QSUB see intrinsics.h */ 183 | /* intrinsic __PKHBT see intrinsics.h */ 184 | /* intrinsic __PKHTB see intrinsics.h */ 185 | 186 | /*-- End CM4 SIMD Intrinsics -----------------------------------------------------*/ 187 | 188 | 189 | 190 | #elif defined ( __GNUC__ ) /*------------------ GNU Compiler ---------------------*/ 191 | /* GNU gcc specific functions */ 192 | 193 | /*------ CM4 SIMD Intrinsics -----------------------------------------------------*/ 194 | __attribute__( ( always_inline ) ) static __INLINE uint32_t __SADD8(uint32_t op1, uint32_t op2) 195 | { 196 | uint32_t result; 197 | 198 | __ASM volatile ("sadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); 199 | return(result); 200 | } 201 | 202 | __attribute__( ( always_inline ) ) static __INLINE uint32_t __QADD8(uint32_t op1, uint32_t op2) 203 | { 204 | uint32_t result; 205 | 206 | __ASM volatile ("qadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); 207 | return(result); 208 | } 209 | 210 | __attribute__( ( always_inline ) ) static __INLINE uint32_t __SHADD8(uint32_t op1, uint32_t op2) 211 | { 212 | uint32_t result; 213 | 214 | __ASM volatile ("shadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); 215 | return(result); 216 | } 217 | 218 | __attribute__( ( always_inline ) ) static __INLINE uint32_t __UADD8(uint32_t op1, uint32_t op2) 219 | { 220 | uint32_t result; 221 | 222 | __ASM volatile ("uadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); 223 | return(result); 224 | } 225 | 226 | __attribute__( ( always_inline ) ) static __INLINE uint32_t __UQADD8(uint32_t op1, uint32_t op2) 227 | { 228 | uint32_t result; 229 | 230 | __ASM volatile ("uqadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); 231 | return(result); 232 | } 233 | 234 | __attribute__( ( always_inline ) ) static __INLINE uint32_t __UHADD8(uint32_t op1, uint32_t op2) 235 | { 236 | uint32_t result; 237 | 238 | __ASM volatile ("uhadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); 239 | return(result); 240 | } 241 | 242 | 243 | __attribute__( ( always_inline ) ) static __INLINE uint32_t __SSUB8(uint32_t op1, uint32_t op2) 244 | { 245 | uint32_t result; 246 | 247 | __ASM volatile ("ssub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); 248 | return(result); 249 | } 250 | 251 | __attribute__( ( always_inline ) ) static __INLINE uint32_t __QSUB8(uint32_t op1, uint32_t op2) 252 | { 253 | uint32_t result; 254 | 255 | __ASM volatile ("qsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); 256 | return(result); 257 | } 258 | 259 | __attribute__( ( always_inline ) ) static __INLINE uint32_t __SHSUB8(uint32_t op1, uint32_t op2) 260 | { 261 | uint32_t result; 262 | 263 | __ASM volatile ("shsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); 264 | return(result); 265 | } 266 | 267 | __attribute__( ( always_inline ) ) static __INLINE uint32_t __USUB8(uint32_t op1, uint32_t op2) 268 | { 269 | uint32_t result; 270 | 271 | __ASM volatile ("usub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); 272 | return(result); 273 | } 274 | 275 | __attribute__( ( always_inline ) ) static __INLINE uint32_t __UQSUB8(uint32_t op1, uint32_t op2) 276 | { 277 | uint32_t result; 278 | 279 | __ASM volatile ("uqsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); 280 | return(result); 281 | } 282 | 283 | __attribute__( ( always_inline ) ) static __INLINE uint32_t __UHSUB8(uint32_t op1, uint32_t op2) 284 | { 285 | uint32_t result; 286 | 287 | __ASM volatile ("uhsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); 288 | return(result); 289 | } 290 | 291 | 292 | __attribute__( ( always_inline ) ) static __INLINE uint32_t __SADD16(uint32_t op1, uint32_t op2) 293 | { 294 | uint32_t result; 295 | 296 | __ASM volatile ("sadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); 297 | return(result); 298 | } 299 | 300 | __attribute__( ( always_inline ) ) static __INLINE uint32_t __QADD16(uint32_t op1, uint32_t op2) 301 | { 302 | uint32_t result; 303 | 304 | __ASM volatile ("qadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); 305 | return(result); 306 | } 307 | 308 | __attribute__( ( always_inline ) ) static __INLINE uint32_t __SHADD16(uint32_t op1, uint32_t op2) 309 | { 310 | uint32_t result; 311 | 312 | __ASM volatile ("shadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); 313 | return(result); 314 | } 315 | 316 | __attribute__( ( always_inline ) ) static __INLINE uint32_t __UADD16(uint32_t op1, uint32_t op2) 317 | { 318 | uint32_t result; 319 | 320 | __ASM volatile ("uadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); 321 | return(result); 322 | } 323 | 324 | __attribute__( ( always_inline ) ) static __INLINE uint32_t __UQADD16(uint32_t op1, uint32_t op2) 325 | { 326 | uint32_t result; 327 | 328 | __ASM volatile ("uqadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); 329 | return(result); 330 | } 331 | 332 | __attribute__( ( always_inline ) ) static __INLINE uint32_t __UHADD16(uint32_t op1, uint32_t op2) 333 | { 334 | uint32_t result; 335 | 336 | __ASM volatile ("uhadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); 337 | return(result); 338 | } 339 | 340 | __attribute__( ( always_inline ) ) static __INLINE uint32_t __SSUB16(uint32_t op1, uint32_t op2) 341 | { 342 | uint32_t result; 343 | 344 | __ASM volatile ("ssub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); 345 | return(result); 346 | } 347 | 348 | __attribute__( ( always_inline ) ) static __INLINE uint32_t __QSUB16(uint32_t op1, uint32_t op2) 349 | { 350 | uint32_t result; 351 | 352 | __ASM volatile ("qsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); 353 | return(result); 354 | } 355 | 356 | __attribute__( ( always_inline ) ) static __INLINE uint32_t __SHSUB16(uint32_t op1, uint32_t op2) 357 | { 358 | uint32_t result; 359 | 360 | __ASM volatile ("shsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); 361 | return(result); 362 | } 363 | 364 | __attribute__( ( always_inline ) ) static __INLINE uint32_t __USUB16(uint32_t op1, uint32_t op2) 365 | { 366 | uint32_t result; 367 | 368 | __ASM volatile ("usub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); 369 | return(result); 370 | } 371 | 372 | __attribute__( ( always_inline ) ) static __INLINE uint32_t __UQSUB16(uint32_t op1, uint32_t op2) 373 | { 374 | uint32_t result; 375 | 376 | __ASM volatile ("uqsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); 377 | return(result); 378 | } 379 | 380 | __attribute__( ( always_inline ) ) static __INLINE uint32_t __UHSUB16(uint32_t op1, uint32_t op2) 381 | { 382 | uint32_t result; 383 | 384 | __ASM volatile ("uhsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); 385 | return(result); 386 | } 387 | 388 | __attribute__( ( always_inline ) ) static __INLINE uint32_t __SASX(uint32_t op1, uint32_t op2) 389 | { 390 | uint32_t result; 391 | 392 | __ASM volatile ("sasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); 393 | return(result); 394 | } 395 | 396 | __attribute__( ( always_inline ) ) static __INLINE uint32_t __QASX(uint32_t op1, uint32_t op2) 397 | { 398 | uint32_t result; 399 | 400 | __ASM volatile ("qasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); 401 | return(result); 402 | } 403 | 404 | __attribute__( ( always_inline ) ) static __INLINE uint32_t __SHASX(uint32_t op1, uint32_t op2) 405 | { 406 | uint32_t result; 407 | 408 | __ASM volatile ("shasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); 409 | return(result); 410 | } 411 | 412 | __attribute__( ( always_inline ) ) static __INLINE uint32_t __UASX(uint32_t op1, uint32_t op2) 413 | { 414 | uint32_t result; 415 | 416 | __ASM volatile ("uasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); 417 | return(result); 418 | } 419 | 420 | __attribute__( ( always_inline ) ) static __INLINE uint32_t __UQASX(uint32_t op1, uint32_t op2) 421 | { 422 | uint32_t result; 423 | 424 | __ASM volatile ("uqasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); 425 | return(result); 426 | } 427 | 428 | __attribute__( ( always_inline ) ) static __INLINE uint32_t __UHASX(uint32_t op1, uint32_t op2) 429 | { 430 | uint32_t result; 431 | 432 | __ASM volatile ("uhasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); 433 | return(result); 434 | } 435 | 436 | __attribute__( ( always_inline ) ) static __INLINE uint32_t __SSAX(uint32_t op1, uint32_t op2) 437 | { 438 | uint32_t result; 439 | 440 | __ASM volatile ("ssax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); 441 | return(result); 442 | } 443 | 444 | __attribute__( ( always_inline ) ) static __INLINE uint32_t __QSAX(uint32_t op1, uint32_t op2) 445 | { 446 | uint32_t result; 447 | 448 | __ASM volatile ("qsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); 449 | return(result); 450 | } 451 | 452 | __attribute__( ( always_inline ) ) static __INLINE uint32_t __SHSAX(uint32_t op1, uint32_t op2) 453 | { 454 | uint32_t result; 455 | 456 | __ASM volatile ("shsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); 457 | return(result); 458 | } 459 | 460 | __attribute__( ( always_inline ) ) static __INLINE uint32_t __USAX(uint32_t op1, uint32_t op2) 461 | { 462 | uint32_t result; 463 | 464 | __ASM volatile ("usax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); 465 | return(result); 466 | } 467 | 468 | __attribute__( ( always_inline ) ) static __INLINE uint32_t __UQSAX(uint32_t op1, uint32_t op2) 469 | { 470 | uint32_t result; 471 | 472 | __ASM volatile ("uqsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); 473 | return(result); 474 | } 475 | 476 | __attribute__( ( always_inline ) ) static __INLINE uint32_t __UHSAX(uint32_t op1, uint32_t op2) 477 | { 478 | uint32_t result; 479 | 480 | __ASM volatile ("uhsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); 481 | return(result); 482 | } 483 | 484 | __attribute__( ( always_inline ) ) static __INLINE uint32_t __USAD8(uint32_t op1, uint32_t op2) 485 | { 486 | uint32_t result; 487 | 488 | __ASM volatile ("usad8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); 489 | return(result); 490 | } 491 | 492 | __attribute__( ( always_inline ) ) static __INLINE uint32_t __USADA8(uint32_t op1, uint32_t op2, uint32_t op3) 493 | { 494 | uint32_t result; 495 | 496 | __ASM volatile ("usada8 %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); 497 | return(result); 498 | } 499 | 500 | #define __SSAT16(ARG1,ARG2) \ 501 | ({ \ 502 | uint32_t __RES, __ARG1 = (ARG1); \ 503 | __ASM ("ssat16 %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \ 504 | __RES; \ 505 | }) 506 | 507 | #define __USAT16(ARG1,ARG2) \ 508 | ({ \ 509 | uint32_t __RES, __ARG1 = (ARG1); \ 510 | __ASM ("usat16 %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \ 511 | __RES; \ 512 | }) 513 | 514 | __attribute__( ( always_inline ) ) static __INLINE uint32_t __UXTB16(uint32_t op1) 515 | { 516 | uint32_t result; 517 | 518 | __ASM volatile ("uxtb16 %0, %1" : "=r" (result) : "r" (op1)); 519 | return(result); 520 | } 521 | 522 | __attribute__( ( always_inline ) ) static __INLINE uint32_t __UXTAB16(uint32_t op1, uint32_t op2) 523 | { 524 | uint32_t result; 525 | 526 | __ASM volatile ("uxtab16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); 527 | return(result); 528 | } 529 | 530 | __attribute__( ( always_inline ) ) static __INLINE uint32_t __SXTB16(uint32_t op1) 531 | { 532 | uint32_t result; 533 | 534 | __ASM volatile ("sxtb16 %0, %1" : "=r" (result) : "r" (op1)); 535 | return(result); 536 | } 537 | 538 | __attribute__( ( always_inline ) ) static __INLINE uint32_t __SXTAB16(uint32_t op1, uint32_t op2) 539 | { 540 | uint32_t result; 541 | 542 | __ASM volatile ("sxtab16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); 543 | return(result); 544 | } 545 | 546 | __attribute__( ( always_inline ) ) static __INLINE uint32_t __SMUAD (uint32_t op1, uint32_t op2) 547 | { 548 | uint32_t result; 549 | 550 | __ASM volatile ("smuad %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); 551 | return(result); 552 | } 553 | 554 | __attribute__( ( always_inline ) ) static __INLINE uint32_t __SMUADX (uint32_t op1, uint32_t op2) 555 | { 556 | uint32_t result; 557 | 558 | __ASM volatile ("smuadx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); 559 | return(result); 560 | } 561 | 562 | __attribute__( ( always_inline ) ) static __INLINE uint32_t __SMLAD (uint32_t op1, uint32_t op2, uint32_t op3) 563 | { 564 | uint32_t result; 565 | 566 | __ASM volatile ("smlad %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); 567 | return(result); 568 | } 569 | 570 | __attribute__( ( always_inline ) ) static __INLINE uint32_t __SMLADX (uint32_t op1, uint32_t op2, uint32_t op3) 571 | { 572 | uint32_t result; 573 | 574 | __ASM volatile ("smladx %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); 575 | return(result); 576 | } 577 | 578 | #define __SMLALD(ARG1,ARG2,ARG3) \ 579 | ({ \ 580 | uint32_t __ARG1 = (ARG1), __ARG2 = (ARG2), __ARG3_H = (uint32_t)((uint64_t)(ARG3) >> 32), __ARG3_L = (uint32_t)((uint64_t)(ARG3) & 0xFFFFFFFFUL); \ 581 | __ASM volatile ("smlald %0, %1, %2, %3" : "=r" (__ARG3_L), "=r" (__ARG3_H) : "r" (__ARG1), "r" (__ARG2), "0" (__ARG3_L), "1" (__ARG3_H) ); \ 582 | (uint64_t)(((uint64_t)__ARG3_H << 32) | __ARG3_L); \ 583 | }) 584 | 585 | #define __SMLALDX(ARG1,ARG2,ARG3) \ 586 | ({ \ 587 | uint32_t __ARG1 = (ARG1), __ARG2 = (ARG2), __ARG3_H = (uint32_t)((uint64_t)(ARG3) >> 32), __ARG3_L = (uint32_t)((uint64_t)(ARG3) & 0xFFFFFFFFUL); \ 588 | __ASM volatile ("smlaldx %0, %1, %2, %3" : "=r" (__ARG3_L), "=r" (__ARG3_H) : "r" (__ARG1), "r" (__ARG2), "0" (__ARG3_L), "1" (__ARG3_H) ); \ 589 | (uint64_t)(((uint64_t)__ARG3_H << 32) | __ARG3_L); \ 590 | }) 591 | 592 | __attribute__( ( always_inline ) ) static __INLINE uint32_t __SMUSD (uint32_t op1, uint32_t op2) 593 | { 594 | uint32_t result; 595 | 596 | __ASM volatile ("smusd %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); 597 | return(result); 598 | } 599 | 600 | __attribute__( ( always_inline ) ) static __INLINE uint32_t __SMUSDX (uint32_t op1, uint32_t op2) 601 | { 602 | uint32_t result; 603 | 604 | __ASM volatile ("smusdx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); 605 | return(result); 606 | } 607 | 608 | __attribute__( ( always_inline ) ) static __INLINE uint32_t __SMLSD (uint32_t op1, uint32_t op2, uint32_t op3) 609 | { 610 | uint32_t result; 611 | 612 | __ASM volatile ("smlsd %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); 613 | return(result); 614 | } 615 | 616 | __attribute__( ( always_inline ) ) static __INLINE uint32_t __SMLSDX (uint32_t op1, uint32_t op2, uint32_t op3) 617 | { 618 | uint32_t result; 619 | 620 | __ASM volatile ("smlsdx %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); 621 | return(result); 622 | } 623 | 624 | #define __SMLSLD(ARG1,ARG2,ARG3) \ 625 | ({ \ 626 | uint32_t __ARG1 = (ARG1), __ARG2 = (ARG2), __ARG3_H = (uint32_t)((ARG3) >> 32), __ARG3_L = (uint32_t)((ARG3) & 0xFFFFFFFFUL); \ 627 | __ASM volatile ("smlsld %0, %1, %2, %3" : "=r" (__ARG3_L), "=r" (__ARG3_H) : "r" (__ARG1), "r" (__ARG2), "0" (__ARG3_L), "1" (__ARG3_H) ); \ 628 | (uint64_t)(((uint64_t)__ARG3_H << 32) | __ARG3_L); \ 629 | }) 630 | 631 | #define __SMLSLDX(ARG1,ARG2,ARG3) \ 632 | ({ \ 633 | uint32_t __ARG1 = (ARG1), __ARG2 = (ARG2), __ARG3_H = (uint32_t)((ARG3) >> 32), __ARG3_L = (uint32_t)((ARG3) & 0xFFFFFFFFUL); \ 634 | __ASM volatile ("smlsldx %0, %1, %2, %3" : "=r" (__ARG3_L), "=r" (__ARG3_H) : "r" (__ARG1), "r" (__ARG2), "0" (__ARG3_L), "1" (__ARG3_H) ); \ 635 | (uint64_t)(((uint64_t)__ARG3_H << 32) | __ARG3_L); \ 636 | }) 637 | 638 | __attribute__( ( always_inline ) ) static __INLINE uint32_t __SEL (uint32_t op1, uint32_t op2) 639 | { 640 | uint32_t result; 641 | 642 | __ASM volatile ("sel %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); 643 | return(result); 644 | } 645 | 646 | __attribute__( ( always_inline ) ) static __INLINE uint32_t __QADD(uint32_t op1, uint32_t op2) 647 | { 648 | uint32_t result; 649 | 650 | __ASM volatile ("qadd %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); 651 | return(result); 652 | } 653 | 654 | __attribute__( ( always_inline ) ) static __INLINE uint32_t __QSUB(uint32_t op1, uint32_t op2) 655 | { 656 | uint32_t result; 657 | 658 | __ASM volatile ("qsub %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); 659 | return(result); 660 | } 661 | 662 | #define __PKHBT(ARG1,ARG2,ARG3) \ 663 | ({ \ 664 | uint32_t __RES, __ARG1 = (ARG1), __ARG2 = (ARG2); \ 665 | __ASM ("pkhbt %0, %1, %2, lsl %3" : "=r" (__RES) : "r" (__ARG1), "r" (__ARG2), "I" (ARG3) ); \ 666 | __RES; \ 667 | }) 668 | 669 | #define __PKHTB(ARG1,ARG2,ARG3) \ 670 | ({ \ 671 | uint32_t __RES, __ARG1 = (ARG1), __ARG2 = (ARG2); \ 672 | if (ARG3 == 0) \ 673 | __ASM ("pkhtb %0, %1, %2" : "=r" (__RES) : "r" (__ARG1), "r" (__ARG2) ); \ 674 | else \ 675 | __ASM ("pkhtb %0, %1, %2, asr %3" : "=r" (__RES) : "r" (__ARG1), "r" (__ARG2), "I" (ARG3) ); \ 676 | __RES; \ 677 | }) 678 | 679 | /*-- End CM4 SIMD Intrinsics -----------------------------------------------------*/ 680 | 681 | 682 | 683 | #elif defined ( __TASKING__ ) /*------------------ TASKING Compiler --------------*/ 684 | /* TASKING carm specific functions */ 685 | 686 | 687 | /*------ CM4 SIMD Intrinsics -----------------------------------------------------*/ 688 | /* not yet supported */ 689 | /*-- End CM4 SIMD Intrinsics -----------------------------------------------------*/ 690 | 691 | 692 | #endif 693 | 694 | /*@} end of group CMSIS_SIMD_intrinsics */ 695 | 696 | 697 | #endif /* __CORE_CM4_SIMD_H */ 698 | 699 | #ifdef __cplusplus 700 | } 701 | #endif 702 | -------------------------------------------------------------------------------- /src/cmsis/core_cm4.h: -------------------------------------------------------------------------------- 1 | /**************************************************************************//** 2 | * @file core_cm4.h 3 | * @brief CMSIS Cortex-M4 Core Peripheral Access Layer Header File 4 | * @version V2.10 5 | * @date 19. July 2011 6 | * 7 | * @note 8 | * Copyright (C) 2009-2011 ARM Limited. All rights reserved. 9 | * 10 | * @par 11 | * ARM Limited (ARM) is supplying this software for use with Cortex-M 12 | * processor based microcontrollers. This file can be freely distributed 13 | * within development tools that are supporting such ARM based processors. 14 | * 15 | * @par 16 | * THIS SOFTWARE IS PROVIDED "AS IS". NO WARRANTIES, WHETHER EXPRESS, IMPLIED 17 | * OR STATUTORY, INCLUDING, BUT NOT LIMITED TO, IMPLIED WARRANTIES OF 18 | * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE APPLY TO THIS SOFTWARE. 19 | * ARM SHALL NOT, IN ANY CIRCUMSTANCES, BE LIABLE FOR SPECIAL, INCIDENTAL, OR 20 | * CONSEQUENTIAL DAMAGES, FOR ANY REASON WHATSOEVER. 21 | * 22 | ******************************************************************************/ 23 | #if defined ( __ICCARM__ ) 24 | #pragma system_include /* treat file as system include file for MISRA check */ 25 | #endif 26 | 27 | #ifdef __cplusplus 28 | extern "C" { 29 | #endif 30 | 31 | #ifndef __CORE_CM4_H_GENERIC 32 | #define __CORE_CM4_H_GENERIC 33 | 34 | 35 | /** \mainpage CMSIS Cortex-M4 36 | 37 | This documentation describes the CMSIS Cortex-M Core Peripheral Access Layer. 38 | It consists of: 39 | 40 | - Cortex-M Core Register Definitions 41 | - Cortex-M functions 42 | - Cortex-M instructions 43 | - Cortex-M SIMD instructions 44 | 45 | The CMSIS Cortex-M4 Core Peripheral Access Layer contains C and assembly functions that ease 46 | access to the Cortex-M Core 47 | */ 48 | 49 | /** \defgroup CMSIS_MISRA_Exceptions CMSIS MISRA-C:2004 Compliance Exceptions 50 | CMSIS violates following MISRA-C2004 Rules: 51 | 52 | - Violates MISRA 2004 Required Rule 8.5, object/function definition in header file.
53 | Function definitions in header files are used to allow 'inlining'. 54 | 55 | - Violates MISRA 2004 Required Rule 18.4, declaration of union type or object of union type: '{...}'.
56 | Unions are used for effective representation of core registers. 57 | 58 | - Violates MISRA 2004 Advisory Rule 19.7, Function-like macro defined.
59 | Function-like macros are used to allow more efficient code. 60 | 61 | */ 62 | 63 | 64 | /******************************************************************************* 65 | * CMSIS definitions 66 | ******************************************************************************/ 67 | /** \defgroup CMSIS_core_definitions CMSIS Core Definitions 68 | This file defines all structures and symbols for CMSIS core: 69 | - CMSIS version number 70 | - Cortex-M core 71 | - Cortex-M core Revision Number 72 | @{ 73 | */ 74 | 75 | /* CMSIS CM4 definitions */ 76 | #define __CM4_CMSIS_VERSION_MAIN (0x02) /*!< [31:16] CMSIS HAL main version */ 77 | #define __CM4_CMSIS_VERSION_SUB (0x10) /*!< [15:0] CMSIS HAL sub version */ 78 | #define __CM4_CMSIS_VERSION ((__CM4_CMSIS_VERSION_MAIN << 16) | __CM4_CMSIS_VERSION_SUB) /*!< CMSIS HAL version number */ 79 | 80 | #define __CORTEX_M (0x04) /*!< Cortex core */ 81 | 82 | 83 | #if defined ( __CC_ARM ) 84 | #define __ASM __asm /*!< asm keyword for ARM Compiler */ 85 | #define __INLINE __inline /*!< inline keyword for ARM Compiler */ 86 | 87 | #elif defined ( __ICCARM__ ) 88 | #define __ASM __asm /*!< asm keyword for IAR Compiler */ 89 | #define __INLINE inline /*!< inline keyword for IAR Compiler. Only available in High optimization mode! */ 90 | 91 | #elif defined ( __GNUC__ ) 92 | #define __ASM __asm /*!< asm keyword for GNU Compiler */ 93 | #define __INLINE inline /*!< inline keyword for GNU Compiler */ 94 | 95 | #elif defined ( __TASKING__ ) 96 | #define __ASM __asm /*!< asm keyword for TASKING Compiler */ 97 | #define __INLINE inline /*!< inline keyword for TASKING Compiler */ 98 | 99 | #endif 100 | 101 | /*!< __FPU_USED to be checked prior to making use of FPU specific registers and functions */ 102 | #if defined ( __CC_ARM ) 103 | #if defined __TARGET_FPU_VFP 104 | #if (__FPU_PRESENT == 1) 105 | #define __FPU_USED 1 106 | #else 107 | #warning "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" 108 | #define __FPU_USED 0 109 | #endif 110 | #else 111 | #define __FPU_USED 0 112 | #endif 113 | 114 | #elif defined ( __ICCARM__ ) 115 | #if defined __ARMVFP__ 116 | #if (__FPU_PRESENT == 1) 117 | #define __FPU_USED 1 118 | #else 119 | #warning "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" 120 | #define __FPU_USED 0 121 | #endif 122 | #else 123 | #define __FPU_USED 0 124 | #endif 125 | 126 | #elif defined ( __GNUC__ ) 127 | #if defined (__VFP_FP__) && !defined(__SOFTFP__) 128 | #if (__FPU_PRESENT == 1) 129 | #define __FPU_USED 1 130 | #else 131 | #warning "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" 132 | #define __FPU_USED 0 133 | #endif 134 | #else 135 | #define __FPU_USED 0 136 | #endif 137 | 138 | #elif defined ( __TASKING__ ) 139 | /* add preprocessor checks to define __FPU_USED */ 140 | #define __FPU_USED 0 141 | #endif 142 | 143 | #include /*!< standard types definitions */ 144 | #include /*!< Core Instruction Access */ 145 | #include /*!< Core Function Access */ 146 | #include /*!< Compiler specific SIMD Intrinsics */ 147 | 148 | #endif /* __CORE_CM4_H_GENERIC */ 149 | 150 | #ifndef __CMSIS_GENERIC 151 | 152 | #ifndef __CORE_CM4_H_DEPENDANT 153 | #define __CORE_CM4_H_DEPENDANT 154 | 155 | /* check device defines and use defaults */ 156 | #if defined __CHECK_DEVICE_DEFINES 157 | #ifndef __CM4_REV 158 | #define __CM4_REV 0x0000 159 | #warning "__CM4_REV not defined in device header file; using default!" 160 | #endif 161 | 162 | #ifndef __FPU_PRESENT 163 | #define __FPU_PRESENT 0 164 | #warning "__FPU_PRESENT not defined in device header file; using default!" 165 | #endif 166 | 167 | #ifndef __MPU_PRESENT 168 | #define __MPU_PRESENT 0 169 | #warning "__MPU_PRESENT not defined in device header file; using default!" 170 | #endif 171 | 172 | #ifndef __NVIC_PRIO_BITS 173 | #define __NVIC_PRIO_BITS 4 174 | #warning "__NVIC_PRIO_BITS not defined in device header file; using default!" 175 | #endif 176 | 177 | #ifndef __Vendor_SysTickConfig 178 | #define __Vendor_SysTickConfig 0 179 | #warning "__Vendor_SysTickConfig not defined in device header file; using default!" 180 | #endif 181 | #endif 182 | 183 | /* IO definitions (access restrictions to peripheral registers) */ 184 | #ifdef __cplusplus 185 | #define __I volatile /*!< defines 'read only' permissions */ 186 | #else 187 | #define __I volatile const /*!< defines 'read only' permissions */ 188 | #endif 189 | #define __O volatile /*!< defines 'write only' permissions */ 190 | #define __IO volatile /*!< defines 'read / write' permissions */ 191 | 192 | /*@} end of group CMSIS_core_definitions */ 193 | 194 | 195 | 196 | /******************************************************************************* 197 | * Register Abstraction 198 | ******************************************************************************/ 199 | /** \defgroup CMSIS_core_register CMSIS Core Register 200 | Core Register contain: 201 | - Core Register 202 | - Core NVIC Register 203 | - Core SCB Register 204 | - Core SysTick Register 205 | - Core Debug Register 206 | - Core MPU Register 207 | - Core FPU Register 208 | */ 209 | 210 | /** \ingroup CMSIS_core_register 211 | \defgroup CMSIS_CORE CMSIS Core 212 | Type definitions for the Cortex-M Core Registers 213 | @{ 214 | */ 215 | 216 | /** \brief Union type to access the Application Program Status Register (APSR). 217 | */ 218 | typedef union 219 | { 220 | struct 221 | { 222 | #if (__CORTEX_M != 0x04) 223 | uint32_t _reserved0:27; /*!< bit: 0..26 Reserved */ 224 | #else 225 | uint32_t _reserved0:16; /*!< bit: 0..15 Reserved */ 226 | uint32_t GE:4; /*!< bit: 16..19 Greater than or Equal flags */ 227 | uint32_t _reserved1:7; /*!< bit: 20..26 Reserved */ 228 | #endif 229 | uint32_t Q:1; /*!< bit: 27 Saturation condition flag */ 230 | uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ 231 | uint32_t C:1; /*!< bit: 29 Carry condition code flag */ 232 | uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ 233 | uint32_t N:1; /*!< bit: 31 Negative condition code flag */ 234 | } b; /*!< Structure used for bit access */ 235 | uint32_t w; /*!< Type used for word access */ 236 | } APSR_Type; 237 | 238 | 239 | /** \brief Union type to access the Interrupt Program Status Register (IPSR). 240 | */ 241 | typedef union 242 | { 243 | struct 244 | { 245 | uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ 246 | uint32_t _reserved0:23; /*!< bit: 9..31 Reserved */ 247 | } b; /*!< Structure used for bit access */ 248 | uint32_t w; /*!< Type used for word access */ 249 | } IPSR_Type; 250 | 251 | 252 | /** \brief Union type to access the Special-Purpose Program Status Registers (xPSR). 253 | */ 254 | typedef union 255 | { 256 | struct 257 | { 258 | uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ 259 | #if (__CORTEX_M != 0x04) 260 | uint32_t _reserved0:15; /*!< bit: 9..23 Reserved */ 261 | #else 262 | uint32_t _reserved0:7; /*!< bit: 9..15 Reserved */ 263 | uint32_t GE:4; /*!< bit: 16..19 Greater than or Equal flags */ 264 | uint32_t _reserved1:4; /*!< bit: 20..23 Reserved */ 265 | #endif 266 | uint32_t T:1; /*!< bit: 24 Thumb bit (read 0) */ 267 | uint32_t IT:2; /*!< bit: 25..26 saved IT state (read 0) */ 268 | uint32_t Q:1; /*!< bit: 27 Saturation condition flag */ 269 | uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ 270 | uint32_t C:1; /*!< bit: 29 Carry condition code flag */ 271 | uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ 272 | uint32_t N:1; /*!< bit: 31 Negative condition code flag */ 273 | } b; /*!< Structure used for bit access */ 274 | uint32_t w; /*!< Type used for word access */ 275 | } xPSR_Type; 276 | 277 | 278 | /** \brief Union type to access the Control Registers (CONTROL). 279 | */ 280 | typedef union 281 | { 282 | struct 283 | { 284 | uint32_t nPRIV:1; /*!< bit: 0 Execution privilege in Thread mode */ 285 | uint32_t SPSEL:1; /*!< bit: 1 Stack to be used */ 286 | uint32_t FPCA:1; /*!< bit: 2 FP extension active flag */ 287 | uint32_t _reserved0:29; /*!< bit: 3..31 Reserved */ 288 | } b; /*!< Structure used for bit access */ 289 | uint32_t w; /*!< Type used for word access */ 290 | } CONTROL_Type; 291 | 292 | /*@} end of group CMSIS_CORE */ 293 | 294 | 295 | /** \ingroup CMSIS_core_register 296 | \defgroup CMSIS_NVIC CMSIS NVIC 297 | Type definitions for the Cortex-M NVIC Registers 298 | @{ 299 | */ 300 | 301 | /** \brief Structure type to access the Nested Vectored Interrupt Controller (NVIC). 302 | */ 303 | typedef struct 304 | { 305 | __IO uint32_t ISER[8]; /*!< Offset: 0x000 (R/W) Interrupt Set Enable Register */ 306 | uint32_t RESERVED0[24]; 307 | __IO uint32_t ICER[8]; /*!< Offset: 0x080 (R/W) Interrupt Clear Enable Register */ 308 | uint32_t RSERVED1[24]; 309 | __IO uint32_t ISPR[8]; /*!< Offset: 0x100 (R/W) Interrupt Set Pending Register */ 310 | uint32_t RESERVED2[24]; 311 | __IO uint32_t ICPR[8]; /*!< Offset: 0x180 (R/W) Interrupt Clear Pending Register */ 312 | uint32_t RESERVED3[24]; 313 | __IO uint32_t IABR[8]; /*!< Offset: 0x200 (R/W) Interrupt Active bit Register */ 314 | uint32_t RESERVED4[56]; 315 | __IO uint8_t IP[240]; /*!< Offset: 0x300 (R/W) Interrupt Priority Register (8Bit wide) */ 316 | uint32_t RESERVED5[644]; 317 | __O uint32_t STIR; /*!< Offset: 0xE00 ( /W) Software Trigger Interrupt Register */ 318 | } NVIC_Type; 319 | 320 | /* Software Triggered Interrupt Register Definitions */ 321 | #define NVIC_STIR_INTID_Pos 0 /*!< STIR: INTLINESNUM Position */ 322 | #define NVIC_STIR_INTID_Msk (0x1FFUL << NVIC_STIR_INTID_Pos) /*!< STIR: INTLINESNUM Mask */ 323 | 324 | /*@} end of group CMSIS_NVIC */ 325 | 326 | 327 | /** \ingroup CMSIS_core_register 328 | \defgroup CMSIS_SCB CMSIS SCB 329 | Type definitions for the Cortex-M System Control Block Registers 330 | @{ 331 | */ 332 | 333 | /** \brief Structure type to access the System Control Block (SCB). 334 | */ 335 | typedef struct 336 | { 337 | __I uint32_t CPUID; /*!< Offset: 0x000 (R/ ) CPUID Base Register */ 338 | __IO uint32_t ICSR; /*!< Offset: 0x004 (R/W) Interrupt Control and State Register */ 339 | __IO uint32_t VTOR; /*!< Offset: 0x008 (R/W) Vector Table Offset Register */ 340 | __IO uint32_t AIRCR; /*!< Offset: 0x00C (R/W) Application Interrupt and Reset Control Register */ 341 | __IO uint32_t SCR; /*!< Offset: 0x010 (R/W) System Control Register */ 342 | __IO uint32_t CCR; /*!< Offset: 0x014 (R/W) Configuration Control Register */ 343 | __IO uint8_t SHP[12]; /*!< Offset: 0x018 (R/W) System Handlers Priority Registers (4-7, 8-11, 12-15) */ 344 | __IO uint32_t SHCSR; /*!< Offset: 0x024 (R/W) System Handler Control and State Register */ 345 | __IO uint32_t CFSR; /*!< Offset: 0x028 (R/W) Configurable Fault Status Register */ 346 | __IO uint32_t HFSR; /*!< Offset: 0x02C (R/W) HardFault Status Register */ 347 | __IO uint32_t DFSR; /*!< Offset: 0x030 (R/W) Debug Fault Status Register */ 348 | __IO uint32_t MMFAR; /*!< Offset: 0x034 (R/W) MemManage Fault Address Register */ 349 | __IO uint32_t BFAR; /*!< Offset: 0x038 (R/W) BusFault Address Register */ 350 | __IO uint32_t AFSR; /*!< Offset: 0x03C (R/W) Auxiliary Fault Status Register */ 351 | __I uint32_t PFR[2]; /*!< Offset: 0x040 (R/ ) Processor Feature Register */ 352 | __I uint32_t DFR; /*!< Offset: 0x048 (R/ ) Debug Feature Register */ 353 | __I uint32_t ADR; /*!< Offset: 0x04C (R/ ) Auxiliary Feature Register */ 354 | __I uint32_t MMFR[4]; /*!< Offset: 0x050 (R/ ) Memory Model Feature Register */ 355 | __I uint32_t ISAR[5]; /*!< Offset: 0x060 (R/ ) Instruction Set Attributes Register */ 356 | uint32_t RESERVED0[5]; 357 | __IO uint32_t CPACR; /*!< Offset: 0x088 (R/W) Coprocessor Access Control Register */ 358 | } SCB_Type; 359 | 360 | /* SCB CPUID Register Definitions */ 361 | #define SCB_CPUID_IMPLEMENTER_Pos 24 /*!< SCB CPUID: IMPLEMENTER Position */ 362 | #define SCB_CPUID_IMPLEMENTER_Msk (0xFFUL << SCB_CPUID_IMPLEMENTER_Pos) /*!< SCB CPUID: IMPLEMENTER Mask */ 363 | 364 | #define SCB_CPUID_VARIANT_Pos 20 /*!< SCB CPUID: VARIANT Position */ 365 | #define SCB_CPUID_VARIANT_Msk (0xFUL << SCB_CPUID_VARIANT_Pos) /*!< SCB CPUID: VARIANT Mask */ 366 | 367 | #define SCB_CPUID_ARCHITECTURE_Pos 16 /*!< SCB CPUID: ARCHITECTURE Position */ 368 | #define SCB_CPUID_ARCHITECTURE_Msk (0xFUL << SCB_CPUID_ARCHITECTURE_Pos) /*!< SCB CPUID: ARCHITECTURE Mask */ 369 | 370 | #define SCB_CPUID_PARTNO_Pos 4 /*!< SCB CPUID: PARTNO Position */ 371 | #define SCB_CPUID_PARTNO_Msk (0xFFFUL << SCB_CPUID_PARTNO_Pos) /*!< SCB CPUID: PARTNO Mask */ 372 | 373 | #define SCB_CPUID_REVISION_Pos 0 /*!< SCB CPUID: REVISION Position */ 374 | #define SCB_CPUID_REVISION_Msk (0xFUL << SCB_CPUID_REVISION_Pos) /*!< SCB CPUID: REVISION Mask */ 375 | 376 | /* SCB Interrupt Control State Register Definitions */ 377 | #define SCB_ICSR_NMIPENDSET_Pos 31 /*!< SCB ICSR: NMIPENDSET Position */ 378 | #define SCB_ICSR_NMIPENDSET_Msk (1UL << SCB_ICSR_NMIPENDSET_Pos) /*!< SCB ICSR: NMIPENDSET Mask */ 379 | 380 | #define SCB_ICSR_PENDSVSET_Pos 28 /*!< SCB ICSR: PENDSVSET Position */ 381 | #define SCB_ICSR_PENDSVSET_Msk (1UL << SCB_ICSR_PENDSVSET_Pos) /*!< SCB ICSR: PENDSVSET Mask */ 382 | 383 | #define SCB_ICSR_PENDSVCLR_Pos 27 /*!< SCB ICSR: PENDSVCLR Position */ 384 | #define SCB_ICSR_PENDSVCLR_Msk (1UL << SCB_ICSR_PENDSVCLR_Pos) /*!< SCB ICSR: PENDSVCLR Mask */ 385 | 386 | #define SCB_ICSR_PENDSTSET_Pos 26 /*!< SCB ICSR: PENDSTSET Position */ 387 | #define SCB_ICSR_PENDSTSET_Msk (1UL << SCB_ICSR_PENDSTSET_Pos) /*!< SCB ICSR: PENDSTSET Mask */ 388 | 389 | #define SCB_ICSR_PENDSTCLR_Pos 25 /*!< SCB ICSR: PENDSTCLR Position */ 390 | #define SCB_ICSR_PENDSTCLR_Msk (1UL << SCB_ICSR_PENDSTCLR_Pos) /*!< SCB ICSR: PENDSTCLR Mask */ 391 | 392 | #define SCB_ICSR_ISRPREEMPT_Pos 23 /*!< SCB ICSR: ISRPREEMPT Position */ 393 | #define SCB_ICSR_ISRPREEMPT_Msk (1UL << SCB_ICSR_ISRPREEMPT_Pos) /*!< SCB ICSR: ISRPREEMPT Mask */ 394 | 395 | #define SCB_ICSR_ISRPENDING_Pos 22 /*!< SCB ICSR: ISRPENDING Position */ 396 | #define SCB_ICSR_ISRPENDING_Msk (1UL << SCB_ICSR_ISRPENDING_Pos) /*!< SCB ICSR: ISRPENDING Mask */ 397 | 398 | #define SCB_ICSR_VECTPENDING_Pos 12 /*!< SCB ICSR: VECTPENDING Position */ 399 | #define SCB_ICSR_VECTPENDING_Msk (0x1FFUL << SCB_ICSR_VECTPENDING_Pos) /*!< SCB ICSR: VECTPENDING Mask */ 400 | 401 | #define SCB_ICSR_RETTOBASE_Pos 11 /*!< SCB ICSR: RETTOBASE Position */ 402 | #define SCB_ICSR_RETTOBASE_Msk (1UL << SCB_ICSR_RETTOBASE_Pos) /*!< SCB ICSR: RETTOBASE Mask */ 403 | 404 | #define SCB_ICSR_VECTACTIVE_Pos 0 /*!< SCB ICSR: VECTACTIVE Position */ 405 | #define SCB_ICSR_VECTACTIVE_Msk (0x1FFUL << SCB_ICSR_VECTACTIVE_Pos) /*!< SCB ICSR: VECTACTIVE Mask */ 406 | 407 | /* SCB Vector Table Offset Register Definitions */ 408 | #define SCB_VTOR_TBLOFF_Pos 7 /*!< SCB VTOR: TBLOFF Position */ 409 | #define SCB_VTOR_TBLOFF_Msk (0x1FFFFFFUL << SCB_VTOR_TBLOFF_Pos) /*!< SCB VTOR: TBLOFF Mask */ 410 | 411 | /* SCB Application Interrupt and Reset Control Register Definitions */ 412 | #define SCB_AIRCR_VECTKEY_Pos 16 /*!< SCB AIRCR: VECTKEY Position */ 413 | #define SCB_AIRCR_VECTKEY_Msk (0xFFFFUL << SCB_AIRCR_VECTKEY_Pos) /*!< SCB AIRCR: VECTKEY Mask */ 414 | 415 | #define SCB_AIRCR_VECTKEYSTAT_Pos 16 /*!< SCB AIRCR: VECTKEYSTAT Position */ 416 | #define SCB_AIRCR_VECTKEYSTAT_Msk (0xFFFFUL << SCB_AIRCR_VECTKEYSTAT_Pos) /*!< SCB AIRCR: VECTKEYSTAT Mask */ 417 | 418 | #define SCB_AIRCR_ENDIANESS_Pos 15 /*!< SCB AIRCR: ENDIANESS Position */ 419 | #define SCB_AIRCR_ENDIANESS_Msk (1UL << SCB_AIRCR_ENDIANESS_Pos) /*!< SCB AIRCR: ENDIANESS Mask */ 420 | 421 | #define SCB_AIRCR_PRIGROUP_Pos 8 /*!< SCB AIRCR: PRIGROUP Position */ 422 | #define SCB_AIRCR_PRIGROUP_Msk (7UL << SCB_AIRCR_PRIGROUP_Pos) /*!< SCB AIRCR: PRIGROUP Mask */ 423 | 424 | #define SCB_AIRCR_SYSRESETREQ_Pos 2 /*!< SCB AIRCR: SYSRESETREQ Position */ 425 | #define SCB_AIRCR_SYSRESETREQ_Msk (1UL << SCB_AIRCR_SYSRESETREQ_Pos) /*!< SCB AIRCR: SYSRESETREQ Mask */ 426 | 427 | #define SCB_AIRCR_VECTCLRACTIVE_Pos 1 /*!< SCB AIRCR: VECTCLRACTIVE Position */ 428 | #define SCB_AIRCR_VECTCLRACTIVE_Msk (1UL << SCB_AIRCR_VECTCLRACTIVE_Pos) /*!< SCB AIRCR: VECTCLRACTIVE Mask */ 429 | 430 | #define SCB_AIRCR_VECTRESET_Pos 0 /*!< SCB AIRCR: VECTRESET Position */ 431 | #define SCB_AIRCR_VECTRESET_Msk (1UL << SCB_AIRCR_VECTRESET_Pos) /*!< SCB AIRCR: VECTRESET Mask */ 432 | 433 | /* SCB System Control Register Definitions */ 434 | #define SCB_SCR_SEVONPEND_Pos 4 /*!< SCB SCR: SEVONPEND Position */ 435 | #define SCB_SCR_SEVONPEND_Msk (1UL << SCB_SCR_SEVONPEND_Pos) /*!< SCB SCR: SEVONPEND Mask */ 436 | 437 | #define SCB_SCR_SLEEPDEEP_Pos 2 /*!< SCB SCR: SLEEPDEEP Position */ 438 | #define SCB_SCR_SLEEPDEEP_Msk (1UL << SCB_SCR_SLEEPDEEP_Pos) /*!< SCB SCR: SLEEPDEEP Mask */ 439 | 440 | #define SCB_SCR_SLEEPONEXIT_Pos 1 /*!< SCB SCR: SLEEPONEXIT Position */ 441 | #define SCB_SCR_SLEEPONEXIT_Msk (1UL << SCB_SCR_SLEEPONEXIT_Pos) /*!< SCB SCR: SLEEPONEXIT Mask */ 442 | 443 | /* SCB Configuration Control Register Definitions */ 444 | #define SCB_CCR_STKALIGN_Pos 9 /*!< SCB CCR: STKALIGN Position */ 445 | #define SCB_CCR_STKALIGN_Msk (1UL << SCB_CCR_STKALIGN_Pos) /*!< SCB CCR: STKALIGN Mask */ 446 | 447 | #define SCB_CCR_BFHFNMIGN_Pos 8 /*!< SCB CCR: BFHFNMIGN Position */ 448 | #define SCB_CCR_BFHFNMIGN_Msk (1UL << SCB_CCR_BFHFNMIGN_Pos) /*!< SCB CCR: BFHFNMIGN Mask */ 449 | 450 | #define SCB_CCR_DIV_0_TRP_Pos 4 /*!< SCB CCR: DIV_0_TRP Position */ 451 | #define SCB_CCR_DIV_0_TRP_Msk (1UL << SCB_CCR_DIV_0_TRP_Pos) /*!< SCB CCR: DIV_0_TRP Mask */ 452 | 453 | #define SCB_CCR_UNALIGN_TRP_Pos 3 /*!< SCB CCR: UNALIGN_TRP Position */ 454 | #define SCB_CCR_UNALIGN_TRP_Msk (1UL << SCB_CCR_UNALIGN_TRP_Pos) /*!< SCB CCR: UNALIGN_TRP Mask */ 455 | 456 | #define SCB_CCR_USERSETMPEND_Pos 1 /*!< SCB CCR: USERSETMPEND Position */ 457 | #define SCB_CCR_USERSETMPEND_Msk (1UL << SCB_CCR_USERSETMPEND_Pos) /*!< SCB CCR: USERSETMPEND Mask */ 458 | 459 | #define SCB_CCR_NONBASETHRDENA_Pos 0 /*!< SCB CCR: NONBASETHRDENA Position */ 460 | #define SCB_CCR_NONBASETHRDENA_Msk (1UL << SCB_CCR_NONBASETHRDENA_Pos) /*!< SCB CCR: NONBASETHRDENA Mask */ 461 | 462 | /* SCB System Handler Control and State Register Definitions */ 463 | #define SCB_SHCSR_USGFAULTENA_Pos 18 /*!< SCB SHCSR: USGFAULTENA Position */ 464 | #define SCB_SHCSR_USGFAULTENA_Msk (1UL << SCB_SHCSR_USGFAULTENA_Pos) /*!< SCB SHCSR: USGFAULTENA Mask */ 465 | 466 | #define SCB_SHCSR_BUSFAULTENA_Pos 17 /*!< SCB SHCSR: BUSFAULTENA Position */ 467 | #define SCB_SHCSR_BUSFAULTENA_Msk (1UL << SCB_SHCSR_BUSFAULTENA_Pos) /*!< SCB SHCSR: BUSFAULTENA Mask */ 468 | 469 | #define SCB_SHCSR_MEMFAULTENA_Pos 16 /*!< SCB SHCSR: MEMFAULTENA Position */ 470 | #define SCB_SHCSR_MEMFAULTENA_Msk (1UL << SCB_SHCSR_MEMFAULTENA_Pos) /*!< SCB SHCSR: MEMFAULTENA Mask */ 471 | 472 | #define SCB_SHCSR_SVCALLPENDED_Pos 15 /*!< SCB SHCSR: SVCALLPENDED Position */ 473 | #define SCB_SHCSR_SVCALLPENDED_Msk (1UL << SCB_SHCSR_SVCALLPENDED_Pos) /*!< SCB SHCSR: SVCALLPENDED Mask */ 474 | 475 | #define SCB_SHCSR_BUSFAULTPENDED_Pos 14 /*!< SCB SHCSR: BUSFAULTPENDED Position */ 476 | #define SCB_SHCSR_BUSFAULTPENDED_Msk (1UL << SCB_SHCSR_BUSFAULTPENDED_Pos) /*!< SCB SHCSR: BUSFAULTPENDED Mask */ 477 | 478 | #define SCB_SHCSR_MEMFAULTPENDED_Pos 13 /*!< SCB SHCSR: MEMFAULTPENDED Position */ 479 | #define SCB_SHCSR_MEMFAULTPENDED_Msk (1UL << SCB_SHCSR_MEMFAULTPENDED_Pos) /*!< SCB SHCSR: MEMFAULTPENDED Mask */ 480 | 481 | #define SCB_SHCSR_USGFAULTPENDED_Pos 12 /*!< SCB SHCSR: USGFAULTPENDED Position */ 482 | #define SCB_SHCSR_USGFAULTPENDED_Msk (1UL << SCB_SHCSR_USGFAULTPENDED_Pos) /*!< SCB SHCSR: USGFAULTPENDED Mask */ 483 | 484 | #define SCB_SHCSR_SYSTICKACT_Pos 11 /*!< SCB SHCSR: SYSTICKACT Position */ 485 | #define SCB_SHCSR_SYSTICKACT_Msk (1UL << SCB_SHCSR_SYSTICKACT_Pos) /*!< SCB SHCSR: SYSTICKACT Mask */ 486 | 487 | #define SCB_SHCSR_PENDSVACT_Pos 10 /*!< SCB SHCSR: PENDSVACT Position */ 488 | #define SCB_SHCSR_PENDSVACT_Msk (1UL << SCB_SHCSR_PENDSVACT_Pos) /*!< SCB SHCSR: PENDSVACT Mask */ 489 | 490 | #define SCB_SHCSR_MONITORACT_Pos 8 /*!< SCB SHCSR: MONITORACT Position */ 491 | #define SCB_SHCSR_MONITORACT_Msk (1UL << SCB_SHCSR_MONITORACT_Pos) /*!< SCB SHCSR: MONITORACT Mask */ 492 | 493 | #define SCB_SHCSR_SVCALLACT_Pos 7 /*!< SCB SHCSR: SVCALLACT Position */ 494 | #define SCB_SHCSR_SVCALLACT_Msk (1UL << SCB_SHCSR_SVCALLACT_Pos) /*!< SCB SHCSR: SVCALLACT Mask */ 495 | 496 | #define SCB_SHCSR_USGFAULTACT_Pos 3 /*!< SCB SHCSR: USGFAULTACT Position */ 497 | #define SCB_SHCSR_USGFAULTACT_Msk (1UL << SCB_SHCSR_USGFAULTACT_Pos) /*!< SCB SHCSR: USGFAULTACT Mask */ 498 | 499 | #define SCB_SHCSR_BUSFAULTACT_Pos 1 /*!< SCB SHCSR: BUSFAULTACT Position */ 500 | #define SCB_SHCSR_BUSFAULTACT_Msk (1UL << SCB_SHCSR_BUSFAULTACT_Pos) /*!< SCB SHCSR: BUSFAULTACT Mask */ 501 | 502 | #define SCB_SHCSR_MEMFAULTACT_Pos 0 /*!< SCB SHCSR: MEMFAULTACT Position */ 503 | #define SCB_SHCSR_MEMFAULTACT_Msk (1UL << SCB_SHCSR_MEMFAULTACT_Pos) /*!< SCB SHCSR: MEMFAULTACT Mask */ 504 | 505 | /* SCB Configurable Fault Status Registers Definitions */ 506 | #define SCB_CFSR_USGFAULTSR_Pos 16 /*!< SCB CFSR: Usage Fault Status Register Position */ 507 | #define SCB_CFSR_USGFAULTSR_Msk (0xFFFFUL << SCB_CFSR_USGFAULTSR_Pos) /*!< SCB CFSR: Usage Fault Status Register Mask */ 508 | 509 | #define SCB_CFSR_BUSFAULTSR_Pos 8 /*!< SCB CFSR: Bus Fault Status Register Position */ 510 | #define SCB_CFSR_BUSFAULTSR_Msk (0xFFUL << SCB_CFSR_BUSFAULTSR_Pos) /*!< SCB CFSR: Bus Fault Status Register Mask */ 511 | 512 | #define SCB_CFSR_MEMFAULTSR_Pos 0 /*!< SCB CFSR: Memory Manage Fault Status Register Position */ 513 | #define SCB_CFSR_MEMFAULTSR_Msk (0xFFUL << SCB_CFSR_MEMFAULTSR_Pos) /*!< SCB CFSR: Memory Manage Fault Status Register Mask */ 514 | 515 | /* SCB Hard Fault Status Registers Definitions */ 516 | #define SCB_HFSR_DEBUGEVT_Pos 31 /*!< SCB HFSR: DEBUGEVT Position */ 517 | #define SCB_HFSR_DEBUGEVT_Msk (1UL << SCB_HFSR_DEBUGEVT_Pos) /*!< SCB HFSR: DEBUGEVT Mask */ 518 | 519 | #define SCB_HFSR_FORCED_Pos 30 /*!< SCB HFSR: FORCED Position */ 520 | #define SCB_HFSR_FORCED_Msk (1UL << SCB_HFSR_FORCED_Pos) /*!< SCB HFSR: FORCED Mask */ 521 | 522 | #define SCB_HFSR_VECTTBL_Pos 1 /*!< SCB HFSR: VECTTBL Position */ 523 | #define SCB_HFSR_VECTTBL_Msk (1UL << SCB_HFSR_VECTTBL_Pos) /*!< SCB HFSR: VECTTBL Mask */ 524 | 525 | /* SCB Debug Fault Status Register Definitions */ 526 | #define SCB_DFSR_EXTERNAL_Pos 4 /*!< SCB DFSR: EXTERNAL Position */ 527 | #define SCB_DFSR_EXTERNAL_Msk (1UL << SCB_DFSR_EXTERNAL_Pos) /*!< SCB DFSR: EXTERNAL Mask */ 528 | 529 | #define SCB_DFSR_VCATCH_Pos 3 /*!< SCB DFSR: VCATCH Position */ 530 | #define SCB_DFSR_VCATCH_Msk (1UL << SCB_DFSR_VCATCH_Pos) /*!< SCB DFSR: VCATCH Mask */ 531 | 532 | #define SCB_DFSR_DWTTRAP_Pos 2 /*!< SCB DFSR: DWTTRAP Position */ 533 | #define SCB_DFSR_DWTTRAP_Msk (1UL << SCB_DFSR_DWTTRAP_Pos) /*!< SCB DFSR: DWTTRAP Mask */ 534 | 535 | #define SCB_DFSR_BKPT_Pos 1 /*!< SCB DFSR: BKPT Position */ 536 | #define SCB_DFSR_BKPT_Msk (1UL << SCB_DFSR_BKPT_Pos) /*!< SCB DFSR: BKPT Mask */ 537 | 538 | #define SCB_DFSR_HALTED_Pos 0 /*!< SCB DFSR: HALTED Position */ 539 | #define SCB_DFSR_HALTED_Msk (1UL << SCB_DFSR_HALTED_Pos) /*!< SCB DFSR: HALTED Mask */ 540 | 541 | /*@} end of group CMSIS_SCB */ 542 | 543 | 544 | /** \ingroup CMSIS_core_register 545 | \defgroup CMSIS_SCnSCB CMSIS System Control and ID Register not in the SCB 546 | Type definitions for the Cortex-M System Control and ID Register not in the SCB 547 | @{ 548 | */ 549 | 550 | /** \brief Structure type to access the System Control and ID Register not in the SCB. 551 | */ 552 | typedef struct 553 | { 554 | uint32_t RESERVED0[1]; 555 | __I uint32_t ICTR; /*!< Offset: 0x004 (R/ ) Interrupt Controller Type Register */ 556 | __IO uint32_t ACTLR; /*!< Offset: 0x008 (R/W) Auxiliary Control Register */ 557 | } SCnSCB_Type; 558 | 559 | /* Interrupt Controller Type Register Definitions */ 560 | #define SCnSCB_ICTR_INTLINESNUM_Pos 0 /*!< ICTR: INTLINESNUM Position */ 561 | #define SCnSCB_ICTR_INTLINESNUM_Msk (0xFUL << SCnSCB_ICTR_INTLINESNUM_Pos) /*!< ICTR: INTLINESNUM Mask */ 562 | 563 | /* Auxiliary Control Register Definitions */ 564 | #define SCnSCB_ACTLR_DISOOFP_Pos 9 /*!< ACTLR: DISOOFP Position */ 565 | #define SCnSCB_ACTLR_DISOOFP_Msk (1UL << SCnSCB_ACTLR_DISOOFP_Pos) /*!< ACTLR: DISOOFP Mask */ 566 | 567 | #define SCnSCB_ACTLR_DISFPCA_Pos 8 /*!< ACTLR: DISFPCA Position */ 568 | #define SCnSCB_ACTLR_DISFPCA_Msk (1UL << SCnSCB_ACTLR_DISFPCA_Pos) /*!< ACTLR: DISFPCA Mask */ 569 | 570 | #define SCnSCB_ACTLR_DISFOLD_Pos 2 /*!< ACTLR: DISFOLD Position */ 571 | #define SCnSCB_ACTLR_DISFOLD_Msk (1UL << SCnSCB_ACTLR_DISFOLD_Pos) /*!< ACTLR: DISFOLD Mask */ 572 | 573 | #define SCnSCB_ACTLR_DISDEFWBUF_Pos 1 /*!< ACTLR: DISDEFWBUF Position */ 574 | #define SCnSCB_ACTLR_DISDEFWBUF_Msk (1UL << SCnSCB_ACTLR_DISDEFWBUF_Pos) /*!< ACTLR: DISDEFWBUF Mask */ 575 | 576 | #define SCnSCB_ACTLR_DISMCYCINT_Pos 0 /*!< ACTLR: DISMCYCINT Position */ 577 | #define SCnSCB_ACTLR_DISMCYCINT_Msk (1UL << SCnSCB_ACTLR_DISMCYCINT_Pos) /*!< ACTLR: DISMCYCINT Mask */ 578 | 579 | /*@} end of group CMSIS_SCnotSCB */ 580 | 581 | 582 | /** \ingroup CMSIS_core_register 583 | \defgroup CMSIS_SysTick CMSIS SysTick 584 | Type definitions for the Cortex-M System Timer Registers 585 | @{ 586 | */ 587 | 588 | /** \brief Structure type to access the System Timer (SysTick). 589 | */ 590 | typedef struct 591 | { 592 | __IO uint32_t CTRL; /*!< Offset: 0x000 (R/W) SysTick Control and Status Register */ 593 | __IO uint32_t LOAD; /*!< Offset: 0x004 (R/W) SysTick Reload Value Register */ 594 | __IO uint32_t VAL; /*!< Offset: 0x008 (R/W) SysTick Current Value Register */ 595 | __I uint32_t CALIB; /*!< Offset: 0x00C (R/ ) SysTick Calibration Register */ 596 | } SysTick_Type; 597 | 598 | /* SysTick Control / Status Register Definitions */ 599 | #define SysTick_CTRL_COUNTFLAG_Pos 16 /*!< SysTick CTRL: COUNTFLAG Position */ 600 | #define SysTick_CTRL_COUNTFLAG_Msk (1UL << SysTick_CTRL_COUNTFLAG_Pos) /*!< SysTick CTRL: COUNTFLAG Mask */ 601 | 602 | #define SysTick_CTRL_CLKSOURCE_Pos 2 /*!< SysTick CTRL: CLKSOURCE Position */ 603 | #define SysTick_CTRL_CLKSOURCE_Msk (1UL << SysTick_CTRL_CLKSOURCE_Pos) /*!< SysTick CTRL: CLKSOURCE Mask */ 604 | 605 | #define SysTick_CTRL_TICKINT_Pos 1 /*!< SysTick CTRL: TICKINT Position */ 606 | #define SysTick_CTRL_TICKINT_Msk (1UL << SysTick_CTRL_TICKINT_Pos) /*!< SysTick CTRL: TICKINT Mask */ 607 | 608 | #define SysTick_CTRL_ENABLE_Pos 0 /*!< SysTick CTRL: ENABLE Position */ 609 | #define SysTick_CTRL_ENABLE_Msk (1UL << SysTick_CTRL_ENABLE_Pos) /*!< SysTick CTRL: ENABLE Mask */ 610 | 611 | /* SysTick Reload Register Definitions */ 612 | #define SysTick_LOAD_RELOAD_Pos 0 /*!< SysTick LOAD: RELOAD Position */ 613 | #define SysTick_LOAD_RELOAD_Msk (0xFFFFFFUL << SysTick_LOAD_RELOAD_Pos) /*!< SysTick LOAD: RELOAD Mask */ 614 | 615 | /* SysTick Current Register Definitions */ 616 | #define SysTick_VAL_CURRENT_Pos 0 /*!< SysTick VAL: CURRENT Position */ 617 | #define SysTick_VAL_CURRENT_Msk (0xFFFFFFUL << SysTick_VAL_CURRENT_Pos) /*!< SysTick VAL: CURRENT Mask */ 618 | 619 | /* SysTick Calibration Register Definitions */ 620 | #define SysTick_CALIB_NOREF_Pos 31 /*!< SysTick CALIB: NOREF Position */ 621 | #define SysTick_CALIB_NOREF_Msk (1UL << SysTick_CALIB_NOREF_Pos) /*!< SysTick CALIB: NOREF Mask */ 622 | 623 | #define SysTick_CALIB_SKEW_Pos 30 /*!< SysTick CALIB: SKEW Position */ 624 | #define SysTick_CALIB_SKEW_Msk (1UL << SysTick_CALIB_SKEW_Pos) /*!< SysTick CALIB: SKEW Mask */ 625 | 626 | #define SysTick_CALIB_TENMS_Pos 0 /*!< SysTick CALIB: TENMS Position */ 627 | #define SysTick_CALIB_TENMS_Msk (0xFFFFFFUL << SysTick_VAL_CURRENT_Pos) /*!< SysTick CALIB: TENMS Mask */ 628 | 629 | /*@} end of group CMSIS_SysTick */ 630 | 631 | 632 | /** \ingroup CMSIS_core_register 633 | \defgroup CMSIS_ITM CMSIS ITM 634 | Type definitions for the Cortex-M Instrumentation Trace Macrocell (ITM) 635 | @{ 636 | */ 637 | 638 | /** \brief Structure type to access the Instrumentation Trace Macrocell Register (ITM). 639 | */ 640 | typedef struct 641 | { 642 | __O union 643 | { 644 | __O uint8_t u8; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 8-bit */ 645 | __O uint16_t u16; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 16-bit */ 646 | __O uint32_t u32; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 32-bit */ 647 | } PORT [32]; /*!< Offset: 0x000 ( /W) ITM Stimulus Port Registers */ 648 | uint32_t RESERVED0[864]; 649 | __IO uint32_t TER; /*!< Offset: 0xE00 (R/W) ITM Trace Enable Register */ 650 | uint32_t RESERVED1[15]; 651 | __IO uint32_t TPR; /*!< Offset: 0xE40 (R/W) ITM Trace Privilege Register */ 652 | uint32_t RESERVED2[15]; 653 | __IO uint32_t TCR; /*!< Offset: 0xE80 (R/W) ITM Trace Control Register */ 654 | } ITM_Type; 655 | 656 | /* ITM Trace Privilege Register Definitions */ 657 | #define ITM_TPR_PRIVMASK_Pos 0 /*!< ITM TPR: PRIVMASK Position */ 658 | #define ITM_TPR_PRIVMASK_Msk (0xFUL << ITM_TPR_PRIVMASK_Pos) /*!< ITM TPR: PRIVMASK Mask */ 659 | 660 | /* ITM Trace Control Register Definitions */ 661 | #define ITM_TCR_BUSY_Pos 23 /*!< ITM TCR: BUSY Position */ 662 | #define ITM_TCR_BUSY_Msk (1UL << ITM_TCR_BUSY_Pos) /*!< ITM TCR: BUSY Mask */ 663 | 664 | #define ITM_TCR_TraceBusID_Pos 16 /*!< ITM TCR: ATBID Position */ 665 | #define ITM_TCR_TraceBusID_Msk (0x7FUL << ITM_TCR_TraceBusID_Pos) /*!< ITM TCR: ATBID Mask */ 666 | 667 | #define ITM_TCR_GTSFREQ_Pos 10 /*!< ITM TCR: Global timestamp frequency Position */ 668 | #define ITM_TCR_GTSFREQ_Msk (3UL << ITM_TCR_GTSFREQ_Pos) /*!< ITM TCR: Global timestamp frequency Mask */ 669 | 670 | #define ITM_TCR_TSPrescale_Pos 8 /*!< ITM TCR: TSPrescale Position */ 671 | #define ITM_TCR_TSPrescale_Msk (3UL << ITM_TCR_TSPrescale_Pos) /*!< ITM TCR: TSPrescale Mask */ 672 | 673 | #define ITM_TCR_SWOENA_Pos 4 /*!< ITM TCR: SWOENA Position */ 674 | #define ITM_TCR_SWOENA_Msk (1UL << ITM_TCR_SWOENA_Pos) /*!< ITM TCR: SWOENA Mask */ 675 | 676 | #define ITM_TCR_TXENA_Pos 3 /*!< ITM TCR: TXENA Position */ 677 | #define ITM_TCR_TXENA_Msk (1UL << ITM_TCR_TXENA_Pos) /*!< ITM TCR: TXENA Mask */ 678 | 679 | #define ITM_TCR_SYNCENA_Pos 2 /*!< ITM TCR: SYNCENA Position */ 680 | #define ITM_TCR_SYNCENA_Msk (1UL << ITM_TCR_SYNCENA_Pos) /*!< ITM TCR: SYNCENA Mask */ 681 | 682 | #define ITM_TCR_TSENA_Pos 1 /*!< ITM TCR: TSENA Position */ 683 | #define ITM_TCR_TSENA_Msk (1UL << ITM_TCR_TSENA_Pos) /*!< ITM TCR: TSENA Mask */ 684 | 685 | #define ITM_TCR_ITMENA_Pos 0 /*!< ITM TCR: ITM Enable bit Position */ 686 | #define ITM_TCR_ITMENA_Msk (1UL << ITM_TCR_ITMENA_Pos) /*!< ITM TCR: ITM Enable bit Mask */ 687 | 688 | /*@}*/ /* end of group CMSIS_ITM */ 689 | 690 | 691 | #if (__MPU_PRESENT == 1) 692 | /** \ingroup CMSIS_core_register 693 | \defgroup CMSIS_MPU CMSIS MPU 694 | Type definitions for the Cortex-M Memory Protection Unit (MPU) 695 | @{ 696 | */ 697 | 698 | /** \brief Structure type to access the Memory Protection Unit (MPU). 699 | */ 700 | typedef struct 701 | { 702 | __I uint32_t TYPE; /*!< Offset: 0x000 (R/ ) MPU Type Register */ 703 | __IO uint32_t CTRL; /*!< Offset: 0x004 (R/W) MPU Control Register */ 704 | __IO uint32_t RNR; /*!< Offset: 0x008 (R/W) MPU Region RNRber Register */ 705 | __IO uint32_t RBAR; /*!< Offset: 0x00C (R/W) MPU Region Base Address Register */ 706 | __IO uint32_t RASR; /*!< Offset: 0x010 (R/W) MPU Region Attribute and Size Register */ 707 | __IO uint32_t RBAR_A1; /*!< Offset: 0x014 (R/W) MPU Alias 1 Region Base Address Register */ 708 | __IO uint32_t RASR_A1; /*!< Offset: 0x018 (R/W) MPU Alias 1 Region Attribute and Size Register */ 709 | __IO uint32_t RBAR_A2; /*!< Offset: 0x01C (R/W) MPU Alias 2 Region Base Address Register */ 710 | __IO uint32_t RASR_A2; /*!< Offset: 0x020 (R/W) MPU Alias 2 Region Attribute and Size Register */ 711 | __IO uint32_t RBAR_A3; /*!< Offset: 0x024 (R/W) MPU Alias 3 Region Base Address Register */ 712 | __IO uint32_t RASR_A3; /*!< Offset: 0x028 (R/W) MPU Alias 3 Region Attribute and Size Register */ 713 | } MPU_Type; 714 | 715 | /* MPU Type Register */ 716 | #define MPU_TYPE_IREGION_Pos 16 /*!< MPU TYPE: IREGION Position */ 717 | #define MPU_TYPE_IREGION_Msk (0xFFUL << MPU_TYPE_IREGION_Pos) /*!< MPU TYPE: IREGION Mask */ 718 | 719 | #define MPU_TYPE_DREGION_Pos 8 /*!< MPU TYPE: DREGION Position */ 720 | #define MPU_TYPE_DREGION_Msk (0xFFUL << MPU_TYPE_DREGION_Pos) /*!< MPU TYPE: DREGION Mask */ 721 | 722 | #define MPU_TYPE_SEPARATE_Pos 0 /*!< MPU TYPE: SEPARATE Position */ 723 | #define MPU_TYPE_SEPARATE_Msk (1UL << MPU_TYPE_SEPARATE_Pos) /*!< MPU TYPE: SEPARATE Mask */ 724 | 725 | /* MPU Control Register */ 726 | #define MPU_CTRL_PRIVDEFENA_Pos 2 /*!< MPU CTRL: PRIVDEFENA Position */ 727 | #define MPU_CTRL_PRIVDEFENA_Msk (1UL << MPU_CTRL_PRIVDEFENA_Pos) /*!< MPU CTRL: PRIVDEFENA Mask */ 728 | 729 | #define MPU_CTRL_HFNMIENA_Pos 1 /*!< MPU CTRL: HFNMIENA Position */ 730 | #define MPU_CTRL_HFNMIENA_Msk (1UL << MPU_CTRL_HFNMIENA_Pos) /*!< MPU CTRL: HFNMIENA Mask */ 731 | 732 | #define MPU_CTRL_ENABLE_Pos 0 /*!< MPU CTRL: ENABLE Position */ 733 | #define MPU_CTRL_ENABLE_Msk (1UL << MPU_CTRL_ENABLE_Pos) /*!< MPU CTRL: ENABLE Mask */ 734 | 735 | /* MPU Region Number Register */ 736 | #define MPU_RNR_REGION_Pos 0 /*!< MPU RNR: REGION Position */ 737 | #define MPU_RNR_REGION_Msk (0xFFUL << MPU_RNR_REGION_Pos) /*!< MPU RNR: REGION Mask */ 738 | 739 | /* MPU Region Base Address Register */ 740 | #define MPU_RBAR_ADDR_Pos 5 /*!< MPU RBAR: ADDR Position */ 741 | #define MPU_RBAR_ADDR_Msk (0x7FFFFFFUL << MPU_RBAR_ADDR_Pos) /*!< MPU RBAR: ADDR Mask */ 742 | 743 | #define MPU_RBAR_VALID_Pos 4 /*!< MPU RBAR: VALID Position */ 744 | #define MPU_RBAR_VALID_Msk (1UL << MPU_RBAR_VALID_Pos) /*!< MPU RBAR: VALID Mask */ 745 | 746 | #define MPU_RBAR_REGION_Pos 0 /*!< MPU RBAR: REGION Position */ 747 | #define MPU_RBAR_REGION_Msk (0xFUL << MPU_RBAR_REGION_Pos) /*!< MPU RBAR: REGION Mask */ 748 | 749 | /* MPU Region Attribute and Size Register */ 750 | #define MPU_RASR_ATTRS_Pos 16 /*!< MPU RASR: MPU Region Attribute field Position */ 751 | #define MPU_RASR_ATTRS_Msk (0xFFFFUL << MPU_RASR_ATTRS_Pos) /*!< MPU RASR: MPU Region Attribute field Mask */ 752 | 753 | #define MPU_RASR_SRD_Pos 8 /*!< MPU RASR: Sub-Region Disable Position */ 754 | #define MPU_RASR_SRD_Msk (0xFFUL << MPU_RASR_SRD_Pos) /*!< MPU RASR: Sub-Region Disable Mask */ 755 | 756 | #define MPU_RASR_SIZE_Pos 1 /*!< MPU RASR: Region Size Field Position */ 757 | #define MPU_RASR_SIZE_Msk (0x1FUL << MPU_RASR_SIZE_Pos) /*!< MPU RASR: Region Size Field Mask */ 758 | 759 | #define MPU_RASR_ENABLE_Pos 0 /*!< MPU RASR: Region enable bit Position */ 760 | #define MPU_RASR_ENABLE_Msk (1UL << MPU_RASR_ENABLE_Pos) /*!< MPU RASR: Region enable bit Disable Mask */ 761 | 762 | /*@} end of group CMSIS_MPU */ 763 | #endif 764 | 765 | 766 | #if (__FPU_PRESENT == 1) 767 | /** \ingroup CMSIS_core_register 768 | \defgroup CMSIS_FPU CMSIS FPU 769 | Type definitions for the Cortex-M Floating Point Unit (FPU) 770 | @{ 771 | */ 772 | 773 | /** \brief Structure type to access the Floating Point Unit (FPU). 774 | */ 775 | typedef struct 776 | { 777 | uint32_t RESERVED0[1]; 778 | __IO uint32_t FPCCR; /*!< Offset: 0x004 (R/W) Floating-Point Context Control Register */ 779 | __IO uint32_t FPCAR; /*!< Offset: 0x008 (R/W) Floating-Point Context Address Register */ 780 | __IO uint32_t FPDSCR; /*!< Offset: 0x00C (R/W) Floating-Point Default Status Control Register */ 781 | __I uint32_t MVFR0; /*!< Offset: 0x010 (R/ ) Media and FP Feature Register 0 */ 782 | __I uint32_t MVFR1; /*!< Offset: 0x014 (R/ ) Media and FP Feature Register 1 */ 783 | } FPU_Type; 784 | 785 | /* Floating-Point Context Control Register */ 786 | #define FPU_FPCCR_ASPEN_Pos 31 /*!< FPCCR: ASPEN bit Position */ 787 | #define FPU_FPCCR_ASPEN_Msk (1UL << FPU_FPCCR_ASPEN_Pos) /*!< FPCCR: ASPEN bit Mask */ 788 | 789 | #define FPU_FPCCR_LSPEN_Pos 30 /*!< FPCCR: LSPEN Position */ 790 | #define FPU_FPCCR_LSPEN_Msk (1UL << FPU_FPCCR_LSPEN_Pos) /*!< FPCCR: LSPEN bit Mask */ 791 | 792 | #define FPU_FPCCR_MONRDY_Pos 8 /*!< FPCCR: MONRDY Position */ 793 | #define FPU_FPCCR_MONRDY_Msk (1UL << FPU_FPCCR_MONRDY_Pos) /*!< FPCCR: MONRDY bit Mask */ 794 | 795 | #define FPU_FPCCR_BFRDY_Pos 6 /*!< FPCCR: BFRDY Position */ 796 | #define FPU_FPCCR_BFRDY_Msk (1UL << FPU_FPCCR_BFRDY_Pos) /*!< FPCCR: BFRDY bit Mask */ 797 | 798 | #define FPU_FPCCR_MMRDY_Pos 5 /*!< FPCCR: MMRDY Position */ 799 | #define FPU_FPCCR_MMRDY_Msk (1UL << FPU_FPCCR_MMRDY_Pos) /*!< FPCCR: MMRDY bit Mask */ 800 | 801 | #define FPU_FPCCR_HFRDY_Pos 4 /*!< FPCCR: HFRDY Position */ 802 | #define FPU_FPCCR_HFRDY_Msk (1UL << FPU_FPCCR_HFRDY_Pos) /*!< FPCCR: HFRDY bit Mask */ 803 | 804 | #define FPU_FPCCR_THREAD_Pos 3 /*!< FPCCR: processor mode bit Position */ 805 | #define FPU_FPCCR_THREAD_Msk (1UL << FPU_FPCCR_THREAD_Pos) /*!< FPCCR: processor mode active bit Mask */ 806 | 807 | #define FPU_FPCCR_USER_Pos 1 /*!< FPCCR: privilege level bit Position */ 808 | #define FPU_FPCCR_USER_Msk (1UL << FPU_FPCCR_USER_Pos) /*!< FPCCR: privilege level bit Mask */ 809 | 810 | #define FPU_FPCCR_LSPACT_Pos 0 /*!< FPCCR: Lazy state preservation active bit Position */ 811 | #define FPU_FPCCR_LSPACT_Msk (1UL << FPU_FPCCR_LSPACT_Pos) /*!< FPCCR: Lazy state preservation active bit Mask */ 812 | 813 | /* Floating-Point Context Address Register */ 814 | #define FPU_FPCAR_ADDRESS_Pos 3 /*!< FPCAR: ADDRESS bit Position */ 815 | #define FPU_FPCAR_ADDRESS_Msk (0x1FFFFFFFUL << FPU_FPCAR_ADDRESS_Pos) /*!< FPCAR: ADDRESS bit Mask */ 816 | 817 | /* Floating-Point Default Status Control Register */ 818 | #define FPU_FPDSCR_AHP_Pos 26 /*!< FPDSCR: AHP bit Position */ 819 | #define FPU_FPDSCR_AHP_Msk (1UL << FPU_FPDSCR_AHP_Pos) /*!< FPDSCR: AHP bit Mask */ 820 | 821 | #define FPU_FPDSCR_DN_Pos 25 /*!< FPDSCR: DN bit Position */ 822 | #define FPU_FPDSCR_DN_Msk (1UL << FPU_FPDSCR_DN_Pos) /*!< FPDSCR: DN bit Mask */ 823 | 824 | #define FPU_FPDSCR_FZ_Pos 24 /*!< FPDSCR: FZ bit Position */ 825 | #define FPU_FPDSCR_FZ_Msk (1UL << FPU_FPDSCR_FZ_Pos) /*!< FPDSCR: FZ bit Mask */ 826 | 827 | #define FPU_FPDSCR_RMode_Pos 22 /*!< FPDSCR: RMode bit Position */ 828 | #define FPU_FPDSCR_RMode_Msk (3UL << FPU_FPDSCR_RMode_Pos) /*!< FPDSCR: RMode bit Mask */ 829 | 830 | /* Media and FP Feature Register 0 */ 831 | #define FPU_MVFR0_FP_rounding_modes_Pos 28 /*!< MVFR0: FP rounding modes bits Position */ 832 | #define FPU_MVFR0_FP_rounding_modes_Msk (0xFUL << FPU_MVFR0_FP_rounding_modes_Pos) /*!< MVFR0: FP rounding modes bits Mask */ 833 | 834 | #define FPU_MVFR0_Short_vectors_Pos 24 /*!< MVFR0: Short vectors bits Position */ 835 | #define FPU_MVFR0_Short_vectors_Msk (0xFUL << FPU_MVFR0_Short_vectors_Pos) /*!< MVFR0: Short vectors bits Mask */ 836 | 837 | #define FPU_MVFR0_Square_root_Pos 20 /*!< MVFR0: Square root bits Position */ 838 | #define FPU_MVFR0_Square_root_Msk (0xFUL << FPU_MVFR0_Square_root_Pos) /*!< MVFR0: Square root bits Mask */ 839 | 840 | #define FPU_MVFR0_Divide_Pos 16 /*!< MVFR0: Divide bits Position */ 841 | #define FPU_MVFR0_Divide_Msk (0xFUL << FPU_MVFR0_Divide_Pos) /*!< MVFR0: Divide bits Mask */ 842 | 843 | #define FPU_MVFR0_FP_excep_trapping_Pos 12 /*!< MVFR0: FP exception trapping bits Position */ 844 | #define FPU_MVFR0_FP_excep_trapping_Msk (0xFUL << FPU_MVFR0_FP_excep_trapping_Pos) /*!< MVFR0: FP exception trapping bits Mask */ 845 | 846 | #define FPU_MVFR0_Double_precision_Pos 8 /*!< MVFR0: Double-precision bits Position */ 847 | #define FPU_MVFR0_Double_precision_Msk (0xFUL << FPU_MVFR0_Double_precision_Pos) /*!< MVFR0: Double-precision bits Mask */ 848 | 849 | #define FPU_MVFR0_Single_precision_Pos 4 /*!< MVFR0: Single-precision bits Position */ 850 | #define FPU_MVFR0_Single_precision_Msk (0xFUL << FPU_MVFR0_Single_precision_Pos) /*!< MVFR0: Single-precision bits Mask */ 851 | 852 | #define FPU_MVFR0_A_SIMD_registers_Pos 0 /*!< MVFR0: A_SIMD registers bits Position */ 853 | #define FPU_MVFR0_A_SIMD_registers_Msk (0xFUL << FPU_MVFR0_A_SIMD_registers_Pos) /*!< MVFR0: A_SIMD registers bits Mask */ 854 | 855 | /* Media and FP Feature Register 1 */ 856 | #define FPU_MVFR1_FP_fused_MAC_Pos 28 /*!< MVFR1: FP fused MAC bits Position */ 857 | #define FPU_MVFR1_FP_fused_MAC_Msk (0xFUL << FPU_MVFR1_FP_fused_MAC_Pos) /*!< MVFR1: FP fused MAC bits Mask */ 858 | 859 | #define FPU_MVFR1_FP_HPFP_Pos 24 /*!< MVFR1: FP HPFP bits Position */ 860 | #define FPU_MVFR1_FP_HPFP_Msk (0xFUL << FPU_MVFR1_FP_HPFP_Pos) /*!< MVFR1: FP HPFP bits Mask */ 861 | 862 | #define FPU_MVFR1_D_NaN_mode_Pos 4 /*!< MVFR1: D_NaN mode bits Position */ 863 | #define FPU_MVFR1_D_NaN_mode_Msk (0xFUL << FPU_MVFR1_D_NaN_mode_Pos) /*!< MVFR1: D_NaN mode bits Mask */ 864 | 865 | #define FPU_MVFR1_FtZ_mode_Pos 0 /*!< MVFR1: FtZ mode bits Position */ 866 | #define FPU_MVFR1_FtZ_mode_Msk (0xFUL << FPU_MVFR1_FtZ_mode_Pos) /*!< MVFR1: FtZ mode bits Mask */ 867 | 868 | /*@} end of group CMSIS_FPU */ 869 | #endif 870 | 871 | 872 | /** \ingroup CMSIS_core_register 873 | \defgroup CMSIS_CoreDebug CMSIS Core Debug 874 | Type definitions for the Cortex-M Core Debug Registers 875 | @{ 876 | */ 877 | 878 | /** \brief Structure type to access the Core Debug Register (CoreDebug). 879 | */ 880 | typedef struct 881 | { 882 | __IO uint32_t DHCSR; /*!< Offset: 0x000 (R/W) Debug Halting Control and Status Register */ 883 | __O uint32_t DCRSR; /*!< Offset: 0x004 ( /W) Debug Core Register Selector Register */ 884 | __IO uint32_t DCRDR; /*!< Offset: 0x008 (R/W) Debug Core Register Data Register */ 885 | __IO uint32_t DEMCR; /*!< Offset: 0x00C (R/W) Debug Exception and Monitor Control Register */ 886 | } CoreDebug_Type; 887 | 888 | /* Debug Halting Control and Status Register */ 889 | #define CoreDebug_DHCSR_DBGKEY_Pos 16 /*!< CoreDebug DHCSR: DBGKEY Position */ 890 | #define CoreDebug_DHCSR_DBGKEY_Msk (0xFFFFUL << CoreDebug_DHCSR_DBGKEY_Pos) /*!< CoreDebug DHCSR: DBGKEY Mask */ 891 | 892 | #define CoreDebug_DHCSR_S_RESET_ST_Pos 25 /*!< CoreDebug DHCSR: S_RESET_ST Position */ 893 | #define CoreDebug_DHCSR_S_RESET_ST_Msk (1UL << CoreDebug_DHCSR_S_RESET_ST_Pos) /*!< CoreDebug DHCSR: S_RESET_ST Mask */ 894 | 895 | #define CoreDebug_DHCSR_S_RETIRE_ST_Pos 24 /*!< CoreDebug DHCSR: S_RETIRE_ST Position */ 896 | #define CoreDebug_DHCSR_S_RETIRE_ST_Msk (1UL << CoreDebug_DHCSR_S_RETIRE_ST_Pos) /*!< CoreDebug DHCSR: S_RETIRE_ST Mask */ 897 | 898 | #define CoreDebug_DHCSR_S_LOCKUP_Pos 19 /*!< CoreDebug DHCSR: S_LOCKUP Position */ 899 | #define CoreDebug_DHCSR_S_LOCKUP_Msk (1UL << CoreDebug_DHCSR_S_LOCKUP_Pos) /*!< CoreDebug DHCSR: S_LOCKUP Mask */ 900 | 901 | #define CoreDebug_DHCSR_S_SLEEP_Pos 18 /*!< CoreDebug DHCSR: S_SLEEP Position */ 902 | #define CoreDebug_DHCSR_S_SLEEP_Msk (1UL << CoreDebug_DHCSR_S_SLEEP_Pos) /*!< CoreDebug DHCSR: S_SLEEP Mask */ 903 | 904 | #define CoreDebug_DHCSR_S_HALT_Pos 17 /*!< CoreDebug DHCSR: S_HALT Position */ 905 | #define CoreDebug_DHCSR_S_HALT_Msk (1UL << CoreDebug_DHCSR_S_HALT_Pos) /*!< CoreDebug DHCSR: S_HALT Mask */ 906 | 907 | #define CoreDebug_DHCSR_S_REGRDY_Pos 16 /*!< CoreDebug DHCSR: S_REGRDY Position */ 908 | #define CoreDebug_DHCSR_S_REGRDY_Msk (1UL << CoreDebug_DHCSR_S_REGRDY_Pos) /*!< CoreDebug DHCSR: S_REGRDY Mask */ 909 | 910 | #define CoreDebug_DHCSR_C_SNAPSTALL_Pos 5 /*!< CoreDebug DHCSR: C_SNAPSTALL Position */ 911 | #define CoreDebug_DHCSR_C_SNAPSTALL_Msk (1UL << CoreDebug_DHCSR_C_SNAPSTALL_Pos) /*!< CoreDebug DHCSR: C_SNAPSTALL Mask */ 912 | 913 | #define CoreDebug_DHCSR_C_MASKINTS_Pos 3 /*!< CoreDebug DHCSR: C_MASKINTS Position */ 914 | #define CoreDebug_DHCSR_C_MASKINTS_Msk (1UL << CoreDebug_DHCSR_C_MASKINTS_Pos) /*!< CoreDebug DHCSR: C_MASKINTS Mask */ 915 | 916 | #define CoreDebug_DHCSR_C_STEP_Pos 2 /*!< CoreDebug DHCSR: C_STEP Position */ 917 | #define CoreDebug_DHCSR_C_STEP_Msk (1UL << CoreDebug_DHCSR_C_STEP_Pos) /*!< CoreDebug DHCSR: C_STEP Mask */ 918 | 919 | #define CoreDebug_DHCSR_C_HALT_Pos 1 /*!< CoreDebug DHCSR: C_HALT Position */ 920 | #define CoreDebug_DHCSR_C_HALT_Msk (1UL << CoreDebug_DHCSR_C_HALT_Pos) /*!< CoreDebug DHCSR: C_HALT Mask */ 921 | 922 | #define CoreDebug_DHCSR_C_DEBUGEN_Pos 0 /*!< CoreDebug DHCSR: C_DEBUGEN Position */ 923 | #define CoreDebug_DHCSR_C_DEBUGEN_Msk (1UL << CoreDebug_DHCSR_C_DEBUGEN_Pos) /*!< CoreDebug DHCSR: C_DEBUGEN Mask */ 924 | 925 | /* Debug Core Register Selector Register */ 926 | #define CoreDebug_DCRSR_REGWnR_Pos 16 /*!< CoreDebug DCRSR: REGWnR Position */ 927 | #define CoreDebug_DCRSR_REGWnR_Msk (1UL << CoreDebug_DCRSR_REGWnR_Pos) /*!< CoreDebug DCRSR: REGWnR Mask */ 928 | 929 | #define CoreDebug_DCRSR_REGSEL_Pos 0 /*!< CoreDebug DCRSR: REGSEL Position */ 930 | #define CoreDebug_DCRSR_REGSEL_Msk (0x1FUL << CoreDebug_DCRSR_REGSEL_Pos) /*!< CoreDebug DCRSR: REGSEL Mask */ 931 | 932 | /* Debug Exception and Monitor Control Register */ 933 | #define CoreDebug_DEMCR_TRCENA_Pos 24 /*!< CoreDebug DEMCR: TRCENA Position */ 934 | #define CoreDebug_DEMCR_TRCENA_Msk (1UL << CoreDebug_DEMCR_TRCENA_Pos) /*!< CoreDebug DEMCR: TRCENA Mask */ 935 | 936 | #define CoreDebug_DEMCR_MON_REQ_Pos 19 /*!< CoreDebug DEMCR: MON_REQ Position */ 937 | #define CoreDebug_DEMCR_MON_REQ_Msk (1UL << CoreDebug_DEMCR_MON_REQ_Pos) /*!< CoreDebug DEMCR: MON_REQ Mask */ 938 | 939 | #define CoreDebug_DEMCR_MON_STEP_Pos 18 /*!< CoreDebug DEMCR: MON_STEP Position */ 940 | #define CoreDebug_DEMCR_MON_STEP_Msk (1UL << CoreDebug_DEMCR_MON_STEP_Pos) /*!< CoreDebug DEMCR: MON_STEP Mask */ 941 | 942 | #define CoreDebug_DEMCR_MON_PEND_Pos 17 /*!< CoreDebug DEMCR: MON_PEND Position */ 943 | #define CoreDebug_DEMCR_MON_PEND_Msk (1UL << CoreDebug_DEMCR_MON_PEND_Pos) /*!< CoreDebug DEMCR: MON_PEND Mask */ 944 | 945 | #define CoreDebug_DEMCR_MON_EN_Pos 16 /*!< CoreDebug DEMCR: MON_EN Position */ 946 | #define CoreDebug_DEMCR_MON_EN_Msk (1UL << CoreDebug_DEMCR_MON_EN_Pos) /*!< CoreDebug DEMCR: MON_EN Mask */ 947 | 948 | #define CoreDebug_DEMCR_VC_HARDERR_Pos 10 /*!< CoreDebug DEMCR: VC_HARDERR Position */ 949 | #define CoreDebug_DEMCR_VC_HARDERR_Msk (1UL << CoreDebug_DEMCR_VC_HARDERR_Pos) /*!< CoreDebug DEMCR: VC_HARDERR Mask */ 950 | 951 | #define CoreDebug_DEMCR_VC_INTERR_Pos 9 /*!< CoreDebug DEMCR: VC_INTERR Position */ 952 | #define CoreDebug_DEMCR_VC_INTERR_Msk (1UL << CoreDebug_DEMCR_VC_INTERR_Pos) /*!< CoreDebug DEMCR: VC_INTERR Mask */ 953 | 954 | #define CoreDebug_DEMCR_VC_BUSERR_Pos 8 /*!< CoreDebug DEMCR: VC_BUSERR Position */ 955 | #define CoreDebug_DEMCR_VC_BUSERR_Msk (1UL << CoreDebug_DEMCR_VC_BUSERR_Pos) /*!< CoreDebug DEMCR: VC_BUSERR Mask */ 956 | 957 | #define CoreDebug_DEMCR_VC_STATERR_Pos 7 /*!< CoreDebug DEMCR: VC_STATERR Position */ 958 | #define CoreDebug_DEMCR_VC_STATERR_Msk (1UL << CoreDebug_DEMCR_VC_STATERR_Pos) /*!< CoreDebug DEMCR: VC_STATERR Mask */ 959 | 960 | #define CoreDebug_DEMCR_VC_CHKERR_Pos 6 /*!< CoreDebug DEMCR: VC_CHKERR Position */ 961 | #define CoreDebug_DEMCR_VC_CHKERR_Msk (1UL << CoreDebug_DEMCR_VC_CHKERR_Pos) /*!< CoreDebug DEMCR: VC_CHKERR Mask */ 962 | 963 | #define CoreDebug_DEMCR_VC_NOCPERR_Pos 5 /*!< CoreDebug DEMCR: VC_NOCPERR Position */ 964 | #define CoreDebug_DEMCR_VC_NOCPERR_Msk (1UL << CoreDebug_DEMCR_VC_NOCPERR_Pos) /*!< CoreDebug DEMCR: VC_NOCPERR Mask */ 965 | 966 | #define CoreDebug_DEMCR_VC_MMERR_Pos 4 /*!< CoreDebug DEMCR: VC_MMERR Position */ 967 | #define CoreDebug_DEMCR_VC_MMERR_Msk (1UL << CoreDebug_DEMCR_VC_MMERR_Pos) /*!< CoreDebug DEMCR: VC_MMERR Mask */ 968 | 969 | #define CoreDebug_DEMCR_VC_CORERESET_Pos 0 /*!< CoreDebug DEMCR: VC_CORERESET Position */ 970 | #define CoreDebug_DEMCR_VC_CORERESET_Msk (1UL << CoreDebug_DEMCR_VC_CORERESET_Pos) /*!< CoreDebug DEMCR: VC_CORERESET Mask */ 971 | 972 | /*@} end of group CMSIS_CoreDebug */ 973 | 974 | 975 | /** \ingroup CMSIS_core_register 976 | @{ 977 | */ 978 | 979 | /* Memory mapping of Cortex-M4 Hardware */ 980 | #define SCS_BASE (0xE000E000UL) /*!< System Control Space Base Address */ 981 | #define ITM_BASE (0xE0000000UL) /*!< ITM Base Address */ 982 | #define CoreDebug_BASE (0xE000EDF0UL) /*!< Core Debug Base Address */ 983 | #define SysTick_BASE (SCS_BASE + 0x0010UL) /*!< SysTick Base Address */ 984 | #define NVIC_BASE (SCS_BASE + 0x0100UL) /*!< NVIC Base Address */ 985 | #define SCB_BASE (SCS_BASE + 0x0D00UL) /*!< System Control Block Base Address */ 986 | 987 | #define SCnSCB ((SCnSCB_Type *) SCS_BASE ) /*!< System control Register not in SCB */ 988 | #define SCB ((SCB_Type *) SCB_BASE ) /*!< SCB configuration struct */ 989 | #define SysTick ((SysTick_Type *) SysTick_BASE ) /*!< SysTick configuration struct */ 990 | #define NVIC ((NVIC_Type *) NVIC_BASE ) /*!< NVIC configuration struct */ 991 | #define ITM ((ITM_Type *) ITM_BASE ) /*!< ITM configuration struct */ 992 | #define CoreDebug ((CoreDebug_Type *) CoreDebug_BASE) /*!< Core Debug configuration struct */ 993 | 994 | #if (__MPU_PRESENT == 1) 995 | #define MPU_BASE (SCS_BASE + 0x0D90UL) /*!< Memory Protection Unit */ 996 | #define MPU ((MPU_Type *) MPU_BASE ) /*!< Memory Protection Unit */ 997 | #endif 998 | 999 | #if (__FPU_PRESENT == 1) 1000 | #define FPU_BASE (SCS_BASE + 0x0F30UL) /*!< Floating Point Unit */ 1001 | #define FPU ((FPU_Type *) FPU_BASE ) /*!< Floating Point Unit */ 1002 | #endif 1003 | 1004 | /*@} */ 1005 | 1006 | 1007 | 1008 | /******************************************************************************* 1009 | * Hardware Abstraction Layer 1010 | ******************************************************************************/ 1011 | /** \defgroup CMSIS_Core_FunctionInterface CMSIS Core Function Interface 1012 | Core Function Interface contains: 1013 | - Core NVIC Functions 1014 | - Core SysTick Functions 1015 | - Core Debug Functions 1016 | - Core Register Access Functions 1017 | */ 1018 | 1019 | 1020 | 1021 | /* ########################## NVIC functions #################################### */ 1022 | /** \ingroup CMSIS_Core_FunctionInterface 1023 | \defgroup CMSIS_Core_NVICFunctions CMSIS Core NVIC Functions 1024 | @{ 1025 | */ 1026 | 1027 | /** \brief Set Priority Grouping 1028 | 1029 | This function sets the priority grouping field using the required unlock sequence. 1030 | The parameter PriorityGroup is assigned to the field SCB->AIRCR [10:8] PRIGROUP field. 1031 | Only values from 0..7 are used. 1032 | In case of a conflict between priority grouping and available 1033 | priority bits (__NVIC_PRIO_BITS) the smallest possible priority group is set. 1034 | 1035 | \param [in] PriorityGroup Priority grouping field 1036 | */ 1037 | static __INLINE void NVIC_SetPriorityGrouping(uint32_t PriorityGroup) 1038 | { 1039 | uint32_t reg_value; 1040 | uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07); /* only values 0..7 are used */ 1041 | 1042 | reg_value = SCB->AIRCR; /* read old register configuration */ 1043 | reg_value &= ~(SCB_AIRCR_VECTKEY_Msk | SCB_AIRCR_PRIGROUP_Msk); /* clear bits to change */ 1044 | reg_value = (reg_value | 1045 | ((uint32_t)0x5FA << SCB_AIRCR_VECTKEY_Pos) | 1046 | (PriorityGroupTmp << 8)); /* Insert write key and priorty group */ 1047 | SCB->AIRCR = reg_value; 1048 | } 1049 | 1050 | 1051 | /** \brief Get Priority Grouping 1052 | 1053 | This function gets the priority grouping from NVIC Interrupt Controller. 1054 | Priority grouping is SCB->AIRCR [10:8] PRIGROUP field. 1055 | 1056 | \return Priority grouping field 1057 | */ 1058 | static __INLINE uint32_t NVIC_GetPriorityGrouping(void) 1059 | { 1060 | return ((SCB->AIRCR & SCB_AIRCR_PRIGROUP_Msk) >> SCB_AIRCR_PRIGROUP_Pos); /* read priority grouping field */ 1061 | } 1062 | 1063 | 1064 | /** \brief Enable External Interrupt 1065 | 1066 | This function enables a device specific interrupt in the NVIC interrupt controller. 1067 | The interrupt number cannot be a negative value. 1068 | 1069 | \param [in] IRQn Number of the external interrupt to enable 1070 | */ 1071 | static __INLINE void NVIC_EnableIRQ(IRQn_Type IRQn) 1072 | { 1073 | /* NVIC->ISER[((uint32_t)(IRQn) >> 5)] = (1 << ((uint32_t)(IRQn) & 0x1F)); enable interrupt */ 1074 | NVIC->ISER[(uint32_t)((int32_t)IRQn) >> 5] = (uint32_t)(1 << ((uint32_t)((int32_t)IRQn) & (uint32_t)0x1F)); /* enable interrupt */ 1075 | } 1076 | 1077 | 1078 | /** \brief Disable External Interrupt 1079 | 1080 | This function disables a device specific interrupt in the NVIC interrupt controller. 1081 | The interrupt number cannot be a negative value. 1082 | 1083 | \param [in] IRQn Number of the external interrupt to disable 1084 | */ 1085 | static __INLINE void NVIC_DisableIRQ(IRQn_Type IRQn) 1086 | { 1087 | NVIC->ICER[((uint32_t)(IRQn) >> 5)] = (1 << ((uint32_t)(IRQn) & 0x1F)); /* disable interrupt */ 1088 | } 1089 | 1090 | 1091 | /** \brief Get Pending Interrupt 1092 | 1093 | This function reads the pending register in the NVIC and returns the pending bit 1094 | for the specified interrupt. 1095 | 1096 | \param [in] IRQn Number of the interrupt for get pending 1097 | \return 0 Interrupt status is not pending 1098 | \return 1 Interrupt status is pending 1099 | */ 1100 | static __INLINE uint32_t NVIC_GetPendingIRQ(IRQn_Type IRQn) 1101 | { 1102 | return((uint32_t) ((NVIC->ISPR[(uint32_t)(IRQn) >> 5] & (1 << ((uint32_t)(IRQn) & 0x1F)))?1:0)); /* Return 1 if pending else 0 */ 1103 | } 1104 | 1105 | 1106 | /** \brief Set Pending Interrupt 1107 | 1108 | This function sets the pending bit for the specified interrupt. 1109 | The interrupt number cannot be a negative value. 1110 | 1111 | \param [in] IRQn Number of the interrupt for set pending 1112 | */ 1113 | static __INLINE void NVIC_SetPendingIRQ(IRQn_Type IRQn) 1114 | { 1115 | NVIC->ISPR[((uint32_t)(IRQn) >> 5)] = (1 << ((uint32_t)(IRQn) & 0x1F)); /* set interrupt pending */ 1116 | } 1117 | 1118 | 1119 | /** \brief Clear Pending Interrupt 1120 | 1121 | This function clears the pending bit for the specified interrupt. 1122 | The interrupt number cannot be a negative value. 1123 | 1124 | \param [in] IRQn Number of the interrupt for clear pending 1125 | */ 1126 | static __INLINE void NVIC_ClearPendingIRQ(IRQn_Type IRQn) 1127 | { 1128 | NVIC->ICPR[((uint32_t)(IRQn) >> 5)] = (1 << ((uint32_t)(IRQn) & 0x1F)); /* Clear pending interrupt */ 1129 | } 1130 | 1131 | 1132 | /** \brief Get Active Interrupt 1133 | 1134 | This function reads the active register in NVIC and returns the active bit. 1135 | \param [in] IRQn Number of the interrupt for get active 1136 | \return 0 Interrupt status is not active 1137 | \return 1 Interrupt status is active 1138 | */ 1139 | static __INLINE uint32_t NVIC_GetActive(IRQn_Type IRQn) 1140 | { 1141 | return((uint32_t)((NVIC->IABR[(uint32_t)(IRQn) >> 5] & (1 << ((uint32_t)(IRQn) & 0x1F)))?1:0)); /* Return 1 if active else 0 */ 1142 | } 1143 | 1144 | 1145 | /** \brief Set Interrupt Priority 1146 | 1147 | This function sets the priority for the specified interrupt. The interrupt 1148 | number can be positive to specify an external (device specific) 1149 | interrupt, or negative to specify an internal (core) interrupt. 1150 | 1151 | Note: The priority cannot be set for every core interrupt. 1152 | 1153 | \param [in] IRQn Number of the interrupt for set priority 1154 | \param [in] priority Priority to set 1155 | */ 1156 | static __INLINE void NVIC_SetPriority(IRQn_Type IRQn, uint32_t priority) 1157 | { 1158 | if(IRQn < 0) { 1159 | SCB->SHP[((uint32_t)(IRQn) & 0xF)-4] = ((priority << (8 - __NVIC_PRIO_BITS)) & 0xff); } /* set Priority for Cortex-M System Interrupts */ 1160 | else { 1161 | NVIC->IP[(uint32_t)(IRQn)] = ((priority << (8 - __NVIC_PRIO_BITS)) & 0xff); } /* set Priority for device specific Interrupts */ 1162 | } 1163 | 1164 | 1165 | /** \brief Get Interrupt Priority 1166 | 1167 | This function reads the priority for the specified interrupt. The interrupt 1168 | number can be positive to specify an external (device specific) 1169 | interrupt, or negative to specify an internal (core) interrupt. 1170 | 1171 | The returned priority value is automatically aligned to the implemented 1172 | priority bits of the microcontroller. 1173 | 1174 | \param [in] IRQn Number of the interrupt for get priority 1175 | \return Interrupt Priority 1176 | */ 1177 | static __INLINE uint32_t NVIC_GetPriority(IRQn_Type IRQn) 1178 | { 1179 | 1180 | if(IRQn < 0) { 1181 | return((uint32_t)(SCB->SHP[((uint32_t)(IRQn) & 0xF)-4] >> (8 - __NVIC_PRIO_BITS))); } /* get priority for Cortex-M system interrupts */ 1182 | else { 1183 | return((uint32_t)(NVIC->IP[(uint32_t)(IRQn)] >> (8 - __NVIC_PRIO_BITS))); } /* get priority for device specific interrupts */ 1184 | } 1185 | 1186 | 1187 | /** \brief Encode Priority 1188 | 1189 | This function encodes the priority for an interrupt with the given priority group, 1190 | preemptive priority value and sub priority value. 1191 | In case of a conflict between priority grouping and available 1192 | priority bits (__NVIC_PRIO_BITS) the samllest possible priority group is set. 1193 | 1194 | The returned priority value can be used for NVIC_SetPriority(...) function 1195 | 1196 | \param [in] PriorityGroup Used priority group 1197 | \param [in] PreemptPriority Preemptive priority value (starting from 0) 1198 | \param [in] SubPriority Sub priority value (starting from 0) 1199 | \return Encoded priority for the interrupt 1200 | */ 1201 | static __INLINE uint32_t NVIC_EncodePriority (uint32_t PriorityGroup, uint32_t PreemptPriority, uint32_t SubPriority) 1202 | { 1203 | uint32_t PriorityGroupTmp = (PriorityGroup & 0x07); /* only values 0..7 are used */ 1204 | uint32_t PreemptPriorityBits; 1205 | uint32_t SubPriorityBits; 1206 | 1207 | PreemptPriorityBits = ((7 - PriorityGroupTmp) > __NVIC_PRIO_BITS) ? __NVIC_PRIO_BITS : 7 - PriorityGroupTmp; 1208 | SubPriorityBits = ((PriorityGroupTmp + __NVIC_PRIO_BITS) < 7) ? 0 : PriorityGroupTmp - 7 + __NVIC_PRIO_BITS; 1209 | 1210 | return ( 1211 | ((PreemptPriority & ((1 << (PreemptPriorityBits)) - 1)) << SubPriorityBits) | 1212 | ((SubPriority & ((1 << (SubPriorityBits )) - 1))) 1213 | ); 1214 | } 1215 | 1216 | 1217 | /** \brief Decode Priority 1218 | 1219 | This function decodes an interrupt priority value with the given priority group to 1220 | preemptive priority value and sub priority value. 1221 | In case of a conflict between priority grouping and available 1222 | priority bits (__NVIC_PRIO_BITS) the samllest possible priority group is set. 1223 | 1224 | The priority value can be retrieved with NVIC_GetPriority(...) function 1225 | 1226 | \param [in] Priority Priority value 1227 | \param [in] PriorityGroup Used priority group 1228 | \param [out] pPreemptPriority Preemptive priority value (starting from 0) 1229 | \param [out] pSubPriority Sub priority value (starting from 0) 1230 | */ 1231 | static __INLINE void NVIC_DecodePriority (uint32_t Priority, uint32_t PriorityGroup, uint32_t* pPreemptPriority, uint32_t* pSubPriority) 1232 | { 1233 | uint32_t PriorityGroupTmp = (PriorityGroup & 0x07); /* only values 0..7 are used */ 1234 | uint32_t PreemptPriorityBits; 1235 | uint32_t SubPriorityBits; 1236 | 1237 | PreemptPriorityBits = ((7 - PriorityGroupTmp) > __NVIC_PRIO_BITS) ? __NVIC_PRIO_BITS : 7 - PriorityGroupTmp; 1238 | SubPriorityBits = ((PriorityGroupTmp + __NVIC_PRIO_BITS) < 7) ? 0 : PriorityGroupTmp - 7 + __NVIC_PRIO_BITS; 1239 | 1240 | *pPreemptPriority = (Priority >> SubPriorityBits) & ((1 << (PreemptPriorityBits)) - 1); 1241 | *pSubPriority = (Priority ) & ((1 << (SubPriorityBits )) - 1); 1242 | } 1243 | 1244 | 1245 | /** \brief System Reset 1246 | 1247 | This function initiate a system reset request to reset the MCU. 1248 | */ 1249 | static __INLINE void NVIC_SystemReset(void) 1250 | { 1251 | __DSB(); /* Ensure all outstanding memory accesses included 1252 | buffered write are completed before reset */ 1253 | SCB->AIRCR = ((0x5FA << SCB_AIRCR_VECTKEY_Pos) | 1254 | (SCB->AIRCR & SCB_AIRCR_PRIGROUP_Msk) | 1255 | SCB_AIRCR_SYSRESETREQ_Msk); /* Keep priority group unchanged */ 1256 | __DSB(); /* Ensure completion of memory access */ 1257 | while(1); /* wait until reset */ 1258 | } 1259 | 1260 | /*@} end of CMSIS_Core_NVICFunctions */ 1261 | 1262 | 1263 | 1264 | /* ################################## SysTick function ############################################ */ 1265 | /** \ingroup CMSIS_Core_FunctionInterface 1266 | \defgroup CMSIS_Core_SysTickFunctions CMSIS Core SysTick Functions 1267 | @{ 1268 | */ 1269 | 1270 | #if (__Vendor_SysTickConfig == 0) 1271 | 1272 | /** \brief System Tick Configuration 1273 | 1274 | This function initialises the system tick timer and its interrupt and start the system tick timer. 1275 | Counter is in free running mode to generate periodical interrupts. 1276 | 1277 | \param [in] ticks Number of ticks between two interrupts 1278 | \return 0 Function succeeded 1279 | \return 1 Function failed 1280 | */ 1281 | static __INLINE uint32_t SysTick_Config(uint32_t ticks) 1282 | { 1283 | if (ticks > SysTick_LOAD_RELOAD_Msk) return (1); /* Reload value impossible */ 1284 | 1285 | SysTick->LOAD = (ticks & SysTick_LOAD_RELOAD_Msk) - 1; /* set reload register */ 1286 | NVIC_SetPriority (SysTick_IRQn, (1<<__NVIC_PRIO_BITS) - 1); /* set Priority for Cortex-M0 System Interrupts */ 1287 | SysTick->VAL = 0; /* Load the SysTick Counter Value */ 1288 | SysTick->CTRL = SysTick_CTRL_CLKSOURCE_Msk | 1289 | SysTick_CTRL_TICKINT_Msk | 1290 | SysTick_CTRL_ENABLE_Msk; /* Enable SysTick IRQ and SysTick Timer */ 1291 | return (0); /* Function successful */ 1292 | } 1293 | 1294 | #endif 1295 | 1296 | /*@} end of CMSIS_Core_SysTickFunctions */ 1297 | 1298 | 1299 | 1300 | /* ##################################### Debug In/Output function ########################################### */ 1301 | /** \ingroup CMSIS_Core_FunctionInterface 1302 | \defgroup CMSIS_core_DebugFunctions CMSIS Core Debug Functions 1303 | @{ 1304 | */ 1305 | 1306 | extern volatile int32_t ITM_RxBuffer; /*!< external variable to receive characters */ 1307 | #define ITM_RXBUFFER_EMPTY 0x5AA55AA5 /*!< value identifying ITM_RxBuffer is ready for next character */ 1308 | 1309 | 1310 | /** \brief ITM Send Character 1311 | 1312 | This function transmits a character via the ITM channel 0. 1313 | It just returns when no debugger is connected that has booked the output. 1314 | It is blocking when a debugger is connected, but the previous character send is not transmitted. 1315 | 1316 | \param [in] ch Character to transmit 1317 | \return Character to transmit 1318 | */ 1319 | static __INLINE uint32_t ITM_SendChar (uint32_t ch) 1320 | { 1321 | if ((CoreDebug->DEMCR & CoreDebug_DEMCR_TRCENA_Msk) && /* Trace enabled */ 1322 | (ITM->TCR & ITM_TCR_ITMENA_Msk) && /* ITM enabled */ 1323 | (ITM->TER & (1UL << 0) ) ) /* ITM Port #0 enabled */ 1324 | { 1325 | while (ITM->PORT[0].u32 == 0); 1326 | ITM->PORT[0].u8 = (uint8_t) ch; 1327 | } 1328 | return (ch); 1329 | } 1330 | 1331 | 1332 | /** \brief ITM Receive Character 1333 | 1334 | This function inputs a character via external variable ITM_RxBuffer. 1335 | It just returns when no debugger is connected that has booked the output. 1336 | It is blocking when a debugger is connected, but the previous character send is not transmitted. 1337 | 1338 | \return Received character 1339 | \return -1 No character received 1340 | */ 1341 | static __INLINE int32_t ITM_ReceiveChar (void) { 1342 | int32_t ch = -1; /* no character available */ 1343 | 1344 | if (ITM_RxBuffer != ITM_RXBUFFER_EMPTY) { 1345 | ch = ITM_RxBuffer; 1346 | ITM_RxBuffer = ITM_RXBUFFER_EMPTY; /* ready for next character */ 1347 | } 1348 | 1349 | return (ch); 1350 | } 1351 | 1352 | 1353 | /** \brief ITM Check Character 1354 | 1355 | This function checks external variable ITM_RxBuffer whether a character is available or not. 1356 | It returns '1' if a character is available and '0' if no character is available. 1357 | 1358 | \return 0 No character available 1359 | \return 1 Character available 1360 | */ 1361 | static __INLINE int32_t ITM_CheckChar (void) { 1362 | 1363 | if (ITM_RxBuffer == ITM_RXBUFFER_EMPTY) { 1364 | return (0); /* no character available */ 1365 | } else { 1366 | return (1); /* character available */ 1367 | } 1368 | } 1369 | 1370 | /*@} end of CMSIS_core_DebugFunctions */ 1371 | 1372 | #endif /* __CORE_CM4_H_DEPENDANT */ 1373 | 1374 | #endif /* __CMSIS_GENERIC */ 1375 | 1376 | #ifdef __cplusplus 1377 | } 1378 | #endif 1379 | --------------------------------------------------------------------------------