diff --git a/STM32/inc/F0/stm32f0.h b/STM32/inc/F0/stm32f0.h new file mode 100644 index 0000000..7abda18 --- /dev/null +++ b/STM32/inc/F0/stm32f0.h @@ -0,0 +1,224 @@ +/* + * stm32f0.h + * + * Copyright 2017 Edward V. Emelianoff + * + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program; if not, write to the Free Software + * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, + * MA 02110-1301, USA. + */ +#pragma once +#ifndef __STM32F0_H__ +#define __STM32F0_H__ + +#include "stm32f0xx.h" + +#ifndef TRUE_INLINE +#define TRUE_INLINE __attribute__((always_inline)) static inline +#endif + +#ifndef NULL +#define NULL (0) +#endif + +// some good things from CMSIS +#define nop() __NOP() + +/************************* RCC *************************/ +// reset clocking registers +TRUE_INLINE void sysreset(void){ + /* Reset the RCC clock configuration to the default reset state ------------*/ + /* Set HSION bit */ + RCC->CR |= (uint32_t)0x00000001; +#if defined (STM32F051x8) || defined (STM32F058x8) + /* Reset SW[1:0], HPRE[3:0], PPRE[2:0], ADCPRE and MCOSEL[2:0] bits */ + RCC->CFGR &= (uint32_t)0xF8FFB80C; +#else + /* Reset SW[1:0], HPRE[3:0], PPRE[2:0], ADCPRE, MCOSEL[2:0], MCOPRE[2:0] and PLLNODIV bits */ + RCC->CFGR &= (uint32_t)0x08FFB80C; +#endif /* STM32F051x8 or STM32F058x8 */ + /* Reset HSEON, CSSON and PLLON bits */ + RCC->CR &= (uint32_t)0xFEF6FFFF; + /* Reset HSEBYP bit */ + RCC->CR &= (uint32_t)0xFFFBFFFF; + /* Reset PLLSRC, PLLXTPRE and PLLMUL[3:0] bits */ + RCC->CFGR &= (uint32_t)0xFFC0FFFF; + /* Reset PREDIV[3:0] bits */ + RCC->CFGR2 &= (uint32_t)0xFFFFFFF0; + #if defined (STM32F072xB) || defined (STM32F078xB) + /* Reset USART2SW[1:0], USART1SW[1:0], I2C1SW, CECSW, USBSW and ADCSW bits */ + RCC->CFGR3 &= (uint32_t)0xFFFCFE2C; +#elif defined (STM32F071xB) + /* Reset USART2SW[1:0], USART1SW[1:0], I2C1SW, CECSW and ADCSW bits */ + RCC->CFGR3 &= (uint32_t)0xFFFFCEAC; +#elif defined (STM32F091xC) || defined (STM32F098xx) + /* Reset USART3SW[1:0], USART2SW[1:0], USART1SW[1:0], I2C1SW, CECSW and ADCSW bits */ + RCC->CFGR3 &= (uint32_t)0xFFF0FEAC; +#elif defined (STM32F030x4) || defined (STM32F030x6) || defined (STM32F030x8) || defined (STM32F031x6) || defined (STM32F038xx) || defined (STM32F030xC) + /* Reset USART1SW[1:0], I2C1SW and ADCSW bits */ + RCC->CFGR3 &= (uint32_t)0xFFFFFEEC; +#elif defined (STM32F051x8) || defined (STM32F058xx) + /* Reset USART1SW[1:0], I2C1SW, CECSW and ADCSW bits */ + RCC->CFGR3 &= (uint32_t)0xFFFFFEAC; +#elif defined (STM32F042x6) || defined (STM32F048xx) + /* Reset USART1SW[1:0], I2C1SW, CECSW, USBSW and ADCSW bits */ + RCC->CFGR3 &= (uint32_t)0xFFFFFE2C; +#elif defined (STM32F070x6) || defined (STM32F070xB) + /* Reset USART1SW[1:0], I2C1SW, USBSW and ADCSW bits */ + RCC->CFGR3 &= (uint32_t)0xFFFFFE6C; + /* Set default USB clock to PLLCLK, since there is no HSI48 */ + RCC->CFGR3 |= (uint32_t)0x00000080; +#else +#error "No target selected" +#endif + /* Disable all interrupts */ + RCC->CIR = 0x00000000; + /* Reset HSI14 bit */ + RCC->CR2 &= (uint32_t)0xFFFFFFFE; + // Enable Prefetch Buffer and set Flash Latency + FLASH->ACR = FLASH_ACR_PRFTBE | FLASH_ACR_LATENCY; + /* HCLK = SYSCLK */ + RCC->CFGR |= RCC_CFGR_HPRE_DIV1; + /* PCLK = HCLK */ + RCC->CFGR |= RCC_CFGR_PPRE_DIV1; + /* PLL configuration = (HSI/2) * 12 = ~48 MHz */ + RCC->CFGR &= ~(RCC_CFGR_PLLSRC | RCC_CFGR_PLLMUL); + RCC->CFGR |= RCC_CFGR_PLLMUL12; + /* Enable PLL */ + RCC->CR |= RCC_CR_PLLON; + /* Wait till PLL is ready */ + while((RCC->CR & RCC_CR_PLLRDY) == 0){} + /* Select PLL as system clock source */ + RCC->CFGR &= ~RCC_CFGR_SW; + RCC->CFGR |= RCC_CFGR_SW_PLL; + /* Wait till PLL is used as system clock source */ + while ((RCC->CFGR & RCC_CFGR_SWS) != RCC_CFGR_SWS_PLL){} +} + +TRUE_INLINE void StartHSE(){ + // disable PLL + RCC->CR &= ~RCC_CR_PLLON; + RCC->CR |= RCC_CR_HSEON; + while ((RCC->CIR & RCC_CIR_HSERDYF) != 0); + RCC->CIR |= RCC_CIR_HSERDYC; // clear rdy flag + /* PLL configuration = (HSE) * 12 = ~48 MHz */ + RCC->CFGR &= ~(RCC_CFGR_PLLSRC | RCC_CFGR_PLLMUL); + RCC->CFGR |= RCC_CFGR_PLLSRC_HSE_PREDIV | RCC_CFGR_PLLMUL12; + RCC->CR |= RCC_CR_PLLON; + while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS) != (uint32_t)RCC_CFGR_SWS_PLL){} +} + +#if !defined (STM32F030x4) && !defined (STM32F030x6) && !defined (STM32F030x8) && !defined (STM32F031x6) && !defined (STM32F038xx) && !defined (STM32F030xC) +TRUE_INLINE void StartHSI48(){ + // disable PLL + RCC->CR &= ~RCC_CR_PLLON; + RCC->CR2 &= RCC_CR2_HSI48ON; // turn on HSI48 + while((RCC->CR2 & RCC_CR2_HSI48RDY) == 0); + RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_PLLSRC | RCC_CFGR_PLLMUL)); + // HSI48/2 * 2 = HSI48 + RCC->CFGR |= (uint32_t)(RCC_CFGR_PLLSRC_HSI48_PREDIV | RCC_CFGR_PLLMUL2); + RCC->CR |= RCC_CR_PLLON; + // select HSI48 as system clock source + RCC->CFGR &= ~RCC_CFGR_SW; + RCC->CFGR |= RCC_CFGR_SW_HSI48; + while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS) != (uint32_t)RCC_CFGR_SWS_HSI48){} +} +#endif + +/************************* GPIO *************************/ + +/******************* Bit definition for GPIO_MODER register *****************/ +// _AI - analog inpt, _O - general output, _AF - alternate function +#define GPIO_MODER_MODER0_AI ((uint32_t)0x00000003) +#define GPIO_MODER_MODER0_O ((uint32_t)0x00000001) +#define GPIO_MODER_MODER0_AF ((uint32_t)0x00000002) +#define GPIO_MODER_MODER1_AI ((uint32_t)0x0000000C) +#define GPIO_MODER_MODER1_O ((uint32_t)0x00000004) +#define GPIO_MODER_MODER1_AF ((uint32_t)0x00000008) +#define GPIO_MODER_MODER2_AI ((uint32_t)0x00000030) +#define GPIO_MODER_MODER2_O ((uint32_t)0x00000010) +#define GPIO_MODER_MODER2_AF ((uint32_t)0x00000020) +#define GPIO_MODER_MODER3_AI ((uint32_t)0x000000C0) +#define GPIO_MODER_MODER3_O ((uint32_t)0x00000040) +#define GPIO_MODER_MODER3_AF ((uint32_t)0x00000080) +#define GPIO_MODER_MODER4_AI ((uint32_t)0x00000300) +#define GPIO_MODER_MODER4_O ((uint32_t)0x00000100) +#define GPIO_MODER_MODER4_AF ((uint32_t)0x00000200) +#define GPIO_MODER_MODER5_AI ((uint32_t)0x00000C00) +#define GPIO_MODER_MODER5_O ((uint32_t)0x00000400) +#define GPIO_MODER_MODER5_AF ((uint32_t)0x00000800) +#define GPIO_MODER_MODER6_AI ((uint32_t)0x00003000) +#define GPIO_MODER_MODER6_O ((uint32_t)0x00001000) +#define GPIO_MODER_MODER6_AF ((uint32_t)0x00002000) +#define GPIO_MODER_MODER7_AI ((uint32_t)0x0000C000) +#define GPIO_MODER_MODER7_O ((uint32_t)0x00004000) +#define GPIO_MODER_MODER7_AF ((uint32_t)0x00008000) +#define GPIO_MODER_MODER8_AI ((uint32_t)0x00030000) +#define GPIO_MODER_MODER8_O ((uint32_t)0x00010000) +#define GPIO_MODER_MODER8_AF ((uint32_t)0x00020000) +#define GPIO_MODER_MODER9_AI ((uint32_t)0x000C0000) +#define GPIO_MODER_MODER9_O ((uint32_t)0x00040000) +#define GPIO_MODER_MODER9_AF ((uint32_t)0x00080000) +#define GPIO_MODER_MODER10_AI ((uint32_t)0x00300000) +#define GPIO_MODER_MODER10_O ((uint32_t)0x00100000) +#define GPIO_MODER_MODER10_AF ((uint32_t)0x00200000) +#define GPIO_MODER_MODER11_AI ((uint32_t)0x00C00000) +#define GPIO_MODER_MODER11_O ((uint32_t)0x00400000) +#define GPIO_MODER_MODER11_AF ((uint32_t)0x00800000) +#define GPIO_MODER_MODER12_AI ((uint32_t)0x03000000) +#define GPIO_MODER_MODER12_O ((uint32_t)0x01000000) +#define GPIO_MODER_MODER12_AF ((uint32_t)0x02000000) +#define GPIO_MODER_MODER13_AI ((uint32_t)0x0C000000) +#define GPIO_MODER_MODER13_O ((uint32_t)0x04000000) +#define GPIO_MODER_MODER13_AF ((uint32_t)0x08000000) +#define GPIO_MODER_MODER14_AI ((uint32_t)0x30000000) +#define GPIO_MODER_MODER14_O ((uint32_t)0x10000000) +#define GPIO_MODER_MODER14_AF ((uint32_t)0x20000000) +#define GPIO_MODER_MODER15_AI ((uint32_t)0xC0000000) +#define GPIO_MODER_MODER15_O ((uint32_t)0x40000000) +#define GPIO_MODER_MODER15_AF ((uint32_t)0x80000000) + +#define pin_toggle(gpioport, gpios) do{ \ + register uint32_t __port = gpioport->ODR; \ + gpioport->BSRR = ((__port & gpios) << 16) | (~__port & gpios);}while(0) + +#define pin_set(gpioport, gpios) do{gpioport->BSRR = gpios;}while(0) +#define pin_clear(gpioport, gpios) do{gpioport->BSRR = (gpios << 16);}while(0) +#define pin_read(gpioport, gpios) (gpioport->IDR & gpios ? 1 : 0) +#define pin_write(gpioport, gpios) do{gpioport->ODR = gpios;}while(0) + +/************************* ADC *************************/ +/* inner termometer calibration values + * Temp = (Vsense - V30)/Avg_Slope + 30 + * Avg_Slope = (V110 - V30) / (110 - 30) + */ +#define TEMP110_CAL_ADDR ((uint16_t*) ((uint32_t) 0x1FFFF7C2)) +#define TEMP30_CAL_ADDR ((uint16_t*) ((uint32_t) 0x1FFFF7B8)) +// VDDA_Actual = 3.3V * VREFINT_CAL / average vref value +#define VREFINT_CAL_ADDR ((uint16_t*) ((uint32_t) 0x1FFFF7BA)) +#define VDD_CALIB ((uint16_t) (330)) +#define VDD_APPLI ((uint16_t) (300)) + +/************************* USART *************************/ + +#define USART_CR2_ADD_SHIFT 24 +// set address/character match value +#define USART_CR2_ADD_VAL(x) ((x) << USART_CR2_ADD_SHIFT) + +//#define do{}while(0) + + + + +#endif // __STM32F0_H__ diff --git a/STM32/inc/F0/stm32f030x6.h b/STM32/inc/F0/stm32f030x6.h new file mode 100644 index 0000000..5f30771 --- /dev/null +++ b/STM32/inc/F0/stm32f030x6.h @@ -0,0 +1,3161 @@ +/** + ****************************************************************************** + * @file stm32f030x6.h + * @author MCD Application Team + * @version V2.2.0 + * @date 05-December-2014 + * @brief CMSIS STM32F030x4/STM32F030x6 devices Peripheral Access Layer Header File. + * + * This file contains: + * - Data structures and the address mapping for all peripherals + * - Peripheral's registers declarations and bits definition + * - Macros to access peripheral’s registers hardware + * + ****************************************************************************** + * @attention + * + *

© COPYRIGHT(c) 2014 STMicroelectronics

+ * + * Redistribution and use in source and binary forms, with or without modification, + * are permitted provided that the following conditions are met: + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * 3. Neither the name of STMicroelectronics nor the names of its contributors + * may be used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************** + */ + +/** @addtogroup CMSIS_Device + * @{ + */ + +/** @addtogroup stm32f030x6 + * @{ + */ + +#ifndef __STM32F030x6_H +#define __STM32F030x6_H + +#ifdef __cplusplus + extern "C" { +#endif /* __cplusplus */ + +/** @addtogroup Configuration_section_for_CMSIS + * @{ + */ + +/** + * @brief Configuration of the Cortex-M0 Processor and Core Peripherals + */ +#define __CM0_REV 0 /*!< Core Revision r0p0 */ +#define __MPU_PRESENT 0 /*!< STM32F0xx do not provide MPU */ +#define __NVIC_PRIO_BITS 2 /*!< STM32F0xx uses 2 Bits for the Priority Levels */ +#define __Vendor_SysTickConfig 0 /*!< Set to 1 if different SysTick Config is used */ + +/** + * @} + */ + +/** @addtogroup Peripheral_interrupt_number_definition + * @{ + */ + +/** + * @brief STM32F030x4/STM32F030x6 device Interrupt Number Definition + */ +typedef enum +{ +/****** Cortex-M0 Processor Exceptions Numbers **************************************************************/ + NonMaskableInt_IRQn = -14, /*!< 2 Non Maskable Interrupt */ + HardFault_IRQn = -13, /*!< 3 Cortex-M0 Hard Fault Interrupt */ + SVC_IRQn = -5, /*!< 11 Cortex-M0 SV Call Interrupt */ + PendSV_IRQn = -2, /*!< 14 Cortex-M0 Pend SV Interrupt */ + SysTick_IRQn = -1, /*!< 15 Cortex-M0 System Tick Interrupt */ + +/****** STM32F030x4/STM32F030x6 specific Interrupt Numbers **************************************/ + WWDG_IRQn = 0, /*!< Window WatchDog Interrupt */ + RTC_IRQn = 2, /*!< RTC Interrupt through EXTI Lines 17, 19 and 20 */ + FLASH_IRQn = 3, /*!< FLASH global Interrupt */ + RCC_IRQn = 4, /*!< RCC Global Interrupts */ + EXTI0_1_IRQn = 5, /*!< EXTI Line 0 and 1 Interrupts */ + EXTI2_3_IRQn = 6, /*!< EXTI Line 2 and 3 Interrupts */ + EXTI4_15_IRQn = 7, /*!< EXTI Line 4 to 15 Interrupts */ + DMA1_Channel1_IRQn = 9, /*!< DMA1 Channel 1 Interrupt */ + DMA1_Channel2_3_IRQn = 10, /*!< DMA1 Channel 2 and Channel 3 Interrupts */ + DMA1_Channel4_5_IRQn = 11, /*!< DMA1 Channel 4 and Channel 5 Interrupts */ + ADC1_IRQn = 12, /*!< ADC1 Interrupts */ + TIM1_BRK_UP_TRG_COM_IRQn = 13, /*!< TIM1 Break, Update, Trigger and Commutation Interrupts */ + TIM1_CC_IRQn = 14, /*!< TIM1 Capture Compare Interrupt */ + TIM3_IRQn = 16, /*!< TIM3 global Interrupt */ + TIM14_IRQn = 19, /*!< TIM14 global Interrupt */ + TIM16_IRQn = 21, /*!< TIM16 global Interrupt */ + TIM17_IRQn = 22, /*!< TIM17 global Interrupt */ + I2C1_IRQn = 23, /*!< I2C1 Event Interrupt */ + SPI1_IRQn = 25, /*!< SPI1 global Interrupt */ + USART1_IRQn = 27 /*!< USART1 global Interrupt */ +} IRQn_Type; + +/** + * @} + */ + +#include "core_cm0.h" /* Cortex-M0 processor and core peripherals */ +#include + +/** @addtogroup Peripheral_registers_structures + * @{ + */ + +/** + * @brief Analog to Digital Converter + */ + +typedef struct +{ + __IO uint32_t ISR; /*!< ADC Interrupt and Status register, Address offset:0x00 */ + __IO uint32_t IER; /*!< ADC Interrupt Enable register, Address offset:0x04 */ + __IO uint32_t CR; /*!< ADC Control register, Address offset:0x08 */ + __IO uint32_t CFGR1; /*!< ADC Configuration register 1, Address offset:0x0C */ + __IO uint32_t CFGR2; /*!< ADC Configuration register 2, Address offset:0x10 */ + __IO uint32_t SMPR; /*!< ADC Sampling time register, Address offset:0x14 */ + uint32_t RESERVED1; /*!< Reserved, 0x18 */ + uint32_t RESERVED2; /*!< Reserved, 0x1C */ + __IO uint32_t TR; /*!< ADC watchdog threshold register, Address offset:0x20 */ + uint32_t RESERVED3; /*!< Reserved, 0x24 */ + __IO uint32_t CHSELR; /*!< ADC channel selection register, Address offset:0x28 */ + uint32_t RESERVED4[5]; /*!< Reserved, 0x2C */ + __IO uint32_t DR; /*!< ADC data register, Address offset:0x40 */ +}ADC_TypeDef; + +typedef struct +{ + __IO uint32_t CCR; +}ADC_Common_TypeDef; + +/** + * @brief CRC calculation unit + */ + +typedef struct +{ + __IO uint32_t DR; /*!< CRC Data register, Address offset: 0x00 */ + __IO uint8_t IDR; /*!< CRC Independent data register, Address offset: 0x04 */ + uint8_t RESERVED0; /*!< Reserved, 0x05 */ + uint16_t RESERVED1; /*!< Reserved, 0x06 */ + __IO uint32_t CR; /*!< CRC Control register, Address offset: 0x08 */ + uint32_t RESERVED2; /*!< Reserved, 0x0C */ + __IO uint32_t INIT; /*!< Initial CRC value register, Address offset: 0x10 */ + __IO uint32_t POL; /*!< CRC polynomial register, Address offset: 0x14 */ +}CRC_TypeDef; + +/** + * @brief Debug MCU + */ + +typedef struct +{ + __IO uint32_t IDCODE; /*!< MCU device ID code, Address offset: 0x00 */ + __IO uint32_t CR; /*!< Debug MCU configuration register, Address offset: 0x04 */ + __IO uint32_t APB1FZ; /*!< Debug MCU APB1 freeze register, Address offset: 0x08 */ + __IO uint32_t APB2FZ; /*!< Debug MCU APB2 freeze register, Address offset: 0x0C */ +}DBGMCU_TypeDef; + +/** + * @brief DMA Controller + */ + +typedef struct +{ + __IO uint32_t CCR; /*!< DMA channel x configuration register */ + __IO uint32_t CNDTR; /*!< DMA channel x number of data register */ + __IO uint32_t CPAR; /*!< DMA channel x peripheral address register */ + __IO uint32_t CMAR; /*!< DMA channel x memory address register */ +}DMA_Channel_TypeDef; + +typedef struct +{ + __IO uint32_t ISR; /*!< DMA interrupt status register, Address offset: 0x00 */ + __IO uint32_t IFCR; /*!< DMA interrupt flag clear register, Address offset: 0x04 */ +}DMA_TypeDef; + +/** + * @brief External Interrupt/Event Controller + */ + +typedef struct +{ + __IO uint32_t IMR; /*!
© COPYRIGHT(c) 2014 STMicroelectronics
+ * + * Redistribution and use in source and binary forms, with or without modification, + * are permitted provided that the following conditions are met: + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * 3. Neither the name of STMicroelectronics nor the names of its contributors + * may be used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************** + */ + +/** @addtogroup CMSIS + * @{ + */ + +/** @addtogroup stm32f0xx + * @{ + */ + +#ifndef __STM32F0xx_H +#define __STM32F0xx_H + +#ifdef __cplusplus + extern "C" { +#endif /* __cplusplus */ + +/** @addtogroup Library_configuration_section + * @{ + */ + +#if !defined (STM32F030x4) && !defined (STM32F030x6) && !defined (STM32F030x8) && \ + !defined (STM32F031x6) && !defined (STM32F038xx) && \ + !defined (STM32F042x6) && !defined (STM32F048xx) && !defined (STM32F070x6) && \ + !defined (STM32F051x8) && !defined (STM32F058xx) && \ + !defined (STM32F071xB) && !defined (STM32F072xB) && !defined (STM32F078xx) && !defined (STM32F070xB) && \ + !defined (STM32F091xC) && !defined (STM32F098xx) && !defined (STM32F030xC) + #error "Define STM32 family, for example -DSTM32F042x6" +#endif + +#ifndef WEAK +#define WEAK __attribute__((weak)) +#endif + +void WEAK reset_handler(void); +void WEAK nmi_handler(void); +void WEAK hard_fault_handler(void); +void WEAK sv_call_handler(void); +void WEAK pend_sv_handler(void); +void WEAK sys_tick_handler(void); + +void WEAK wwdg_isr(void); +void WEAK pvd_isr(void); +void WEAK rtc_isr(void); +void WEAK flash_isr(void); +void WEAK rcc_isr(void); +void WEAK exti0_1_isr(void); +void WEAK exti2_3_isr(void); +void WEAK exti4_15_isr(void); +void WEAK tsc_isr(void); +void WEAK dma1_channel1_isr(void); +void WEAK dma1_channel2_3_isr(void); +void WEAK dma1_channel4_5_isr(void); +void WEAK adc_comp_isr(void); +void WEAK tim1_brk_up_trg_com_isr(void); +void WEAK tim1_cc_isr(void); +void WEAK tim2_isr(void); +void WEAK tim3_isr(void); +void WEAK tim6_dac_isr(void); +void WEAK tim7_isr(void); +void WEAK tim14_isr(void); +void WEAK tim15_isr(void); +void WEAK tim16_isr(void); +void WEAK tim17_isr(void); +void WEAK i2c1_isr(void); +void WEAK i2c2_isr(void); +void WEAK spi1_isr(void); +void WEAK spi2_isr(void); +void WEAK usart1_isr(void); +void WEAK usart2_isr(void); +void WEAK usart3_4_isr(void); +void WEAK cec_can_isr(void); +void WEAK usb_isr(void); + + +/** + * @brief CMSIS Device version number V2.2.0 + */ +#define __STM32F0xx_CMSIS_DEVICE_VERSION_MAIN (0x02) /*!< [31:24] main version */ +#define __STM32F0xx_CMSIS_DEVICE_VERSION_SUB1 (0x00) /*!< [23:16] sub1 version */ +#define __STM32F0xx_CMSIS_DEVICE_VERSION_SUB2 (0x00) /*!< [15:8] sub2 version */ +#define __STM32F0xx_CMSIS_DEVICE_VERSION_RC (0x00) /*!< [7:0] release candidate */ +#define __STM32F0xx_CMSIS_DEVICE_VERSION ((__CMSIS_DEVICE_VERSION_MAIN << 24)\ + |(__CMSIS_DEVICE_HAL_VERSION_SUB1 << 16)\ + |(__CMSIS_DEVICE_HAL_VERSION_SUB2 << 8 )\ + |(__CMSIS_DEVICE_HAL_VERSION_RC)) + +/** + * @} + */ + +/** @addtogroup Device_Included + * @{ + */ + +// arch-dependent defines +#if defined(STM32F030x4) + #include "stm32f030x6.h" +#elif defined(STM32F030x6) + #include "stm32f030x6.h" +#elif defined(STM32F030x8) + #include "stm32f030x8.h" +#elif defined(STM32F031x6) + #include "stm32f031x6.h" +#elif defined(STM32F038xx) + #include "stm32f038xx.h" +#elif defined(STM32F042x6) + #include "stm32f042x6.h" +#elif defined(STM32F048xx) + #include "stm32f048xx.h" +#elif defined(STM32F051x8) + #include "stm32f051x8.h" +#elif defined(STM32F058xx) + #include "stm32f058xx.h" +#elif defined(STM32F070x6) + #include "stm32f070x6.h" +#elif defined(STM32F070xB) + #include "stm32f070xb.h" +#elif defined(STM32F071xB) + #include "stm32f071xb.h" +#elif defined(STM32F072xB) + #include "stm32f072xb.h" +#elif defined(STM32F078xx) + #include "stm32f078xx.h" +#elif defined(STM32F091xC) + #include "stm32f091xc.h" +#elif defined(STM32F098xx) + #include "stm32f098xx.h" +#elif defined(STM32F030xC) + #include "stm32f030xc.h" +#endif + +/** + * @} + */ + +/** @addtogroup Exported_types + * @{ + */ +typedef enum +{ + RESET = 0, + SET = !RESET +} FlagStatus, ITStatus; + +typedef enum +{ + DISABLE = 0, + ENABLE = !DISABLE +} FunctionalState; +#define IS_FUNCTIONAL_STATE(STATE) (((STATE) == DISABLE) || ((STATE) == ENABLE)) + +typedef enum +{ + ERROR = 0, + SUCCESS = !ERROR +} ErrorStatus; + +/** + * @} + */ + + +/** @addtogroup Exported_macros + * @{ + */ +#define SET_BIT(REG, BIT) ((REG) |= (BIT)) + +#define CLEAR_BIT(REG, BIT) ((REG) &= ~(BIT)) + +#define READ_BIT(REG, BIT) ((REG) & (BIT)) + +#define CLEAR_REG(REG) ((REG) = (0x0)) + +#define WRITE_REG(REG, VAL) ((REG) = (VAL)) + +#define READ_REG(REG) ((REG)) + +#define MODIFY_REG(REG, CLEARMASK, SETMASK) WRITE_REG((REG), (((READ_REG(REG)) & (~(CLEARMASK))) | (SETMASK))) + + +/** + * @} + */ + +#ifdef __cplusplus +} +#endif /* __cplusplus */ + +#endif /* __STM32F0xx_H */ +/** + * @} + */ + +/** + * @} + */ + + + + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/STM32/inc/README b/STM32/inc/README new file mode 100644 index 0000000..5fffda6 --- /dev/null +++ b/STM32/inc/README @@ -0,0 +1 @@ +including files \ No newline at end of file diff --git a/STM32/inc/cm/core_cm0.h b/STM32/inc/cm/core_cm0.h new file mode 100644 index 0000000..09f3bb7 --- /dev/null +++ b/STM32/inc/cm/core_cm0.h @@ -0,0 +1,713 @@ +/**************************************************************************//** + * @file core_cm0.h + * @brief CMSIS Cortex-M0 Core Peripheral Access Layer Header File + * @version V4.00 + * @date 22. August 2014 + * + * @note + * + ******************************************************************************/ +/* Copyright (c) 2009 - 2014 ARM LIMITED + + All rights reserved. + Redistribution and use in source and binary forms, with or without + modification, are permitted provided that the following conditions are met: + - Redistributions of source code must retain the above copyright + notice, this list of conditions and the following disclaimer. + - Redistributions in binary form must reproduce the above copyright + notice, this list of conditions and the following disclaimer in the + documentation and/or other materials provided with the distribution. + - Neither the name of ARM nor the names of its contributors may be used + to endorse or promote products derived from this software without + specific prior written permission. + * + THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE + LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + POSSIBILITY OF SUCH DAMAGE. + ---------------------------------------------------------------------------*/ + + +#if defined ( __ICCARM__ ) + #pragma system_include /* treat file as system include file for MISRA check */ +#endif + +#ifndef __CORE_CM0_H_GENERIC +#define __CORE_CM0_H_GENERIC + +#ifdef __cplusplus + extern "C" { +#endif + +/** \page CMSIS_MISRA_Exceptions MISRA-C:2004 Compliance Exceptions + CMSIS violates the following MISRA-C:2004 rules: + + \li Required Rule 8.5, object/function definition in header file.
+ Function definitions in header files are used to allow 'inlining'. + + \li Required Rule 18.4, declaration of union type or object of union type: '{...}'.
+ Unions are used for effective representation of core registers. + + \li Advisory Rule 19.7, Function-like macro defined.
+ Function-like macros are used to allow more efficient code. + */ + + +/******************************************************************************* + * CMSIS definitions + ******************************************************************************/ +/** \ingroup Cortex_M0 + @{ + */ + +/* CMSIS CM0 definitions */ +#define __CM0_CMSIS_VERSION_MAIN (0x04) /*!< [31:16] CMSIS HAL main version */ +#define __CM0_CMSIS_VERSION_SUB (0x00) /*!< [15:0] CMSIS HAL sub version */ +#define __CM0_CMSIS_VERSION ((__CM0_CMSIS_VERSION_MAIN << 16) | \ + __CM0_CMSIS_VERSION_SUB ) /*!< CMSIS HAL version number */ + +#define __CORTEX_M (0x00) /*!< Cortex-M Core */ + + +#if defined ( __CC_ARM ) + #define __ASM __asm /*!< asm keyword for ARM Compiler */ + #define __INLINE __inline /*!< inline keyword for ARM Compiler */ + #define __STATIC_INLINE static __inline + +#elif defined ( __GNUC__ ) + #define __ASM __asm /*!< asm keyword for GNU Compiler */ + #define __INLINE inline /*!< inline keyword for GNU Compiler */ + #define __STATIC_INLINE static inline + +#elif defined ( __ICCARM__ ) + #define __ASM __asm /*!< asm keyword for IAR Compiler */ + #define __INLINE inline /*!< inline keyword for IAR Compiler. Only available in High optimization mode! */ + #define __STATIC_INLINE static inline + +#elif defined ( __TMS470__ ) + #define __ASM __asm /*!< asm keyword for TI CCS Compiler */ + #define __STATIC_INLINE static inline + +#elif defined ( __TASKING__ ) + #define __ASM __asm /*!< asm keyword for TASKING Compiler */ + #define __INLINE inline /*!< inline keyword for TASKING Compiler */ + #define __STATIC_INLINE static inline + +#elif defined ( __CSMC__ ) + #define __packed + #define __ASM _asm /*!< asm keyword for COSMIC Compiler */ + #define __INLINE inline /*use -pc99 on compile line !< inline keyword for COSMIC Compiler */ + #define __STATIC_INLINE static inline + +#endif + +/** __FPU_USED indicates whether an FPU is used or not. + This core does not support an FPU at all +*/ +#define __FPU_USED 0 + +#if defined ( __CC_ARM ) + #if defined __TARGET_FPU_VFP + #warning "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #endif + +#elif defined ( __GNUC__ ) + #if defined (__VFP_FP__) && !defined(__SOFTFP__) + #warning "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #endif + +#elif defined ( __ICCARM__ ) + #if defined __ARMVFP__ + #warning "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #endif + +#elif defined ( __TMS470__ ) + #if defined __TI__VFP_SUPPORT____ + #warning "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #endif + +#elif defined ( __TASKING__ ) + #if defined __FPU_VFP__ + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #endif + +#elif defined ( __CSMC__ ) /* Cosmic */ + #if ( __CSMC__ & 0x400) // FPU present for parser + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #endif +#endif + +#include /* standard types definitions */ +#include /* Core Instruction Access */ +#include /* Core Function Access */ + +#ifdef __cplusplus +} +#endif + +#endif /* __CORE_CM0_H_GENERIC */ + +#ifndef __CMSIS_GENERIC + +#ifndef __CORE_CM0_H_DEPENDANT +#define __CORE_CM0_H_DEPENDANT + +#ifdef __cplusplus + extern "C" { +#endif + +/* check device defines and use defaults */ +#if defined __CHECK_DEVICE_DEFINES + #ifndef __CM0_REV + #define __CM0_REV 0x0000 + #warning "__CM0_REV not defined in device header file; using default!" + #endif + + #ifndef __NVIC_PRIO_BITS + #define __NVIC_PRIO_BITS 2 + #warning "__NVIC_PRIO_BITS not defined in device header file; using default!" + #endif + + #ifndef __Vendor_SysTickConfig + #define __Vendor_SysTickConfig 0 + #warning "__Vendor_SysTickConfig not defined in device header file; using default!" + #endif +#endif + +/* IO definitions (access restrictions to peripheral registers) */ +/** + \defgroup CMSIS_glob_defs CMSIS Global Defines + + IO Type Qualifiers are used + \li to specify the access to peripheral variables. + \li for automatic generation of peripheral register debug information. +*/ +#ifdef __cplusplus + #define __I volatile /*!< Defines 'read only' permissions */ +#else + #define __I volatile const /*!< Defines 'read only' permissions */ +#endif +#define __O volatile /*!< Defines 'write only' permissions */ +#define __IO volatile /*!< Defines 'read / write' permissions */ + +/*@} end of group Cortex_M0 */ + + + +/******************************************************************************* + * Register Abstraction + Core Register contain: + - Core Register + - Core NVIC Register + - Core SCB Register + - Core SysTick Register + ******************************************************************************/ +/** \defgroup CMSIS_core_register Defines and Type Definitions + \brief Type definitions and defines for Cortex-M processor based devices. +*/ + +/** \ingroup CMSIS_core_register + \defgroup CMSIS_CORE Status and Control Registers + \brief Core Register type definitions. + @{ + */ + +/** \brief Union type to access the Application Program Status Register (APSR). + */ +typedef union +{ + struct + { +#if (__CORTEX_M != 0x04) + uint32_t _reserved0:27; /*!< bit: 0..26 Reserved */ +#else + uint32_t _reserved0:16; /*!< bit: 0..15 Reserved */ + uint32_t GE:4; /*!< bit: 16..19 Greater than or Equal flags */ + uint32_t _reserved1:7; /*!< bit: 20..26 Reserved */ +#endif + uint32_t Q:1; /*!< bit: 27 Saturation condition flag */ + uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ + uint32_t C:1; /*!< bit: 29 Carry condition code flag */ + uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ + uint32_t N:1; /*!< bit: 31 Negative condition code flag */ + } b; /*!< Structure used for bit access */ + uint32_t w; /*!< Type used for word access */ +} APSR_Type; + + +/** \brief Union type to access the Interrupt Program Status Register (IPSR). + */ +typedef union +{ + struct + { + uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ + uint32_t _reserved0:23; /*!< bit: 9..31 Reserved */ + } b; /*!< Structure used for bit access */ + uint32_t w; /*!< Type used for word access */ +} IPSR_Type; + + +/** \brief Union type to access the Special-Purpose Program Status Registers (xPSR). + */ +typedef union +{ + struct + { + uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ +#if (__CORTEX_M != 0x04) + uint32_t _reserved0:15; /*!< bit: 9..23 Reserved */ +#else + uint32_t _reserved0:7; /*!< bit: 9..15 Reserved */ + uint32_t GE:4; /*!< bit: 16..19 Greater than or Equal flags */ + uint32_t _reserved1:4; /*!< bit: 20..23 Reserved */ +#endif + uint32_t T:1; /*!< bit: 24 Thumb bit (read 0) */ + uint32_t IT:2; /*!< bit: 25..26 saved IT state (read 0) */ + uint32_t Q:1; /*!< bit: 27 Saturation condition flag */ + uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ + uint32_t C:1; /*!< bit: 29 Carry condition code flag */ + uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ + uint32_t N:1; /*!< bit: 31 Negative condition code flag */ + } b; /*!< Structure used for bit access */ + uint32_t w; /*!< Type used for word access */ +} xPSR_Type; + + +/** \brief Union type to access the Control Registers (CONTROL). + */ +typedef union +{ + struct + { + uint32_t nPRIV:1; /*!< bit: 0 Execution privilege in Thread mode */ + uint32_t SPSEL:1; /*!< bit: 1 Stack to be used */ + uint32_t FPCA:1; /*!< bit: 2 FP extension active flag */ + uint32_t _reserved0:29; /*!< bit: 3..31 Reserved */ + } b; /*!< Structure used for bit access */ + uint32_t w; /*!< Type used for word access */ +} CONTROL_Type; + +/*@} end of group CMSIS_CORE */ + + +/** \ingroup CMSIS_core_register + \defgroup CMSIS_NVIC Nested Vectored Interrupt Controller (NVIC) + \brief Type definitions for the NVIC Registers + @{ + */ + +/** \brief Structure type to access the Nested Vectored Interrupt Controller (NVIC). + */ +typedef struct +{ + __IO uint32_t ISER[1]; /*!< Offset: 0x000 (R/W) Interrupt Set Enable Register */ + uint32_t RESERVED0[31]; + __IO uint32_t ICER[1]; /*!< Offset: 0x080 (R/W) Interrupt Clear Enable Register */ + uint32_t RSERVED1[31]; + __IO uint32_t ISPR[1]; /*!< Offset: 0x100 (R/W) Interrupt Set Pending Register */ + uint32_t RESERVED2[31]; + __IO uint32_t ICPR[1]; /*!< Offset: 0x180 (R/W) Interrupt Clear Pending Register */ + uint32_t RESERVED3[31]; + uint32_t RESERVED4[64]; + __IO uint32_t IP[8]; /*!< Offset: 0x300 (R/W) Interrupt Priority Register */ +} NVIC_Type; + +/*@} end of group CMSIS_NVIC */ + + +/** \ingroup CMSIS_core_register + \defgroup CMSIS_SCB System Control Block (SCB) + \brief Type definitions for the System Control Block Registers + @{ + */ + +/** \brief Structure type to access the System Control Block (SCB). + */ +typedef struct +{ + __I uint32_t CPUID; /*!< Offset: 0x000 (R/ ) CPUID Base Register */ + __IO uint32_t ICSR; /*!< Offset: 0x004 (R/W) Interrupt Control and State Register */ + uint32_t RESERVED0; + __IO uint32_t AIRCR; /*!< Offset: 0x00C (R/W) Application Interrupt and Reset Control Register */ + __IO uint32_t SCR; /*!< Offset: 0x010 (R/W) System Control Register */ + __IO uint32_t CCR; /*!< Offset: 0x014 (R/W) Configuration Control Register */ + uint32_t RESERVED1; + __IO uint32_t SHP[2]; /*!< Offset: 0x01C (R/W) System Handlers Priority Registers. [0] is RESERVED */ + __IO uint32_t SHCSR; /*!< Offset: 0x024 (R/W) System Handler Control and State Register */ +} SCB_Type; + +/* SCB CPUID Register Definitions */ +#define SCB_CPUID_IMPLEMENTER_Pos 24 /*!< SCB CPUID: IMPLEMENTER Position */ +#define SCB_CPUID_IMPLEMENTER_Msk (0xFFUL << SCB_CPUID_IMPLEMENTER_Pos) /*!< SCB CPUID: IMPLEMENTER Mask */ + +#define SCB_CPUID_VARIANT_Pos 20 /*!< SCB CPUID: VARIANT Position */ +#define SCB_CPUID_VARIANT_Msk (0xFUL << SCB_CPUID_VARIANT_Pos) /*!< SCB CPUID: VARIANT Mask */ + +#define SCB_CPUID_ARCHITECTURE_Pos 16 /*!< SCB CPUID: ARCHITECTURE Position */ +#define SCB_CPUID_ARCHITECTURE_Msk (0xFUL << SCB_CPUID_ARCHITECTURE_Pos) /*!< SCB CPUID: ARCHITECTURE Mask */ + +#define SCB_CPUID_PARTNO_Pos 4 /*!< SCB CPUID: PARTNO Position */ +#define SCB_CPUID_PARTNO_Msk (0xFFFUL << SCB_CPUID_PARTNO_Pos) /*!< SCB CPUID: PARTNO Mask */ + +#define SCB_CPUID_REVISION_Pos 0 /*!< SCB CPUID: REVISION Position */ +#define SCB_CPUID_REVISION_Msk (0xFUL << SCB_CPUID_REVISION_Pos) /*!< SCB CPUID: REVISION Mask */ + +/* SCB Interrupt Control State Register Definitions */ +#define SCB_ICSR_NMIPENDSET_Pos 31 /*!< SCB ICSR: NMIPENDSET Position */ +#define SCB_ICSR_NMIPENDSET_Msk (1UL << SCB_ICSR_NMIPENDSET_Pos) /*!< SCB ICSR: NMIPENDSET Mask */ + +#define SCB_ICSR_PENDSVSET_Pos 28 /*!< SCB ICSR: PENDSVSET Position */ +#define SCB_ICSR_PENDSVSET_Msk (1UL << SCB_ICSR_PENDSVSET_Pos) /*!< SCB ICSR: PENDSVSET Mask */ + +#define SCB_ICSR_PENDSVCLR_Pos 27 /*!< SCB ICSR: PENDSVCLR Position */ +#define SCB_ICSR_PENDSVCLR_Msk (1UL << SCB_ICSR_PENDSVCLR_Pos) /*!< SCB ICSR: PENDSVCLR Mask */ + +#define SCB_ICSR_PENDSTSET_Pos 26 /*!< SCB ICSR: PENDSTSET Position */ +#define SCB_ICSR_PENDSTSET_Msk (1UL << SCB_ICSR_PENDSTSET_Pos) /*!< SCB ICSR: PENDSTSET Mask */ + +#define SCB_ICSR_PENDSTCLR_Pos 25 /*!< SCB ICSR: PENDSTCLR Position */ +#define SCB_ICSR_PENDSTCLR_Msk (1UL << SCB_ICSR_PENDSTCLR_Pos) /*!< SCB ICSR: PENDSTCLR Mask */ + +#define SCB_ICSR_ISRPREEMPT_Pos 23 /*!< SCB ICSR: ISRPREEMPT Position */ +#define SCB_ICSR_ISRPREEMPT_Msk (1UL << SCB_ICSR_ISRPREEMPT_Pos) /*!< SCB ICSR: ISRPREEMPT Mask */ + +#define SCB_ICSR_ISRPENDING_Pos 22 /*!< SCB ICSR: ISRPENDING Position */ +#define SCB_ICSR_ISRPENDING_Msk (1UL << SCB_ICSR_ISRPENDING_Pos) /*!< SCB ICSR: ISRPENDING Mask */ + +#define SCB_ICSR_VECTPENDING_Pos 12 /*!< SCB ICSR: VECTPENDING Position */ +#define SCB_ICSR_VECTPENDING_Msk (0x1FFUL << SCB_ICSR_VECTPENDING_Pos) /*!< SCB ICSR: VECTPENDING Mask */ + +#define SCB_ICSR_VECTACTIVE_Pos 0 /*!< SCB ICSR: VECTACTIVE Position */ +#define SCB_ICSR_VECTACTIVE_Msk (0x1FFUL << SCB_ICSR_VECTACTIVE_Pos) /*!< SCB ICSR: VECTACTIVE Mask */ + +/* SCB Application Interrupt and Reset Control Register Definitions */ +#define SCB_AIRCR_VECTKEY_Pos 16 /*!< SCB AIRCR: VECTKEY Position */ +#define SCB_AIRCR_VECTKEY_Msk (0xFFFFUL << SCB_AIRCR_VECTKEY_Pos) /*!< SCB AIRCR: VECTKEY Mask */ + +#define SCB_AIRCR_VECTKEYSTAT_Pos 16 /*!< SCB AIRCR: VECTKEYSTAT Position */ +#define SCB_AIRCR_VECTKEYSTAT_Msk (0xFFFFUL << SCB_AIRCR_VECTKEYSTAT_Pos) /*!< SCB AIRCR: VECTKEYSTAT Mask */ + +#define SCB_AIRCR_ENDIANESS_Pos 15 /*!< SCB AIRCR: ENDIANESS Position */ +#define SCB_AIRCR_ENDIANESS_Msk (1UL << SCB_AIRCR_ENDIANESS_Pos) /*!< SCB AIRCR: ENDIANESS Mask */ + +#define SCB_AIRCR_SYSRESETREQ_Pos 2 /*!< SCB AIRCR: SYSRESETREQ Position */ +#define SCB_AIRCR_SYSRESETREQ_Msk (1UL << SCB_AIRCR_SYSRESETREQ_Pos) /*!< SCB AIRCR: SYSRESETREQ Mask */ + +#define SCB_AIRCR_VECTCLRACTIVE_Pos 1 /*!< SCB AIRCR: VECTCLRACTIVE Position */ +#define SCB_AIRCR_VECTCLRACTIVE_Msk (1UL << SCB_AIRCR_VECTCLRACTIVE_Pos) /*!< SCB AIRCR: VECTCLRACTIVE Mask */ + +/* SCB System Control Register Definitions */ +#define SCB_SCR_SEVONPEND_Pos 4 /*!< SCB SCR: SEVONPEND Position */ +#define SCB_SCR_SEVONPEND_Msk (1UL << SCB_SCR_SEVONPEND_Pos) /*!< SCB SCR: SEVONPEND Mask */ + +#define SCB_SCR_SLEEPDEEP_Pos 2 /*!< SCB SCR: SLEEPDEEP Position */ +#define SCB_SCR_SLEEPDEEP_Msk (1UL << SCB_SCR_SLEEPDEEP_Pos) /*!< SCB SCR: SLEEPDEEP Mask */ + +#define SCB_SCR_SLEEPONEXIT_Pos 1 /*!< SCB SCR: SLEEPONEXIT Position */ +#define SCB_SCR_SLEEPONEXIT_Msk (1UL << SCB_SCR_SLEEPONEXIT_Pos) /*!< SCB SCR: SLEEPONEXIT Mask */ + +/* SCB Configuration Control Register Definitions */ +#define SCB_CCR_STKALIGN_Pos 9 /*!< SCB CCR: STKALIGN Position */ +#define SCB_CCR_STKALIGN_Msk (1UL << SCB_CCR_STKALIGN_Pos) /*!< SCB CCR: STKALIGN Mask */ + +#define SCB_CCR_UNALIGN_TRP_Pos 3 /*!< SCB CCR: UNALIGN_TRP Position */ +#define SCB_CCR_UNALIGN_TRP_Msk (1UL << SCB_CCR_UNALIGN_TRP_Pos) /*!< SCB CCR: UNALIGN_TRP Mask */ + +/* SCB System Handler Control and State Register Definitions */ +#define SCB_SHCSR_SVCALLPENDED_Pos 15 /*!< SCB SHCSR: SVCALLPENDED Position */ +#define SCB_SHCSR_SVCALLPENDED_Msk (1UL << SCB_SHCSR_SVCALLPENDED_Pos) /*!< SCB SHCSR: SVCALLPENDED Mask */ + +/*@} end of group CMSIS_SCB */ + + +/** \ingroup CMSIS_core_register + \defgroup CMSIS_SysTick System Tick Timer (SysTick) + \brief Type definitions for the System Timer Registers. + @{ + */ + +/** \brief Structure type to access the System Timer (SysTick). + */ +typedef struct +{ + __IO uint32_t CTRL; /*!< Offset: 0x000 (R/W) SysTick Control and Status Register */ + __IO uint32_t LOAD; /*!< Offset: 0x004 (R/W) SysTick Reload Value Register */ + __IO uint32_t VAL; /*!< Offset: 0x008 (R/W) SysTick Current Value Register */ + __I uint32_t CALIB; /*!< Offset: 0x00C (R/ ) SysTick Calibration Register */ +} SysTick_Type; + +/* SysTick Control / Status Register Definitions */ +// == 0 if counted to 0 since last reading +#define SysTick_CTRL_COUNTFLAG_Pos 16 /*!< SysTick CTRL: COUNTFLAG Position */ +#define SysTick_CTRL_COUNTFLAG_Msk (1UL << SysTick_CTRL_COUNTFLAG_Pos) /*!< SysTick CTRL: COUNTFLAG Mask */ +// 0 = reference clock, 1 = processor clock +#define SysTick_CTRL_CLKSOURCE_Pos 2 /*!< SysTick CTRL: CLKSOURCE Position */ +#define SysTick_CTRL_CLKSOURCE_Msk (1UL << SysTick_CTRL_CLKSOURCE_Pos) /*!< SysTick CTRL: CLKSOURCE Mask */ +// generate interrupt on 0 +#define SysTick_CTRL_TICKINT_Pos 1 /*!< SysTick CTRL: TICKINT Position */ +#define SysTick_CTRL_TICKINT_Msk (1UL << SysTick_CTRL_TICKINT_Pos) /*!< SysTick CTRL: TICKINT Mask */ +// enable counter +#define SysTick_CTRL_ENABLE_Pos 0 /*!< SysTick CTRL: ENABLE Position */ +#define SysTick_CTRL_ENABLE_Msk (1UL << SysTick_CTRL_ENABLE_Pos) /*!< SysTick CTRL: ENABLE Mask */ + +/* SysTick Reload Register Definitions */ +#define SysTick_LOAD_RELOAD_Pos 0 /*!< SysTick LOAD: RELOAD Position */ +#define SysTick_LOAD_RELOAD_Msk (0xFFFFFFUL << SysTick_LOAD_RELOAD_Pos) /*!< SysTick LOAD: RELOAD Mask */ + +/* SysTick Current Register Definitions */ +#define SysTick_VAL_CURRENT_Pos 0 /*!< SysTick VAL: CURRENT Position */ +#define SysTick_VAL_CURRENT_Msk (0xFFFFFFUL << SysTick_VAL_CURRENT_Pos) /*!< SysTick VAL: CURRENT Mask */ + +/* SysTick Calibration Register Definitions */ +#define SysTick_CALIB_NOREF_Pos 31 /*!< SysTick CALIB: NOREF Position */ +#define SysTick_CALIB_NOREF_Msk (1UL << SysTick_CALIB_NOREF_Pos) /*!< SysTick CALIB: NOREF Mask */ + +#define SysTick_CALIB_SKEW_Pos 30 /*!< SysTick CALIB: SKEW Position */ +#define SysTick_CALIB_SKEW_Msk (1UL << SysTick_CALIB_SKEW_Pos) /*!< SysTick CALIB: SKEW Mask */ + +#define SysTick_CALIB_TENMS_Pos 0 /*!< SysTick CALIB: TENMS Position */ +#define SysTick_CALIB_TENMS_Msk (0xFFFFFFUL << SysTick_CALIB_TENMS_Pos) /*!< SysTick CALIB: TENMS Mask */ + +/*@} end of group CMSIS_SysTick */ + + +/** \ingroup CMSIS_core_register + \defgroup CMSIS_CoreDebug Core Debug Registers (CoreDebug) + \brief Cortex-M0 Core Debug Registers (DCB registers, SHCSR, and DFSR) + are only accessible over DAP and not via processor. Therefore + they are not covered by the Cortex-M0 header file. + @{ + */ +/*@} end of group CMSIS_CoreDebug */ + + +/** \ingroup CMSIS_core_register + \defgroup CMSIS_core_base Core Definitions + \brief Definitions for base addresses, unions, and structures. + @{ + */ + +/* Memory mapping of Cortex-M0 Hardware */ +#define SCS_BASE (0xE000E000UL) /*!< System Control Space Base Address */ +#define SysTick_BASE (SCS_BASE + 0x0010UL) /*!< SysTick Base Address */ +#define NVIC_BASE (SCS_BASE + 0x0100UL) /*!< NVIC Base Address */ +#define SCB_BASE (SCS_BASE + 0x0D00UL) /*!< System Control Block Base Address */ + +#define SCB ((SCB_Type *) SCB_BASE ) /*!< SCB configuration struct */ +#define SysTick ((SysTick_Type *) SysTick_BASE ) /*!< SysTick configuration struct */ +#define NVIC ((NVIC_Type *) NVIC_BASE ) /*!< NVIC configuration struct */ + + +/*@} */ + + + +/******************************************************************************* + * Hardware Abstraction Layer + Core Function Interface contains: + - Core NVIC Functions + - Core SysTick Functions + - Core Register Access Functions + ******************************************************************************/ +/** \defgroup CMSIS_Core_FunctionInterface Functions and Instructions Reference +*/ + + + +/* ########################## NVIC functions #################################### */ +/** \ingroup CMSIS_Core_FunctionInterface + \defgroup CMSIS_Core_NVICFunctions NVIC Functions + \brief Functions that manage interrupts and exceptions via the NVIC. + @{ + */ + +/* Interrupt Priorities are WORD accessible only under ARMv6M */ +/* The following MACROS handle generation of the register offset and byte masks */ +#define _BIT_SHIFT(IRQn) ( (((uint32_t)(IRQn) ) & 0x03) * 8 ) +#define _SHP_IDX(IRQn) ( ((((uint32_t)(IRQn) & 0x0F)-8) >> 2) ) +#define _IP_IDX(IRQn) ( ((uint32_t)(IRQn) >> 2) ) + + +/** \brief Enable External Interrupt + + The function enables a device-specific interrupt in the NVIC interrupt controller. + + \param [in] IRQn External interrupt number. Value cannot be negative. + */ +__STATIC_INLINE void NVIC_EnableIRQ(IRQn_Type IRQn) +{ + NVIC->ISER[0] = (1 << ((uint32_t)(IRQn) & 0x1F)); +} + + +/** \brief Disable External Interrupt + + The function disables a device-specific interrupt in the NVIC interrupt controller. + + \param [in] IRQn External interrupt number. Value cannot be negative. + */ +__STATIC_INLINE void NVIC_DisableIRQ(IRQn_Type IRQn) +{ + NVIC->ICER[0] = (1 << ((uint32_t)(IRQn) & 0x1F)); +} + + +/** \brief Get Pending Interrupt + + The function reads the pending register in the NVIC and returns the pending bit + for the specified interrupt. + + \param [in] IRQn Interrupt number. + + \return 0 Interrupt status is not pending. + \return 1 Interrupt status is pending. + */ +__STATIC_INLINE uint32_t NVIC_GetPendingIRQ(IRQn_Type IRQn) +{ + return((uint32_t) ((NVIC->ISPR[0] & (1 << ((uint32_t)(IRQn) & 0x1F)))?1:0)); +} + + +/** \brief Set Pending Interrupt + + The function sets the pending bit of an external interrupt. + + \param [in] IRQn Interrupt number. Value cannot be negative. + */ +__STATIC_INLINE void NVIC_SetPendingIRQ(IRQn_Type IRQn) +{ + NVIC->ISPR[0] = (1 << ((uint32_t)(IRQn) & 0x1F)); +} + + +/** \brief Clear Pending Interrupt + + The function clears the pending bit of an external interrupt. + + \param [in] IRQn External interrupt number. Value cannot be negative. + */ +__STATIC_INLINE void NVIC_ClearPendingIRQ(IRQn_Type IRQn) +{ + NVIC->ICPR[0] = (1 << ((uint32_t)(IRQn) & 0x1F)); /* Clear pending interrupt */ +} + + +/** \brief Set Interrupt Priority + + The function sets the priority of an interrupt. + + \note The priority cannot be set for every core interrupt. + + \param [in] IRQn Interrupt number. + \param [in] priority Priority to set. + */ +__STATIC_INLINE void NVIC_SetPriority(IRQn_Type IRQn, uint32_t priority) +{ + if(IRQn < 0) { + SCB->SHP[_SHP_IDX(IRQn)] = (SCB->SHP[_SHP_IDX(IRQn)] & ~(0xFF << _BIT_SHIFT(IRQn))) | + (((priority << (8 - __NVIC_PRIO_BITS)) & 0xFF) << _BIT_SHIFT(IRQn)); } + else { + NVIC->IP[_IP_IDX(IRQn)] = (NVIC->IP[_IP_IDX(IRQn)] & ~(0xFF << _BIT_SHIFT(IRQn))) | + (((priority << (8 - __NVIC_PRIO_BITS)) & 0xFF) << _BIT_SHIFT(IRQn)); } +} + + +/** \brief Get Interrupt Priority + + The function reads the priority of an interrupt. The interrupt + number can be positive to specify an external (device specific) + interrupt, or negative to specify an internal (core) interrupt. + + + \param [in] IRQn Interrupt number. + \return Interrupt Priority. Value is aligned automatically to the implemented + priority bits of the microcontroller. + */ +__STATIC_INLINE uint32_t NVIC_GetPriority(IRQn_Type IRQn) +{ + + if(IRQn < 0) { + return((uint32_t)(((SCB->SHP[_SHP_IDX(IRQn)] >> _BIT_SHIFT(IRQn) ) & 0xFF) >> (8 - __NVIC_PRIO_BITS))); } /* get priority for Cortex-M0 system interrupts */ + else { + return((uint32_t)(((NVIC->IP[ _IP_IDX(IRQn)] >> _BIT_SHIFT(IRQn) ) & 0xFF) >> (8 - __NVIC_PRIO_BITS))); } /* get priority for device specific interrupts */ +} + + +/** \brief System Reset + + The function initiates a system reset request to reset the MCU. + */ +__STATIC_INLINE void NVIC_SystemReset(void) +{ + __DSB(); /* Ensure all outstanding memory accesses included + buffered write are completed before reset */ + SCB->AIRCR = ((0x5FA << SCB_AIRCR_VECTKEY_Pos) | + SCB_AIRCR_SYSRESETREQ_Msk); + __DSB(); /* Ensure completion of memory access */ + while(1); /* wait until reset */ +} + +/*@} end of CMSIS_Core_NVICFunctions */ + + + +/* ################################## SysTick function ############################################ */ +/** \ingroup CMSIS_Core_FunctionInterface + \defgroup CMSIS_Core_SysTickFunctions SysTick Functions + \brief Functions that configure the System. + @{ + */ + +#if (__Vendor_SysTickConfig == 0) + +/** \brief System Tick Configuration + + The function initializes the System Timer and its interrupt, and starts the System Tick Timer. + Counter is in free running mode to generate periodic interrupts. + + \param [in] ticks Number of ticks between two interrupts. + \param [in] div8 Does systick run directly from source (0) or from F/8 (1) + + \return 0 Function succeeded. + \return 1 Function failed. + + \note When the variable __Vendor_SysTickConfig is set to 1, then the + function SysTick_Config is not included. In this case, the file device.h + must contain a vendor-specific implementation of this function. + + */ +__STATIC_INLINE uint32_t SysTick_Config(uint32_t ticks, uint32_t div8) +{ + if ((ticks - 1) > SysTick_LOAD_RELOAD_Msk) return (1); /* Reload value impossible */ + + SysTick->LOAD = ticks - 1; /* set reload register */ + NVIC_SetPriority (SysTick_IRQn, (1<<__NVIC_PRIO_BITS) - 1); /* set Priority for Systick Interrupt */ + SysTick->VAL = 0; /* Load the SysTick Counter Value */ + SysTick->CTRL = SysTick_CTRL_TICKINT_Msk | + SysTick_CTRL_ENABLE_Msk; + if(!div8) SysTick->CTRL |= SysTick_CTRL_CLKSOURCE_Msk; + return (0); +} + +#endif + +/*@} end of CMSIS_Core_SysTickFunctions */ + + + + +#ifdef __cplusplus +} +#endif + +#endif /* __CORE_CM0_H_DEPENDANT */ + +#endif /* __CMSIS_GENERIC */ diff --git a/STM32/inc/cm/core_cmFunc.h b/STM32/inc/cm/core_cmFunc.h new file mode 100644 index 0000000..a1bd88c --- /dev/null +++ b/STM32/inc/cm/core_cmFunc.h @@ -0,0 +1,637 @@ +/**************************************************************************//** + * @file core_cmFunc.h + * @brief CMSIS Cortex-M Core Function Access Header File + * @version V4.00 + * @date 28. August 2014 + * + * @note + * + ******************************************************************************/ +/* Copyright (c) 2009 - 2014 ARM LIMITED + + All rights reserved. + Redistribution and use in source and binary forms, with or without + modification, are permitted provided that the following conditions are met: + - Redistributions of source code must retain the above copyright + notice, this list of conditions and the following disclaimer. + - Redistributions in binary form must reproduce the above copyright + notice, this list of conditions and the following disclaimer in the + documentation and/or other materials provided with the distribution. + - Neither the name of ARM nor the names of its contributors may be used + to endorse or promote products derived from this software without + specific prior written permission. + * + THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE + LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + POSSIBILITY OF SUCH DAMAGE. + ---------------------------------------------------------------------------*/ + + +#ifndef __CORE_CMFUNC_H +#define __CORE_CMFUNC_H + + +/* ########################### Core Function Access ########################### */ +/** \ingroup CMSIS_Core_FunctionInterface + \defgroup CMSIS_Core_RegAccFunctions CMSIS Core Register Access Functions + @{ + */ + +#if defined ( __CC_ARM ) /*------------------RealView Compiler -----------------*/ +/* ARM armcc specific functions */ + +#if (__ARMCC_VERSION < 400677) + #error "Please use ARM Compiler Toolchain V4.0.677 or later!" +#endif + +/* intrinsic void __enable_irq(); */ +/* intrinsic void __disable_irq(); */ + +/** \brief Get Control Register + + This function returns the content of the Control Register. + + \return Control Register value + */ +__STATIC_INLINE uint32_t __get_CONTROL(void) +{ + register uint32_t __regControl __ASM("control"); + return(__regControl); +} + + +/** \brief Set Control Register + + This function writes the given value to the Control Register. + + \param [in] control Control Register value to set + */ +__STATIC_INLINE void __set_CONTROL(uint32_t control) +{ + register uint32_t __regControl __ASM("control"); + __regControl = control; +} + + +/** \brief Get IPSR Register + + This function returns the content of the IPSR Register. + + \return IPSR Register value + */ +__STATIC_INLINE uint32_t __get_IPSR(void) +{ + register uint32_t __regIPSR __ASM("ipsr"); + return(__regIPSR); +} + + +/** \brief Get APSR Register + + This function returns the content of the APSR Register. + + \return APSR Register value + */ +__STATIC_INLINE uint32_t __get_APSR(void) +{ + register uint32_t __regAPSR __ASM("apsr"); + return(__regAPSR); +} + + +/** \brief Get xPSR Register + + This function returns the content of the xPSR Register. + + \return xPSR Register value + */ +__STATIC_INLINE uint32_t __get_xPSR(void) +{ + register uint32_t __regXPSR __ASM("xpsr"); + return(__regXPSR); +} + + +/** \brief Get Process Stack Pointer + + This function returns the current value of the Process Stack Pointer (PSP). + + \return PSP Register value + */ +__STATIC_INLINE uint32_t __get_PSP(void) +{ + register uint32_t __regProcessStackPointer __ASM("psp"); + return(__regProcessStackPointer); +} + + +/** \brief Set Process Stack Pointer + + This function assigns the given value to the Process Stack Pointer (PSP). + + \param [in] topOfProcStack Process Stack Pointer value to set + */ +__STATIC_INLINE void __set_PSP(uint32_t topOfProcStack) +{ + register uint32_t __regProcessStackPointer __ASM("psp"); + __regProcessStackPointer = topOfProcStack; +} + + +/** \brief Get Main Stack Pointer + + This function returns the current value of the Main Stack Pointer (MSP). + + \return MSP Register value + */ +__STATIC_INLINE uint32_t __get_MSP(void) +{ + register uint32_t __regMainStackPointer __ASM("msp"); + return(__regMainStackPointer); +} + + +/** \brief Set Main Stack Pointer + + This function assigns the given value to the Main Stack Pointer (MSP). + + \param [in] topOfMainStack Main Stack Pointer value to set + */ +__STATIC_INLINE void __set_MSP(uint32_t topOfMainStack) +{ + register uint32_t __regMainStackPointer __ASM("msp"); + __regMainStackPointer = topOfMainStack; +} + + +/** \brief Get Priority Mask + + This function returns the current state of the priority mask bit from the Priority Mask Register. + + \return Priority Mask value + */ +__STATIC_INLINE uint32_t __get_PRIMASK(void) +{ + register uint32_t __regPriMask __ASM("primask"); + return(__regPriMask); +} + + +/** \brief Set Priority Mask + + This function assigns the given value to the Priority Mask Register. + + \param [in] priMask Priority Mask + */ +__STATIC_INLINE void __set_PRIMASK(uint32_t priMask) +{ + register uint32_t __regPriMask __ASM("primask"); + __regPriMask = (priMask); +} + + +#if (__CORTEX_M >= 0x03) || (__CORTEX_SC >= 300) + +/** \brief Enable FIQ + + This function enables FIQ interrupts by clearing the F-bit in the CPSR. + Can only be executed in Privileged modes. + */ +#define __enable_fault_irq __enable_fiq + + +/** \brief Disable FIQ + + This function disables FIQ interrupts by setting the F-bit in the CPSR. + Can only be executed in Privileged modes. + */ +#define __disable_fault_irq __disable_fiq + + +/** \brief Get Base Priority + + This function returns the current value of the Base Priority register. + + \return Base Priority register value + */ +__STATIC_INLINE uint32_t __get_BASEPRI(void) +{ + register uint32_t __regBasePri __ASM("basepri"); + return(__regBasePri); +} + + +/** \brief Set Base Priority + + This function assigns the given value to the Base Priority register. + + \param [in] basePri Base Priority value to set + */ +__STATIC_INLINE void __set_BASEPRI(uint32_t basePri) +{ + register uint32_t __regBasePri __ASM("basepri"); + __regBasePri = (basePri & 0xff); +} + + +/** \brief Get Fault Mask + + This function returns the current value of the Fault Mask register. + + \return Fault Mask register value + */ +__STATIC_INLINE uint32_t __get_FAULTMASK(void) +{ + register uint32_t __regFaultMask __ASM("faultmask"); + return(__regFaultMask); +} + + +/** \brief Set Fault Mask + + This function assigns the given value to the Fault Mask register. + + \param [in] faultMask Fault Mask value to set + */ +__STATIC_INLINE void __set_FAULTMASK(uint32_t faultMask) +{ + register uint32_t __regFaultMask __ASM("faultmask"); + __regFaultMask = (faultMask & (uint32_t)1); +} + +#endif /* (__CORTEX_M >= 0x03) || (__CORTEX_SC >= 300) */ + + +#if (__CORTEX_M == 0x04) || (__CORTEX_M == 0x07) + +/** \brief Get FPSCR + + This function returns the current value of the Floating Point Status/Control register. + + \return Floating Point Status/Control register value + */ +__STATIC_INLINE uint32_t __get_FPSCR(void) +{ +#if (__FPU_PRESENT == 1) && (__FPU_USED == 1) + register uint32_t __regfpscr __ASM("fpscr"); + return(__regfpscr); +#else + return(0); +#endif +} + + +/** \brief Set FPSCR + + This function assigns the given value to the Floating Point Status/Control register. + + \param [in] fpscr Floating Point Status/Control value to set + */ +__STATIC_INLINE void __set_FPSCR(uint32_t fpscr) +{ +#if (__FPU_PRESENT == 1) && (__FPU_USED == 1) + register uint32_t __regfpscr __ASM("fpscr"); + __regfpscr = (fpscr); +#endif +} + +#endif /* (__CORTEX_M == 0x04) || (__CORTEX_M == 0x07) */ + + +#elif defined ( __GNUC__ ) /*------------------ GNU Compiler ---------------------*/ +/* GNU gcc specific functions */ + +/** \brief Enable IRQ Interrupts + + This function enables IRQ interrupts by clearing the I-bit in the CPSR. + Can only be executed in Privileged modes. + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE void __enable_irq(void) +{ + __ASM volatile ("cpsie i" : : : "memory"); +} + + +/** \brief Disable IRQ Interrupts + + This function disables IRQ interrupts by setting the I-bit in the CPSR. + Can only be executed in Privileged modes. + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE void __disable_irq(void) +{ + __ASM volatile ("cpsid i" : : : "memory"); +} + + +/** \brief Get Control Register + + This function returns the content of the Control Register. + + \return Control Register value + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_CONTROL(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, control" : "=r" (result) ); + return(result); +} + + +/** \brief Set Control Register + + This function writes the given value to the Control Register. + + \param [in] control Control Register value to set + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE void __set_CONTROL(uint32_t control) +{ + __ASM volatile ("MSR control, %0" : : "r" (control) : "memory"); +} + + +/** \brief Get IPSR Register + + This function returns the content of the IPSR Register. + + \return IPSR Register value + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_IPSR(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, ipsr" : "=r" (result) ); + return(result); +} + + +/** \brief Get APSR Register + + This function returns the content of the APSR Register. + + \return APSR Register value + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_APSR(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, apsr" : "=r" (result) ); + return(result); +} + + +/** \brief Get xPSR Register + + This function returns the content of the xPSR Register. + + \return xPSR Register value + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_xPSR(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, xpsr" : "=r" (result) ); + return(result); +} + + +/** \brief Get Process Stack Pointer + + This function returns the current value of the Process Stack Pointer (PSP). + + \return PSP Register value + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_PSP(void) +{ + register uint32_t result; + + __ASM volatile ("MRS %0, psp\n" : "=r" (result) ); + return(result); +} + + +/** \brief Set Process Stack Pointer + + This function assigns the given value to the Process Stack Pointer (PSP). + + \param [in] topOfProcStack Process Stack Pointer value to set + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE void __set_PSP(uint32_t topOfProcStack) +{ + __ASM volatile ("MSR psp, %0\n" : : "r" (topOfProcStack) : "sp"); +} + + +/** \brief Get Main Stack Pointer + + This function returns the current value of the Main Stack Pointer (MSP). + + \return MSP Register value + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_MSP(void) +{ + register uint32_t result; + + __ASM volatile ("MRS %0, msp\n" : "=r" (result) ); + return(result); +} + + +/** \brief Set Main Stack Pointer + + This function assigns the given value to the Main Stack Pointer (MSP). + + \param [in] topOfMainStack Main Stack Pointer value to set + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE void __set_MSP(uint32_t topOfMainStack) +{ + __ASM volatile ("MSR msp, %0\n" : : "r" (topOfMainStack) : "sp"); +} + + +/** \brief Get Priority Mask + + This function returns the current state of the priority mask bit from the Priority Mask Register. + + \return Priority Mask value + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_PRIMASK(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, primask" : "=r" (result) ); + return(result); +} + + +/** \brief Set Priority Mask + + This function assigns the given value to the Priority Mask Register. + + \param [in] priMask Priority Mask + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE void __set_PRIMASK(uint32_t priMask) +{ + __ASM volatile ("MSR primask, %0" : : "r" (priMask) : "memory"); +} + + +#if (__CORTEX_M >= 0x03) + +/** \brief Enable FIQ + + This function enables FIQ interrupts by clearing the F-bit in the CPSR. + Can only be executed in Privileged modes. + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE void __enable_fault_irq(void) +{ + __ASM volatile ("cpsie f" : : : "memory"); +} + + +/** \brief Disable FIQ + + This function disables FIQ interrupts by setting the F-bit in the CPSR. + Can only be executed in Privileged modes. + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE void __disable_fault_irq(void) +{ + __ASM volatile ("cpsid f" : : : "memory"); +} + + +/** \brief Get Base Priority + + This function returns the current value of the Base Priority register. + + \return Base Priority register value + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_BASEPRI(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, basepri_max" : "=r" (result) ); + return(result); +} + + +/** \brief Set Base Priority + + This function assigns the given value to the Base Priority register. + + \param [in] basePri Base Priority value to set + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE void __set_BASEPRI(uint32_t value) +{ + __ASM volatile ("MSR basepri, %0" : : "r" (value) : "memory"); +} + + +/** \brief Get Fault Mask + + This function returns the current value of the Fault Mask register. + + \return Fault Mask register value + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_FAULTMASK(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, faultmask" : "=r" (result) ); + return(result); +} + + +/** \brief Set Fault Mask + + This function assigns the given value to the Fault Mask register. + + \param [in] faultMask Fault Mask value to set + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE void __set_FAULTMASK(uint32_t faultMask) +{ + __ASM volatile ("MSR faultmask, %0" : : "r" (faultMask) : "memory"); +} + +#endif /* (__CORTEX_M >= 0x03) */ + + +#if (__CORTEX_M == 0x04) || (__CORTEX_M == 0x07) + +/** \brief Get FPSCR + + This function returns the current value of the Floating Point Status/Control register. + + \return Floating Point Status/Control register value + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_FPSCR(void) +{ +#if (__FPU_PRESENT == 1) && (__FPU_USED == 1) + uint32_t result; + + /* Empty asm statement works as a scheduling barrier */ + __ASM volatile (""); + __ASM volatile ("VMRS %0, fpscr" : "=r" (result) ); + __ASM volatile (""); + return(result); +#else + return(0); +#endif +} + + +/** \brief Set FPSCR + + This function assigns the given value to the Floating Point Status/Control register. + + \param [in] fpscr Floating Point Status/Control value to set + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE void __set_FPSCR(uint32_t fpscr) +{ +#if (__FPU_PRESENT == 1) && (__FPU_USED == 1) + /* Empty asm statement works as a scheduling barrier */ + __ASM volatile (""); + __ASM volatile ("VMSR fpscr, %0" : : "r" (fpscr) : "vfpcc"); + __ASM volatile (""); +#endif +} + +#endif /* (__CORTEX_M == 0x04) || (__CORTEX_M == 0x07) */ + + +#elif defined ( __ICCARM__ ) /*------------------ ICC Compiler -------------------*/ +/* IAR iccarm specific functions */ +#include + + +#elif defined ( __TMS470__ ) /*---------------- TI CCS Compiler ------------------*/ +/* TI CCS specific functions */ +#include + + +#elif defined ( __TASKING__ ) /*------------------ TASKING Compiler --------------*/ +/* TASKING carm specific functions */ +/* + * The CMSIS functions have been implemented as intrinsics in the compiler. + * Please use "carm -?i" to get an up to date list of all intrinsics, + * Including the CMSIS ones. + */ + + +#elif defined ( __CSMC__ ) /*------------------ COSMIC Compiler -------------------*/ +/* Cosmic specific functions */ +#include + +#endif + +/*@} end of CMSIS_Core_RegAccFunctions */ + +#endif /* __CORE_CMFUNC_H */ diff --git a/STM32/inc/cm/core_cmInstr.h b/STM32/inc/cm/core_cmInstr.h new file mode 100644 index 0000000..cabf4a0 --- /dev/null +++ b/STM32/inc/cm/core_cmInstr.h @@ -0,0 +1,880 @@ +/**************************************************************************//** + * @file core_cmInstr.h + * @brief CMSIS Cortex-M Core Instruction Access Header File + * @version V4.00 + * @date 28. August 2014 + * + * @note + * + ******************************************************************************/ +/* Copyright (c) 2009 - 2014 ARM LIMITED + + All rights reserved. + Redistribution and use in source and binary forms, with or without + modification, are permitted provided that the following conditions are met: + - Redistributions of source code must retain the above copyright + notice, this list of conditions and the following disclaimer. + - Redistributions in binary form must reproduce the above copyright + notice, this list of conditions and the following disclaimer in the + documentation and/or other materials provided with the distribution. + - Neither the name of ARM nor the names of its contributors may be used + to endorse or promote products derived from this software without + specific prior written permission. + * + THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE + LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + POSSIBILITY OF SUCH DAMAGE. + ---------------------------------------------------------------------------*/ + + +#ifndef __CORE_CMINSTR_H +#define __CORE_CMINSTR_H + + +/* ########################## Core Instruction Access ######################### */ +/** \defgroup CMSIS_Core_InstructionInterface CMSIS Core Instruction Interface + Access to dedicated instructions + @{ +*/ + +#if defined ( __CC_ARM ) /*------------------RealView Compiler -----------------*/ +/* ARM armcc specific functions */ + +#if (__ARMCC_VERSION < 400677) + #error "Please use ARM Compiler Toolchain V4.0.677 or later!" +#endif + + +/** \brief No Operation + + No Operation does nothing. This instruction can be used for code alignment purposes. + */ +#define __NOP __nop + + +/** \brief Wait For Interrupt + + Wait For Interrupt is a hint instruction that suspends execution + until one of a number of events occurs. + */ +#define __WFI __wfi + + +/** \brief Wait For Event + + Wait For Event is a hint instruction that permits the processor to enter + a low-power state until one of a number of events occurs. + */ +#define __WFE __wfe + + +/** \brief Send Event + + Send Event is a hint instruction. It causes an event to be signaled to the CPU. + */ +#define __SEV __sev + + +/** \brief Instruction Synchronization Barrier + + Instruction Synchronization Barrier flushes the pipeline in the processor, + so that all instructions following the ISB are fetched from cache or + memory, after the instruction has been completed. + */ +#define __ISB() __isb(0xF) + + +/** \brief Data Synchronization Barrier + + This function acts as a special kind of Data Memory Barrier. + It completes when all explicit memory accesses before this instruction complete. + */ +#define __DSB() __dsb(0xF) + + +/** \brief Data Memory Barrier + + This function ensures the apparent order of the explicit memory operations before + and after the instruction, without ensuring their completion. + */ +#define __DMB() __dmb(0xF) + + +/** \brief Reverse byte order (32 bit) + + This function reverses the byte order in integer value. + + \param [in] value Value to reverse + \return Reversed value + */ +#define __REV __rev + + +/** \brief Reverse byte order (16 bit) + + This function reverses the byte order in two unsigned short values. + + \param [in] value Value to reverse + \return Reversed value + */ +#ifndef __NO_EMBEDDED_ASM +__attribute__((section(".rev16_text"))) __STATIC_INLINE __ASM uint32_t __REV16(uint32_t value) +{ + rev16 r0, r0 + bx lr +} +#endif + +/** \brief Reverse byte order in signed short value + + This function reverses the byte order in a signed short value with sign extension to integer. + + \param [in] value Value to reverse + \return Reversed value + */ +#ifndef __NO_EMBEDDED_ASM +__attribute__((section(".revsh_text"))) __STATIC_INLINE __ASM int32_t __REVSH(int32_t value) +{ + revsh r0, r0 + bx lr +} +#endif + + +/** \brief Rotate Right in unsigned value (32 bit) + + This function Rotate Right (immediate) provides the value of the contents of a register rotated by a variable number of bits. + + \param [in] value Value to rotate + \param [in] value Number of Bits to rotate + \return Rotated value + */ +#define __ROR __ror + + +/** \brief Breakpoint + + This function causes the processor to enter Debug state. + Debug tools can use this to investigate system state when the instruction at a particular address is reached. + + \param [in] value is ignored by the processor. + If required, a debugger can use it to store additional information about the breakpoint. + */ +#define __BKPT(value) __breakpoint(value) + + +#if (__CORTEX_M >= 0x03) || (__CORTEX_SC >= 300) + +/** \brief Reverse bit order of value + + This function reverses the bit order of the given value. + + \param [in] value Value to reverse + \return Reversed value + */ +#define __RBIT __rbit + + +/** \brief LDR Exclusive (8 bit) + + This function executes a exclusive LDR instruction for 8 bit value. + + \param [in] ptr Pointer to data + \return value of type uint8_t at (*ptr) + */ +#define __LDREXB(ptr) ((uint8_t ) __ldrex(ptr)) + + +/** \brief LDR Exclusive (16 bit) + + This function executes a exclusive LDR instruction for 16 bit values. + + \param [in] ptr Pointer to data + \return value of type uint16_t at (*ptr) + */ +#define __LDREXH(ptr) ((uint16_t) __ldrex(ptr)) + + +/** \brief LDR Exclusive (32 bit) + + This function executes a exclusive LDR instruction for 32 bit values. + + \param [in] ptr Pointer to data + \return value of type uint32_t at (*ptr) + */ +#define __LDREXW(ptr) ((uint32_t ) __ldrex(ptr)) + + +/** \brief STR Exclusive (8 bit) + + This function executes a exclusive STR instruction for 8 bit values. + + \param [in] value Value to store + \param [in] ptr Pointer to location + \return 0 Function succeeded + \return 1 Function failed + */ +#define __STREXB(value, ptr) __strex(value, ptr) + + +/** \brief STR Exclusive (16 bit) + + This function executes a exclusive STR instruction for 16 bit values. + + \param [in] value Value to store + \param [in] ptr Pointer to location + \return 0 Function succeeded + \return 1 Function failed + */ +#define __STREXH(value, ptr) __strex(value, ptr) + + +/** \brief STR Exclusive (32 bit) + + This function executes a exclusive STR instruction for 32 bit values. + + \param [in] value Value to store + \param [in] ptr Pointer to location + \return 0 Function succeeded + \return 1 Function failed + */ +#define __STREXW(value, ptr) __strex(value, ptr) + + +/** \brief Remove the exclusive lock + + This function removes the exclusive lock which is created by LDREX. + + */ +#define __CLREX __clrex + + +/** \brief Signed Saturate + + This function saturates a signed value. + + \param [in] value Value to be saturated + \param [in] sat Bit position to saturate to (1..32) + \return Saturated value + */ +#define __SSAT __ssat + + +/** \brief Unsigned Saturate + + This function saturates an unsigned value. + + \param [in] value Value to be saturated + \param [in] sat Bit position to saturate to (0..31) + \return Saturated value + */ +#define __USAT __usat + + +/** \brief Count leading zeros + + This function counts the number of leading zeros of a data value. + + \param [in] value Value to count the leading zeros + \return number of leading zeros in value + */ +#define __CLZ __clz + + +/** \brief Rotate Right with Extend (32 bit) + + This function moves each bit of a bitstring right by one bit. The carry input is shifted in at the left end of the bitstring. + + \param [in] value Value to rotate + \return Rotated value + */ +#ifndef __NO_EMBEDDED_ASM +__attribute__((section(".rrx_text"))) __STATIC_INLINE __ASM uint32_t __RRX(uint32_t value) +{ + rrx r0, r0 + bx lr +} +#endif + + +/** \brief LDRT Unprivileged (8 bit) + + This function executes a Unprivileged LDRT instruction for 8 bit value. + + \param [in] ptr Pointer to data + \return value of type uint8_t at (*ptr) + */ +#define __LDRBT(ptr) ((uint8_t ) __ldrt(ptr)) + + +/** \brief LDRT Unprivileged (16 bit) + + This function executes a Unprivileged LDRT instruction for 16 bit values. + + \param [in] ptr Pointer to data + \return value of type uint16_t at (*ptr) + */ +#define __LDRHT(ptr) ((uint16_t) __ldrt(ptr)) + + +/** \brief LDRT Unprivileged (32 bit) + + This function executes a Unprivileged LDRT instruction for 32 bit values. + + \param [in] ptr Pointer to data + \return value of type uint32_t at (*ptr) + */ +#define __LDRT(ptr) ((uint32_t ) __ldrt(ptr)) + + +/** \brief STRT Unprivileged (8 bit) + + This function executes a Unprivileged STRT instruction for 8 bit values. + + \param [in] value Value to store + \param [in] ptr Pointer to location + */ +#define __STRBT(value, ptr) __strt(value, ptr) + + +/** \brief STRT Unprivileged (16 bit) + + This function executes a Unprivileged STRT instruction for 16 bit values. + + \param [in] value Value to store + \param [in] ptr Pointer to location + */ +#define __STRHT(value, ptr) __strt(value, ptr) + + +/** \brief STRT Unprivileged (32 bit) + + This function executes a Unprivileged STRT instruction for 32 bit values. + + \param [in] value Value to store + \param [in] ptr Pointer to location + */ +#define __STRT(value, ptr) __strt(value, ptr) + +#endif /* (__CORTEX_M >= 0x03) || (__CORTEX_SC >= 300) */ + + +#elif defined ( __GNUC__ ) /*------------------ GNU Compiler ---------------------*/ +/* GNU gcc specific functions */ + +/* Define macros for porting to both thumb1 and thumb2. + * For thumb1, use low register (r0-r7), specified by constrant "l" + * Otherwise, use general registers, specified by constrant "r" */ +#if defined (__thumb__) && !defined (__thumb2__) +#define __CMSIS_GCC_OUT_REG(r) "=l" (r) +#define __CMSIS_GCC_USE_REG(r) "l" (r) +#else +#define __CMSIS_GCC_OUT_REG(r) "=r" (r) +#define __CMSIS_GCC_USE_REG(r) "r" (r) +#endif + +/** \brief No Operation + + No Operation does nothing. This instruction can be used for code alignment purposes. + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE void __NOP(void) +{ + __ASM volatile ("nop"); +} + + +/** \brief Wait For Interrupt + + Wait For Interrupt is a hint instruction that suspends execution + until one of a number of events occurs. + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE void __WFI(void) +{ + __ASM volatile ("wfi"); +} + + +/** \brief Wait For Event + + Wait For Event is a hint instruction that permits the processor to enter + a low-power state until one of a number of events occurs. + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE void __WFE(void) +{ + __ASM volatile ("wfe"); +} + + +/** \brief Send Event + + Send Event is a hint instruction. It causes an event to be signaled to the CPU. + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE void __SEV(void) +{ + __ASM volatile ("sev"); +} + + +/** \brief Instruction Synchronization Barrier + + Instruction Synchronization Barrier flushes the pipeline in the processor, + so that all instructions following the ISB are fetched from cache or + memory, after the instruction has been completed. + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE void __ISB(void) +{ + __ASM volatile ("isb"); +} + + +/** \brief Data Synchronization Barrier + + This function acts as a special kind of Data Memory Barrier. + It completes when all explicit memory accesses before this instruction complete. + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE void __DSB(void) +{ + __ASM volatile ("dsb"); +} + + +/** \brief Data Memory Barrier + + This function ensures the apparent order of the explicit memory operations before + and after the instruction, without ensuring their completion. + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE void __DMB(void) +{ + __ASM volatile ("dmb"); +} + + +/** \brief Reverse byte order (32 bit) + + This function reverses the byte order in integer value. + + \param [in] value Value to reverse + \return Reversed value + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __REV(uint32_t value) +{ +#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 5) + return __builtin_bswap32(value); +#else + uint32_t result; + + __ASM volatile ("rev %0, %1" : __CMSIS_GCC_OUT_REG (result) : __CMSIS_GCC_USE_REG (value) ); + return(result); +#endif +} + + +/** \brief Reverse byte order (16 bit) + + This function reverses the byte order in two unsigned short values. + + \param [in] value Value to reverse + \return Reversed value + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __REV16(uint32_t value) +{ + uint32_t result; + + __ASM volatile ("rev16 %0, %1" : __CMSIS_GCC_OUT_REG (result) : __CMSIS_GCC_USE_REG (value) ); + return(result); +} + + +/** \brief Reverse byte order in signed short value + + This function reverses the byte order in a signed short value with sign extension to integer. + + \param [in] value Value to reverse + \return Reversed value + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE int32_t __REVSH(int32_t value) +{ +#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 8) + return (short)__builtin_bswap16(value); +#else + uint32_t result; + + __ASM volatile ("revsh %0, %1" : __CMSIS_GCC_OUT_REG (result) : __CMSIS_GCC_USE_REG (value) ); + return(result); +#endif +} + + +/** \brief Rotate Right in unsigned value (32 bit) + + This function Rotate Right (immediate) provides the value of the contents of a register rotated by a variable number of bits. + + \param [in] value Value to rotate + \param [in] value Number of Bits to rotate + \return Rotated value + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __ROR(uint32_t op1, uint32_t op2) +{ + return (op1 >> op2) | (op1 << (32 - op2)); +} + + +/** \brief Breakpoint + + This function causes the processor to enter Debug state. + Debug tools can use this to investigate system state when the instruction at a particular address is reached. + + \param [in] value is ignored by the processor. + If required, a debugger can use it to store additional information about the breakpoint. + */ +#define __BKPT(value) __ASM volatile ("bkpt "#value) + + +#if (__CORTEX_M >= 0x03) || (__CORTEX_SC >= 300) + +/** \brief Reverse bit order of value + + This function reverses the bit order of the given value. + + \param [in] value Value to reverse + \return Reversed value + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __RBIT(uint32_t value) +{ + uint32_t result; + + __ASM volatile ("rbit %0, %1" : "=r" (result) : "r" (value) ); + return(result); +} + + +/** \brief LDR Exclusive (8 bit) + + This function executes a exclusive LDR instruction for 8 bit value. + + \param [in] ptr Pointer to data + \return value of type uint8_t at (*ptr) + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE uint8_t __LDREXB(volatile uint8_t *addr) +{ + uint32_t result; + +#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 8) + __ASM volatile ("ldrexb %0, %1" : "=r" (result) : "Q" (*addr) ); +#else + /* Prior to GCC 4.8, "Q" will be expanded to [rx, #0] which is not + accepted by assembler. So has to use following less efficient pattern. + */ + __ASM volatile ("ldrexb %0, [%1]" : "=r" (result) : "r" (addr) : "memory" ); +#endif + return ((uint8_t) result); /* Add explicit type cast here */ +} + + +/** \brief LDR Exclusive (16 bit) + + This function executes a exclusive LDR instruction for 16 bit values. + + \param [in] ptr Pointer to data + \return value of type uint16_t at (*ptr) + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE uint16_t __LDREXH(volatile uint16_t *addr) +{ + uint32_t result; + +#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 8) + __ASM volatile ("ldrexh %0, %1" : "=r" (result) : "Q" (*addr) ); +#else + /* Prior to GCC 4.8, "Q" will be expanded to [rx, #0] which is not + accepted by assembler. So has to use following less efficient pattern. + */ + __ASM volatile ("ldrexh %0, [%1]" : "=r" (result) : "r" (addr) : "memory" ); +#endif + return ((uint16_t) result); /* Add explicit type cast here */ +} + + +/** \brief LDR Exclusive (32 bit) + + This function executes a exclusive LDR instruction for 32 bit values. + + \param [in] ptr Pointer to data + \return value of type uint32_t at (*ptr) + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __LDREXW(volatile uint32_t *addr) +{ + uint32_t result; + + __ASM volatile ("ldrex %0, %1" : "=r" (result) : "Q" (*addr) ); + return(result); +} + + +/** \brief STR Exclusive (8 bit) + + This function executes a exclusive STR instruction for 8 bit values. + + \param [in] value Value to store + \param [in] ptr Pointer to location + \return 0 Function succeeded + \return 1 Function failed + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __STREXB(uint8_t value, volatile uint8_t *addr) +{ + uint32_t result; + + __ASM volatile ("strexb %0, %2, %1" : "=&r" (result), "=Q" (*addr) : "r" ((uint32_t)value) ); + return(result); +} + + +/** \brief STR Exclusive (16 bit) + + This function executes a exclusive STR instruction for 16 bit values. + + \param [in] value Value to store + \param [in] ptr Pointer to location + \return 0 Function succeeded + \return 1 Function failed + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __STREXH(uint16_t value, volatile uint16_t *addr) +{ + uint32_t result; + + __ASM volatile ("strexh %0, %2, %1" : "=&r" (result), "=Q" (*addr) : "r" ((uint32_t)value) ); + return(result); +} + + +/** \brief STR Exclusive (32 bit) + + This function executes a exclusive STR instruction for 32 bit values. + + \param [in] value Value to store + \param [in] ptr Pointer to location + \return 0 Function succeeded + \return 1 Function failed + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __STREXW(uint32_t value, volatile uint32_t *addr) +{ + uint32_t result; + + __ASM volatile ("strex %0, %2, %1" : "=&r" (result), "=Q" (*addr) : "r" (value) ); + return(result); +} + + +/** \brief Remove the exclusive lock + + This function removes the exclusive lock which is created by LDREX. + + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE void __CLREX(void) +{ + __ASM volatile ("clrex" ::: "memory"); +} + + +/** \brief Signed Saturate + + This function saturates a signed value. + + \param [in] value Value to be saturated + \param [in] sat Bit position to saturate to (1..32) + \return Saturated value + */ +#define __SSAT(ARG1,ARG2) \ +({ \ + uint32_t __RES, __ARG1 = (ARG1); \ + __ASM ("ssat %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \ + __RES; \ + }) + + +/** \brief Unsigned Saturate + + This function saturates an unsigned value. + + \param [in] value Value to be saturated + \param [in] sat Bit position to saturate to (0..31) + \return Saturated value + */ +#define __USAT(ARG1,ARG2) \ +({ \ + uint32_t __RES, __ARG1 = (ARG1); \ + __ASM ("usat %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \ + __RES; \ + }) + + +/** \brief Count leading zeros + + This function counts the number of leading zeros of a data value. + + \param [in] value Value to count the leading zeros + \return number of leading zeros in value + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE uint8_t __CLZ(uint32_t value) +{ + uint32_t result; + + __ASM volatile ("clz %0, %1" : "=r" (result) : "r" (value) ); + return ((uint8_t) result); /* Add explicit type cast here */ +} + + +/** \brief Rotate Right with Extend (32 bit) + + This function moves each bit of a bitstring right by one bit. The carry input is shifted in at the left end of the bitstring. + + \param [in] value Value to rotate + \return Rotated value + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __RRX(uint32_t value) +{ + uint32_t result; + + __ASM volatile ("rrx %0, %1" : __CMSIS_GCC_OUT_REG (result) : __CMSIS_GCC_USE_REG (value) ); + return(result); +} + + +/** \brief LDRT Unprivileged (8 bit) + + This function executes a Unprivileged LDRT instruction for 8 bit value. + + \param [in] ptr Pointer to data + \return value of type uint8_t at (*ptr) + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE uint8_t __LDRBT(volatile uint8_t *addr) +{ + uint32_t result; + +#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 8) + __ASM volatile ("ldrbt %0, %1" : "=r" (result) : "Q" (*addr) ); +#else + /* Prior to GCC 4.8, "Q" will be expanded to [rx, #0] which is not + accepted by assembler. So has to use following less efficient pattern. + */ + __ASM volatile ("ldrbt %0, [%1]" : "=r" (result) : "r" (addr) : "memory" ); +#endif + return ((uint8_t) result); /* Add explicit type cast here */ +} + + +/** \brief LDRT Unprivileged (16 bit) + + This function executes a Unprivileged LDRT instruction for 16 bit values. + + \param [in] ptr Pointer to data + \return value of type uint16_t at (*ptr) + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE uint16_t __LDRHT(volatile uint16_t *addr) +{ + uint32_t result; + +#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 8) + __ASM volatile ("ldrht %0, %1" : "=r" (result) : "Q" (*addr) ); +#else + /* Prior to GCC 4.8, "Q" will be expanded to [rx, #0] which is not + accepted by assembler. So has to use following less efficient pattern. + */ + __ASM volatile ("ldrht %0, [%1]" : "=r" (result) : "r" (addr) : "memory" ); +#endif + return ((uint16_t) result); /* Add explicit type cast here */ +} + + +/** \brief LDRT Unprivileged (32 bit) + + This function executes a Unprivileged LDRT instruction for 32 bit values. + + \param [in] ptr Pointer to data + \return value of type uint32_t at (*ptr) + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __LDRT(volatile uint32_t *addr) +{ + uint32_t result; + + __ASM volatile ("ldrt %0, %1" : "=r" (result) : "Q" (*addr) ); + return(result); +} + + +/** \brief STRT Unprivileged (8 bit) + + This function executes a Unprivileged STRT instruction for 8 bit values. + + \param [in] value Value to store + \param [in] ptr Pointer to location + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE void __STRBT(uint8_t value, volatile uint8_t *addr) +{ + __ASM volatile ("strbt %1, %0" : "=Q" (*addr) : "r" ((uint32_t)value) ); +} + + +/** \brief STRT Unprivileged (16 bit) + + This function executes a Unprivileged STRT instruction for 16 bit values. + + \param [in] value Value to store + \param [in] ptr Pointer to location + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE void __STRHT(uint16_t value, volatile uint16_t *addr) +{ + __ASM volatile ("strht %1, %0" : "=Q" (*addr) : "r" ((uint32_t)value) ); +} + + +/** \brief STRT Unprivileged (32 bit) + + This function executes a Unprivileged STRT instruction for 32 bit values. + + \param [in] value Value to store + \param [in] ptr Pointer to location + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE void __STRT(uint32_t value, volatile uint32_t *addr) +{ + __ASM volatile ("strt %1, %0" : "=Q" (*addr) : "r" (value) ); +} + +#endif /* (__CORTEX_M >= 0x03) || (__CORTEX_SC >= 300) */ + + +#elif defined ( __ICCARM__ ) /*------------------ ICC Compiler -------------------*/ +/* IAR iccarm specific functions */ +#include + + +#elif defined ( __TMS470__ ) /*---------------- TI CCS Compiler ------------------*/ +/* TI CCS specific functions */ +#include + + +#elif defined ( __TASKING__ ) /*------------------ TASKING Compiler --------------*/ +/* TASKING carm specific functions */ +/* + * The CMSIS functions have been implemented as intrinsics in the compiler. + * Please use "carm -?i" to get an up to date list of all intrinsics, + * Including the CMSIS ones. + */ + + +#elif defined ( __CSMC__ ) /*------------------ COSMIC Compiler -------------------*/ +/* Cosmic specific functions */ +#include + +#endif + +/*@}*/ /* end of group CMSIS_Core_InstructionInterface */ + +#endif /* __CORE_CMINSTR_H */ diff --git a/STM32/inc/cm/core_cmSimd.h b/STM32/inc/cm/core_cmSimd.h new file mode 100644 index 0000000..0466561 --- /dev/null +++ b/STM32/inc/cm/core_cmSimd.h @@ -0,0 +1,697 @@ +/**************************************************************************//** + * @file core_cmSimd.h + * @brief CMSIS Cortex-M SIMD Header File + * @version V4.00 + * @date 22. August 2014 + * + * @note + * + ******************************************************************************/ +/* Copyright (c) 2009 - 2014 ARM LIMITED + + All rights reserved. + Redistribution and use in source and binary forms, with or without + modification, are permitted provided that the following conditions are met: + - Redistributions of source code must retain the above copyright + notice, this list of conditions and the following disclaimer. + - Redistributions in binary form must reproduce the above copyright + notice, this list of conditions and the following disclaimer in the + documentation and/or other materials provided with the distribution. + - Neither the name of ARM nor the names of its contributors may be used + to endorse or promote products derived from this software without + specific prior written permission. + * + THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE + LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + POSSIBILITY OF SUCH DAMAGE. + ---------------------------------------------------------------------------*/ + + +#if defined ( __ICCARM__ ) + #pragma system_include /* treat file as system include file for MISRA check */ +#endif + +#ifndef __CORE_CMSIMD_H +#define __CORE_CMSIMD_H + +#ifdef __cplusplus + extern "C" { +#endif + + +/******************************************************************************* + * Hardware Abstraction Layer + ******************************************************************************/ + + +/* ################### Compiler specific Intrinsics ########################### */ +/** \defgroup CMSIS_SIMD_intrinsics CMSIS SIMD Intrinsics + Access to dedicated SIMD instructions + @{ +*/ + +#if defined ( __CC_ARM ) /*------------------RealView Compiler -----------------*/ +/* ARM armcc specific functions */ +#define __SADD8 __sadd8 +#define __QADD8 __qadd8 +#define __SHADD8 __shadd8 +#define __UADD8 __uadd8 +#define __UQADD8 __uqadd8 +#define __UHADD8 __uhadd8 +#define __SSUB8 __ssub8 +#define __QSUB8 __qsub8 +#define __SHSUB8 __shsub8 +#define __USUB8 __usub8 +#define __UQSUB8 __uqsub8 +#define __UHSUB8 __uhsub8 +#define __SADD16 __sadd16 +#define __QADD16 __qadd16 +#define __SHADD16 __shadd16 +#define __UADD16 __uadd16 +#define __UQADD16 __uqadd16 +#define __UHADD16 __uhadd16 +#define __SSUB16 __ssub16 +#define __QSUB16 __qsub16 +#define __SHSUB16 __shsub16 +#define __USUB16 __usub16 +#define __UQSUB16 __uqsub16 +#define __UHSUB16 __uhsub16 +#define __SASX __sasx +#define __QASX __qasx +#define __SHASX __shasx +#define __UASX __uasx +#define __UQASX __uqasx +#define __UHASX __uhasx +#define __SSAX __ssax +#define __QSAX __qsax +#define __SHSAX __shsax +#define __USAX __usax +#define __UQSAX __uqsax +#define __UHSAX __uhsax +#define __USAD8 __usad8 +#define __USADA8 __usada8 +#define __SSAT16 __ssat16 +#define __USAT16 __usat16 +#define __UXTB16 __uxtb16 +#define __UXTAB16 __uxtab16 +#define __SXTB16 __sxtb16 +#define __SXTAB16 __sxtab16 +#define __SMUAD __smuad +#define __SMUADX __smuadx +#define __SMLAD __smlad +#define __SMLADX __smladx +#define __SMLALD __smlald +#define __SMLALDX __smlaldx +#define __SMUSD __smusd +#define __SMUSDX __smusdx +#define __SMLSD __smlsd +#define __SMLSDX __smlsdx +#define __SMLSLD __smlsld +#define __SMLSLDX __smlsldx +#define __SEL __sel +#define __QADD __qadd +#define __QSUB __qsub + +#define __PKHBT(ARG1,ARG2,ARG3) ( ((((uint32_t)(ARG1)) ) & 0x0000FFFFUL) | \ + ((((uint32_t)(ARG2)) << (ARG3)) & 0xFFFF0000UL) ) + +#define __PKHTB(ARG1,ARG2,ARG3) ( ((((uint32_t)(ARG1)) ) & 0xFFFF0000UL) | \ + ((((uint32_t)(ARG2)) >> (ARG3)) & 0x0000FFFFUL) ) + +#define __SMMLA(ARG1,ARG2,ARG3) ( (int32_t)((((int64_t)(ARG1) * (ARG2)) + \ + ((int64_t)(ARG3) << 32) ) >> 32)) + + +#elif defined ( __GNUC__ ) /*------------------ GNU Compiler ---------------------*/ +/* GNU gcc specific functions */ +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SADD8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("sadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __QADD8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("qadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SHADD8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("shadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UADD8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UQADD8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uqadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UHADD8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uhadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SSUB8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("ssub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __QSUB8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("qsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SHSUB8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("shsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __USUB8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("usub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UQSUB8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uqsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UHSUB8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uhsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SADD16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("sadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __QADD16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("qadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SHADD16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("shadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UADD16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UQADD16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uqadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UHADD16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uhadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SSUB16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("ssub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __QSUB16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("qsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SHSUB16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("shsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __USUB16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("usub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UQSUB16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uqsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UHSUB16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uhsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SASX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("sasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __QASX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("qasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SHASX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("shasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UASX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UQASX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uqasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UHASX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uhasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SSAX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("ssax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __QSAX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("qsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SHSAX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("shsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __USAX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("usax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UQSAX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uqsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UHSAX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uhsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __USAD8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("usad8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __USADA8(uint32_t op1, uint32_t op2, uint32_t op3) +{ + uint32_t result; + + __ASM volatile ("usada8 %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); + return(result); +} + +#define __SSAT16(ARG1,ARG2) \ +({ \ + uint32_t __RES, __ARG1 = (ARG1); \ + __ASM ("ssat16 %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \ + __RES; \ + }) + +#define __USAT16(ARG1,ARG2) \ +({ \ + uint32_t __RES, __ARG1 = (ARG1); \ + __ASM ("usat16 %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \ + __RES; \ + }) + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UXTB16(uint32_t op1) +{ + uint32_t result; + + __ASM volatile ("uxtb16 %0, %1" : "=r" (result) : "r" (op1)); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UXTAB16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uxtab16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SXTB16(uint32_t op1) +{ + uint32_t result; + + __ASM volatile ("sxtb16 %0, %1" : "=r" (result) : "r" (op1)); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SXTAB16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("sxtab16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SMUAD (uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("smuad %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SMUADX (uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("smuadx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SMLAD (uint32_t op1, uint32_t op2, uint32_t op3) +{ + uint32_t result; + + __ASM volatile ("smlad %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SMLADX (uint32_t op1, uint32_t op2, uint32_t op3) +{ + uint32_t result; + + __ASM volatile ("smladx %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint64_t __SMLALD (uint32_t op1, uint32_t op2, uint64_t acc) +{ + union llreg_u{ + uint32_t w32[2]; + uint64_t w64; + } llr; + llr.w64 = acc; + +#ifndef __ARMEB__ // Little endian + __ASM volatile ("smlald %0, %1, %2, %3" : "=r" (llr.w32[0]), "=r" (llr.w32[1]): "r" (op1), "r" (op2) , "0" (llr.w32[0]), "1" (llr.w32[1]) ); +#else // Big endian + __ASM volatile ("smlald %0, %1, %2, %3" : "=r" (llr.w32[1]), "=r" (llr.w32[0]): "r" (op1), "r" (op2) , "0" (llr.w32[1]), "1" (llr.w32[0]) ); +#endif + + return(llr.w64); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint64_t __SMLALDX (uint32_t op1, uint32_t op2, uint64_t acc) +{ + union llreg_u{ + uint32_t w32[2]; + uint64_t w64; + } llr; + llr.w64 = acc; + +#ifndef __ARMEB__ // Little endian + __ASM volatile ("smlaldx %0, %1, %2, %3" : "=r" (llr.w32[0]), "=r" (llr.w32[1]): "r" (op1), "r" (op2) , "0" (llr.w32[0]), "1" (llr.w32[1]) ); +#else // Big endian + __ASM volatile ("smlaldx %0, %1, %2, %3" : "=r" (llr.w32[1]), "=r" (llr.w32[0]): "r" (op1), "r" (op2) , "0" (llr.w32[1]), "1" (llr.w32[0]) ); +#endif + + return(llr.w64); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SMUSD (uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("smusd %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SMUSDX (uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("smusdx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SMLSD (uint32_t op1, uint32_t op2, uint32_t op3) +{ + uint32_t result; + + __ASM volatile ("smlsd %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SMLSDX (uint32_t op1, uint32_t op2, uint32_t op3) +{ + uint32_t result; + + __ASM volatile ("smlsdx %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint64_t __SMLSLD (uint32_t op1, uint32_t op2, uint64_t acc) +{ + union llreg_u{ + uint32_t w32[2]; + uint64_t w64; + } llr; + llr.w64 = acc; + +#ifndef __ARMEB__ // Little endian + __ASM volatile ("smlsld %0, %1, %2, %3" : "=r" (llr.w32[0]), "=r" (llr.w32[1]): "r" (op1), "r" (op2) , "0" (llr.w32[0]), "1" (llr.w32[1]) ); +#else // Big endian + __ASM volatile ("smlsld %0, %1, %2, %3" : "=r" (llr.w32[1]), "=r" (llr.w32[0]): "r" (op1), "r" (op2) , "0" (llr.w32[1]), "1" (llr.w32[0]) ); +#endif + + return(llr.w64); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint64_t __SMLSLDX (uint32_t op1, uint32_t op2, uint64_t acc) +{ + union llreg_u{ + uint32_t w32[2]; + uint64_t w64; + } llr; + llr.w64 = acc; + +#ifndef __ARMEB__ // Little endian + __ASM volatile ("smlsldx %0, %1, %2, %3" : "=r" (llr.w32[0]), "=r" (llr.w32[1]): "r" (op1), "r" (op2) , "0" (llr.w32[0]), "1" (llr.w32[1]) ); +#else // Big endian + __ASM volatile ("smlsldx %0, %1, %2, %3" : "=r" (llr.w32[1]), "=r" (llr.w32[0]): "r" (op1), "r" (op2) , "0" (llr.w32[1]), "1" (llr.w32[0]) ); +#endif + + return(llr.w64); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SEL (uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("sel %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __QADD(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("qadd %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __QSUB(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("qsub %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +#define __PKHBT(ARG1,ARG2,ARG3) \ +({ \ + uint32_t __RES, __ARG1 = (ARG1), __ARG2 = (ARG2); \ + __ASM ("pkhbt %0, %1, %2, lsl %3" : "=r" (__RES) : "r" (__ARG1), "r" (__ARG2), "I" (ARG3) ); \ + __RES; \ + }) + +#define __PKHTB(ARG1,ARG2,ARG3) \ +({ \ + uint32_t __RES, __ARG1 = (ARG1), __ARG2 = (ARG2); \ + if (ARG3 == 0) \ + __ASM ("pkhtb %0, %1, %2" : "=r" (__RES) : "r" (__ARG1), "r" (__ARG2) ); \ + else \ + __ASM ("pkhtb %0, %1, %2, asr %3" : "=r" (__RES) : "r" (__ARG1), "r" (__ARG2), "I" (ARG3) ); \ + __RES; \ + }) + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SMMLA (int32_t op1, int32_t op2, int32_t op3) +{ + int32_t result; + + __ASM volatile ("smmla %0, %1, %2, %3" : "=r" (result): "r" (op1), "r" (op2), "r" (op3) ); + return(result); +} + + +#elif defined ( __ICCARM__ ) /*------------------ ICC Compiler -------------------*/ +/* IAR iccarm specific functions */ +#include + + +#elif defined ( __TMS470__ ) /*---------------- TI CCS Compiler ------------------*/ +/* TI CCS specific functions */ +#include + + +#elif defined ( __TASKING__ ) /*------------------ TASKING Compiler --------------*/ +/* TASKING carm specific functions */ +/* not yet supported */ + + +#elif defined ( __CSMC__ ) /*------------------ COSMIC Compiler -------------------*/ +/* Cosmic specific functions */ +#include + +#endif + +/*@} end of group CMSIS_SIMD_intrinsics */ + + +#ifdef __cplusplus +} +#endif + +#endif /* __CORE_CMSIMD_H */ diff --git a/STM32/inc/gen042 b/STM32/inc/gen042 new file mode 100755 index 0000000..ffa2e03 --- /dev/null +++ b/STM32/inc/gen042 @@ -0,0 +1,2 @@ +#!/bin/sh +CFLAGS="-IF0 -Icm -DSTM32F030x6" geany -g stm32f030.c.tags F0/stm32f030x6.h F0/stm32f0.h F0/stm32f0xx.h cm/core_cm0.h cm/core_cmFunc.h cm/core_cmInstr.h cm/core_cmSimd.h startup/vector.c diff --git a/STM32/inc/ld/devices.data b/STM32/inc/ld/devices.data new file mode 100644 index 0000000..1ad1fab --- /dev/null +++ b/STM32/inc/ld/devices.data @@ -0,0 +1,393 @@ +################################################################################ +# +# Device chip tree definition file. +# +# Copyright (c) 2013 Frantisek Burian +# Copyright (C) 2013 Werner Almesberger +# +# Line description: +# ( ...) +# +# : is the pattern for the chip description to be searched for. +# The case of the pattern string is ignored. +# Pattern match symbols: +# ? - matches exactly one character +# * - matches none or more characters +# + - matches single or more characters +# +# : is the parent group name, where the search will continue. +# There are special parents names that controls traversing: +# "END" - Exit traversal. +# "+" - Don't change the parent. Use for split long line to two. +# +# : space-separated list of preprocessor symbols supplied to the linker. +# -D option name is automatically prepended to each symbol definition +# +# All lines starting with # symbol are treated as Comments +# +# Recommended tree hierarchy: +# +# +# +- +# +- +# +- END +# +# You can split the long line into two or more by using "+" in the parent field, +# and defining same regex with appropriate parent on the next line. Example: +# +# device + PARAM1=aaa PARAM2=bbbb PARAM3=ccc PARAM4=dddd PARAM5=eeee +# device parent PARAM6=ffff PARAM7=gggg PARAM8=hhhh +# parent END +# +# The order of the lines is important. After the regex match, its parent will +# be used for match on the next line. If two regexp lines matches input, only +# the first will be evaluated, except special group definition "+" +# +# The regex matches entire sym +# +# Example: +# +# --- devices.data file --- +# stm32f05[01]?4* stm32f0 ROM=16K RAM=4K +# stm32f0 stm32 ROM_OFF=0x08000000 RAM_OFF=0x20000000 +# stm32 END +# +# --- queried chip name --- +# stm32f051c8t6 +# +# --- output of the awk script --- +# -DROM=16K -DRAM=4K -DROM_OFF=0x08000000 -DRAM_OFF=0x20000000 +# +# The generated linker script file will contain sections rom and ram with +# appropriate initialization code, specified in linker file source linker.ld.S +# + +################################################################################ +# the STM32 chips + +stm32f03[01]?4* stm32f0 ROM=16K RAM=4K +stm32f03[01]?6* stm32f0 ROM=32K RAM=4K +stm32f030?8* stm32f0 ROM=64K RAM=8K +stm32f050?4* stm32f0 ROM=16K RAM=4K +stm32f050?6* stm32f0 ROM=32K RAM=4K +stm32f051?4* stm32f0 ROM=16K RAM=8K +stm32f051?6* stm32f0 ROM=32K RAM=8K +stm32f051?8* stm32f0 ROM=64K RAM=8K +stm32f072?8* stm32f0 ROM=64K RAM=16K +stm32f07[12]?B* stm32f0 ROM=128K RAM=16K + +stm32f10[012]?4* stm32f1 ROM=16K RAM=4K +stm32f103?4* stm32f1 ROM=16K RAM=6K +stm32f100?6* stm32f1 ROM=32K RAM=4K +stm32f103?6* stm32f1 ROM=32K RAM=10K +stm32f10[12]?6* stm32f1 ROM=32K RAM=6K +stm32f100?8* stm32f1 ROM=64K RAM=8K +stm32f10[12]?8* stm32f1 ROM=64K RAM=10K +stm32f103?8* stm32f1 ROM=64K RAM=20K +stm32f100?b* stm32f1 ROM=128K RAM=8K +stm32f10[12]?b* stm32f1 ROM=128K RAM=16K +stm32f103?b* stm32f1 ROM=128K RAM=20K +stm32f10[57]?b* stm32f1 ROM=128K RAM=64K +stm32f100?c* stm32f1 ROM=256K RAM=24K +stm32f101?c* stm32f1 ROM=256K RAM=32K +stm32f103?c* stm32f1 ROM=256K RAM=48K +stm32f10[57]?c* stm32f1 ROM=256K RAM=64K +stm32f100?d* stm32f1 ROM=384K RAM=32K +stm32f101?d* stm32f1 ROM=384K RAM=48K +stm32f103?d* stm32f1 ROM=384K RAM=64K +stm32f100?e* stm32f1 ROM=512K RAM=32K +stm32f101?e* stm32f1 ROM=512K RAM=48K +stm32f103?e* stm32f1 ROM=512K RAM=64K +stm32f100?f* stm32f1 ROM=768K RAM=80K +stm32f103?f* stm32f1 ROM=768K RAM=96K +stm32f100?g* stm32f1 ROM=1024K RAM=80K +stm32f103?g* stm32f1 ROM=1024K RAM=96K + +stm32f205?b* stm32f2 ROM=128K RAM=64K +stm32f205?c* stm32f2 ROM=256K RAM=96K +stm32f207?c* stm32f2 ROM=256K RAM=128K +stm32f2[01][57]?e* stm32f2 ROM=512K RAM=128K +stm32f20[57]?f* stm32f2 ROM=768K RAM=128K +stm32f2[01][57]?g* stm32f2 ROM=1024K RAM=128K + +stm32f302?b* stm32f3ccm ROM=128K RAM=24K CCM=8K +stm32f302?c* stm32f3ccm ROM=256K RAM=32K CCM=8K +stm32f303?b* stm32f3ccm ROM=128K RAM=40K CCM=8K +stm32f3[01]3?c* stm32f3ccm ROM=256K RAM=48K CCM=8K +stm32f373?8* stm32f3 ROM=64K RAM=16K +stm32f373?b* stm32f3 ROM=128K RAM=24K +stm32f3[78]3?8* stm32f3 ROM=256K RAM=32K + +stm32f401?b* stm32f4 ROM=128K RAM=64K +stm32f401?c* stm32f4 ROM=256K RAM=64K +stm32f401?d* stm32f4 ROM=512K RAM=96K +stm32f401?e* stm32f4 ROM=384K RAM=96K +stm32f4[01][57]?e* stm32f4ccm ROM=512K RAM=128K CCM=64K +stm32f4[01][57]?g* stm32f4ccm ROM=1024K RAM=128K CCM=64K +stm32f4[23][79]?g* stm32f4ccm ROM=1024K RAM=192K CCM=64K +stm32f4[23][79]?i* stm32f4ccm ROM=2048K RAM=192K CCM=64K + +stm32l0???6* stm32l0 ROM=32K RAM=8K +stm32l0???8* stm32l0 ROM=64K RAM=8K + +stm32l100?6* stm32l1 ROM=32K RAM=4K +stm32l100?8* stm32l1 ROM=64K RAM=8K +stm32l100?b* stm32l1 ROM=128K RAM=10K +stm32l100?c* stm32l1 ROM=256K RAM=16K +stm32l15[12]?6* stm32l1eep ROM=32K RAM=10K EEP=4K +stm32l15[12]?8* stm32l1eep ROM=64K RAM=10K EEP=4K +stm32l15[12]?b* stm32l1eep ROM=128K RAM=16K EEP=4K +stm32l15[12]?c* stm32l1eep ROM=256K RAM=32K EEP=8K +stm32l15[12]?d* stm32l1eep ROM=384K RAM=48K EEP=12K +stm32l162?c* stm32l1eep ROM=256K RAM=32K EEP=8K +stm32l162?d* stm32l1eep ROM=384K RAM=48K EEP=12K + +stm32ts60 stm32t ROM=32K RAM=10K + +stm32w108c8 stm32w ROM=64K RAM=8K +stm32w108?b stm32w ROM=128K RAM=8K +stm32w108cz stm32w ROM=192K RAM=12K +stm32w108cc stm32w ROM=256K RAM=16K + +################################################################################ +# the SAM3 chips + +sam3a4* sam3a ROM=256K RAM=32K RAM1=32K +sam3a8* sam3a ROM=512K RAM=64K RAM1=32K + +sam3n00* sam3n ROM=16K RAM=4K +sam3n0* sam3n ROM=32K RAM=8K +sam3n1* sam3n ROM=64K RAM=8K +sam3n2* sam3n ROM=128K RAM=16K +sam3n4* sam3n ROM=256K RAM=24K + +sam3s1* sam3s ROM=64K RAM=16K +sam3s2* sam3s ROM=128K RAM=32K +sam3s4* sam3s ROM=256K RAM=48K +sam3s8* sam3s ROM=512K RAM=64K +sam3sd8* sam3s ROM=512K RAM=64K + +sam3u1* sam3u ROM=64K RAM=8K RAM1=8K +sam3u2* sam3u ROM=128K RAM=16K RAM1=16K +sam3u4* sam3u ROM=265K RAM=32K RAM1=16K + +sam3x4c* sam3x ROM=256K RAM=32K RAM1=32K +sam3x4e* sam3xnfc ROM=256K RAM=32K RAM1=32K +sam3x8c* sam3x ROM=512K RAM=64K RAM1=32K +sam3x8e* sam3xnfc ROM=512K RAM=64K RAM1=32K + +################################################################################ +# the lpc chips + +lpc1311* lpc13 ROM=8K RAM=4K +lpc1313* lpc13 ROM=32K RAM=8K +lpc1342* lpc13 ROM=16K RAM=4K +lpc1343* lpc13 ROM=32K RAM=8K +lpc1315* lpc13u ROM=32K RAM=8K +lpc1316* lpc13u ROM=48K RAM=8K +lpc1317* lpc13u ROM=64K RAM=8K RAM1=2K +lpc1345* lpc13u ROM=32K RAM=8K USBRAM=2K +lpc1346* lpc13u ROM=48K RAM=8K USBRAM=2K +lpc1346* lpc13u ROM=64K RAM=8K USBRAM=2K RAM1=2K + +lpc1751* lpc175x ROM=32K RAM=8K +lpc1752* lpc175x ROM=64K RAM=16K +lpc1754* lpc175x ROM=128K RAM=16K RAM1=16K +lpc1756* lpc175x ROM=256K RAM=16K RAM1=16K +lpc1758* lpc175x ROM=512K RAM=32K RAM1=16K RAM2=16K +lpc1759* lpc175x ROM=512K RAM=32K RAM1=16K RAM2=16K +lpc1763* lpc176x ROM=256K RAM=32K RAM1=16K RAM2=16K +lpc1764* lpc176x ROM=128K RAM=16K RAM1=16K +lpc1765* lpc176x ROM=256K RAM=32K RAM1=16K RAM2=16K +lpc1766* lpc176x ROM=256K RAM=32K RAM1=16K RAM2=16K +lpc1767* lpc176x ROM=512K RAM=32K RAM1=16K RAM2=16K +lpc1768* lpc176x ROM=512K RAM=32K RAM1=16K RAM2=16K +lpc1769* lpc176x ROM=512K RAM=32K RAM1=16K RAM2=16K +lpc1774* lpc177x ROM=128K RAM=32K RAM1=8K +lpc1776* lpc177x ROM=256K RAM=64K RAM1=16K +lpc1777* lpc177x ROM=512K RAM=64K RAM1=16K RAM2=16K +lpc1778* lpc177x ROM=512K RAM=64K RAM1=16K RAM2=16K +lpc1785* lpc178x ROM=256K RAM=64K RAM1=16K +lpc1786* lpc178x ROM=256K RAM=64K RAM1=16K +lpc1787* lpc178x ROM=512K RAM=64K RAM1=16K RAM2=16K +lpc1788* lpc178x ROM=512K RAM=64K RAM1=16K RAM2=16K + +################################################################################ +# the efm32 chips + +# Zero Gecko +efm32zg???f4 efm32zg ROM=4K RAM=2K +efm32zg???f8 efm32zg ROM=8K RAM=2K +efm32zg???f16 efm32zg ROM=16K RAM=4K +efm32zg???f32 efm32zg ROM=32K RAM=4K + +# Tiny Gecko +efm32tg108f4 efm32tg ROM=4K RAM=1K +efm32tg110f4 efm32tg ROM=4K RAM=2K +efm32tg???f8 efm32tg ROM=8K RAM=2K +efm32tg???f16 efm32tg ROM=16K RAM=4K +efm32tg???f32 efm32tg ROM=32K RAM=4K + +# Gecko +efm32g200f16 efm32g ROM=16K RAM=8K +efm32g???f32 efm32g ROM=32K RAM=8K +efm32g???f64 efm32g ROM=64K RAM=16K +efm32g???f128 efm32g ROM=128K RAM=16K + +# Large Gecko +efm32lg???f64 efm32lg ROM=64K RAM=32K +efm32lg???f128 efm32lg ROM=128K RAM=32K +efm32lg???f256 efm32lg ROM=256K RAM=32K + +# Giant Gecko +efm32gg???f512 efm32gg ROM=512K RAM=128K +efm32gg???f1024 efm32gg ROM=1024K RAM=128K + +# Wonder Gecko +efm32wg???f64 efm32gg ROM=64K RAM=32K +efm32wg???f128 efm32gg ROM=128K RAM=32K +efm32wg???f256 efm32gg ROM=256K RAM=32K + +################################################################################ +# the TI cortex M3 chips + +lm3s101 lm3sandstorm ROM=8K RAM=2K +lm3s102 lm3sandstorm ROM=8K RAM=2K + +lm3s300 lm3sandstorm ROM=16K RAM=4K +lm3s301 lm3sandstorm ROM=16K RAM=2K +lm3s308 lm3sandstorm ROM=16K RAM=4K +lm3s310 lm3sandstorm ROM=16K RAM=4K +lm3s315 lm3sandstorm ROM=16K RAM=4K +lm3s316 lm3sandstorm ROM=16K RAM=4K +lm3s317 lm3sandstorm ROM=16K RAM=4K +lm3s328 lm3sandstorm ROM=16K RAM=4K +lm3s600 lm3sandstorm ROM=32K RAM=8K +lm3s601 lm3sandstorm ROM=32K RAM=8K +lm3s608 lm3sandstorm ROM=32K RAM=8K +lm3s610 lm3sandstorm ROM=32K RAM=8K +lm3s611 lm3sandstorm ROM=32K RAM=8K +lm3s612 lm3sandstorm ROM=32K RAM=8K +lm3s613 lm3sandstorm ROM=32K RAM=8K +lm3s615 lm3sandstorm ROM=32K RAM=8K +lm3s617 lm3sandstorm ROM=32K RAM=8K +lm3s618 lm3sandstorm ROM=32K RAM=8K +lm3s628 lm3sandstorm ROM=32K RAM=8K +lm3s800 lm3sandstorm ROM=64K RAM=8K +lm3s801 lm3sandstorm ROM=64K RAM=8K +lm3s808 lm3sandstorm ROM=64K RAM=8K +lm3s811 lm3sandstorm ROM=64K RAM=8K +lm3s812 lm3sandstorm ROM=64K RAM=8K +lm3s815 lm3sandstorm ROM=64K RAM=8K +lm3s817 lm3sandstorm ROM=64K RAM=8K +lm3s818 lm3sandstorm ROM=64K RAM=8K +lm3s828 lm3sandstorm ROM=64K RAM=8K + +lm3s1110 lm3fury ROM=64K RAM=16K +lm3s1133 lm3fury ROM=64K RAM=16K +lm3s1138 lm3fury ROM=64K RAM=16K +lm3s1150 lm3fury ROM=64K RAM=16K +lm3s1162 lm3fury ROM=64K RAM=16K +lm3s1165 lm3fury ROM=64K RAM=16K +lm3s1332 lm3fury ROM=96K RAM=16K +lm3s1435 lm3fury ROM=96K RAM=32K +lm3s1439 lm3fury ROM=96K RAM=32K +lm3s1512 lm3fury ROM=96K RAM=64K +lm3s1538 lm3fury ROM=96K RAM=64K +lm3s1601 lm3fury ROM=128K RAM=32K +lm3s1607 lm3fury ROM=128K RAM=32K +lm3s1608 lm3fury ROM=128K RAM=32K +lm3s1620 lm3fury ROM=128K RAM=32K +lm3s8962 lm3fury ROM=256K RAM=64K + +################################################################################ +# the TI cortex R4F chips + +rm46l852* rm46l ROM=1280K RAM=192K + +################################################################################ +################################################################################ +################################################################################ +# the STM32 family groups + +stm32f3ccm stm32f3 CCM_OFF=0x10000000 +stm32f4ccm stm32f4 CCM_OFF=0x10000000 +stm32l1eep stm32l1 EEP_OFF=0x08080000 + +################################################################################ +# the SAM3 family groups +sam3xnfc sam3x NFCRAM=4K NFCRAM_OFF=0x20100000 + +################################################################################ +# the lpc family groups + + +lpc13u lpc13 USBRAM_OFF=0x20004000 + +lpc17[56]x lpc17 RAM1_OFF=0x2007C000 RAM2_OFF=0x20080000 +lpc17[78]x lpc17 RAM1_OFF=0x20000000 RAM2_OFF=0x20040000 + +################################################################################ +################################################################################ +################################################################################ +# the STM32 families + +stm32f0 stm32 ROM_OFF=0x08000000 RAM_OFF=0x20000000 -mcpu=cortex-m0 -mthumb -DSTM32F0 -lopencm3_stm32f0 -msoft-float +stm32f1 stm32 ROM_OFF=0x08000000 RAM_OFF=0x20000000 -mcpu=cortex-m3 -mthumb -DSTM32F1 -lopencm3_stm32f1 -msoft-float +stm32f2 stm32 ROM_OFF=0x08000000 RAM_OFF=0x20000000 -mcpu=cortex-m3 -mthumb -DSTM32F2 -lopencm3_stm32f2 -msoft-float +stm32f3 stm32 ROM_OFF=0x08000000 RAM_OFF=0x20000000 -mcpu=cortex-m4 -mthumb -DSTM32F3 -lopencm3_stm32f3 -mfloat-abi=hard -mfpu=fpv4-sp-d16 +stm32f4 stm32 ROM_OFF=0x08000000 RAM_OFF=0x20000000 -mcpu=cortex-m4 -mthumb -DSTM32F4 -lopencm3_stm32f4 -mfloat-abi=hard -mfpu=fpv4-sp-d16 +stm32l0 stm32 ROM_OFF=0x08000000 RAM_OFF=0x20000000 -mcpu=cortex-m0 -mthumb -DSTM32L0 -lopencm3_stm32l0 -msoft-float +stm32l1 stm32 ROM_OFF=0x08000000 RAM_OFF=0x20000000 -mcpu=cortex-m3 -mthumb -DSTM32L1 -lopencm3_stm32l1 -msoft-float +stm32w stm32 ROM_OFF=0x08000000 RAM_OFF=0x20000000 -mcpu=cortex-m3 -mthumb +stm32t stm32 ROM_OFF=0x08000000 RAM_OFF=0x20000000 -mcpu=cortex-m3 -mthumb + +################################################################################ +# the SAM3 families + +sam3a sam3 ROM_OFF=0x00080000 RAM_OFF=0x20000000 RAM1_OFF=0x20080000 +sam3n sam3 ROM_OFF=0x00400000 RAM_OFF=0x20000000 +sam3s sam3 ROM_OFF=0x00400000 RAM_OFF=0x20000000 +sam3u sam3 ROM_OFF=0x00080000 RAM_OFF=0x20000000 RAM1_OFF=0x20080000 NFCRAM=4K NFCRAM_OFF=0x20100000 +sam3x sam3 ROM_OFF=0x00080000 RAM_OFF=0x20000000 RAM1_OFF=0x20080000 + +################################################################################ +# the lpc families + +lpc13 lpc ROM_OFF=0x00000000 RAM_OFF=0x10000000 RAM1_OFF=0x20000000 +lpc17 lpc ROM_OFF=0x00000000 RAM_OFF=0x10000000 + +################################################################################ +# the efm32 Gecko families + +efm32zg efm32 ROM_OFF=0x00000000 RAM_OFF=0x20000000 RAM1_OFF=0x10000000 +efm32tg efm32 ROM_OFF=0x00000000 RAM_OFF=0x20000000 RAM1_OFF=0x10000000 +efm32g efm32 ROM_OFF=0x00000000 RAM_OFF=0x20000000 RAM1_OFF=0x10000000 +efm32lg efm32 ROM_OFF=0x00000000 RAM_OFF=0x20000000 RAM1_OFF=0x10000000 +efm32gg efm32 ROM_OFF=0x00000000 RAM_OFF=0x20000000 RAM1_OFF=0x10000000 +efm32wg efm32 ROM_OFF=0x00000000 RAM_OFF=0x20000000 RAM1_OFF=0x10000000 + +################################################################################ +# Cortex LM3 families + +lm3fury lm3 ROM_OFF=0x00000000 RAM_OFF=0x20000000 +lm3sandstorm lm3 ROM_OFF=0x00000000 RAM_OFF=0x20000000 + + +################################################################################ +# Cortex R4F families + +rm46l rm4 ROM_OFF=0x00000000 RAM_OFF=0x08000000 RAM1_OFF=0x08400000 + +################################################################################ +################################################################################ +################################################################################ +# the architectures + +stm32 END +sam3 END +lpc END +efm32 END +lm3 END +rm4 END + diff --git a/STM32/inc/ld/stm32f0.ld b/STM32/inc/ld/stm32f0.ld new file mode 100644 index 0000000..3fc2ccb --- /dev/null +++ b/STM32/inc/ld/stm32f0.ld @@ -0,0 +1,106 @@ +/* + * This file is part of the libopencm3 project. + * + * Copyright (C) 2009 Uwe Hermann + * + * This library is free software: you can redistribute it and/or modify + * it under the terms of the GNU Lesser General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This library is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public License + * along with this library. If not, see . + */ + +/* Generic linker script for STM32 targets using libopencm3. */ + +/* Memory regions must be defined in the ld script which includes this one. */ + +/* Enforce emmition of the vector table. */ +EXTERN (vector_table) + +/* Define the entry point of the output file. */ +ENTRY(reset_handler) + +/* Define sections. */ +SECTIONS +{ + .text : { + *(.vectors) /* Vector table */ + *(.text*) /* Program code */ + . = ALIGN(4); + *(.rodata*) /* Read-only data */ + . = ALIGN(4); + } >rom + + /* C++ Static constructors/destructors, also used for __attribute__ + * ((constructor)) and the likes */ + .preinit_array : { + . = ALIGN(4); + __preinit_array_start = .; + KEEP (*(.preinit_array)) + __preinit_array_end = .; + } >rom + .init_array : { + . = ALIGN(4); + __init_array_start = .; + KEEP (*(SORT(.init_array.*))) + KEEP (*(.init_array)) + __init_array_end = .; + } >rom + .fini_array : { + . = ALIGN(4); + __fini_array_start = .; + KEEP (*(.fini_array)) + KEEP (*(SORT(.fini_array.*))) + __fini_array_end = .; + } >rom + + /* + * Another section used by C++ stuff, appears when using newlib with + * 64bit (long long) printf support + */ + .ARM.extab : { + *(.ARM.extab*) + } >rom + .ARM.exidx : { + __exidx_start = .; + *(.ARM.exidx*) + __exidx_end = .; + } >rom + + . = ALIGN(4); + _etext = .; + + .data : { + _data = .; + *(.data*) /* Read-write initialized data */ + . = ALIGN(4); + _edata = .; + } >ram AT >rom + _data_loadaddr = LOADADDR(.data); + + .bss : { + *(.bss*) /* Read-write zero initialized data */ + *(COMMON) + . = ALIGN(4); + _ebss = .; + } >ram + + /* + * The .eh_frame section appears to be used for C++ exception handling. + * You may need to fix this if you're using C++. + */ + /DISCARD/ : { *(.eh_frame) } + + . = ALIGN(4); + end = .; +} + +PROVIDE(_stack = ORIGIN(ram) + LENGTH(ram)); + diff --git a/STM32/inc/startup/vector.c b/STM32/inc/startup/vector.c new file mode 100644 index 0000000..acba5c2 --- /dev/null +++ b/STM32/inc/startup/vector.c @@ -0,0 +1,186 @@ +/* + * This file is part of the libopencm3 project. + * + * Copyright (C) 2010 Piotr Esden-Tempski , + * Copyright (C) 2012 chrysn + * + * This library is free software: you can redistribute it and/or modify + * it under the terms of the GNU Lesser General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This library is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public License + * along with this library. If not, see . + */ +#include "stm32f0xx.h" + +/* Initialization template for the interrupt vector table. This definition is + * used by the startup code generator (vector.c) to set the initial values for + * the interrupt handling routines to the chip family specific _isr weak + * symbols. */ +#define NVIC_IRQ_COUNT 32 + +#define F0_IRQ_HANDLERS \ + wwdg_isr, \ + pvd_isr, \ + rtc_isr, \ + flash_isr, \ + rcc_isr, \ + exti0_1_isr, \ + exti2_3_isr, \ + exti4_15_isr, \ + tsc_isr, \ + dma1_channel1_isr, \ + dma1_channel2_3_isr, \ + dma1_channel4_5_isr, \ + adc_comp_isr, \ + tim1_brk_up_trg_com_isr, \ + tim1_cc_isr, \ + tim2_isr, \ + tim3_isr, \ + tim6_dac_isr, \ + tim7_isr, \ + tim14_isr, \ + tim15_isr, \ + tim16_isr, \ + tim17_isr, \ + i2c1_isr, \ + i2c2_isr, \ + spi1_isr, \ + spi2_isr, \ + usart1_isr, \ + usart2_isr, \ + usart3_4_isr, \ + cec_can_isr, \ + usb_isr + +typedef void (*vector_table_entry_t)(void); +typedef void (*funcp_t) (void); + +typedef struct { + unsigned int *initial_sp_value; /**< Initial stack pointer value. */ + vector_table_entry_t reset; + vector_table_entry_t nmi; + vector_table_entry_t hard_fault; + vector_table_entry_t memory_manage_fault; /* not in CM0 */ + vector_table_entry_t bus_fault; /* not in CM0 */ + vector_table_entry_t usage_fault; /* not in CM0 */ + vector_table_entry_t reserved_x001c[4]; + vector_table_entry_t sv_call; + vector_table_entry_t debug_monitor; /* not in CM0 */ + vector_table_entry_t reserved_x0034; + vector_table_entry_t pend_sv; + vector_table_entry_t systick; + vector_table_entry_t irq[NVIC_IRQ_COUNT]; +} vector_table_t; + +/* Symbols exported by the linker script(s): */ +extern unsigned _data_loadaddr, _data, _edata, _ebss, _stack; +extern funcp_t __preinit_array_start, __preinit_array_end; +extern funcp_t __init_array_start, __init_array_end; +extern funcp_t __fini_array_start, __fini_array_end; + +void main(void); +void blocking_handler(void); +void null_handler(void); + +__attribute__ ((section(".vectors"))) +vector_table_t vector_table = { + .initial_sp_value = &_stack, + .reset = reset_handler, + .nmi = nmi_handler, + .hard_fault = hard_fault_handler, + .sv_call = sv_call_handler, + .pend_sv = pend_sv_handler, + .systick = sys_tick_handler, + .irq = { + F0_IRQ_HANDLERS + } +}; + +void WEAK __attribute__ ((naked)) reset_handler(void) +{ + volatile unsigned *src, *dest; + funcp_t *fp; + + for (src = &_data_loadaddr, dest = &_data; + dest < &_edata; + src++, dest++) { + *dest = *src; + } + + while (dest < &_ebss) { + *dest++ = 0; + } + + /* Constructors. */ + for (fp = &__preinit_array_start; fp < &__preinit_array_end; fp++) { + (*fp)(); + } + for (fp = &__init_array_start; fp < &__init_array_end; fp++) { + (*fp)(); + } + + /* Call the application's entry point. */ + main(); + + /* Destructors. */ + for (fp = &__fini_array_start; fp < &__fini_array_end; fp++) { + (*fp)(); + } + +} + +void blocking_handler(void) +{ + while (1); +} + +void null_handler(void) +{ + /* Do nothing. */ +} + +#pragma weak nmi_handler = null_handler +#pragma weak hard_fault_handler = blocking_handler +#pragma weak sv_call_handler = null_handler +#pragma weak pend_sv_handler = null_handler +#pragma weak sys_tick_handler = null_handler + +#pragma weak wwdg_isr = blocking_handler +#pragma weak pvd_isr = blocking_handler +#pragma weak rtc_isr = blocking_handler +#pragma weak flash_isr = blocking_handler +#pragma weak rcc_isr = blocking_handler +#pragma weak exti0_1_isr = blocking_handler +#pragma weak exti2_3_isr = blocking_handler +#pragma weak exti4_15_isr = blocking_handler +#pragma weak tsc_isr = blocking_handler +#pragma weak dma1_channel1_isr = blocking_handler +#pragma weak dma1_channel2_3_isr = blocking_handler +#pragma weak dma1_channel4_5_isr = blocking_handler +#pragma weak adc_comp_isr = blocking_handler +#pragma weak tim1_brk_up_trg_com_isr = blocking_handler +#pragma weak tim1_cc_isr = blocking_handler +#pragma weak tim2_isr = blocking_handler +#pragma weak tim3_isr = blocking_handler +#pragma weak tim6_dac_isr = blocking_handler +#pragma weak tim7_isr = blocking_handler +#pragma weak tim14_isr = blocking_handler +#pragma weak tim15_isr = blocking_handler +#pragma weak tim16_isr = blocking_handler +#pragma weak tim17_isr = blocking_handler +#pragma weak i2c1_isr = blocking_handler +#pragma weak i2c2_isr = blocking_handler +#pragma weak spi1_isr = blocking_handler +#pragma weak spi2_isr = blocking_handler +#pragma weak usart1_isr = blocking_handler +#pragma weak usart2_isr = blocking_handler +#pragma weak usart3_4_isr = blocking_handler +#pragma weak cec_can_isr = blocking_handler +#pragma weak usb_isr = blocking_handler diff --git a/STM32/inc/stm32f030.c.tags b/STM32/inc/stm32f030.c.tags new file mode 100644 index 0000000..ef55f4c --- /dev/null +++ b/STM32/inc/stm32f030.c.tags @@ -0,0 +1,2698 @@ +# format=tagmanager +ADCÌ65536Ö0 +ADC1Ì65536Ö0 +ADC1_BASEÌ65536Ö0 +ADC1_COMP_IRQHandlerÌ65536Ö0 +ADC1_COMP_IRQnÌ65536Ö0 +ADC_BASEÌ65536Ö0 +ADC_CCR_TSENÌ65536Ö0 +ADC_CCR_VBATENÌ65536Ö0 +ADC_CCR_VREFENÌ65536Ö0 +ADC_CFGR1_ALIGNÌ65536Ö0 +ADC_CFGR1_AUTDLYÌ65536Ö0 +ADC_CFGR1_AUTOFFÌ65536Ö0 +ADC_CFGR1_AWDCHÌ65536Ö0 +ADC_CFGR1_AWDCH_0Ì65536Ö0 +ADC_CFGR1_AWDCH_1Ì65536Ö0 +ADC_CFGR1_AWDCH_2Ì65536Ö0 +ADC_CFGR1_AWDCH_3Ì65536Ö0 +ADC_CFGR1_AWDCH_4Ì65536Ö0 +ADC_CFGR1_AWDENÌ65536Ö0 +ADC_CFGR1_AWDSGLÌ65536Ö0 +ADC_CFGR1_CONTÌ65536Ö0 +ADC_CFGR1_DISCENÌ65536Ö0 +ADC_CFGR1_DMACFGÌ65536Ö0 +ADC_CFGR1_DMAENÌ65536Ö0 +ADC_CFGR1_EXTENÌ65536Ö0 +ADC_CFGR1_EXTEN_0Ì65536Ö0 +ADC_CFGR1_EXTEN_1Ì65536Ö0 +ADC_CFGR1_EXTSELÌ65536Ö0 +ADC_CFGR1_EXTSEL_0Ì65536Ö0 +ADC_CFGR1_EXTSEL_1Ì65536Ö0 +ADC_CFGR1_EXTSEL_2Ì65536Ö0 +ADC_CFGR1_OVRMODÌ65536Ö0 +ADC_CFGR1_RESÌ65536Ö0 +ADC_CFGR1_RES_0Ì65536Ö0 +ADC_CFGR1_RES_1Ì65536Ö0 +ADC_CFGR1_SCANDIRÌ65536Ö0 +ADC_CFGR1_WAITÌ65536Ö0 +ADC_CFGR2_CKMODEÌ65536Ö0 +ADC_CFGR2_CKMODE_0Ì65536Ö0 +ADC_CFGR2_CKMODE_1Ì65536Ö0 +ADC_CFGR2_JITOFFDIV2Ì65536Ö0 +ADC_CFGR2_JITOFFDIV4Ì65536Ö0 +ADC_CHSELR_CHSEL0Ì65536Ö0 +ADC_CHSELR_CHSEL1Ì65536Ö0 +ADC_CHSELR_CHSEL10Ì65536Ö0 +ADC_CHSELR_CHSEL11Ì65536Ö0 +ADC_CHSELR_CHSEL12Ì65536Ö0 +ADC_CHSELR_CHSEL13Ì65536Ö0 +ADC_CHSELR_CHSEL14Ì65536Ö0 +ADC_CHSELR_CHSEL15Ì65536Ö0 +ADC_CHSELR_CHSEL16Ì65536Ö0 +ADC_CHSELR_CHSEL17Ì65536Ö0 +ADC_CHSELR_CHSEL18Ì65536Ö0 +ADC_CHSELR_CHSEL2Ì65536Ö0 +ADC_CHSELR_CHSEL3Ì65536Ö0 +ADC_CHSELR_CHSEL4Ì65536Ö0 +ADC_CHSELR_CHSEL5Ì65536Ö0 +ADC_CHSELR_CHSEL6Ì65536Ö0 +ADC_CHSELR_CHSEL7Ì65536Ö0 +ADC_CHSELR_CHSEL8Ì65536Ö0 +ADC_CHSELR_CHSEL9Ì65536Ö0 +ADC_CR_ADCALÌ65536Ö0 +ADC_CR_ADDISÌ65536Ö0 +ADC_CR_ADENÌ65536Ö0 +ADC_CR_ADSTARTÌ65536Ö0 +ADC_CR_ADSTPÌ65536Ö0 +ADC_DR_DATAÌ65536Ö0 +ADC_HTR_HTÌ65536Ö0 +ADC_IER_ADRDYIEÌ65536Ö0 +ADC_IER_AWDIEÌ65536Ö0 +ADC_IER_EOCIEÌ65536Ö0 +ADC_IER_EOSEQIEÌ65536Ö0 +ADC_IER_EOSIEÌ65536Ö0 +ADC_IER_EOSMPIEÌ65536Ö0 +ADC_IER_OVRIEÌ65536Ö0 +ADC_ISR_ADRDYÌ65536Ö0 +ADC_ISR_AWDÌ65536Ö0 +ADC_ISR_EOCÌ65536Ö0 +ADC_ISR_EOSÌ65536Ö0 +ADC_ISR_EOSEQÌ65536Ö0 +ADC_ISR_EOSMPÌ65536Ö0 +ADC_ISR_OVRÌ65536Ö0 +ADC_LTR_LTÌ65536Ö0 +ADC_SMPR1_SMPRÌ65536Ö0 +ADC_SMPR1_SMPR_0Ì65536Ö0 +ADC_SMPR1_SMPR_1Ì65536Ö0 +ADC_SMPR1_SMPR_2Ì65536Ö0 +ADC_SMPR_SMPÌ65536Ö0 +ADC_SMPR_SMP_0Ì65536Ö0 +ADC_SMPR_SMP_1Ì65536Ö0 +ADC_SMPR_SMP_2Ì65536Ö0 +ADC_TR_HTÌ65536Ö0 +ADC_TR_LTÌ65536Ö0 +AHB2PERIPH_BASEÌ65536Ö0 +AHBPERIPH_BASEÌ65536Ö0 +APBPERIPH_BASEÌ65536Ö0 +CLEAR_BITÌ131072Í(REG,BIT)Ö0 +CLEAR_REGÌ131072Í(REG)Ö0 +CRCÌ65536Ö0 +CRC_BASEÌ65536Ö0 +CRC_CR_RESETÌ65536Ö0 +CRC_CR_REV_INÌ65536Ö0 +CRC_CR_REV_IN_0Ì65536Ö0 +CRC_CR_REV_IN_1Ì65536Ö0 +CRC_CR_REV_OUTÌ65536Ö0 +CRC_DR_DRÌ65536Ö0 +CRC_IDR_IDRÌ65536Ö0 +CRC_INIT_INITÌ65536Ö0 +DBGMCUÌ65536Ö0 +DBGMCU_APB1_FZ_DBG_I2C1_SMBUS_TIMEOUTÌ65536Ö0 +DBGMCU_APB1_FZ_DBG_IWDG_STOPÌ65536Ö0 +DBGMCU_APB1_FZ_DBG_RTC_STOPÌ65536Ö0 +DBGMCU_APB1_FZ_DBG_TIM14_STOPÌ65536Ö0 +DBGMCU_APB1_FZ_DBG_TIM3_STOPÌ65536Ö0 +DBGMCU_APB1_FZ_DBG_WWDG_STOPÌ65536Ö0 +DBGMCU_APB2_FZ_DBG_TIM16_STOPÌ65536Ö0 +DBGMCU_APB2_FZ_DBG_TIM17_STOPÌ65536Ö0 +DBGMCU_APB2_FZ_DBG_TIM1_STOPÌ65536Ö0 +DBGMCU_BASEÌ65536Ö0 +DBGMCU_CR_DBG_STANDBYÌ65536Ö0 +DBGMCU_CR_DBG_STOPÌ65536Ö0 +DBGMCU_IDCODE_DEV_IDÌ65536Ö0 +DBGMCU_IDCODE_REV_IDÌ65536Ö0 +DBGMCU_IDCODE_REV_ID_0Ì65536Ö0 +DBGMCU_IDCODE_REV_ID_1Ì65536Ö0 +DBGMCU_IDCODE_REV_ID_10Ì65536Ö0 +DBGMCU_IDCODE_REV_ID_11Ì65536Ö0 +DBGMCU_IDCODE_REV_ID_12Ì65536Ö0 +DBGMCU_IDCODE_REV_ID_13Ì65536Ö0 +DBGMCU_IDCODE_REV_ID_14Ì65536Ö0 +DBGMCU_IDCODE_REV_ID_15Ì65536Ö0 +DBGMCU_IDCODE_REV_ID_2Ì65536Ö0 +DBGMCU_IDCODE_REV_ID_3Ì65536Ö0 +DBGMCU_IDCODE_REV_ID_4Ì65536Ö0 +DBGMCU_IDCODE_REV_ID_5Ì65536Ö0 +DBGMCU_IDCODE_REV_ID_6Ì65536Ö0 +DBGMCU_IDCODE_REV_ID_7Ì65536Ö0 +DBGMCU_IDCODE_REV_ID_8Ì65536Ö0 +DBGMCU_IDCODE_REV_ID_9Ì65536Ö0 +DMA1Ì65536Ö0 +DMA1_BASEÌ65536Ö0 +DMA1_Channel1Ì65536Ö0 +DMA1_Channel1_BASEÌ65536Ö0 +DMA1_Channel2Ì65536Ö0 +DMA1_Channel2_BASEÌ65536Ö0 +DMA1_Channel3Ì65536Ö0 +DMA1_Channel3_BASEÌ65536Ö0 +DMA1_Channel4Ì65536Ö0 +DMA1_Channel4_5_6_7_IRQHandlerÌ65536Ö0 +DMA1_Channel4_5_6_7_IRQnÌ65536Ö0 +DMA1_Channel4_BASEÌ65536Ö0 +DMA1_Channel5Ì65536Ö0 +DMA1_Channel5_BASEÌ65536Ö0 +DMA_CCR_CIRCÌ65536Ö0 +DMA_CCR_DIRÌ65536Ö0 +DMA_CCR_ENÌ65536Ö0 +DMA_CCR_HTIEÌ65536Ö0 +DMA_CCR_MEM2MEMÌ65536Ö0 +DMA_CCR_MINCÌ65536Ö0 +DMA_CCR_MSIZEÌ65536Ö0 +DMA_CCR_MSIZE_0Ì65536Ö0 +DMA_CCR_MSIZE_1Ì65536Ö0 +DMA_CCR_PINCÌ65536Ö0 +DMA_CCR_PLÌ65536Ö0 +DMA_CCR_PL_0Ì65536Ö0 +DMA_CCR_PL_1Ì65536Ö0 +DMA_CCR_PSIZEÌ65536Ö0 +DMA_CCR_PSIZE_0Ì65536Ö0 +DMA_CCR_PSIZE_1Ì65536Ö0 +DMA_CCR_TCIEÌ65536Ö0 +DMA_CCR_TEIEÌ65536Ö0 +DMA_CMAR_MAÌ65536Ö0 +DMA_CNDTR_NDTÌ65536Ö0 +DMA_CPAR_PAÌ65536Ö0 +DMA_IFCR_CGIF1Ì65536Ö0 +DMA_IFCR_CGIF2Ì65536Ö0 +DMA_IFCR_CGIF3Ì65536Ö0 +DMA_IFCR_CGIF4Ì65536Ö0 +DMA_IFCR_CGIF5Ì65536Ö0 +DMA_IFCR_CHTIF1Ì65536Ö0 +DMA_IFCR_CHTIF2Ì65536Ö0 +DMA_IFCR_CHTIF3Ì65536Ö0 +DMA_IFCR_CHTIF4Ì65536Ö0 +DMA_IFCR_CHTIF5Ì65536Ö0 +DMA_IFCR_CTCIF1Ì65536Ö0 +DMA_IFCR_CTCIF2Ì65536Ö0 +DMA_IFCR_CTCIF3Ì65536Ö0 +DMA_IFCR_CTCIF4Ì65536Ö0 +DMA_IFCR_CTCIF5Ì65536Ö0 +DMA_IFCR_CTEIF1Ì65536Ö0 +DMA_IFCR_CTEIF2Ì65536Ö0 +DMA_IFCR_CTEIF3Ì65536Ö0 +DMA_IFCR_CTEIF4Ì65536Ö0 +DMA_IFCR_CTEIF5Ì65536Ö0 +DMA_ISR_GIF1Ì65536Ö0 +DMA_ISR_GIF2Ì65536Ö0 +DMA_ISR_GIF3Ì65536Ö0 +DMA_ISR_GIF4Ì65536Ö0 +DMA_ISR_GIF5Ì65536Ö0 +DMA_ISR_HTIF1Ì65536Ö0 +DMA_ISR_HTIF2Ì65536Ö0 +DMA_ISR_HTIF3Ì65536Ö0 +DMA_ISR_HTIF4Ì65536Ö0 +DMA_ISR_HTIF5Ì65536Ö0 +DMA_ISR_TCIF1Ì65536Ö0 +DMA_ISR_TCIF2Ì65536Ö0 +DMA_ISR_TCIF3Ì65536Ö0 +DMA_ISR_TCIF4Ì65536Ö0 +DMA_ISR_TCIF5Ì65536Ö0 +DMA_ISR_TEIF1Ì65536Ö0 +DMA_ISR_TEIF2Ì65536Ö0 +DMA_ISR_TEIF3Ì65536Ö0 +DMA_ISR_TEIF4Ì65536Ö0 +DMA_ISR_TEIF5Ì65536Ö0 +EXTIÌ65536Ö0 +EXTI_BASEÌ65536Ö0 +EXTI_EMR_MR0Ì65536Ö0 +EXTI_EMR_MR1Ì65536Ö0 +EXTI_EMR_MR10Ì65536Ö0 +EXTI_EMR_MR11Ì65536Ö0 +EXTI_EMR_MR12Ì65536Ö0 +EXTI_EMR_MR13Ì65536Ö0 +EXTI_EMR_MR14Ì65536Ö0 +EXTI_EMR_MR15Ì65536Ö0 +EXTI_EMR_MR16Ì65536Ö0 +EXTI_EMR_MR17Ì65536Ö0 +EXTI_EMR_MR19Ì65536Ö0 +EXTI_EMR_MR2Ì65536Ö0 +EXTI_EMR_MR21Ì65536Ö0 +EXTI_EMR_MR22Ì65536Ö0 +EXTI_EMR_MR23Ì65536Ö0 +EXTI_EMR_MR25Ì65536Ö0 +EXTI_EMR_MR27Ì65536Ö0 +EXTI_EMR_MR3Ì65536Ö0 +EXTI_EMR_MR4Ì65536Ö0 +EXTI_EMR_MR5Ì65536Ö0 +EXTI_EMR_MR6Ì65536Ö0 +EXTI_EMR_MR7Ì65536Ö0 +EXTI_EMR_MR8Ì65536Ö0 +EXTI_EMR_MR9Ì65536Ö0 +EXTI_FTSR_TR0Ì65536Ö0 +EXTI_FTSR_TR1Ì65536Ö0 +EXTI_FTSR_TR10Ì65536Ö0 +EXTI_FTSR_TR11Ì65536Ö0 +EXTI_FTSR_TR12Ì65536Ö0 +EXTI_FTSR_TR13Ì65536Ö0 +EXTI_FTSR_TR14Ì65536Ö0 +EXTI_FTSR_TR15Ì65536Ö0 +EXTI_FTSR_TR16Ì65536Ö0 +EXTI_FTSR_TR17Ì65536Ö0 +EXTI_FTSR_TR19Ì65536Ö0 +EXTI_FTSR_TR2Ì65536Ö0 +EXTI_FTSR_TR3Ì65536Ö0 +EXTI_FTSR_TR4Ì65536Ö0 +EXTI_FTSR_TR5Ì65536Ö0 +EXTI_FTSR_TR6Ì65536Ö0 +EXTI_FTSR_TR7Ì65536Ö0 +EXTI_FTSR_TR8Ì65536Ö0 +EXTI_FTSR_TR9Ì65536Ö0 +EXTI_IMR_MR0Ì65536Ö0 +EXTI_IMR_MR1Ì65536Ö0 +EXTI_IMR_MR10Ì65536Ö0 +EXTI_IMR_MR11Ì65536Ö0 +EXTI_IMR_MR12Ì65536Ö0 +EXTI_IMR_MR13Ì65536Ö0 +EXTI_IMR_MR14Ì65536Ö0 +EXTI_IMR_MR15Ì65536Ö0 +EXTI_IMR_MR16Ì65536Ö0 +EXTI_IMR_MR17Ì65536Ö0 +EXTI_IMR_MR19Ì65536Ö0 +EXTI_IMR_MR2Ì65536Ö0 +EXTI_IMR_MR21Ì65536Ö0 +EXTI_IMR_MR22Ì65536Ö0 +EXTI_IMR_MR23Ì65536Ö0 +EXTI_IMR_MR25Ì65536Ö0 +EXTI_IMR_MR27Ì65536Ö0 +EXTI_IMR_MR3Ì65536Ö0 +EXTI_IMR_MR4Ì65536Ö0 +EXTI_IMR_MR5Ì65536Ö0 +EXTI_IMR_MR6Ì65536Ö0 +EXTI_IMR_MR7Ì65536Ö0 +EXTI_IMR_MR8Ì65536Ö0 +EXTI_IMR_MR9Ì65536Ö0 +EXTI_PR_PR0Ì65536Ö0 +EXTI_PR_PR1Ì65536Ö0 +EXTI_PR_PR10Ì65536Ö0 +EXTI_PR_PR11Ì65536Ö0 +EXTI_PR_PR12Ì65536Ö0 +EXTI_PR_PR13Ì65536Ö0 +EXTI_PR_PR14Ì65536Ö0 +EXTI_PR_PR15Ì65536Ö0 +EXTI_PR_PR16Ì65536Ö0 +EXTI_PR_PR17Ì65536Ö0 +EXTI_PR_PR19Ì65536Ö0 +EXTI_PR_PR2Ì65536Ö0 +EXTI_PR_PR3Ì65536Ö0 +EXTI_PR_PR4Ì65536Ö0 +EXTI_PR_PR5Ì65536Ö0 +EXTI_PR_PR6Ì65536Ö0 +EXTI_PR_PR7Ì65536Ö0 +EXTI_PR_PR8Ì65536Ö0 +EXTI_PR_PR9Ì65536Ö0 +EXTI_RTSR_TR0Ì65536Ö0 +EXTI_RTSR_TR1Ì65536Ö0 +EXTI_RTSR_TR10Ì65536Ö0 +EXTI_RTSR_TR11Ì65536Ö0 +EXTI_RTSR_TR12Ì65536Ö0 +EXTI_RTSR_TR13Ì65536Ö0 +EXTI_RTSR_TR14Ì65536Ö0 +EXTI_RTSR_TR15Ì65536Ö0 +EXTI_RTSR_TR16Ì65536Ö0 +EXTI_RTSR_TR17Ì65536Ö0 +EXTI_RTSR_TR19Ì65536Ö0 +EXTI_RTSR_TR2Ì65536Ö0 +EXTI_RTSR_TR3Ì65536Ö0 +EXTI_RTSR_TR4Ì65536Ö0 +EXTI_RTSR_TR5Ì65536Ö0 +EXTI_RTSR_TR6Ì65536Ö0 +EXTI_RTSR_TR7Ì65536Ö0 +EXTI_RTSR_TR8Ì65536Ö0 +EXTI_RTSR_TR9Ì65536Ö0 +EXTI_SWIER_SWIER0Ì65536Ö0 +EXTI_SWIER_SWIER1Ì65536Ö0 +EXTI_SWIER_SWIER10Ì65536Ö0 +EXTI_SWIER_SWIER11Ì65536Ö0 +EXTI_SWIER_SWIER12Ì65536Ö0 +EXTI_SWIER_SWIER13Ì65536Ö0 +EXTI_SWIER_SWIER14Ì65536Ö0 +EXTI_SWIER_SWIER15Ì65536Ö0 +EXTI_SWIER_SWIER16Ì65536Ö0 +EXTI_SWIER_SWIER17Ì65536Ö0 +EXTI_SWIER_SWIER19Ì65536Ö0 +EXTI_SWIER_SWIER2Ì65536Ö0 +EXTI_SWIER_SWIER3Ì65536Ö0 +EXTI_SWIER_SWIER4Ì65536Ö0 +EXTI_SWIER_SWIER5Ì65536Ö0 +EXTI_SWIER_SWIER6Ì65536Ö0 +EXTI_SWIER_SWIER7Ì65536Ö0 +EXTI_SWIER_SWIER8Ì65536Ö0 +EXTI_SWIER_SWIER9Ì65536Ö0 +F0_IRQ_HANDLERSÌ65536Ö0 +FLASHÌ65536Ö0 +FLASH_ACR_LATENCYÌ65536Ö0 +FLASH_ACR_PRFTBEÌ65536Ö0 +FLASH_ACR_PRFTBSÌ65536Ö0 +FLASH_AR_FARÌ65536Ö0 +FLASH_BASEÌ65536Ö0 +FLASH_CR_EOPIEÌ65536Ö0 +FLASH_CR_ERRIEÌ65536Ö0 +FLASH_CR_LOCKÌ65536Ö0 +FLASH_CR_MERÌ65536Ö0 +FLASH_CR_OBL_LAUNCHÌ65536Ö0 +FLASH_CR_OPTERÌ65536Ö0 +FLASH_CR_OPTPGÌ65536Ö0 +FLASH_CR_OPTWREÌ65536Ö0 +FLASH_CR_PERÌ65536Ö0 +FLASH_CR_PGÌ65536Ö0 +FLASH_CR_STRTÌ65536Ö0 +FLASH_FKEY1Ì65536Ö0 +FLASH_FKEY2Ì65536Ö0 +FLASH_KEYR_FKEYRÌ65536Ö0 +FLASH_OBR_BOOT1Ì65536Ö0 +FLASH_OBR_IWDG_SWÌ65536Ö0 +FLASH_OBR_OPTERRÌ65536Ö0 +FLASH_OBR_RDPRT1Ì65536Ö0 +FLASH_OBR_RDPRT2Ì65536Ö0 +FLASH_OBR_USERÌ65536Ö0 +FLASH_OBR_VDDA_ANALOGÌ65536Ö0 +FLASH_OBR_VDDA_MONITORÌ65536Ö0 +FLASH_OBR_nBOOT1Ì65536Ö0 +FLASH_OBR_nRST_STDBYÌ65536Ö0 +FLASH_OBR_nRST_STOPÌ65536Ö0 +FLASH_OPTKEY1Ì65536Ö0 +FLASH_OPTKEY2Ì65536Ö0 +FLASH_OPTKEYR_OPTKEYRÌ65536Ö0 +FLASH_R_BASEÌ65536Ö0 +FLASH_SR_BSYÌ65536Ö0 +FLASH_SR_EOPÌ65536Ö0 +FLASH_SR_PGERRÌ65536Ö0 +FLASH_SR_WRPERRÌ65536Ö0 +FLASH_SR_WRPRTERRÌ65536Ö0 +FLASH_WRPR_WRPÌ65536Ö0 +GPIOAÌ65536Ö0 +GPIOA_BASEÌ65536Ö0 +GPIOBÌ65536Ö0 +GPIOB_BASEÌ65536Ö0 +GPIOCÌ65536Ö0 +GPIOC_BASEÌ65536Ö0 +GPIODÌ65536Ö0 +GPIOD_BASEÌ65536Ö0 +GPIOFÌ65536Ö0 +GPIOF_BASEÌ65536Ö0 +GPIO_AFRH_AFRH0Ì65536Ö0 +GPIO_AFRH_AFRH1Ì65536Ö0 +GPIO_AFRH_AFRH2Ì65536Ö0 +GPIO_AFRH_AFRH3Ì65536Ö0 +GPIO_AFRH_AFRH4Ì65536Ö0 +GPIO_AFRH_AFRH5Ì65536Ö0 +GPIO_AFRH_AFRH6Ì65536Ö0 +GPIO_AFRH_AFRH7Ì65536Ö0 +GPIO_AFRL_AFRL0Ì65536Ö0 +GPIO_AFRL_AFRL1Ì65536Ö0 +GPIO_AFRL_AFRL2Ì65536Ö0 +GPIO_AFRL_AFRL3Ì65536Ö0 +GPIO_AFRL_AFRL4Ì65536Ö0 +GPIO_AFRL_AFRL5Ì65536Ö0 +GPIO_AFRL_AFRL6Ì65536Ö0 +GPIO_AFRL_AFRL7Ì65536Ö0 +GPIO_BRR_BR_0Ì65536Ö0 +GPIO_BRR_BR_1Ì65536Ö0 +GPIO_BRR_BR_10Ì65536Ö0 +GPIO_BRR_BR_11Ì65536Ö0 +GPIO_BRR_BR_12Ì65536Ö0 +GPIO_BRR_BR_13Ì65536Ö0 +GPIO_BRR_BR_14Ì65536Ö0 +GPIO_BRR_BR_15Ì65536Ö0 +GPIO_BRR_BR_2Ì65536Ö0 +GPIO_BRR_BR_3Ì65536Ö0 +GPIO_BRR_BR_4Ì65536Ö0 +GPIO_BRR_BR_5Ì65536Ö0 +GPIO_BRR_BR_6Ì65536Ö0 +GPIO_BRR_BR_7Ì65536Ö0 +GPIO_BRR_BR_8Ì65536Ö0 +GPIO_BRR_BR_9Ì65536Ö0 +GPIO_BSRR_BR_0Ì65536Ö0 +GPIO_BSRR_BR_1Ì65536Ö0 +GPIO_BSRR_BR_10Ì65536Ö0 +GPIO_BSRR_BR_11Ì65536Ö0 +GPIO_BSRR_BR_12Ì65536Ö0 +GPIO_BSRR_BR_13Ì65536Ö0 +GPIO_BSRR_BR_14Ì65536Ö0 +GPIO_BSRR_BR_15Ì65536Ö0 +GPIO_BSRR_BR_2Ì65536Ö0 +GPIO_BSRR_BR_3Ì65536Ö0 +GPIO_BSRR_BR_4Ì65536Ö0 +GPIO_BSRR_BR_5Ì65536Ö0 +GPIO_BSRR_BR_6Ì65536Ö0 +GPIO_BSRR_BR_7Ì65536Ö0 +GPIO_BSRR_BR_8Ì65536Ö0 +GPIO_BSRR_BR_9Ì65536Ö0 +GPIO_BSRR_BS_0Ì65536Ö0 +GPIO_BSRR_BS_1Ì65536Ö0 +GPIO_BSRR_BS_10Ì65536Ö0 +GPIO_BSRR_BS_11Ì65536Ö0 +GPIO_BSRR_BS_12Ì65536Ö0 +GPIO_BSRR_BS_13Ì65536Ö0 +GPIO_BSRR_BS_14Ì65536Ö0 +GPIO_BSRR_BS_15Ì65536Ö0 +GPIO_BSRR_BS_2Ì65536Ö0 +GPIO_BSRR_BS_3Ì65536Ö0 +GPIO_BSRR_BS_4Ì65536Ö0 +GPIO_BSRR_BS_5Ì65536Ö0 +GPIO_BSRR_BS_6Ì65536Ö0 +GPIO_BSRR_BS_7Ì65536Ö0 +GPIO_BSRR_BS_8Ì65536Ö0 +GPIO_BSRR_BS_9Ì65536Ö0 +GPIO_IDR_0Ì65536Ö0 +GPIO_IDR_1Ì65536Ö0 +GPIO_IDR_10Ì65536Ö0 +GPIO_IDR_11Ì65536Ö0 +GPIO_IDR_12Ì65536Ö0 +GPIO_IDR_13Ì65536Ö0 +GPIO_IDR_14Ì65536Ö0 +GPIO_IDR_15Ì65536Ö0 +GPIO_IDR_2Ì65536Ö0 +GPIO_IDR_3Ì65536Ö0 +GPIO_IDR_4Ì65536Ö0 +GPIO_IDR_5Ì65536Ö0 +GPIO_IDR_6Ì65536Ö0 +GPIO_IDR_7Ì65536Ö0 +GPIO_IDR_8Ì65536Ö0 +GPIO_IDR_9Ì65536Ö0 +GPIO_LCKR_LCK0Ì65536Ö0 +GPIO_LCKR_LCK1Ì65536Ö0 +GPIO_LCKR_LCK10Ì65536Ö0 +GPIO_LCKR_LCK11Ì65536Ö0 +GPIO_LCKR_LCK12Ì65536Ö0 +GPIO_LCKR_LCK13Ì65536Ö0 +GPIO_LCKR_LCK14Ì65536Ö0 +GPIO_LCKR_LCK15Ì65536Ö0 +GPIO_LCKR_LCK2Ì65536Ö0 +GPIO_LCKR_LCK3Ì65536Ö0 +GPIO_LCKR_LCK4Ì65536Ö0 +GPIO_LCKR_LCK5Ì65536Ö0 +GPIO_LCKR_LCK6Ì65536Ö0 +GPIO_LCKR_LCK7Ì65536Ö0 +GPIO_LCKR_LCK8Ì65536Ö0 +GPIO_LCKR_LCK9Ì65536Ö0 +GPIO_LCKR_LCKKÌ65536Ö0 +GPIO_MODER_MODER0Ì65536Ö0 +GPIO_MODER_MODER0_0Ì65536Ö0 +GPIO_MODER_MODER0_1Ì65536Ö0 +GPIO_MODER_MODER0_AFÌ65536Ö0 +GPIO_MODER_MODER0_AIÌ65536Ö0 +GPIO_MODER_MODER0_OÌ65536Ö0 +GPIO_MODER_MODER1Ì65536Ö0 +GPIO_MODER_MODER10Ì65536Ö0 +GPIO_MODER_MODER10_0Ì65536Ö0 +GPIO_MODER_MODER10_1Ì65536Ö0 +GPIO_MODER_MODER10_AFÌ65536Ö0 +GPIO_MODER_MODER10_AIÌ65536Ö0 +GPIO_MODER_MODER10_OÌ65536Ö0 +GPIO_MODER_MODER11Ì65536Ö0 +GPIO_MODER_MODER11_0Ì65536Ö0 +GPIO_MODER_MODER11_1Ì65536Ö0 +GPIO_MODER_MODER11_AFÌ65536Ö0 +GPIO_MODER_MODER11_AIÌ65536Ö0 +GPIO_MODER_MODER11_OÌ65536Ö0 +GPIO_MODER_MODER12Ì65536Ö0 +GPIO_MODER_MODER12_0Ì65536Ö0 +GPIO_MODER_MODER12_1Ì65536Ö0 +GPIO_MODER_MODER12_AFÌ65536Ö0 +GPIO_MODER_MODER12_AIÌ65536Ö0 +GPIO_MODER_MODER12_OÌ65536Ö0 +GPIO_MODER_MODER13Ì65536Ö0 +GPIO_MODER_MODER13_0Ì65536Ö0 +GPIO_MODER_MODER13_1Ì65536Ö0 +GPIO_MODER_MODER13_AFÌ65536Ö0 +GPIO_MODER_MODER13_AIÌ65536Ö0 +GPIO_MODER_MODER13_OÌ65536Ö0 +GPIO_MODER_MODER14Ì65536Ö0 +GPIO_MODER_MODER14_0Ì65536Ö0 +GPIO_MODER_MODER14_1Ì65536Ö0 +GPIO_MODER_MODER14_AFÌ65536Ö0 +GPIO_MODER_MODER14_AIÌ65536Ö0 +GPIO_MODER_MODER14_OÌ65536Ö0 +GPIO_MODER_MODER15Ì65536Ö0 +GPIO_MODER_MODER15_0Ì65536Ö0 +GPIO_MODER_MODER15_1Ì65536Ö0 +GPIO_MODER_MODER15_AFÌ65536Ö0 +GPIO_MODER_MODER15_AIÌ65536Ö0 +GPIO_MODER_MODER15_OÌ65536Ö0 +GPIO_MODER_MODER1_0Ì65536Ö0 +GPIO_MODER_MODER1_1Ì65536Ö0 +GPIO_MODER_MODER1_AFÌ65536Ö0 +GPIO_MODER_MODER1_AIÌ65536Ö0 +GPIO_MODER_MODER1_OÌ65536Ö0 +GPIO_MODER_MODER2Ì65536Ö0 +GPIO_MODER_MODER2_0Ì65536Ö0 +GPIO_MODER_MODER2_1Ì65536Ö0 +GPIO_MODER_MODER2_AFÌ65536Ö0 +GPIO_MODER_MODER2_AIÌ65536Ö0 +GPIO_MODER_MODER2_OÌ65536Ö0 +GPIO_MODER_MODER3Ì65536Ö0 +GPIO_MODER_MODER3_0Ì65536Ö0 +GPIO_MODER_MODER3_1Ì65536Ö0 +GPIO_MODER_MODER3_AFÌ65536Ö0 +GPIO_MODER_MODER3_AIÌ65536Ö0 +GPIO_MODER_MODER3_OÌ65536Ö0 +GPIO_MODER_MODER4Ì65536Ö0 +GPIO_MODER_MODER4_0Ì65536Ö0 +GPIO_MODER_MODER4_1Ì65536Ö0 +GPIO_MODER_MODER4_AFÌ65536Ö0 +GPIO_MODER_MODER4_AIÌ65536Ö0 +GPIO_MODER_MODER4_OÌ65536Ö0 +GPIO_MODER_MODER5Ì65536Ö0 +GPIO_MODER_MODER5_0Ì65536Ö0 +GPIO_MODER_MODER5_1Ì65536Ö0 +GPIO_MODER_MODER5_AFÌ65536Ö0 +GPIO_MODER_MODER5_AIÌ65536Ö0 +GPIO_MODER_MODER5_OÌ65536Ö0 +GPIO_MODER_MODER6Ì65536Ö0 +GPIO_MODER_MODER6_0Ì65536Ö0 +GPIO_MODER_MODER6_1Ì65536Ö0 +GPIO_MODER_MODER6_AFÌ65536Ö0 +GPIO_MODER_MODER6_AIÌ65536Ö0 +GPIO_MODER_MODER6_OÌ65536Ö0 +GPIO_MODER_MODER7Ì65536Ö0 +GPIO_MODER_MODER7_0Ì65536Ö0 +GPIO_MODER_MODER7_1Ì65536Ö0 +GPIO_MODER_MODER7_AFÌ65536Ö0 +GPIO_MODER_MODER7_AIÌ65536Ö0 +GPIO_MODER_MODER7_OÌ65536Ö0 +GPIO_MODER_MODER8Ì65536Ö0 +GPIO_MODER_MODER8_0Ì65536Ö0 +GPIO_MODER_MODER8_1Ì65536Ö0 +GPIO_MODER_MODER8_AFÌ65536Ö0 +GPIO_MODER_MODER8_AIÌ65536Ö0 +GPIO_MODER_MODER8_OÌ65536Ö0 +GPIO_MODER_MODER9Ì65536Ö0 +GPIO_MODER_MODER9_0Ì65536Ö0 +GPIO_MODER_MODER9_1Ì65536Ö0 +GPIO_MODER_MODER9_AFÌ65536Ö0 +GPIO_MODER_MODER9_AIÌ65536Ö0 +GPIO_MODER_MODER9_OÌ65536Ö0 +GPIO_ODR_0Ì65536Ö0 +GPIO_ODR_1Ì65536Ö0 +GPIO_ODR_10Ì65536Ö0 +GPIO_ODR_11Ì65536Ö0 +GPIO_ODR_12Ì65536Ö0 +GPIO_ODR_13Ì65536Ö0 +GPIO_ODR_14Ì65536Ö0 +GPIO_ODR_15Ì65536Ö0 +GPIO_ODR_2Ì65536Ö0 +GPIO_ODR_3Ì65536Ö0 +GPIO_ODR_4Ì65536Ö0 +GPIO_ODR_5Ì65536Ö0 +GPIO_ODR_6Ì65536Ö0 +GPIO_ODR_7Ì65536Ö0 +GPIO_ODR_8Ì65536Ö0 +GPIO_ODR_9Ì65536Ö0 +GPIO_OSPEEDER_OSPEEDR0Ì65536Ö0 +GPIO_OSPEEDER_OSPEEDR0_0Ì65536Ö0 +GPIO_OSPEEDER_OSPEEDR0_1Ì65536Ö0 +GPIO_OSPEEDER_OSPEEDR1Ì65536Ö0 +GPIO_OSPEEDER_OSPEEDR10Ì65536Ö0 +GPIO_OSPEEDER_OSPEEDR10_0Ì65536Ö0 +GPIO_OSPEEDER_OSPEEDR10_1Ì65536Ö0 +GPIO_OSPEEDER_OSPEEDR11Ì65536Ö0 +GPIO_OSPEEDER_OSPEEDR11_0Ì65536Ö0 +GPIO_OSPEEDER_OSPEEDR11_1Ì65536Ö0 +GPIO_OSPEEDER_OSPEEDR12Ì65536Ö0 +GPIO_OSPEEDER_OSPEEDR12_0Ì65536Ö0 +GPIO_OSPEEDER_OSPEEDR12_1Ì65536Ö0 +GPIO_OSPEEDER_OSPEEDR13Ì65536Ö0 +GPIO_OSPEEDER_OSPEEDR13_0Ì65536Ö0 +GPIO_OSPEEDER_OSPEEDR13_1Ì65536Ö0 +GPIO_OSPEEDER_OSPEEDR14Ì65536Ö0 +GPIO_OSPEEDER_OSPEEDR14_0Ì65536Ö0 +GPIO_OSPEEDER_OSPEEDR14_1Ì65536Ö0 +GPIO_OSPEEDER_OSPEEDR15Ì65536Ö0 +GPIO_OSPEEDER_OSPEEDR15_0Ì65536Ö0 +GPIO_OSPEEDER_OSPEEDR15_1Ì65536Ö0 +GPIO_OSPEEDER_OSPEEDR1_0Ì65536Ö0 +GPIO_OSPEEDER_OSPEEDR1_1Ì65536Ö0 +GPIO_OSPEEDER_OSPEEDR2Ì65536Ö0 +GPIO_OSPEEDER_OSPEEDR2_0Ì65536Ö0 +GPIO_OSPEEDER_OSPEEDR2_1Ì65536Ö0 +GPIO_OSPEEDER_OSPEEDR3Ì65536Ö0 +GPIO_OSPEEDER_OSPEEDR3_0Ì65536Ö0 +GPIO_OSPEEDER_OSPEEDR3_1Ì65536Ö0 +GPIO_OSPEEDER_OSPEEDR4Ì65536Ö0 +GPIO_OSPEEDER_OSPEEDR4_0Ì65536Ö0 +GPIO_OSPEEDER_OSPEEDR4_1Ì65536Ö0 +GPIO_OSPEEDER_OSPEEDR5Ì65536Ö0 +GPIO_OSPEEDER_OSPEEDR5_0Ì65536Ö0 +GPIO_OSPEEDER_OSPEEDR5_1Ì65536Ö0 +GPIO_OSPEEDER_OSPEEDR6Ì65536Ö0 +GPIO_OSPEEDER_OSPEEDR6_0Ì65536Ö0 +GPIO_OSPEEDER_OSPEEDR6_1Ì65536Ö0 +GPIO_OSPEEDER_OSPEEDR7Ì65536Ö0 +GPIO_OSPEEDER_OSPEEDR7_0Ì65536Ö0 +GPIO_OSPEEDER_OSPEEDR7_1Ì65536Ö0 +GPIO_OSPEEDER_OSPEEDR8Ì65536Ö0 +GPIO_OSPEEDER_OSPEEDR8_0Ì65536Ö0 +GPIO_OSPEEDER_OSPEEDR8_1Ì65536Ö0 +GPIO_OSPEEDER_OSPEEDR9Ì65536Ö0 +GPIO_OSPEEDER_OSPEEDR9_0Ì65536Ö0 +GPIO_OSPEEDER_OSPEEDR9_1Ì65536Ö0 +GPIO_OSPEEDR_OSPEEDR0Ì65536Ö0 +GPIO_OSPEEDR_OSPEEDR0_0Ì65536Ö0 +GPIO_OSPEEDR_OSPEEDR0_1Ì65536Ö0 +GPIO_OSPEEDR_OSPEEDR1Ì65536Ö0 +GPIO_OSPEEDR_OSPEEDR10Ì65536Ö0 +GPIO_OSPEEDR_OSPEEDR10_0Ì65536Ö0 +GPIO_OSPEEDR_OSPEEDR10_1Ì65536Ö0 +GPIO_OSPEEDR_OSPEEDR11Ì65536Ö0 +GPIO_OSPEEDR_OSPEEDR11_0Ì65536Ö0 +GPIO_OSPEEDR_OSPEEDR11_1Ì65536Ö0 +GPIO_OSPEEDR_OSPEEDR12Ì65536Ö0 +GPIO_OSPEEDR_OSPEEDR12_0Ì65536Ö0 +GPIO_OSPEEDR_OSPEEDR12_1Ì65536Ö0 +GPIO_OSPEEDR_OSPEEDR13Ì65536Ö0 +GPIO_OSPEEDR_OSPEEDR13_0Ì65536Ö0 +GPIO_OSPEEDR_OSPEEDR13_1Ì65536Ö0 +GPIO_OSPEEDR_OSPEEDR14Ì65536Ö0 +GPIO_OSPEEDR_OSPEEDR14_0Ì65536Ö0 +GPIO_OSPEEDR_OSPEEDR14_1Ì65536Ö0 +GPIO_OSPEEDR_OSPEEDR15Ì65536Ö0 +GPIO_OSPEEDR_OSPEEDR15_0Ì65536Ö0 +GPIO_OSPEEDR_OSPEEDR15_1Ì65536Ö0 +GPIO_OSPEEDR_OSPEEDR1_0Ì65536Ö0 +GPIO_OSPEEDR_OSPEEDR1_1Ì65536Ö0 +GPIO_OSPEEDR_OSPEEDR2Ì65536Ö0 +GPIO_OSPEEDR_OSPEEDR2_0Ì65536Ö0 +GPIO_OSPEEDR_OSPEEDR2_1Ì65536Ö0 +GPIO_OSPEEDR_OSPEEDR3Ì65536Ö0 +GPIO_OSPEEDR_OSPEEDR3_0Ì65536Ö0 +GPIO_OSPEEDR_OSPEEDR3_1Ì65536Ö0 +GPIO_OSPEEDR_OSPEEDR4Ì65536Ö0 +GPIO_OSPEEDR_OSPEEDR4_0Ì65536Ö0 +GPIO_OSPEEDR_OSPEEDR4_1Ì65536Ö0 +GPIO_OSPEEDR_OSPEEDR5Ì65536Ö0 +GPIO_OSPEEDR_OSPEEDR5_0Ì65536Ö0 +GPIO_OSPEEDR_OSPEEDR5_1Ì65536Ö0 +GPIO_OSPEEDR_OSPEEDR6Ì65536Ö0 +GPIO_OSPEEDR_OSPEEDR6_0Ì65536Ö0 +GPIO_OSPEEDR_OSPEEDR6_1Ì65536Ö0 +GPIO_OSPEEDR_OSPEEDR7Ì65536Ö0 +GPIO_OSPEEDR_OSPEEDR7_0Ì65536Ö0 +GPIO_OSPEEDR_OSPEEDR7_1Ì65536Ö0 +GPIO_OSPEEDR_OSPEEDR8Ì65536Ö0 +GPIO_OSPEEDR_OSPEEDR8_0Ì65536Ö0 +GPIO_OSPEEDR_OSPEEDR8_1Ì65536Ö0 +GPIO_OSPEEDR_OSPEEDR9Ì65536Ö0 +GPIO_OSPEEDR_OSPEEDR9_0Ì65536Ö0 +GPIO_OSPEEDR_OSPEEDR9_1Ì65536Ö0 +GPIO_OTYPER_OT_0Ì65536Ö0 +GPIO_OTYPER_OT_1Ì65536Ö0 +GPIO_OTYPER_OT_10Ì65536Ö0 +GPIO_OTYPER_OT_11Ì65536Ö0 +GPIO_OTYPER_OT_12Ì65536Ö0 +GPIO_OTYPER_OT_13Ì65536Ö0 +GPIO_OTYPER_OT_14Ì65536Ö0 +GPIO_OTYPER_OT_15Ì65536Ö0 +GPIO_OTYPER_OT_2Ì65536Ö0 +GPIO_OTYPER_OT_3Ì65536Ö0 +GPIO_OTYPER_OT_4Ì65536Ö0 +GPIO_OTYPER_OT_5Ì65536Ö0 +GPIO_OTYPER_OT_6Ì65536Ö0 +GPIO_OTYPER_OT_7Ì65536Ö0 +GPIO_OTYPER_OT_8Ì65536Ö0 +GPIO_OTYPER_OT_9Ì65536Ö0 +GPIO_PUPDR_PUPDR0Ì65536Ö0 +GPIO_PUPDR_PUPDR0_0Ì65536Ö0 +GPIO_PUPDR_PUPDR0_1Ì65536Ö0 +GPIO_PUPDR_PUPDR1Ì65536Ö0 +GPIO_PUPDR_PUPDR10Ì65536Ö0 +GPIO_PUPDR_PUPDR10_0Ì65536Ö0 +GPIO_PUPDR_PUPDR10_1Ì65536Ö0 +GPIO_PUPDR_PUPDR11Ì65536Ö0 +GPIO_PUPDR_PUPDR11_0Ì65536Ö0 +GPIO_PUPDR_PUPDR11_1Ì65536Ö0 +GPIO_PUPDR_PUPDR12Ì65536Ö0 +GPIO_PUPDR_PUPDR12_0Ì65536Ö0 +GPIO_PUPDR_PUPDR12_1Ì65536Ö0 +GPIO_PUPDR_PUPDR13Ì65536Ö0 +GPIO_PUPDR_PUPDR13_0Ì65536Ö0 +GPIO_PUPDR_PUPDR13_1Ì65536Ö0 +GPIO_PUPDR_PUPDR14Ì65536Ö0 +GPIO_PUPDR_PUPDR14_0Ì65536Ö0 +GPIO_PUPDR_PUPDR14_1Ì65536Ö0 +GPIO_PUPDR_PUPDR15Ì65536Ö0 +GPIO_PUPDR_PUPDR15_0Ì65536Ö0 +GPIO_PUPDR_PUPDR15_1Ì65536Ö0 +GPIO_PUPDR_PUPDR1_0Ì65536Ö0 +GPIO_PUPDR_PUPDR1_1Ì65536Ö0 +GPIO_PUPDR_PUPDR2Ì65536Ö0 +GPIO_PUPDR_PUPDR2_0Ì65536Ö0 +GPIO_PUPDR_PUPDR2_1Ì65536Ö0 +GPIO_PUPDR_PUPDR3Ì65536Ö0 +GPIO_PUPDR_PUPDR3_0Ì65536Ö0 +GPIO_PUPDR_PUPDR3_1Ì65536Ö0 +GPIO_PUPDR_PUPDR4Ì65536Ö0 +GPIO_PUPDR_PUPDR4_0Ì65536Ö0 +GPIO_PUPDR_PUPDR4_1Ì65536Ö0 +GPIO_PUPDR_PUPDR5Ì65536Ö0 +GPIO_PUPDR_PUPDR5_0Ì65536Ö0 +GPIO_PUPDR_PUPDR5_1Ì65536Ö0 +GPIO_PUPDR_PUPDR6Ì65536Ö0 +GPIO_PUPDR_PUPDR6_0Ì65536Ö0 +GPIO_PUPDR_PUPDR6_1Ì65536Ö0 +GPIO_PUPDR_PUPDR7Ì65536Ö0 +GPIO_PUPDR_PUPDR7_0Ì65536Ö0 +GPIO_PUPDR_PUPDR7_1Ì65536Ö0 +GPIO_PUPDR_PUPDR8Ì65536Ö0 +GPIO_PUPDR_PUPDR8_0Ì65536Ö0 +GPIO_PUPDR_PUPDR8_1Ì65536Ö0 +GPIO_PUPDR_PUPDR9Ì65536Ö0 +GPIO_PUPDR_PUPDR9_0Ì65536Ö0 +GPIO_PUPDR_PUPDR9_1Ì65536Ö0 +I2C1Ì65536Ö0 +I2C1_BASEÌ65536Ö0 +I2C_CR1_ADDRIEÌ65536Ö0 +I2C_CR1_ALERTENÌ65536Ö0 +I2C_CR1_ANFOFFÌ65536Ö0 +I2C_CR1_DFNÌ65536Ö0 +I2C_CR1_ERRIEÌ65536Ö0 +I2C_CR1_GCENÌ65536Ö0 +I2C_CR1_NACKIEÌ65536Ö0 +I2C_CR1_NOSTRETCHÌ65536Ö0 +I2C_CR1_PEÌ65536Ö0 +I2C_CR1_PECENÌ65536Ö0 +I2C_CR1_RXDMAENÌ65536Ö0 +I2C_CR1_RXIEÌ65536Ö0 +I2C_CR1_SBCÌ65536Ö0 +I2C_CR1_SMBDENÌ65536Ö0 +I2C_CR1_SMBHENÌ65536Ö0 +I2C_CR1_STOPIEÌ65536Ö0 +I2C_CR1_SWRSTÌ65536Ö0 +I2C_CR1_TCIEÌ65536Ö0 +I2C_CR1_TXDMAENÌ65536Ö0 +I2C_CR1_TXIEÌ65536Ö0 +I2C_CR1_WUPENÌ65536Ö0 +I2C_CR2_ADD10Ì65536Ö0 +I2C_CR2_AUTOENDÌ65536Ö0 +I2C_CR2_HEAD10RÌ65536Ö0 +I2C_CR2_NACKÌ65536Ö0 +I2C_CR2_NBYTESÌ65536Ö0 +I2C_CR2_PECBYTEÌ65536Ö0 +I2C_CR2_RD_WRNÌ65536Ö0 +I2C_CR2_RELOADÌ65536Ö0 +I2C_CR2_SADDÌ65536Ö0 +I2C_CR2_STARTÌ65536Ö0 +I2C_CR2_STOPÌ65536Ö0 +I2C_ICR_ADDRCFÌ65536Ö0 +I2C_ICR_ALERTCFÌ65536Ö0 +I2C_ICR_ARLOCFÌ65536Ö0 +I2C_ICR_BERRCFÌ65536Ö0 +I2C_ICR_NACKCFÌ65536Ö0 +I2C_ICR_OVRCFÌ65536Ö0 +I2C_ICR_PECCFÌ65536Ö0 +I2C_ICR_STOPCFÌ65536Ö0 +I2C_ICR_TIMOUTCFÌ65536Ö0 +I2C_ISR_ADDCODEÌ65536Ö0 +I2C_ISR_ADDRÌ65536Ö0 +I2C_ISR_ALERTÌ65536Ö0 +I2C_ISR_ARLOÌ65536Ö0 +I2C_ISR_BERRÌ65536Ö0 +I2C_ISR_BUSYÌ65536Ö0 +I2C_ISR_DIRÌ65536Ö0 +I2C_ISR_NACKFÌ65536Ö0 +I2C_ISR_OVRÌ65536Ö0 +I2C_ISR_PECERRÌ65536Ö0 +I2C_ISR_RXNEÌ65536Ö0 +I2C_ISR_STOPFÌ65536Ö0 +I2C_ISR_TCÌ65536Ö0 +I2C_ISR_TCRÌ65536Ö0 +I2C_ISR_TIMEOUTÌ65536Ö0 +I2C_ISR_TXEÌ65536Ö0 +I2C_ISR_TXISÌ65536Ö0 +I2C_OAR1_OA1Ì65536Ö0 +I2C_OAR1_OA1ENÌ65536Ö0 +I2C_OAR1_OA1MODEÌ65536Ö0 +I2C_OAR2_OA2Ì65536Ö0 +I2C_OAR2_OA2ENÌ65536Ö0 +I2C_OAR2_OA2MSKÌ65536Ö0 +I2C_PECR_PECÌ65536Ö0 +I2C_RXDR_RXDATAÌ65536Ö0 +I2C_TIMEOUTR_TEXTENÌ65536Ö0 +I2C_TIMEOUTR_TIDLEÌ65536Ö0 +I2C_TIMEOUTR_TIMEOUTAÌ65536Ö0 +I2C_TIMEOUTR_TIMEOUTBÌ65536Ö0 +I2C_TIMEOUTR_TIMOUTENÌ65536Ö0 +I2C_TIMINGR_PRESCÌ65536Ö0 +I2C_TIMINGR_SCLDELÌ65536Ö0 +I2C_TIMINGR_SCLHÌ65536Ö0 +I2C_TIMINGR_SCLLÌ65536Ö0 +I2C_TIMINGR_SDADELÌ65536Ö0 +I2C_TXDR_TXDATAÌ65536Ö0 +INT16_CÌ131072Í(c)Ö0 +INT16_MAXÌ65536Ö0 +INT16_MINÌ65536Ö0 +INT16_WIDTHÌ65536Ö0 +INT32_CÌ131072Í(c)Ö0 +INT32_MAXÌ65536Ö0 +INT32_MINÌ65536Ö0 +INT32_WIDTHÌ65536Ö0 +INT64_CÌ131072Í(c)Ö0 +INT64_MAXÌ65536Ö0 +INT64_MINÌ65536Ö0 +INT64_WIDTHÌ65536Ö0 +INT8_CÌ131072Í(c)Ö0 +INT8_MAXÌ65536Ö0 +INT8_MINÌ65536Ö0 +INT8_WIDTHÌ65536Ö0 +INTMAX_CÌ131072Í(c)Ö0 +INTMAX_MAXÌ65536Ö0 +INTMAX_MINÌ65536Ö0 +INTMAX_WIDTHÌ65536Ö0 +INTPTR_MAXÌ65536Ö0 +INTPTR_MINÌ65536Ö0 +INTPTR_WIDTHÌ65536Ö0 +INT_FAST16_MAXÌ65536Ö0 +INT_FAST16_MINÌ65536Ö0 +INT_FAST16_WIDTHÌ65536Ö0 +INT_FAST32_MAXÌ65536Ö0 +INT_FAST32_MINÌ65536Ö0 +INT_FAST32_WIDTHÌ65536Ö0 +INT_FAST64_MAXÌ65536Ö0 +INT_FAST64_MINÌ65536Ö0 +INT_FAST64_WIDTHÌ65536Ö0 +INT_FAST8_MAXÌ65536Ö0 +INT_FAST8_MINÌ65536Ö0 +INT_FAST8_WIDTHÌ65536Ö0 +INT_LEAST16_MAXÌ65536Ö0 +INT_LEAST16_MINÌ65536Ö0 +INT_LEAST16_WIDTHÌ65536Ö0 +INT_LEAST32_MAXÌ65536Ö0 +INT_LEAST32_MINÌ65536Ö0 +INT_LEAST32_WIDTHÌ65536Ö0 +INT_LEAST64_MAXÌ65536Ö0 +INT_LEAST64_MINÌ65536Ö0 +INT_LEAST64_WIDTHÌ65536Ö0 +INT_LEAST8_MAXÌ65536Ö0 +INT_LEAST8_MINÌ65536Ö0 +INT_LEAST8_WIDTHÌ65536Ö0 +IS_ADC_ALL_INSTANCEÌ131072Í(INSTANCE)Ö0 +IS_ADC_COMMON_INSTANCEÌ131072Í(INSTANCE)Ö0 +IS_CRC_ALL_INSTANCEÌ131072Í(INSTANCE)Ö0 +IS_DMA_ALL_INSTANCEÌ131072Í(INSTANCE)Ö0 +IS_FUNCTIONAL_STATEÌ131072Í(STATE)Ö0 +IS_GPIO_AF_INSTANCEÌ131072Í(INSTANCE)Ö0 +IS_GPIO_ALL_INSTANCEÌ131072Í(INSTANCE)Ö0 +IS_GPIO_LOCK_INSTANCEÌ131072Í(INSTANCE)Ö0 +IS_I2C_ALL_INSTANCEÌ131072Í(INSTANCE)Ö0 +IS_IWDG_ALL_INSTANCEÌ131072Í(INSTANCE)Ö0 +IS_RTC_ALL_INSTANCEÌ131072Í(INSTANCE)Ö0 +IS_SMBUS_ALL_INSTANCEÌ131072Í(INSTANCE)Ö0 +IS_SPI_ALL_INSTANCEÌ131072Í(INSTANCE)Ö0 +IS_TIM_32B_COUNTER_INSTANCEÌ131072Í(INSTANCE)Ö0 +IS_TIM_BREAK_INSTANCEÌ131072Í(INSTANCE)Ö0 +IS_TIM_CC1_INSTANCEÌ131072Í(INSTANCE)Ö0 +IS_TIM_CC2_INSTANCEÌ131072Í(INSTANCE)Ö0 +IS_TIM_CC3_INSTANCEÌ131072Í(INSTANCE)Ö0 +IS_TIM_CC4_INSTANCEÌ131072Í(INSTANCE)Ö0 +IS_TIM_CCXN_INSTANCEÌ131072Í(INSTANCE,CHANNEL)Ö0 +IS_TIM_CCX_INSTANCEÌ131072Í(INSTANCE,CHANNEL)Ö0 +IS_TIM_CLOCKSOURCE_ETRMODE1_INSTANCEÌ131072Í(INSTANCE)Ö0 +IS_TIM_CLOCKSOURCE_ETRMODE2_INSTANCEÌ131072Í(INSTANCE)Ö0 +IS_TIM_CLOCKSOURCE_ITRX_INSTANCEÌ131072Í(INSTANCE)Ö0 +IS_TIM_CLOCKSOURCE_TIX_INSTANCEÌ131072Í(INSTANCE)Ö0 +IS_TIM_CLOCK_DIVISION_INSTANCEÌ131072Í(INSTANCE)Ö0 +IS_TIM_COMMUTATION_EVENT_INSTANCEÌ131072Í(INSTANCE)Ö0 +IS_TIM_COUNTER_MODE_SELECT_INSTANCEÌ131072Í(INSTANCE)Ö0 +IS_TIM_DMABURST_INSTANCEÌ131072Í(INSTANCE)Ö0 +IS_TIM_DMA_CC_INSTANCEÌ131072Í(INSTANCE)Ö0 +IS_TIM_DMA_INSTANCEÌ131072Í(INSTANCE)Ö0 +IS_TIM_ENCODER_INTERFACE_INSTANCEÌ131072Í(INSTANCE)Ö0 +IS_TIM_HALL_INTERFACE_INSTANCEÌ131072Í(INSTANCE)Ö0 +IS_TIM_INSTANCEÌ131072Í(INSTANCE)Ö0 +IS_TIM_MASTER_INSTANCEÌ131072Í(INSTANCE)Ö0 +IS_TIM_OCXREF_CLEAR_INSTANCEÌ131072Í(INSTANCE)Ö0 +IS_TIM_REMAP_INSTANCEÌ131072Í(INSTANCE)Ö0 +IS_TIM_REPETITION_COUNTER_INSTANCEÌ131072Í(INSTANCE)Ö0 +IS_TIM_SLAVE_INSTANCEÌ131072Í(INSTANCE)Ö0 +IS_TIM_XOR_INSTANCEÌ131072Í(INSTANCE)Ö0 +IS_UART_AUTOBAUDRATE_DETECTION_INSTANCEÌ131072Í(INSTANCE)Ö0 +IS_UART_DRIVER_ENABLE_INSTANCEÌ131072Í(INSTANCE)Ö0 +IS_UART_HALFDUPLEX_INSTANCEÌ131072Í(INSTANCE)Ö0 +IS_UART_HWFLOW_INSTANCEÌ131072Í(INSTANCE)Ö0 +IS_UART_INSTANCEÌ131072Í(INSTANCE)Ö0 +IS_USART_AUTOBAUDRATE_DETECTION_INSTANCEÌ131072Í(INSTANCE)Ö0 +IS_USART_INSTANCEÌ131072Í(INSTANCE)Ö0 +IS_WWDG_ALL_INSTANCEÌ131072Í(INSTANCE)Ö0 +IWDGÌ65536Ö0 +IWDG_BASEÌ65536Ö0 +IWDG_KR_KEYÌ65536Ö0 +IWDG_PR_PRÌ65536Ö0 +IWDG_PR_PR_0Ì65536Ö0 +IWDG_PR_PR_1Ì65536Ö0 +IWDG_PR_PR_2Ì65536Ö0 +IWDG_RLR_RLÌ65536Ö0 +IWDG_SR_PVUÌ65536Ö0 +IWDG_SR_RVUÌ65536Ö0 +IWDG_SR_WVUÌ65536Ö0 +IWDG_WINR_WINÌ65536Ö0 +MODIFY_REGÌ131072Í(REG,CLEARMASK,SETMASK)Ö0 +NULLÌ65536Ö0 +NVICÌ65536Ö0 +NVIC_BASEÌ65536Ö0 +NVIC_IRQ_COUNTÌ65536Ö0 +OBÌ65536Ö0 +OB_BASEÌ65536Ö0 +OB_RDP_RDPÌ65536Ö0 +OB_RDP_nRDPÌ65536Ö0 +OB_USER_USERÌ65536Ö0 +OB_USER_nUSERÌ65536Ö0 +OB_WRP0_WRP0Ì65536Ö0 +OB_WRP0_nWRP0Ì65536Ö0 +OB_WRP1_WRP1Ì65536Ö0 +OB_WRP1_nWRP1Ì65536Ö0 +PERIPH_BASEÌ65536Ö0 +PTRDIFF_MAXÌ65536Ö0 +PTRDIFF_MINÌ65536Ö0 +PTRDIFF_WIDTHÌ65536Ö0 +PWRÌ65536Ö0 +PWR_BASEÌ65536Ö0 +PWR_CR_CSBFÌ65536Ö0 +PWR_CR_CWUFÌ65536Ö0 +PWR_CR_DBPÌ65536Ö0 +PWR_CR_LPDSÌ65536Ö0 +PWR_CR_PDDSÌ65536Ö0 +PWR_CSR_EWUP1Ì65536Ö0 +PWR_CSR_EWUP2Ì65536Ö0 +PWR_CSR_SBFÌ65536Ö0 +PWR_CSR_WUFÌ65536Ö0 +RCCÌ65536Ö0 +RCC_AHBENR_CRCENÌ65536Ö0 +RCC_AHBENR_DMA1ENÌ65536Ö0 +RCC_AHBENR_DMAENÌ65536Ö0 +RCC_AHBENR_FLITFENÌ65536Ö0 +RCC_AHBENR_GPIOAENÌ65536Ö0 +RCC_AHBENR_GPIOBENÌ65536Ö0 +RCC_AHBENR_GPIOCENÌ65536Ö0 +RCC_AHBENR_GPIODENÌ65536Ö0 +RCC_AHBENR_GPIOFENÌ65536Ö0 +RCC_AHBENR_SRAMENÌ65536Ö0 +RCC_AHBENR_TSENÌ65536Ö0 +RCC_AHBRSTR_GPIOARSTÌ65536Ö0 +RCC_AHBRSTR_GPIOBRSTÌ65536Ö0 +RCC_AHBRSTR_GPIOCRSTÌ65536Ö0 +RCC_AHBRSTR_GPIODRSTÌ65536Ö0 +RCC_AHBRSTR_GPIOFRSTÌ65536Ö0 +RCC_APB1ENR_I2C1ENÌ65536Ö0 +RCC_APB1ENR_PWRENÌ65536Ö0 +RCC_APB1ENR_TIM14ENÌ65536Ö0 +RCC_APB1ENR_TIM3ENÌ65536Ö0 +RCC_APB1ENR_WWDGENÌ65536Ö0 +RCC_APB1RSTR_I2C1RSTÌ65536Ö0 +RCC_APB1RSTR_PWRRSTÌ65536Ö0 +RCC_APB1RSTR_TIM14RSTÌ65536Ö0 +RCC_APB1RSTR_TIM3RSTÌ65536Ö0 +RCC_APB1RSTR_WWDGRSTÌ65536Ö0 +RCC_APB2ENR_ADC1ENÌ65536Ö0 +RCC_APB2ENR_ADCENÌ65536Ö0 +RCC_APB2ENR_DBGMCUENÌ65536Ö0 +RCC_APB2ENR_SPI1ENÌ65536Ö0 +RCC_APB2ENR_SYSCFGCOMPENÌ65536Ö0 +RCC_APB2ENR_SYSCFGENÌ65536Ö0 +RCC_APB2ENR_TIM16ENÌ65536Ö0 +RCC_APB2ENR_TIM17ENÌ65536Ö0 +RCC_APB2ENR_TIM1ENÌ65536Ö0 +RCC_APB2ENR_USART1ENÌ65536Ö0 +RCC_APB2RSTR_ADC1RSTÌ65536Ö0 +RCC_APB2RSTR_ADCRSTÌ65536Ö0 +RCC_APB2RSTR_DBGMCURSTÌ65536Ö0 +RCC_APB2RSTR_SPI1RSTÌ65536Ö0 +RCC_APB2RSTR_SYSCFGRSTÌ65536Ö0 +RCC_APB2RSTR_TIM16RSTÌ65536Ö0 +RCC_APB2RSTR_TIM17RSTÌ65536Ö0 +RCC_APB2RSTR_TIM1RSTÌ65536Ö0 +RCC_APB2RSTR_USART1RSTÌ65536Ö0 +RCC_BASEÌ65536Ö0 +RCC_BDCR_BDRSTÌ65536Ö0 +RCC_BDCR_LSEBYPÌ65536Ö0 +RCC_BDCR_LSEDRVÌ65536Ö0 +RCC_BDCR_LSEDRV_0Ì65536Ö0 +RCC_BDCR_LSEDRV_1Ì65536Ö0 +RCC_BDCR_LSEONÌ65536Ö0 +RCC_BDCR_LSERDYÌ65536Ö0 +RCC_BDCR_RTCENÌ65536Ö0 +RCC_BDCR_RTCSELÌ65536Ö0 +RCC_BDCR_RTCSEL_0Ì65536Ö0 +RCC_BDCR_RTCSEL_1Ì65536Ö0 +RCC_BDCR_RTCSEL_HSEÌ65536Ö0 +RCC_BDCR_RTCSEL_LSEÌ65536Ö0 +RCC_BDCR_RTCSEL_LSIÌ65536Ö0 +RCC_BDCR_RTCSEL_NOCLOCKÌ65536Ö0 +RCC_CFGR2_PREDIVÌ65536Ö0 +RCC_CFGR2_PREDIV_0Ì65536Ö0 +RCC_CFGR2_PREDIV_1Ì65536Ö0 +RCC_CFGR2_PREDIV_2Ì65536Ö0 +RCC_CFGR2_PREDIV_3Ì65536Ö0 +RCC_CFGR2_PREDIV_DIV1Ì65536Ö0 +RCC_CFGR2_PREDIV_DIV10Ì65536Ö0 +RCC_CFGR2_PREDIV_DIV11Ì65536Ö0 +RCC_CFGR2_PREDIV_DIV12Ì65536Ö0 +RCC_CFGR2_PREDIV_DIV13Ì65536Ö0 +RCC_CFGR2_PREDIV_DIV14Ì65536Ö0 +RCC_CFGR2_PREDIV_DIV15Ì65536Ö0 +RCC_CFGR2_PREDIV_DIV16Ì65536Ö0 +RCC_CFGR2_PREDIV_DIV2Ì65536Ö0 +RCC_CFGR2_PREDIV_DIV3Ì65536Ö0 +RCC_CFGR2_PREDIV_DIV4Ì65536Ö0 +RCC_CFGR2_PREDIV_DIV5Ì65536Ö0 +RCC_CFGR2_PREDIV_DIV6Ì65536Ö0 +RCC_CFGR2_PREDIV_DIV7Ì65536Ö0 +RCC_CFGR2_PREDIV_DIV8Ì65536Ö0 +RCC_CFGR2_PREDIV_DIV9Ì65536Ö0 +RCC_CFGR3_I2C1SWÌ65536Ö0 +RCC_CFGR3_I2C1SW_HSIÌ65536Ö0 +RCC_CFGR3_I2C1SW_SYSCLKÌ65536Ö0 +RCC_CFGR3_USART1SWÌ65536Ö0 +RCC_CFGR3_USART1SW_0Ì65536Ö0 +RCC_CFGR3_USART1SW_1Ì65536Ö0 +RCC_CFGR3_USART1SW_HSIÌ65536Ö0 +RCC_CFGR3_USART1SW_LSEÌ65536Ö0 +RCC_CFGR3_USART1SW_PCLKÌ65536Ö0 +RCC_CFGR3_USART1SW_SYSCLKÌ65536Ö0 +RCC_CFGR_ADCPREÌ65536Ö0 +RCC_CFGR_ADCPRE_DIV2Ì65536Ö0 +RCC_CFGR_ADCPRE_DIV4Ì65536Ö0 +RCC_CFGR_HPREÌ65536Ö0 +RCC_CFGR_HPRE_0Ì65536Ö0 +RCC_CFGR_HPRE_1Ì65536Ö0 +RCC_CFGR_HPRE_2Ì65536Ö0 +RCC_CFGR_HPRE_3Ì65536Ö0 +RCC_CFGR_HPRE_DIV1Ì65536Ö0 +RCC_CFGR_HPRE_DIV128Ì65536Ö0 +RCC_CFGR_HPRE_DIV16Ì65536Ö0 +RCC_CFGR_HPRE_DIV2Ì65536Ö0 +RCC_CFGR_HPRE_DIV256Ì65536Ö0 +RCC_CFGR_HPRE_DIV4Ì65536Ö0 +RCC_CFGR_HPRE_DIV512Ì65536Ö0 +RCC_CFGR_HPRE_DIV64Ì65536Ö0 +RCC_CFGR_HPRE_DIV8Ì65536Ö0 +RCC_CFGR_MCOÌ65536Ö0 +RCC_CFGR_MCOPREÌ65536Ö0 +RCC_CFGR_MCOPRE_DIV1Ì65536Ö0 +RCC_CFGR_MCOPRE_DIV128Ì65536Ö0 +RCC_CFGR_MCOPRE_DIV16Ì65536Ö0 +RCC_CFGR_MCOPRE_DIV2Ì65536Ö0 +RCC_CFGR_MCOPRE_DIV32Ì65536Ö0 +RCC_CFGR_MCOPRE_DIV4Ì65536Ö0 +RCC_CFGR_MCOPRE_DIV64Ì65536Ö0 +RCC_CFGR_MCOPRE_DIV8Ì65536Ö0 +RCC_CFGR_MCO_0Ì65536Ö0 +RCC_CFGR_MCO_1Ì65536Ö0 +RCC_CFGR_MCO_2Ì65536Ö0 +RCC_CFGR_MCO_3Ì65536Ö0 +RCC_CFGR_MCO_HSEÌ65536Ö0 +RCC_CFGR_MCO_HSIÌ65536Ö0 +RCC_CFGR_MCO_HSI14Ì65536Ö0 +RCC_CFGR_MCO_LSEÌ65536Ö0 +RCC_CFGR_MCO_LSIÌ65536Ö0 +RCC_CFGR_MCO_NOCLOCKÌ65536Ö0 +RCC_CFGR_MCO_PLLÌ65536Ö0 +RCC_CFGR_MCO_SYSCLKÌ65536Ö0 +RCC_CFGR_PLLMULÌ65536Ö0 +RCC_CFGR_PLLMUL10Ì65536Ö0 +RCC_CFGR_PLLMUL11Ì65536Ö0 +RCC_CFGR_PLLMUL12Ì65536Ö0 +RCC_CFGR_PLLMUL13Ì65536Ö0 +RCC_CFGR_PLLMUL14Ì65536Ö0 +RCC_CFGR_PLLMUL15Ì65536Ö0 +RCC_CFGR_PLLMUL16Ì65536Ö0 +RCC_CFGR_PLLMUL2Ì65536Ö0 +RCC_CFGR_PLLMUL3Ì65536Ö0 +RCC_CFGR_PLLMUL4Ì65536Ö0 +RCC_CFGR_PLLMUL5Ì65536Ö0 +RCC_CFGR_PLLMUL6Ì65536Ö0 +RCC_CFGR_PLLMUL7Ì65536Ö0 +RCC_CFGR_PLLMUL8Ì65536Ö0 +RCC_CFGR_PLLMUL9Ì65536Ö0 +RCC_CFGR_PLLMUL_0Ì65536Ö0 +RCC_CFGR_PLLMUL_1Ì65536Ö0 +RCC_CFGR_PLLMUL_2Ì65536Ö0 +RCC_CFGR_PLLMUL_3Ì65536Ö0 +RCC_CFGR_PLLNODIVÌ65536Ö0 +RCC_CFGR_PLLSRCÌ65536Ö0 +RCC_CFGR_PLLSRC_HSE_PREDIVÌ65536Ö0 +RCC_CFGR_PLLSRC_HSI_DIV2Ì65536Ö0 +RCC_CFGR_PLLXTPREÌ65536Ö0 +RCC_CFGR_PLLXTPRE_HSE_PREDIV_DIV1Ì65536Ö0 +RCC_CFGR_PLLXTPRE_HSE_PREDIV_DIV2Ì65536Ö0 +RCC_CFGR_PPREÌ65536Ö0 +RCC_CFGR_PPRE_0Ì65536Ö0 +RCC_CFGR_PPRE_1Ì65536Ö0 +RCC_CFGR_PPRE_2Ì65536Ö0 +RCC_CFGR_PPRE_DIV1Ì65536Ö0 +RCC_CFGR_PPRE_DIV16Ì65536Ö0 +RCC_CFGR_PPRE_DIV2Ì65536Ö0 +RCC_CFGR_PPRE_DIV4Ì65536Ö0 +RCC_CFGR_PPRE_DIV8Ì65536Ö0 +RCC_CFGR_SWÌ65536Ö0 +RCC_CFGR_SWSÌ65536Ö0 +RCC_CFGR_SWS_0Ì65536Ö0 +RCC_CFGR_SWS_1Ì65536Ö0 +RCC_CFGR_SWS_HSEÌ65536Ö0 +RCC_CFGR_SWS_HSIÌ65536Ö0 +RCC_CFGR_SWS_PLLÌ65536Ö0 +RCC_CFGR_SW_0Ì65536Ö0 +RCC_CFGR_SW_1Ì65536Ö0 +RCC_CFGR_SW_HSEÌ65536Ö0 +RCC_CFGR_SW_HSIÌ65536Ö0 +RCC_CFGR_SW_PLLÌ65536Ö0 +RCC_CIR_CSSCÌ65536Ö0 +RCC_CIR_CSSFÌ65536Ö0 +RCC_CIR_HSERDYCÌ65536Ö0 +RCC_CIR_HSERDYFÌ65536Ö0 +RCC_CIR_HSERDYIEÌ65536Ö0 +RCC_CIR_HSI14RDYCÌ65536Ö0 +RCC_CIR_HSI14RDYFÌ65536Ö0 +RCC_CIR_HSI14RDYIEÌ65536Ö0 +RCC_CIR_HSIRDYCÌ65536Ö0 +RCC_CIR_HSIRDYFÌ65536Ö0 +RCC_CIR_HSIRDYIEÌ65536Ö0 +RCC_CIR_LSERDYCÌ65536Ö0 +RCC_CIR_LSERDYFÌ65536Ö0 +RCC_CIR_LSERDYIEÌ65536Ö0 +RCC_CIR_LSIRDYCÌ65536Ö0 +RCC_CIR_LSIRDYFÌ65536Ö0 +RCC_CIR_LSIRDYIEÌ65536Ö0 +RCC_CIR_PLLRDYCÌ65536Ö0 +RCC_CIR_PLLRDYFÌ65536Ö0 +RCC_CIR_PLLRDYIEÌ65536Ö0 +RCC_CR2_HSI14CALÌ65536Ö0 +RCC_CR2_HSI14DISÌ65536Ö0 +RCC_CR2_HSI14ONÌ65536Ö0 +RCC_CR2_HSI14RDYÌ65536Ö0 +RCC_CR2_HSI14TRIMÌ65536Ö0 +RCC_CRS_IRQHandlerÌ65536Ö0 +RCC_CRS_IRQnÌ65536Ö0 +RCC_CR_CSSONÌ65536Ö0 +RCC_CR_HSEBYPÌ65536Ö0 +RCC_CR_HSEONÌ65536Ö0 +RCC_CR_HSERDYÌ65536Ö0 +RCC_CR_HSICALÌ65536Ö0 +RCC_CR_HSICAL_0Ì65536Ö0 +RCC_CR_HSICAL_1Ì65536Ö0 +RCC_CR_HSICAL_2Ì65536Ö0 +RCC_CR_HSICAL_3Ì65536Ö0 +RCC_CR_HSICAL_4Ì65536Ö0 +RCC_CR_HSICAL_5Ì65536Ö0 +RCC_CR_HSICAL_6Ì65536Ö0 +RCC_CR_HSICAL_7Ì65536Ö0 +RCC_CR_HSIONÌ65536Ö0 +RCC_CR_HSIRDYÌ65536Ö0 +RCC_CR_HSITRIMÌ65536Ö0 +RCC_CR_HSITRIM_0Ì65536Ö0 +RCC_CR_HSITRIM_1Ì65536Ö0 +RCC_CR_HSITRIM_2Ì65536Ö0 +RCC_CR_HSITRIM_3Ì65536Ö0 +RCC_CR_HSITRIM_4Ì65536Ö0 +RCC_CR_PLLONÌ65536Ö0 +RCC_CR_PLLRDYÌ65536Ö0 +RCC_CSR_IWDGRSTFÌ65536Ö0 +RCC_CSR_LPWRRSTFÌ65536Ö0 +RCC_CSR_LSIONÌ65536Ö0 +RCC_CSR_LSIRDYÌ65536Ö0 +RCC_CSR_OBLÌ65536Ö0 +RCC_CSR_OBLRSTFÌ65536Ö0 +RCC_CSR_PINRSTFÌ65536Ö0 +RCC_CSR_PORRSTFÌ65536Ö0 +RCC_CSR_RMVFÌ65536Ö0 +RCC_CSR_SFTRSTFÌ65536Ö0 +RCC_CSR_V18PWRRSTFÌ65536Ö0 +RCC_CSR_WWDGRSTFÌ65536Ö0 +READ_BITÌ131072Í(REG,BIT)Ö0 +READ_REGÌ131072Í(REG)Ö0 +RTCÌ65536Ö0 +RTC_ALRMAR_DTÌ65536Ö0 +RTC_ALRMAR_DT_0Ì65536Ö0 +RTC_ALRMAR_DT_1Ì65536Ö0 +RTC_ALRMAR_DUÌ65536Ö0 +RTC_ALRMAR_DU_0Ì65536Ö0 +RTC_ALRMAR_DU_1Ì65536Ö0 +RTC_ALRMAR_DU_2Ì65536Ö0 +RTC_ALRMAR_DU_3Ì65536Ö0 +RTC_ALRMAR_HTÌ65536Ö0 +RTC_ALRMAR_HT_0Ì65536Ö0 +RTC_ALRMAR_HT_1Ì65536Ö0 +RTC_ALRMAR_HUÌ65536Ö0 +RTC_ALRMAR_HU_0Ì65536Ö0 +RTC_ALRMAR_HU_1Ì65536Ö0 +RTC_ALRMAR_HU_2Ì65536Ö0 +RTC_ALRMAR_HU_3Ì65536Ö0 +RTC_ALRMAR_MNTÌ65536Ö0 +RTC_ALRMAR_MNT_0Ì65536Ö0 +RTC_ALRMAR_MNT_1Ì65536Ö0 +RTC_ALRMAR_MNT_2Ì65536Ö0 +RTC_ALRMAR_MNUÌ65536Ö0 +RTC_ALRMAR_MNU_0Ì65536Ö0 +RTC_ALRMAR_MNU_1Ì65536Ö0 +RTC_ALRMAR_MNU_2Ì65536Ö0 +RTC_ALRMAR_MNU_3Ì65536Ö0 +RTC_ALRMAR_MSK1Ì65536Ö0 +RTC_ALRMAR_MSK2Ì65536Ö0 +RTC_ALRMAR_MSK3Ì65536Ö0 +RTC_ALRMAR_MSK4Ì65536Ö0 +RTC_ALRMAR_PMÌ65536Ö0 +RTC_ALRMAR_STÌ65536Ö0 +RTC_ALRMAR_ST_0Ì65536Ö0 +RTC_ALRMAR_ST_1Ì65536Ö0 +RTC_ALRMAR_ST_2Ì65536Ö0 +RTC_ALRMAR_SUÌ65536Ö0 +RTC_ALRMAR_SU_0Ì65536Ö0 +RTC_ALRMAR_SU_1Ì65536Ö0 +RTC_ALRMAR_SU_2Ì65536Ö0 +RTC_ALRMAR_SU_3Ì65536Ö0 +RTC_ALRMAR_WDSELÌ65536Ö0 +RTC_ALRMASSR_MASKSSÌ65536Ö0 +RTC_ALRMASSR_MASKSS_0Ì65536Ö0 +RTC_ALRMASSR_MASKSS_1Ì65536Ö0 +RTC_ALRMASSR_MASKSS_2Ì65536Ö0 +RTC_ALRMASSR_MASKSS_3Ì65536Ö0 +RTC_ALRMASSR_SSÌ65536Ö0 +RTC_BASEÌ65536Ö0 +RTC_CALR_CALMÌ65536Ö0 +RTC_CALR_CALM_0Ì65536Ö0 +RTC_CALR_CALM_1Ì65536Ö0 +RTC_CALR_CALM_2Ì65536Ö0 +RTC_CALR_CALM_3Ì65536Ö0 +RTC_CALR_CALM_4Ì65536Ö0 +RTC_CALR_CALM_5Ì65536Ö0 +RTC_CALR_CALM_6Ì65536Ö0 +RTC_CALR_CALM_7Ì65536Ö0 +RTC_CALR_CALM_8Ì65536Ö0 +RTC_CALR_CALPÌ65536Ö0 +RTC_CALR_CALW16Ì65536Ö0 +RTC_CALR_CALW8Ì65536Ö0 +RTC_CR_ADD1HÌ65536Ö0 +RTC_CR_ALRAEÌ65536Ö0 +RTC_CR_ALRAIEÌ65536Ö0 +RTC_CR_BCKÌ65536Ö0 +RTC_CR_BYPSHADÌ65536Ö0 +RTC_CR_COEÌ65536Ö0 +RTC_CR_COSELÌ65536Ö0 +RTC_CR_FMTÌ65536Ö0 +RTC_CR_OSELÌ65536Ö0 +RTC_CR_OSEL_0Ì65536Ö0 +RTC_CR_OSEL_1Ì65536Ö0 +RTC_CR_POLÌ65536Ö0 +RTC_CR_REFCKONÌ65536Ö0 +RTC_CR_SUB1HÌ65536Ö0 +RTC_CR_TSEÌ65536Ö0 +RTC_CR_TSEDGEÌ65536Ö0 +RTC_CR_TSIEÌ65536Ö0 +RTC_DR_DTÌ65536Ö0 +RTC_DR_DT_0Ì65536Ö0 +RTC_DR_DT_1Ì65536Ö0 +RTC_DR_DUÌ65536Ö0 +RTC_DR_DU_0Ì65536Ö0 +RTC_DR_DU_1Ì65536Ö0 +RTC_DR_DU_2Ì65536Ö0 +RTC_DR_DU_3Ì65536Ö0 +RTC_DR_MTÌ65536Ö0 +RTC_DR_MUÌ65536Ö0 +RTC_DR_MU_0Ì65536Ö0 +RTC_DR_MU_1Ì65536Ö0 +RTC_DR_MU_2Ì65536Ö0 +RTC_DR_MU_3Ì65536Ö0 +RTC_DR_WDUÌ65536Ö0 +RTC_DR_WDU_0Ì65536Ö0 +RTC_DR_WDU_1Ì65536Ö0 +RTC_DR_WDU_2Ì65536Ö0 +RTC_DR_YTÌ65536Ö0 +RTC_DR_YT_0Ì65536Ö0 +RTC_DR_YT_1Ì65536Ö0 +RTC_DR_YT_2Ì65536Ö0 +RTC_DR_YT_3Ì65536Ö0 +RTC_DR_YUÌ65536Ö0 +RTC_DR_YU_0Ì65536Ö0 +RTC_DR_YU_1Ì65536Ö0 +RTC_DR_YU_2Ì65536Ö0 +RTC_DR_YU_3Ì65536Ö0 +RTC_ISR_ALRAFÌ65536Ö0 +RTC_ISR_ALRAWFÌ65536Ö0 +RTC_ISR_INITÌ65536Ö0 +RTC_ISR_INITFÌ65536Ö0 +RTC_ISR_INITSÌ65536Ö0 +RTC_ISR_RECALPFÌ65536Ö0 +RTC_ISR_RSFÌ65536Ö0 +RTC_ISR_SHPFÌ65536Ö0 +RTC_ISR_TAMP1FÌ65536Ö0 +RTC_ISR_TAMP2FÌ65536Ö0 +RTC_ISR_TSFÌ65536Ö0 +RTC_ISR_TSOVFÌ65536Ö0 +RTC_PRER_PREDIV_AÌ65536Ö0 +RTC_PRER_PREDIV_SÌ65536Ö0 +RTC_SHIFTR_ADD1SÌ65536Ö0 +RTC_SHIFTR_SUBFSÌ65536Ö0 +RTC_SSR_SSÌ65536Ö0 +RTC_TAFCR_ALARMOUTTYPEÌ65536Ö0 +RTC_TAFCR_TAMP1EÌ65536Ö0 +RTC_TAFCR_TAMP1TRGÌ65536Ö0 +RTC_TAFCR_TAMP2EÌ65536Ö0 +RTC_TAFCR_TAMP2TRGÌ65536Ö0 +RTC_TAFCR_TAMPFLTÌ65536Ö0 +RTC_TAFCR_TAMPFLT_0Ì65536Ö0 +RTC_TAFCR_TAMPFLT_1Ì65536Ö0 +RTC_TAFCR_TAMPFREQÌ65536Ö0 +RTC_TAFCR_TAMPFREQ_0Ì65536Ö0 +RTC_TAFCR_TAMPFREQ_1Ì65536Ö0 +RTC_TAFCR_TAMPFREQ_2Ì65536Ö0 +RTC_TAFCR_TAMPIEÌ65536Ö0 +RTC_TAFCR_TAMPPRCHÌ65536Ö0 +RTC_TAFCR_TAMPPRCH_0Ì65536Ö0 +RTC_TAFCR_TAMPPRCH_1Ì65536Ö0 +RTC_TAFCR_TAMPPUDISÌ65536Ö0 +RTC_TAFCR_TAMPTSÌ65536Ö0 +RTC_TR_HTÌ65536Ö0 +RTC_TR_HT_0Ì65536Ö0 +RTC_TR_HT_1Ì65536Ö0 +RTC_TR_HUÌ65536Ö0 +RTC_TR_HU_0Ì65536Ö0 +RTC_TR_HU_1Ì65536Ö0 +RTC_TR_HU_2Ì65536Ö0 +RTC_TR_HU_3Ì65536Ö0 +RTC_TR_MNTÌ65536Ö0 +RTC_TR_MNT_0Ì65536Ö0 +RTC_TR_MNT_1Ì65536Ö0 +RTC_TR_MNT_2Ì65536Ö0 +RTC_TR_MNUÌ65536Ö0 +RTC_TR_MNU_0Ì65536Ö0 +RTC_TR_MNU_1Ì65536Ö0 +RTC_TR_MNU_2Ì65536Ö0 +RTC_TR_MNU_3Ì65536Ö0 +RTC_TR_PMÌ65536Ö0 +RTC_TR_STÌ65536Ö0 +RTC_TR_ST_0Ì65536Ö0 +RTC_TR_ST_1Ì65536Ö0 +RTC_TR_ST_2Ì65536Ö0 +RTC_TR_SUÌ65536Ö0 +RTC_TR_SU_0Ì65536Ö0 +RTC_TR_SU_1Ì65536Ö0 +RTC_TR_SU_2Ì65536Ö0 +RTC_TR_SU_3Ì65536Ö0 +RTC_TSDR_DTÌ65536Ö0 +RTC_TSDR_DT_0Ì65536Ö0 +RTC_TSDR_DT_1Ì65536Ö0 +RTC_TSDR_DUÌ65536Ö0 +RTC_TSDR_DU_0Ì65536Ö0 +RTC_TSDR_DU_1Ì65536Ö0 +RTC_TSDR_DU_2Ì65536Ö0 +RTC_TSDR_DU_3Ì65536Ö0 +RTC_TSDR_MTÌ65536Ö0 +RTC_TSDR_MUÌ65536Ö0 +RTC_TSDR_MU_0Ì65536Ö0 +RTC_TSDR_MU_1Ì65536Ö0 +RTC_TSDR_MU_2Ì65536Ö0 +RTC_TSDR_MU_3Ì65536Ö0 +RTC_TSDR_WDUÌ65536Ö0 +RTC_TSDR_WDU_0Ì65536Ö0 +RTC_TSDR_WDU_1Ì65536Ö0 +RTC_TSDR_WDU_2Ì65536Ö0 +RTC_TSSSR_SSÌ65536Ö0 +RTC_TSTR_HTÌ65536Ö0 +RTC_TSTR_HT_0Ì65536Ö0 +RTC_TSTR_HT_1Ì65536Ö0 +RTC_TSTR_HUÌ65536Ö0 +RTC_TSTR_HU_0Ì65536Ö0 +RTC_TSTR_HU_1Ì65536Ö0 +RTC_TSTR_HU_2Ì65536Ö0 +RTC_TSTR_HU_3Ì65536Ö0 +RTC_TSTR_MNTÌ65536Ö0 +RTC_TSTR_MNT_0Ì65536Ö0 +RTC_TSTR_MNT_1Ì65536Ö0 +RTC_TSTR_MNT_2Ì65536Ö0 +RTC_TSTR_MNUÌ65536Ö0 +RTC_TSTR_MNU_0Ì65536Ö0 +RTC_TSTR_MNU_1Ì65536Ö0 +RTC_TSTR_MNU_2Ì65536Ö0 +RTC_TSTR_MNU_3Ì65536Ö0 +RTC_TSTR_PMÌ65536Ö0 +RTC_TSTR_STÌ65536Ö0 +RTC_TSTR_ST_0Ì65536Ö0 +RTC_TSTR_ST_1Ì65536Ö0 +RTC_TSTR_ST_2Ì65536Ö0 +RTC_TSTR_SUÌ65536Ö0 +RTC_TSTR_SU_0Ì65536Ö0 +RTC_TSTR_SU_1Ì65536Ö0 +RTC_TSTR_SU_2Ì65536Ö0 +RTC_TSTR_SU_3Ì65536Ö0 +RTC_WPR_KEYÌ65536Ö0 +SCBÌ65536Ö0 +SCB_AIRCR_ENDIANESS_MskÌ65536Ö0 +SCB_AIRCR_ENDIANESS_PosÌ65536Ö0 +SCB_AIRCR_SYSRESETREQ_MskÌ65536Ö0 +SCB_AIRCR_SYSRESETREQ_PosÌ65536Ö0 +SCB_AIRCR_VECTCLRACTIVE_MskÌ65536Ö0 +SCB_AIRCR_VECTCLRACTIVE_PosÌ65536Ö0 +SCB_AIRCR_VECTKEYSTAT_MskÌ65536Ö0 +SCB_AIRCR_VECTKEYSTAT_PosÌ65536Ö0 +SCB_AIRCR_VECTKEY_MskÌ65536Ö0 +SCB_AIRCR_VECTKEY_PosÌ65536Ö0 +SCB_BASEÌ65536Ö0 +SCB_CCR_STKALIGN_MskÌ65536Ö0 +SCB_CCR_STKALIGN_PosÌ65536Ö0 +SCB_CCR_UNALIGN_TRP_MskÌ65536Ö0 +SCB_CCR_UNALIGN_TRP_PosÌ65536Ö0 +SCB_CPUID_ARCHITECTURE_MskÌ65536Ö0 +SCB_CPUID_ARCHITECTURE_PosÌ65536Ö0 +SCB_CPUID_IMPLEMENTER_MskÌ65536Ö0 +SCB_CPUID_IMPLEMENTER_PosÌ65536Ö0 +SCB_CPUID_PARTNO_MskÌ65536Ö0 +SCB_CPUID_PARTNO_PosÌ65536Ö0 +SCB_CPUID_REVISION_MskÌ65536Ö0 +SCB_CPUID_REVISION_PosÌ65536Ö0 +SCB_CPUID_VARIANT_MskÌ65536Ö0 +SCB_CPUID_VARIANT_PosÌ65536Ö0 +SCB_ICSR_ISRPENDING_MskÌ65536Ö0 +SCB_ICSR_ISRPENDING_PosÌ65536Ö0 +SCB_ICSR_ISRPREEMPT_MskÌ65536Ö0 +SCB_ICSR_ISRPREEMPT_PosÌ65536Ö0 +SCB_ICSR_NMIPENDSET_MskÌ65536Ö0 +SCB_ICSR_NMIPENDSET_PosÌ65536Ö0 +SCB_ICSR_PENDSTCLR_MskÌ65536Ö0 +SCB_ICSR_PENDSTCLR_PosÌ65536Ö0 +SCB_ICSR_PENDSTSET_MskÌ65536Ö0 +SCB_ICSR_PENDSTSET_PosÌ65536Ö0 +SCB_ICSR_PENDSVCLR_MskÌ65536Ö0 +SCB_ICSR_PENDSVCLR_PosÌ65536Ö0 +SCB_ICSR_PENDSVSET_MskÌ65536Ö0 +SCB_ICSR_PENDSVSET_PosÌ65536Ö0 +SCB_ICSR_VECTACTIVE_MskÌ65536Ö0 +SCB_ICSR_VECTACTIVE_PosÌ65536Ö0 +SCB_ICSR_VECTPENDING_MskÌ65536Ö0 +SCB_ICSR_VECTPENDING_PosÌ65536Ö0 +SCB_SCR_SEVONPEND_MskÌ65536Ö0 +SCB_SCR_SEVONPEND_PosÌ65536Ö0 +SCB_SCR_SLEEPDEEP_MskÌ65536Ö0 +SCB_SCR_SLEEPDEEP_PosÌ65536Ö0 +SCB_SCR_SLEEPONEXIT_MskÌ65536Ö0 +SCB_SCR_SLEEPONEXIT_PosÌ65536Ö0 +SCB_SHCSR_SVCALLPENDED_MskÌ65536Ö0 +SCB_SHCSR_SVCALLPENDED_PosÌ65536Ö0 +SCS_BASEÌ65536Ö0 +SET_BITÌ131072Í(REG,BIT)Ö0 +SIG_ATOMIC_MAXÌ65536Ö0 +SIG_ATOMIC_MINÌ65536Ö0 +SIG_ATOMIC_WIDTHÌ65536Ö0 +SIZE_MAXÌ65536Ö0 +SIZE_WIDTHÌ65536Ö0 +SPI1Ì65536Ö0 +SPI1_BASEÌ65536Ö0 +SPI_CR1_BIDIMODEÌ65536Ö0 +SPI_CR1_BIDIOEÌ65536Ö0 +SPI_CR1_BRÌ65536Ö0 +SPI_CR1_BR_0Ì65536Ö0 +SPI_CR1_BR_1Ì65536Ö0 +SPI_CR1_BR_2Ì65536Ö0 +SPI_CR1_CPHAÌ65536Ö0 +SPI_CR1_CPOLÌ65536Ö0 +SPI_CR1_CRCENÌ65536Ö0 +SPI_CR1_CRCLÌ65536Ö0 +SPI_CR1_CRCNEXTÌ65536Ö0 +SPI_CR1_LSBFIRSTÌ65536Ö0 +SPI_CR1_MSTRÌ65536Ö0 +SPI_CR1_RXONLYÌ65536Ö0 +SPI_CR1_SPEÌ65536Ö0 +SPI_CR1_SSIÌ65536Ö0 +SPI_CR1_SSMÌ65536Ö0 +SPI_CR2_DSÌ65536Ö0 +SPI_CR2_DS_0Ì65536Ö0 +SPI_CR2_DS_1Ì65536Ö0 +SPI_CR2_DS_2Ì65536Ö0 +SPI_CR2_DS_3Ì65536Ö0 +SPI_CR2_ERRIEÌ65536Ö0 +SPI_CR2_FRFÌ65536Ö0 +SPI_CR2_FRXTHÌ65536Ö0 +SPI_CR2_LDMARXÌ65536Ö0 +SPI_CR2_LDMATXÌ65536Ö0 +SPI_CR2_NSSPÌ65536Ö0 +SPI_CR2_RXDMAENÌ65536Ö0 +SPI_CR2_RXNEIEÌ65536Ö0 +SPI_CR2_SSOEÌ65536Ö0 +SPI_CR2_TXDMAENÌ65536Ö0 +SPI_CR2_TXEIEÌ65536Ö0 +SPI_CRCPR_CRCPOLYÌ65536Ö0 +SPI_DR_DRÌ65536Ö0 +SPI_I2SCFGR_CHLENÌ65536Ö0 +SPI_I2SCFGR_CKPOLÌ65536Ö0 +SPI_I2SCFGR_DATLENÌ65536Ö0 +SPI_I2SCFGR_DATLEN_0Ì65536Ö0 +SPI_I2SCFGR_DATLEN_1Ì65536Ö0 +SPI_I2SCFGR_I2SCFGÌ65536Ö0 +SPI_I2SCFGR_I2SCFG_0Ì65536Ö0 +SPI_I2SCFGR_I2SCFG_1Ì65536Ö0 +SPI_I2SCFGR_I2SEÌ65536Ö0 +SPI_I2SCFGR_I2SMODÌ65536Ö0 +SPI_I2SCFGR_I2SSTDÌ65536Ö0 +SPI_I2SCFGR_I2SSTD_0Ì65536Ö0 +SPI_I2SCFGR_I2SSTD_1Ì65536Ö0 +SPI_I2SCFGR_PCMSYNCÌ65536Ö0 +SPI_I2SPR_I2SDIVÌ65536Ö0 +SPI_I2SPR_MCKOEÌ65536Ö0 +SPI_I2SPR_ODDÌ65536Ö0 +SPI_RXCRCR_RXCRCÌ65536Ö0 +SPI_SR_BSYÌ65536Ö0 +SPI_SR_CHSIDEÌ65536Ö0 +SPI_SR_CRCERRÌ65536Ö0 +SPI_SR_FREÌ65536Ö0 +SPI_SR_FRLVLÌ65536Ö0 +SPI_SR_FRLVL_0Ì65536Ö0 +SPI_SR_FRLVL_1Ì65536Ö0 +SPI_SR_FTLVLÌ65536Ö0 +SPI_SR_FTLVL_0Ì65536Ö0 +SPI_SR_FTLVL_1Ì65536Ö0 +SPI_SR_MODFÌ65536Ö0 +SPI_SR_OVRÌ65536Ö0 +SPI_SR_RXNEÌ65536Ö0 +SPI_SR_TXEÌ65536Ö0 +SPI_SR_UDRÌ65536Ö0 +SPI_TXCRCR_TXCRCÌ65536Ö0 +SRAM_BASEÌ65536Ö0 +STM32F030x6Ì65536Ö0 +SYSCFGÌ65536Ö0 +SYSCFG_BASEÌ65536Ö0 +SYSCFG_CFGR1_ADC_DMA_RMPÌ65536Ö0 +SYSCFG_CFGR1_DMA_RMPÌ65536Ö0 +SYSCFG_CFGR1_I2C_FMP_I2C1Ì65536Ö0 +SYSCFG_CFGR1_I2C_FMP_PA10Ì65536Ö0 +SYSCFG_CFGR1_I2C_FMP_PA9Ì65536Ö0 +SYSCFG_CFGR1_I2C_FMP_PB6Ì65536Ö0 +SYSCFG_CFGR1_I2C_FMP_PB7Ì65536Ö0 +SYSCFG_CFGR1_I2C_FMP_PB8Ì65536Ö0 +SYSCFG_CFGR1_I2C_FMP_PB9Ì65536Ö0 +SYSCFG_CFGR1_MEM_MODEÌ65536Ö0 +SYSCFG_CFGR1_MEM_MODE_0Ì65536Ö0 +SYSCFG_CFGR1_MEM_MODE_1Ì65536Ö0 +SYSCFG_CFGR1_TIM16_DMA_RMPÌ65536Ö0 +SYSCFG_CFGR1_TIM17_DMA_RMPÌ65536Ö0 +SYSCFG_CFGR1_USART1RX_DMA_RMPÌ65536Ö0 +SYSCFG_CFGR1_USART1TX_DMA_RMPÌ65536Ö0 +SYSCFG_CFGR2_LOCKUP_LOCKÌ65536Ö0 +SYSCFG_CFGR2_SRAM_PARITY_LOCKÌ65536Ö0 +SYSCFG_CFGR2_SRAM_PEÌ65536Ö0 +SYSCFG_CFGR2_SRAM_PEFÌ65536Ö0 +SYSCFG_EXTICR1_EXTI0Ì65536Ö0 +SYSCFG_EXTICR1_EXTI0_PAÌ65536Ö0 +SYSCFG_EXTICR1_EXTI0_PBÌ65536Ö0 +SYSCFG_EXTICR1_EXTI0_PCÌ65536Ö0 +SYSCFG_EXTICR1_EXTI0_PDÌ65536Ö0 +SYSCFG_EXTICR1_EXTI0_PFÌ65536Ö0 +SYSCFG_EXTICR1_EXTI1Ì65536Ö0 +SYSCFG_EXTICR1_EXTI1_PAÌ65536Ö0 +SYSCFG_EXTICR1_EXTI1_PBÌ65536Ö0 +SYSCFG_EXTICR1_EXTI1_PCÌ65536Ö0 +SYSCFG_EXTICR1_EXTI1_PDÌ65536Ö0 +SYSCFG_EXTICR1_EXTI1_PFÌ65536Ö0 +SYSCFG_EXTICR1_EXTI2Ì65536Ö0 +SYSCFG_EXTICR1_EXTI2_PAÌ65536Ö0 +SYSCFG_EXTICR1_EXTI2_PBÌ65536Ö0 +SYSCFG_EXTICR1_EXTI2_PCÌ65536Ö0 +SYSCFG_EXTICR1_EXTI2_PDÌ65536Ö0 +SYSCFG_EXTICR1_EXTI2_PFÌ65536Ö0 +SYSCFG_EXTICR1_EXTI3Ì65536Ö0 +SYSCFG_EXTICR1_EXTI3_PAÌ65536Ö0 +SYSCFG_EXTICR1_EXTI3_PBÌ65536Ö0 +SYSCFG_EXTICR1_EXTI3_PCÌ65536Ö0 +SYSCFG_EXTICR1_EXTI3_PDÌ65536Ö0 +SYSCFG_EXTICR1_EXTI3_PFÌ65536Ö0 +SYSCFG_EXTICR2_EXTI4Ì65536Ö0 +SYSCFG_EXTICR2_EXTI4_PAÌ65536Ö0 +SYSCFG_EXTICR2_EXTI4_PBÌ65536Ö0 +SYSCFG_EXTICR2_EXTI4_PCÌ65536Ö0 +SYSCFG_EXTICR2_EXTI4_PDÌ65536Ö0 +SYSCFG_EXTICR2_EXTI4_PFÌ65536Ö0 +SYSCFG_EXTICR2_EXTI5Ì65536Ö0 +SYSCFG_EXTICR2_EXTI5_PAÌ65536Ö0 +SYSCFG_EXTICR2_EXTI5_PBÌ65536Ö0 +SYSCFG_EXTICR2_EXTI5_PCÌ65536Ö0 +SYSCFG_EXTICR2_EXTI5_PDÌ65536Ö0 +SYSCFG_EXTICR2_EXTI5_PFÌ65536Ö0 +SYSCFG_EXTICR2_EXTI6Ì65536Ö0 +SYSCFG_EXTICR2_EXTI6_PAÌ65536Ö0 +SYSCFG_EXTICR2_EXTI6_PBÌ65536Ö0 +SYSCFG_EXTICR2_EXTI6_PCÌ65536Ö0 +SYSCFG_EXTICR2_EXTI6_PDÌ65536Ö0 +SYSCFG_EXTICR2_EXTI6_PFÌ65536Ö0 +SYSCFG_EXTICR2_EXTI7Ì65536Ö0 +SYSCFG_EXTICR2_EXTI7_PAÌ65536Ö0 +SYSCFG_EXTICR2_EXTI7_PBÌ65536Ö0 +SYSCFG_EXTICR2_EXTI7_PCÌ65536Ö0 +SYSCFG_EXTICR2_EXTI7_PDÌ65536Ö0 +SYSCFG_EXTICR2_EXTI7_PFÌ65536Ö0 +SYSCFG_EXTICR3_EXTI10Ì65536Ö0 +SYSCFG_EXTICR3_EXTI10_PAÌ65536Ö0 +SYSCFG_EXTICR3_EXTI10_PBÌ65536Ö0 +SYSCFG_EXTICR3_EXTI10_PCÌ65536Ö0 +SYSCFG_EXTICR3_EXTI10_PDÌ65536Ö0 +SYSCFG_EXTICR3_EXTI10_PFÌ65536Ö0 +SYSCFG_EXTICR3_EXTI11Ì65536Ö0 +SYSCFG_EXTICR3_EXTI11_PAÌ65536Ö0 +SYSCFG_EXTICR3_EXTI11_PBÌ65536Ö0 +SYSCFG_EXTICR3_EXTI11_PCÌ65536Ö0 +SYSCFG_EXTICR3_EXTI11_PDÌ65536Ö0 +SYSCFG_EXTICR3_EXTI11_PFÌ65536Ö0 +SYSCFG_EXTICR3_EXTI8Ì65536Ö0 +SYSCFG_EXTICR3_EXTI8_PAÌ65536Ö0 +SYSCFG_EXTICR3_EXTI8_PBÌ65536Ö0 +SYSCFG_EXTICR3_EXTI8_PCÌ65536Ö0 +SYSCFG_EXTICR3_EXTI8_PDÌ65536Ö0 +SYSCFG_EXTICR3_EXTI8_PFÌ65536Ö0 +SYSCFG_EXTICR3_EXTI9Ì65536Ö0 +SYSCFG_EXTICR3_EXTI9_PAÌ65536Ö0 +SYSCFG_EXTICR3_EXTI9_PBÌ65536Ö0 +SYSCFG_EXTICR3_EXTI9_PCÌ65536Ö0 +SYSCFG_EXTICR3_EXTI9_PDÌ65536Ö0 +SYSCFG_EXTICR3_EXTI9_PFÌ65536Ö0 +SYSCFG_EXTICR4_EXTI12Ì65536Ö0 +SYSCFG_EXTICR4_EXTI12_PAÌ65536Ö0 +SYSCFG_EXTICR4_EXTI12_PBÌ65536Ö0 +SYSCFG_EXTICR4_EXTI12_PCÌ65536Ö0 +SYSCFG_EXTICR4_EXTI12_PDÌ65536Ö0 +SYSCFG_EXTICR4_EXTI12_PFÌ65536Ö0 +SYSCFG_EXTICR4_EXTI13Ì65536Ö0 +SYSCFG_EXTICR4_EXTI13_PAÌ65536Ö0 +SYSCFG_EXTICR4_EXTI13_PBÌ65536Ö0 +SYSCFG_EXTICR4_EXTI13_PCÌ65536Ö0 +SYSCFG_EXTICR4_EXTI13_PDÌ65536Ö0 +SYSCFG_EXTICR4_EXTI13_PFÌ65536Ö0 +SYSCFG_EXTICR4_EXTI14Ì65536Ö0 +SYSCFG_EXTICR4_EXTI14_PAÌ65536Ö0 +SYSCFG_EXTICR4_EXTI14_PBÌ65536Ö0 +SYSCFG_EXTICR4_EXTI14_PCÌ65536Ö0 +SYSCFG_EXTICR4_EXTI14_PDÌ65536Ö0 +SYSCFG_EXTICR4_EXTI14_PFÌ65536Ö0 +SYSCFG_EXTICR4_EXTI15Ì65536Ö0 +SYSCFG_EXTICR4_EXTI15_PAÌ65536Ö0 +SYSCFG_EXTICR4_EXTI15_PBÌ65536Ö0 +SYSCFG_EXTICR4_EXTI15_PCÌ65536Ö0 +SYSCFG_EXTICR4_EXTI15_PDÌ65536Ö0 +SYSCFG_EXTICR4_EXTI15_PFÌ65536Ö0 +StartHSEÌ16Í()Ö0Ïinline void +SysTickÌ65536Ö0 +SysTick_BASEÌ65536Ö0 +SysTick_CALIB_NOREF_MskÌ65536Ö0 +SysTick_CALIB_NOREF_PosÌ65536Ö0 +SysTick_CALIB_SKEW_MskÌ65536Ö0 +SysTick_CALIB_SKEW_PosÌ65536Ö0 +SysTick_CALIB_TENMS_MskÌ65536Ö0 +SysTick_CALIB_TENMS_PosÌ65536Ö0 +SysTick_CTRL_CLKSOURCE_MskÌ65536Ö0 +SysTick_CTRL_CLKSOURCE_PosÌ65536Ö0 +SysTick_CTRL_COUNTFLAG_MskÌ65536Ö0 +SysTick_CTRL_COUNTFLAG_PosÌ65536Ö0 +SysTick_CTRL_ENABLE_MskÌ65536Ö0 +SysTick_CTRL_ENABLE_PosÌ65536Ö0 +SysTick_CTRL_TICKINT_MskÌ65536Ö0 +SysTick_CTRL_TICKINT_PosÌ65536Ö0 +SysTick_LOAD_RELOAD_MskÌ65536Ö0 +SysTick_LOAD_RELOAD_PosÌ65536Ö0 +SysTick_VAL_CURRENT_MskÌ65536Ö0 +SysTick_VAL_CURRENT_PosÌ65536Ö0 +TEMP110_CAL_ADDRÌ65536Ö0 +TEMP30_CAL_ADDRÌ65536Ö0 +TIM1Ì65536Ö0 +TIM14Ì65536Ö0 +TIM14_BASEÌ65536Ö0 +TIM14_OR_TI1_RMPÌ65536Ö0 +TIM14_OR_TI1_RMP_0Ì65536Ö0 +TIM14_OR_TI1_RMP_1Ì65536Ö0 +TIM16Ì65536Ö0 +TIM16_BASEÌ65536Ö0 +TIM17Ì65536Ö0 +TIM17_BASEÌ65536Ö0 +TIM1_BASEÌ65536Ö0 +TIM3Ì65536Ö0 +TIM3_BASEÌ65536Ö0 +TIM6_DAC_IRQHandlerÌ65536Ö0 +TIM6_DAC_IRQnÌ65536Ö0 +TIM_ARR_ARRÌ65536Ö0 +TIM_BDTR_AOEÌ65536Ö0 +TIM_BDTR_BKEÌ65536Ö0 +TIM_BDTR_BKPÌ65536Ö0 +TIM_BDTR_DTGÌ65536Ö0 +TIM_BDTR_DTG_0Ì65536Ö0 +TIM_BDTR_DTG_1Ì65536Ö0 +TIM_BDTR_DTG_2Ì65536Ö0 +TIM_BDTR_DTG_3Ì65536Ö0 +TIM_BDTR_DTG_4Ì65536Ö0 +TIM_BDTR_DTG_5Ì65536Ö0 +TIM_BDTR_DTG_6Ì65536Ö0 +TIM_BDTR_DTG_7Ì65536Ö0 +TIM_BDTR_LOCKÌ65536Ö0 +TIM_BDTR_LOCK_0Ì65536Ö0 +TIM_BDTR_LOCK_1Ì65536Ö0 +TIM_BDTR_MOEÌ65536Ö0 +TIM_BDTR_OSSIÌ65536Ö0 +TIM_BDTR_OSSRÌ65536Ö0 +TIM_CCER_CC1EÌ65536Ö0 +TIM_CCER_CC1NEÌ65536Ö0 +TIM_CCER_CC1NPÌ65536Ö0 +TIM_CCER_CC1PÌ65536Ö0 +TIM_CCER_CC2EÌ65536Ö0 +TIM_CCER_CC2NEÌ65536Ö0 +TIM_CCER_CC2NPÌ65536Ö0 +TIM_CCER_CC2PÌ65536Ö0 +TIM_CCER_CC3EÌ65536Ö0 +TIM_CCER_CC3NEÌ65536Ö0 +TIM_CCER_CC3NPÌ65536Ö0 +TIM_CCER_CC3PÌ65536Ö0 +TIM_CCER_CC4EÌ65536Ö0 +TIM_CCER_CC4NPÌ65536Ö0 +TIM_CCER_CC4PÌ65536Ö0 +TIM_CCMR1_CC1SÌ65536Ö0 +TIM_CCMR1_CC1S_0Ì65536Ö0 +TIM_CCMR1_CC1S_1Ì65536Ö0 +TIM_CCMR1_CC2SÌ65536Ö0 +TIM_CCMR1_CC2S_0Ì65536Ö0 +TIM_CCMR1_CC2S_1Ì65536Ö0 +TIM_CCMR1_IC1FÌ65536Ö0 +TIM_CCMR1_IC1F_0Ì65536Ö0 +TIM_CCMR1_IC1F_1Ì65536Ö0 +TIM_CCMR1_IC1F_2Ì65536Ö0 +TIM_CCMR1_IC1F_3Ì65536Ö0 +TIM_CCMR1_IC1PSCÌ65536Ö0 +TIM_CCMR1_IC1PSC_0Ì65536Ö0 +TIM_CCMR1_IC1PSC_1Ì65536Ö0 +TIM_CCMR1_IC2FÌ65536Ö0 +TIM_CCMR1_IC2F_0Ì65536Ö0 +TIM_CCMR1_IC2F_1Ì65536Ö0 +TIM_CCMR1_IC2F_2Ì65536Ö0 +TIM_CCMR1_IC2F_3Ì65536Ö0 +TIM_CCMR1_IC2PSCÌ65536Ö0 +TIM_CCMR1_IC2PSC_0Ì65536Ö0 +TIM_CCMR1_IC2PSC_1Ì65536Ö0 +TIM_CCMR1_OC1CEÌ65536Ö0 +TIM_CCMR1_OC1FEÌ65536Ö0 +TIM_CCMR1_OC1MÌ65536Ö0 +TIM_CCMR1_OC1M_0Ì65536Ö0 +TIM_CCMR1_OC1M_1Ì65536Ö0 +TIM_CCMR1_OC1M_2Ì65536Ö0 +TIM_CCMR1_OC1PEÌ65536Ö0 +TIM_CCMR1_OC2CEÌ65536Ö0 +TIM_CCMR1_OC2FEÌ65536Ö0 +TIM_CCMR1_OC2MÌ65536Ö0 +TIM_CCMR1_OC2M_0Ì65536Ö0 +TIM_CCMR1_OC2M_1Ì65536Ö0 +TIM_CCMR1_OC2M_2Ì65536Ö0 +TIM_CCMR1_OC2PEÌ65536Ö0 +TIM_CCMR2_CC3SÌ65536Ö0 +TIM_CCMR2_CC3S_0Ì65536Ö0 +TIM_CCMR2_CC3S_1Ì65536Ö0 +TIM_CCMR2_CC4SÌ65536Ö0 +TIM_CCMR2_CC4S_0Ì65536Ö0 +TIM_CCMR2_CC4S_1Ì65536Ö0 +TIM_CCMR2_IC3FÌ65536Ö0 +TIM_CCMR2_IC3F_0Ì65536Ö0 +TIM_CCMR2_IC3F_1Ì65536Ö0 +TIM_CCMR2_IC3F_2Ì65536Ö0 +TIM_CCMR2_IC3F_3Ì65536Ö0 +TIM_CCMR2_IC3PSCÌ65536Ö0 +TIM_CCMR2_IC3PSC_0Ì65536Ö0 +TIM_CCMR2_IC3PSC_1Ì65536Ö0 +TIM_CCMR2_IC4FÌ65536Ö0 +TIM_CCMR2_IC4F_0Ì65536Ö0 +TIM_CCMR2_IC4F_1Ì65536Ö0 +TIM_CCMR2_IC4F_2Ì65536Ö0 +TIM_CCMR2_IC4F_3Ì65536Ö0 +TIM_CCMR2_IC4PSCÌ65536Ö0 +TIM_CCMR2_IC4PSC_0Ì65536Ö0 +TIM_CCMR2_IC4PSC_1Ì65536Ö0 +TIM_CCMR2_OC3CEÌ65536Ö0 +TIM_CCMR2_OC3FEÌ65536Ö0 +TIM_CCMR2_OC3MÌ65536Ö0 +TIM_CCMR2_OC3M_0Ì65536Ö0 +TIM_CCMR2_OC3M_1Ì65536Ö0 +TIM_CCMR2_OC3M_2Ì65536Ö0 +TIM_CCMR2_OC3PEÌ65536Ö0 +TIM_CCMR2_OC4CEÌ65536Ö0 +TIM_CCMR2_OC4FEÌ65536Ö0 +TIM_CCMR2_OC4MÌ65536Ö0 +TIM_CCMR2_OC4M_0Ì65536Ö0 +TIM_CCMR2_OC4M_1Ì65536Ö0 +TIM_CCMR2_OC4M_2Ì65536Ö0 +TIM_CCMR2_OC4PEÌ65536Ö0 +TIM_CCR1_CCR1Ì65536Ö0 +TIM_CCR2_CCR2Ì65536Ö0 +TIM_CCR3_CCR3Ì65536Ö0 +TIM_CCR4_CCR4Ì65536Ö0 +TIM_CNT_CNTÌ65536Ö0 +TIM_CR1_ARPEÌ65536Ö0 +TIM_CR1_CENÌ65536Ö0 +TIM_CR1_CKDÌ65536Ö0 +TIM_CR1_CKD_0Ì65536Ö0 +TIM_CR1_CKD_1Ì65536Ö0 +TIM_CR1_CMSÌ65536Ö0 +TIM_CR1_CMS_0Ì65536Ö0 +TIM_CR1_CMS_1Ì65536Ö0 +TIM_CR1_DIRÌ65536Ö0 +TIM_CR1_OPMÌ65536Ö0 +TIM_CR1_UDISÌ65536Ö0 +TIM_CR1_URSÌ65536Ö0 +TIM_CR2_CCDSÌ65536Ö0 +TIM_CR2_CCPCÌ65536Ö0 +TIM_CR2_CCUSÌ65536Ö0 +TIM_CR2_MMSÌ65536Ö0 +TIM_CR2_MMS_0Ì65536Ö0 +TIM_CR2_MMS_1Ì65536Ö0 +TIM_CR2_MMS_2Ì65536Ö0 +TIM_CR2_OIS1Ì65536Ö0 +TIM_CR2_OIS1NÌ65536Ö0 +TIM_CR2_OIS2Ì65536Ö0 +TIM_CR2_OIS2NÌ65536Ö0 +TIM_CR2_OIS3Ì65536Ö0 +TIM_CR2_OIS3NÌ65536Ö0 +TIM_CR2_OIS4Ì65536Ö0 +TIM_CR2_TI1SÌ65536Ö0 +TIM_DCR_DBAÌ65536Ö0 +TIM_DCR_DBA_0Ì65536Ö0 +TIM_DCR_DBA_1Ì65536Ö0 +TIM_DCR_DBA_2Ì65536Ö0 +TIM_DCR_DBA_3Ì65536Ö0 +TIM_DCR_DBA_4Ì65536Ö0 +TIM_DCR_DBLÌ65536Ö0 +TIM_DCR_DBL_0Ì65536Ö0 +TIM_DCR_DBL_1Ì65536Ö0 +TIM_DCR_DBL_2Ì65536Ö0 +TIM_DCR_DBL_3Ì65536Ö0 +TIM_DCR_DBL_4Ì65536Ö0 +TIM_DIER_BIEÌ65536Ö0 +TIM_DIER_CC1DEÌ65536Ö0 +TIM_DIER_CC1IEÌ65536Ö0 +TIM_DIER_CC2DEÌ65536Ö0 +TIM_DIER_CC2IEÌ65536Ö0 +TIM_DIER_CC3DEÌ65536Ö0 +TIM_DIER_CC3IEÌ65536Ö0 +TIM_DIER_CC4DEÌ65536Ö0 +TIM_DIER_CC4IEÌ65536Ö0 +TIM_DIER_COMDEÌ65536Ö0 +TIM_DIER_COMIEÌ65536Ö0 +TIM_DIER_TDEÌ65536Ö0 +TIM_DIER_TIEÌ65536Ö0 +TIM_DIER_UDEÌ65536Ö0 +TIM_DIER_UIEÌ65536Ö0 +TIM_DMAR_DMABÌ65536Ö0 +TIM_EGR_BGÌ65536Ö0 +TIM_EGR_CC1GÌ65536Ö0 +TIM_EGR_CC2GÌ65536Ö0 +TIM_EGR_CC3GÌ65536Ö0 +TIM_EGR_CC4GÌ65536Ö0 +TIM_EGR_COMGÌ65536Ö0 +TIM_EGR_TGÌ65536Ö0 +TIM_EGR_UGÌ65536Ö0 +TIM_PSC_PSCÌ65536Ö0 +TIM_RCR_REPÌ65536Ö0 +TIM_SMCR_ECEÌ65536Ö0 +TIM_SMCR_ETFÌ65536Ö0 +TIM_SMCR_ETF_0Ì65536Ö0 +TIM_SMCR_ETF_1Ì65536Ö0 +TIM_SMCR_ETF_2Ì65536Ö0 +TIM_SMCR_ETF_3Ì65536Ö0 +TIM_SMCR_ETPÌ65536Ö0 +TIM_SMCR_ETPSÌ65536Ö0 +TIM_SMCR_ETPS_0Ì65536Ö0 +TIM_SMCR_ETPS_1Ì65536Ö0 +TIM_SMCR_MSMÌ65536Ö0 +TIM_SMCR_OCCSÌ65536Ö0 +TIM_SMCR_SMSÌ65536Ö0 +TIM_SMCR_SMS_0Ì65536Ö0 +TIM_SMCR_SMS_1Ì65536Ö0 +TIM_SMCR_SMS_2Ì65536Ö0 +TIM_SMCR_TSÌ65536Ö0 +TIM_SMCR_TS_0Ì65536Ö0 +TIM_SMCR_TS_1Ì65536Ö0 +TIM_SMCR_TS_2Ì65536Ö0 +TIM_SR_BIFÌ65536Ö0 +TIM_SR_CC1IFÌ65536Ö0 +TIM_SR_CC1OFÌ65536Ö0 +TIM_SR_CC2IFÌ65536Ö0 +TIM_SR_CC2OFÌ65536Ö0 +TIM_SR_CC3IFÌ65536Ö0 +TIM_SR_CC3OFÌ65536Ö0 +TIM_SR_CC4IFÌ65536Ö0 +TIM_SR_CC4OFÌ65536Ö0 +TIM_SR_COMIFÌ65536Ö0 +TIM_SR_TIFÌ65536Ö0 +TIM_SR_UIFÌ65536Ö0 +TRUE_INLINEÌ65536Ö0 +UINT16_CÌ131072Í(c)Ö0 +UINT16_MAXÌ65536Ö0 +UINT16_WIDTHÌ65536Ö0 +UINT32_CÌ131072Í(c)Ö0 +UINT32_MAXÌ65536Ö0 +UINT32_WIDTHÌ65536Ö0 +UINT64_CÌ131072Í(c)Ö0 +UINT64_MAXÌ65536Ö0 +UINT64_WIDTHÌ65536Ö0 +UINT8_CÌ131072Í(c)Ö0 +UINT8_MAXÌ65536Ö0 +UINT8_WIDTHÌ65536Ö0 +UINTMAX_CÌ131072Í(c)Ö0 +UINTMAX_MAXÌ65536Ö0 +UINTMAX_WIDTHÌ65536Ö0 +UINTPTR_MAXÌ65536Ö0 +UINTPTR_WIDTHÌ65536Ö0 +UINT_FAST16_MAXÌ65536Ö0 +UINT_FAST16_WIDTHÌ65536Ö0 +UINT_FAST32_MAXÌ65536Ö0 +UINT_FAST32_WIDTHÌ65536Ö0 +UINT_FAST64_MAXÌ65536Ö0 +UINT_FAST64_WIDTHÌ65536Ö0 +UINT_FAST8_MAXÌ65536Ö0 +UINT_FAST8_WIDTHÌ65536Ö0 +UINT_LEAST16_MAXÌ65536Ö0 +UINT_LEAST16_WIDTHÌ65536Ö0 +UINT_LEAST32_MAXÌ65536Ö0 +UINT_LEAST32_WIDTHÌ65536Ö0 +UINT_LEAST64_MAXÌ65536Ö0 +UINT_LEAST64_WIDTHÌ65536Ö0 +UINT_LEAST8_MAXÌ65536Ö0 +UINT_LEAST8_WIDTHÌ65536Ö0 +USART1Ì65536Ö0 +USART1_BASEÌ65536Ö0 +USART_BRR_DIV_FRACTIONÌ65536Ö0 +USART_BRR_DIV_MANTISSAÌ65536Ö0 +USART_CR1_CMIEÌ65536Ö0 +USART_CR1_DEATÌ65536Ö0 +USART_CR1_DEAT_0Ì65536Ö0 +USART_CR1_DEAT_1Ì65536Ö0 +USART_CR1_DEAT_2Ì65536Ö0 +USART_CR1_DEAT_3Ì65536Ö0 +USART_CR1_DEAT_4Ì65536Ö0 +USART_CR1_DEDTÌ65536Ö0 +USART_CR1_DEDT_0Ì65536Ö0 +USART_CR1_DEDT_1Ì65536Ö0 +USART_CR1_DEDT_2Ì65536Ö0 +USART_CR1_DEDT_3Ì65536Ö0 +USART_CR1_DEDT_4Ì65536Ö0 +USART_CR1_EOBIEÌ65536Ö0 +USART_CR1_IDLEIEÌ65536Ö0 +USART_CR1_MÌ65536Ö0 +USART_CR1_M0Ì65536Ö0 +USART_CR1_MMEÌ65536Ö0 +USART_CR1_OVER8Ì65536Ö0 +USART_CR1_PCEÌ65536Ö0 +USART_CR1_PEIEÌ65536Ö0 +USART_CR1_PSÌ65536Ö0 +USART_CR1_REÌ65536Ö0 +USART_CR1_RTOIEÌ65536Ö0 +USART_CR1_RXNEIEÌ65536Ö0 +USART_CR1_TCIEÌ65536Ö0 +USART_CR1_TEÌ65536Ö0 +USART_CR1_TXEIEÌ65536Ö0 +USART_CR1_UEÌ65536Ö0 +USART_CR1_UESMÌ65536Ö0 +USART_CR1_WAKEÌ65536Ö0 +USART_CR2_ABRENÌ65536Ö0 +USART_CR2_ABRMODEÌ65536Ö0 +USART_CR2_ABRMODE_0Ì65536Ö0 +USART_CR2_ABRMODE_1Ì65536Ö0 +USART_CR2_ADDÌ65536Ö0 +USART_CR2_ADDM7Ì65536Ö0 +USART_CR2_ADD_SHIFTÌ65536Ö0 +USART_CR2_ADD_VALÌ131072Í(x)Ö0 +USART_CR2_CLKENÌ65536Ö0 +USART_CR2_CPHAÌ65536Ö0 +USART_CR2_CPOLÌ65536Ö0 +USART_CR2_DATAINVÌ65536Ö0 +USART_CR2_LBCLÌ65536Ö0 +USART_CR2_LBDIEÌ65536Ö0 +USART_CR2_LBDLÌ65536Ö0 +USART_CR2_LINENÌ65536Ö0 +USART_CR2_MSBFIRSTÌ65536Ö0 +USART_CR2_RTOENÌ65536Ö0 +USART_CR2_RXINVÌ65536Ö0 +USART_CR2_STOPÌ65536Ö0 +USART_CR2_STOP_0Ì65536Ö0 +USART_CR2_STOP_1Ì65536Ö0 +USART_CR2_SWAPÌ65536Ö0 +USART_CR2_TXINVÌ65536Ö0 +USART_CR3_CTSEÌ65536Ö0 +USART_CR3_CTSIEÌ65536Ö0 +USART_CR3_DDREÌ65536Ö0 +USART_CR3_DEMÌ65536Ö0 +USART_CR3_DEPÌ65536Ö0 +USART_CR3_DMARÌ65536Ö0 +USART_CR3_DMATÌ65536Ö0 +USART_CR3_EIEÌ65536Ö0 +USART_CR3_HDSELÌ65536Ö0 +USART_CR3_IRENÌ65536Ö0 +USART_CR3_IRLPÌ65536Ö0 +USART_CR3_NACKÌ65536Ö0 +USART_CR3_ONEBITÌ65536Ö0 +USART_CR3_OVRDISÌ65536Ö0 +USART_CR3_RTSEÌ65536Ö0 +USART_CR3_SCARCNTÌ65536Ö0 +USART_CR3_SCARCNT_0Ì65536Ö0 +USART_CR3_SCARCNT_1Ì65536Ö0 +USART_CR3_SCARCNT_2Ì65536Ö0 +USART_CR3_SCENÌ65536Ö0 +USART_CR3_WUFIEÌ65536Ö0 +USART_CR3_WUSÌ65536Ö0 +USART_CR3_WUS_0Ì65536Ö0 +USART_CR3_WUS_1Ì65536Ö0 +USART_GTPR_GTÌ65536Ö0 +USART_GTPR_PSCÌ65536Ö0 +USART_ICR_CMCFÌ65536Ö0 +USART_ICR_CTSCFÌ65536Ö0 +USART_ICR_EOBCFÌ65536Ö0 +USART_ICR_FECFÌ65536Ö0 +USART_ICR_IDLECFÌ65536Ö0 +USART_ICR_LBDCFÌ65536Ö0 +USART_ICR_NCFÌ65536Ö0 +USART_ICR_ORECFÌ65536Ö0 +USART_ICR_PECFÌ65536Ö0 +USART_ICR_RTOCFÌ65536Ö0 +USART_ICR_TCCFÌ65536Ö0 +USART_ICR_WUCFÌ65536Ö0 +USART_ISR_ABREÌ65536Ö0 +USART_ISR_ABRFÌ65536Ö0 +USART_ISR_BUSYÌ65536Ö0 +USART_ISR_CMFÌ65536Ö0 +USART_ISR_CTSÌ65536Ö0 +USART_ISR_CTSIFÌ65536Ö0 +USART_ISR_EOBFÌ65536Ö0 +USART_ISR_FEÌ65536Ö0 +USART_ISR_IDLEÌ65536Ö0 +USART_ISR_LBDFÌ65536Ö0 +USART_ISR_NEÌ65536Ö0 +USART_ISR_OREÌ65536Ö0 +USART_ISR_PEÌ65536Ö0 +USART_ISR_REACKÌ65536Ö0 +USART_ISR_RTOFÌ65536Ö0 +USART_ISR_RWUÌ65536Ö0 +USART_ISR_RXNEÌ65536Ö0 +USART_ISR_SBKFÌ65536Ö0 +USART_ISR_TCÌ65536Ö0 +USART_ISR_TEACKÌ65536Ö0 +USART_ISR_TXEÌ65536Ö0 +USART_ISR_WUFÌ65536Ö0 +USART_RDR_RDRÌ65536Ö0 +USART_RQR_ABRRQÌ65536Ö0 +USART_RQR_MMRQÌ65536Ö0 +USART_RQR_RXFRQÌ65536Ö0 +USART_RQR_SBKRQÌ65536Ö0 +USART_RQR_TXFRQÌ65536Ö0 +USART_RTOR_BLENÌ65536Ö0 +USART_RTOR_RTOÌ65536Ö0 +USART_TDR_TDRÌ65536Ö0 +VDD_APPLIÌ65536Ö0 +VDD_CALIBÌ65536Ö0 +VREFINT_CAL_ADDRÌ65536Ö0 +WCHAR_MAXÌ65536Ö0 +WCHAR_MINÌ65536Ö0 +WCHAR_WIDTHÌ65536Ö0 +WEAKÌ65536Ö0 +WINT_MAXÌ65536Ö0 +WINT_MINÌ65536Ö0 +WINT_WIDTHÌ65536Ö0 +WRITE_REGÌ131072Í(REG,VAL)Ö0 +WWDGÌ65536Ö0 +WWDG_BASEÌ65536Ö0 +WWDG_CFR_EWIÌ65536Ö0 +WWDG_CFR_WÌ65536Ö0 +WWDG_CFR_W0Ì65536Ö0 +WWDG_CFR_W1Ì65536Ö0 +WWDG_CFR_W2Ì65536Ö0 +WWDG_CFR_W3Ì65536Ö0 +WWDG_CFR_W4Ì65536Ö0 +WWDG_CFR_W5Ì65536Ö0 +WWDG_CFR_W6Ì65536Ö0 +WWDG_CFR_WDGTBÌ65536Ö0 +WWDG_CFR_WDGTB0Ì65536Ö0 +WWDG_CFR_WDGTB1Ì65536Ö0 +WWDG_CR_TÌ65536Ö0 +WWDG_CR_T0Ì65536Ö0 +WWDG_CR_T1Ì65536Ö0 +WWDG_CR_T2Ì65536Ö0 +WWDG_CR_T3Ì65536Ö0 +WWDG_CR_T4Ì65536Ö0 +WWDG_CR_T5Ì65536Ö0 +WWDG_CR_T6Ì65536Ö0 +WWDG_CR_WDGAÌ65536Ö0 +WWDG_SR_EWIFÌ65536Ö0 +_ATFILE_SOURCEÌ65536Ö0 +_BITS_STDINT_INTN_HÌ65536Ö0 +_BITS_STDINT_UINTN_HÌ65536Ö0 +_BITS_TYPESIZES_HÌ65536Ö0 +_BITS_TYPES_HÌ65536Ö0 +_BITS_WCHAR_HÌ65536Ö0 +_BIT_SHIFTÌ131072Í(IRQn)Ö0 +_DEFAULT_SOURCEÌ65536Ö0 +_FEATURES_HÌ65536Ö0 +_FORTIFY_SOURCEÌ65536Ö0 +_GCC_WRAP_STDINT_HÌ65536Ö0 +_GNU_SOURCEÌ65536Ö0 +_IP_IDXÌ131072Í(IRQn)Ö0 +_ISOC11_SOURCEÌ65536Ö0 +_ISOC95_SOURCEÌ65536Ö0 +_ISOC99_SOURCEÌ65536Ö0 +_LARGEFILE64_SOURCEÌ65536Ö0 +_LARGEFILE_SOURCEÌ65536Ö0 +_LP64Ì65536Ö0 +_POSIX_C_SOURCEÌ65536Ö0 +_POSIX_SOURCEÌ65536Ö0 +_SHP_IDXÌ131072Í(IRQn)Ö0 +_STDC_PREDEF_HÌ65536Ö0 +_STDINT_HÌ65536Ö0 +_SYS_CDEFS_HÌ65536Ö0 +_XOPEN_SOURCEÌ65536Ö0 +_XOPEN_SOURCE_EXTENDEDÌ65536Ö0 +__ASMÌ65536Ö0 +__ASMNAMEÌ131072Í(cname)Ö0 +__ASMNAME2Ì131072Í(prefix,cname)Ö0 +__ATOMIC_ACQUIREÌ65536Ö0 +__ATOMIC_ACQ_RELÌ65536Ö0 +__ATOMIC_CONSUMEÌ65536Ö0 +__ATOMIC_HLE_ACQUIREÌ65536Ö0 +__ATOMIC_HLE_RELEASEÌ65536Ö0 +__ATOMIC_RELAXEDÌ65536Ö0 +__ATOMIC_RELEASEÌ65536Ö0 +__ATOMIC_SEQ_CSTÌ65536Ö0 +__BEGIN_DECLSÌ65536Ö0 +__BIGGEST_ALIGNMENT__Ì65536Ö0 +__BKPTÌ131072Í(value)Ö0 +__BLKCNT64_T_TYPEÌ65536Ö0 +__BLKCNT_T_TYPEÌ65536Ö0 +__BLKSIZE_T_TYPEÌ65536Ö0 +__BYTE_ORDER__Ì65536Ö0 +__CHAR16_TYPE__Ì65536Ö0 +__CHAR32_TYPE__Ì65536Ö0 +__CHAR_BIT__Ì65536Ö0 +__CLOCKID_T_TYPEÌ65536Ö0 +__CLOCK_T_TYPEÌ65536Ö0 +__CM0_CMSIS_VERSIONÌ65536Ö0 +__CM0_CMSIS_VERSION_MAINÌ65536Ö0 +__CM0_CMSIS_VERSION_SUBÌ65536Ö0 +__CM0_REVÌ65536Ö0 +__CMSIS_GCC_OUT_REGÌ131072Í(r)Ö0 +__CMSIS_GCC_USE_REGÌ131072Í(r)Ö0 +__CONCATÌ131072Í(x,y)Ö0 +__CORE_CM0_H_DEPENDANTÌ65536Ö0 +__CORE_CM0_H_GENERICÌ65536Ö0 +__CORE_CMFUNC_HÌ65536Ö0 +__CORE_CMINSTR_HÌ65536Ö0 +__CORE_CMSIMD_HÌ65536Ö0 +__CORTEX_MÌ65536Ö0 +__CPU_MASK_TYPEÌ65536Ö0 +__DADDR_T_TYPEÌ65536Ö0 +__DBL_DECIMAL_DIG__Ì65536Ö0 +__DBL_DENORM_MIN__Ì65536Ö0 +__DBL_DIG__Ì65536Ö0 +__DBL_EPSILON__Ì65536Ö0 +__DBL_HAS_DENORM__Ì65536Ö0 +__DBL_HAS_INFINITY__Ì65536Ö0 +__DBL_HAS_QUIET_NAN__Ì65536Ö0 +__DBL_MANT_DIG__Ì65536Ö0 +__DBL_MAX_10_EXP__Ì65536Ö0 +__DBL_MAX_EXP__Ì65536Ö0 +__DBL_MAX__Ì65536Ö0 +__DBL_MIN_10_EXP__Ì65536Ö0 +__DBL_MIN_EXP__Ì65536Ö0 +__DBL_MIN__Ì65536Ö0 +__DEC128_EPSILON__Ì65536Ö0 +__DEC128_MANT_DIG__Ì65536Ö0 +__DEC128_MAX_EXP__Ì65536Ö0 +__DEC128_MAX__Ì65536Ö0 +__DEC128_MIN_EXP__Ì65536Ö0 +__DEC128_MIN__Ì65536Ö0 +__DEC128_SUBNORMAL_MIN__Ì65536Ö0 +__DEC32_EPSILON__Ì65536Ö0 +__DEC32_MANT_DIG__Ì65536Ö0 +__DEC32_MAX_EXP__Ì65536Ö0 +__DEC32_MAX__Ì65536Ö0 +__DEC32_MIN_EXP__Ì65536Ö0 +__DEC32_MIN__Ì65536Ö0 +__DEC32_SUBNORMAL_MIN__Ì65536Ö0 +__DEC64_EPSILON__Ì65536Ö0 +__DEC64_MANT_DIG__Ì65536Ö0 +__DEC64_MAX_EXP__Ì65536Ö0 +__DEC64_MAX__Ì65536Ö0 +__DEC64_MIN_EXP__Ì65536Ö0 +__DEC64_MIN__Ì65536Ö0 +__DEC64_SUBNORMAL_MIN__Ì65536Ö0 +__DECIMAL_BID_FORMAT__Ì65536Ö0 +__DECIMAL_DIG__Ì65536Ö0 +__DEC_EVAL_METHOD__Ì65536Ö0 +__DEPRECATEDÌ65536Ö0 +__DEV_T_TYPEÌ65536Ö0 +__ELF__Ì65536Ö0 +__END_DECLSÌ65536Ö0 +__EXCEPTIONSÌ65536Ö0 +__FD_SETSIZEÌ65536Ö0 +__FINITE_MATH_ONLY__Ì65536Ö0 +__FLOAT_WORD_ORDER__Ì65536Ö0 +__FLT_DECIMAL_DIG__Ì65536Ö0 +__FLT_DENORM_MIN__Ì65536Ö0 +__FLT_DIG__Ì65536Ö0 +__FLT_EPSILON__Ì65536Ö0 +__FLT_EVAL_METHOD__Ì65536Ö0 +__FLT_HAS_DENORM__Ì65536Ö0 +__FLT_HAS_INFINITY__Ì65536Ö0 +__FLT_HAS_QUIET_NAN__Ì65536Ö0 +__FLT_MANT_DIG__Ì65536Ö0 +__FLT_MAX_10_EXP__Ì65536Ö0 +__FLT_MAX_EXP__Ì65536Ö0 +__FLT_MAX__Ì65536Ö0 +__FLT_MIN_10_EXP__Ì65536Ö0 +__FLT_MIN_EXP__Ì65536Ö0 +__FLT_MIN__Ì65536Ö0 +__FLT_RADIX__Ì65536Ö0 +__FPU_USEDÌ65536Ö0 +__FSBLKCNT64_T_TYPEÌ65536Ö0 +__FSBLKCNT_T_TYPEÌ65536Ö0 +__FSFILCNT64_T_TYPEÌ65536Ö0 +__FSFILCNT_T_TYPEÌ65536Ö0 +__FSID_T_TYPEÌ65536Ö0 +__FSWORD_T_TYPEÌ65536Ö0 +__FXSR__Ì65536Ö0 +__GCC_ATOMIC_BOOL_LOCK_FREEÌ65536Ö0 +__GCC_ATOMIC_CHAR16_T_LOCK_FREEÌ65536Ö0 +__GCC_ATOMIC_CHAR32_T_LOCK_FREEÌ65536Ö0 +__GCC_ATOMIC_CHAR_LOCK_FREEÌ65536Ö0 +__GCC_ATOMIC_INT_LOCK_FREEÌ65536Ö0 +__GCC_ATOMIC_LLONG_LOCK_FREEÌ65536Ö0 +__GCC_ATOMIC_LONG_LOCK_FREEÌ65536Ö0 +__GCC_ATOMIC_POINTER_LOCK_FREEÌ65536Ö0 +__GCC_ATOMIC_SHORT_LOCK_FREEÌ65536Ö0 +__GCC_ATOMIC_TEST_AND_SET_TRUEVALÌ65536Ö0 +__GCC_ATOMIC_WCHAR_T_LOCK_FREEÌ65536Ö0 +__GCC_HAVE_DWARF2_CFI_ASMÌ65536Ö0 +__GCC_HAVE_SYNC_COMPARE_AND_SWAP_1Ì65536Ö0 +__GCC_HAVE_SYNC_COMPARE_AND_SWAP_2Ì65536Ö0 +__GCC_HAVE_SYNC_COMPARE_AND_SWAP_4Ì65536Ö0 +__GCC_HAVE_SYNC_COMPARE_AND_SWAP_8Ì65536Ö0 +__GCC_IEC_559Ì65536Ö0 +__GCC_IEC_559_COMPLEXÌ65536Ö0 +__GID_T_TYPEÌ65536Ö0 +__GLIBCXX_BITSIZE_INT_N_0Ì65536Ö0 +__GLIBCXX_TYPE_INT_N_0Ì65536Ö0 +__GLIBC_INTERNAL_STARTING_HEADER_IMPLEMENTATIONÌ65536Ö0 +__GLIBC_MINOR__Ì65536Ö0 +__GLIBC_PREREQÌ131072Í(maj,min)Ö0 +__GLIBC_USEÌ131072Í(F)Ö0 +__GLIBC_USE_DEPRECATED_GETSÌ65536Ö0 +__GLIBC_USE_IEC_60559_BFP_EXTÌ65536Ö0 +__GLIBC_USE_IEC_60559_FUNCS_EXTÌ65536Ö0 +__GLIBC_USE_IEC_60559_TYPES_EXTÌ65536Ö0 +__GLIBC_USE_LIB_EXT2Ì65536Ö0 +__GLIBC__Ì65536Ö0 +__GNUC_GNU_INLINE__Ì65536Ö0 +__GNUC_MINOR__Ì65536Ö0 +__GNUC_PATCHLEVEL__Ì65536Ö0 +__GNUC_PREREQÌ131072Í(maj,min)Ö0 +__GNUC__Ì65536Ö0 +__GNUG__Ì65536Ö0 +__GNU_LIBRARY__Ì65536Ö0 +__GXX_ABI_VERSIONÌ65536Ö0 +__GXX_RTTIÌ65536Ö0 +__GXX_WEAK__Ì65536Ö0 +__HAVE_GENERIC_SELECTIONÌ65536Ö0 +__IÌ65536Ö0 +__ID_T_TYPEÌ65536Ö0 +__INLINEÌ65536Ö0 +__INO64_T_TYPEÌ65536Ö0 +__INO_T_MATCHES_INO64_TÌ65536Ö0 +__INO_T_TYPEÌ65536Ö0 +__INT16_CÌ131072Í(c)Ö0 +__INT16_MAX__Ì65536Ö0 +__INT16_TYPE__Ì65536Ö0 +__INT32_CÌ131072Í(c)Ö0 +__INT32_MAX__Ì65536Ö0 +__INT32_TYPE__Ì65536Ö0 +__INT64_CÌ131072Í(c)Ö0 +__INT64_MAX__Ì65536Ö0 +__INT64_TYPE__Ì65536Ö0 +__INT8_CÌ131072Í(c)Ö0 +__INT8_MAX__Ì65536Ö0 +__INT8_TYPE__Ì65536Ö0 +__INTMAX_CÌ131072Í(c)Ö0 +__INTMAX_MAX__Ì65536Ö0 +__INTMAX_TYPE__Ì65536Ö0 +__INTPTR_MAX__Ì65536Ö0 +__INTPTR_TYPE__Ì65536Ö0 +__INT_FAST16_MAX__Ì65536Ö0 +__INT_FAST16_TYPE__Ì65536Ö0 +__INT_FAST32_MAX__Ì65536Ö0 +__INT_FAST32_TYPE__Ì65536Ö0 +__INT_FAST64_MAX__Ì65536Ö0 +__INT_FAST64_TYPE__Ì65536Ö0 +__INT_FAST8_MAX__Ì65536Ö0 +__INT_FAST8_TYPE__Ì65536Ö0 +__INT_LEAST16_MAX__Ì65536Ö0 +__INT_LEAST16_TYPE__Ì65536Ö0 +__INT_LEAST32_MAX__Ì65536Ö0 +__INT_LEAST32_TYPE__Ì65536Ö0 +__INT_LEAST64_MAX__Ì65536Ö0 +__INT_LEAST64_TYPE__Ì65536Ö0 +__INT_LEAST8_MAX__Ì65536Ö0 +__INT_LEAST8_TYPE__Ì65536Ö0 +__INT_MAX__Ì65536Ö0 +__IOÌ65536Ö0 +__KERNEL_STRICT_NAMESÌ65536Ö0 +__KEY_T_TYPEÌ65536Ö0 +__LDBL_DENORM_MIN__Ì65536Ö0 +__LDBL_DIG__Ì65536Ö0 +__LDBL_EPSILON__Ì65536Ö0 +__LDBL_HAS_DENORM__Ì65536Ö0 +__LDBL_HAS_INFINITY__Ì65536Ö0 +__LDBL_HAS_QUIET_NAN__Ì65536Ö0 +__LDBL_MANT_DIG__Ì65536Ö0 +__LDBL_MAX_10_EXP__Ì65536Ö0 +__LDBL_MAX_EXP__Ì65536Ö0 +__LDBL_MAX__Ì65536Ö0 +__LDBL_MIN_10_EXP__Ì65536Ö0 +__LDBL_MIN_EXP__Ì65536Ö0 +__LDBL_MIN__Ì65536Ö0 +__LDBL_REDIRÌ131072Í(name,proto)Ö0 +__LDBL_REDIR1Ì131072Í(name,proto,alias)Ö0 +__LDBL_REDIR1_NTHÌ131072Í(name,proto,alias)Ö0 +__LDBL_REDIR_DECLÌ131072Í(name)Ö0 +__LDBL_REDIR_NTHÌ131072Í(name,proto)Ö0 +__LEAFÌ65536Ö0 +__LEAF_ATTRÌ65536Ö0 +__LONG_LONG_MAX__Ì65536Ö0 +__LONG_MAX__Ì65536Ö0 +__LP64__Ì65536Ö0 +__MMX__Ì65536Ö0 +__MODE_T_TYPEÌ65536Ö0 +__MPU_PRESENTÌ65536Ö0 +__NLINK_T_TYPEÌ65536Ö0 +__NO_INLINE__Ì65536Ö0 +__NTHÌ131072Í(fct)Ö0 +__NTHNLÌ131072Í(fct)Ö0 +__NVIC_PRIO_BITSÌ65536Ö0 +__OÌ65536Ö0 +__OFF64_T_TYPEÌ65536Ö0 +__OFF_T_MATCHES_OFF64_TÌ65536Ö0 +__OFF_T_TYPEÌ65536Ö0 +__ORDER_BIG_ENDIAN__Ì65536Ö0 +__ORDER_LITTLE_ENDIAN__Ì65536Ö0 +__ORDER_PDP_ENDIAN__Ì65536Ö0 +__PÌ65536Ö0 +__PÌ131072Í(args)Ö0 +__PID_T_TYPEÌ65536Ö0 +__PKHBTÌ131072Í(ARG1,ARG2,ARG3)Ö0 +__PKHTBÌ131072Í(ARG1,ARG2,ARG3)Ö0 +__PMTÌ65536Ö0 +__PMTÌ131072Í(args)Ö0 +__PRAGMA_REDEFINE_EXTNAMEÌ65536Ö0 +__PTRDIFF_MAX__Ì65536Ö0 +__PTRDIFF_TYPE__Ì65536Ö0 +__REDIRECTÌ131072Í(name,proto,alias)Ö0 +__REDIRECT_LDBLÌ131072Í(name,proto,alias)Ö0 +__REDIRECT_NTHÌ131072Í(name,proto,alias)Ö0 +__REDIRECT_NTHNLÌ131072Í(name,proto,alias)Ö0 +__REDIRECT_NTH_LDBLÌ131072Í(name,proto,alias)Ö0 +__REGISTER_PREFIX__Ì65536Ö0 +__RLIM64_T_TYPEÌ65536Ö0 +__RLIM_T_MATCHES_RLIM64_TÌ65536Ö0 +__RLIM_T_TYPEÌ65536Ö0 +__S16_TYPEÌ65536Ö0 +__S32_TYPEÌ65536Ö0 +__S64_TYPEÌ65536Ö0 +__SCHAR_MAX__Ì65536Ö0 +__SHRT_MAX__Ì65536Ö0 +__SIG_ATOMIC_MAX__Ì65536Ö0 +__SIG_ATOMIC_MIN__Ì65536Ö0 +__SIG_ATOMIC_TYPE__Ì65536Ö0 +__SIZEOF_DOUBLE__Ì65536Ö0 +__SIZEOF_FLOAT128__Ì65536Ö0 +__SIZEOF_FLOAT80__Ì65536Ö0 +__SIZEOF_FLOAT__Ì65536Ö0 +__SIZEOF_INT128__Ì65536Ö0 +__SIZEOF_INT__Ì65536Ö0 +__SIZEOF_LONG_DOUBLE__Ì65536Ö0 +__SIZEOF_LONG_LONG__Ì65536Ö0 +__SIZEOF_LONG__Ì65536Ö0 +__SIZEOF_POINTER__Ì65536Ö0 +__SIZEOF_PTRDIFF_T__Ì65536Ö0 +__SIZEOF_SHORT__Ì65536Ö0 +__SIZEOF_SIZE_T__Ì65536Ö0 +__SIZEOF_WCHAR_T__Ì65536Ö0 +__SIZEOF_WINT_T__Ì65536Ö0 +__SIZE_MAX__Ì65536Ö0 +__SIZE_TYPE__Ì65536Ö0 +__SLONG32_TYPEÌ65536Ö0 +__SLONGWORD_TYPEÌ65536Ö0 +__SQUAD_TYPEÌ65536Ö0 +__SSAT16Ì131072Í(ARG1,ARG2)Ö0 +__SSE2_MATH__Ì65536Ö0 +__SSE2__Ì65536Ö0 +__SSE_MATH__Ì65536Ö0 +__SSE__Ì65536Ö0 +__SSIZE_T_TYPEÌ65536Ö0 +__SSP_STRONG__Ì65536Ö0 +__STATIC_INLINEÌ65536Ö0 +__STDC_HOSTED__Ì65536Ö0 +__STDC_IEC_559_COMPLEX__Ì65536Ö0 +__STDC_IEC_559__Ì65536Ö0 +__STDC_ISO_10646__Ì65536Ö0 +__STDC_NO_THREADS__Ì65536Ö0 +__STDC__Ì65536Ö0 +__STD_TYPEÌ65536Ö0 +__STM32F030x6_HÌ65536Ö0 +__STM32F0_H__Ì65536Ö0 +__STM32F0xx_CMSIS_DEVICE_VERSIONÌ65536Ö0 +__STM32F0xx_CMSIS_DEVICE_VERSION_MAINÌ65536Ö0 +__STM32F0xx_CMSIS_DEVICE_VERSION_RCÌ65536Ö0 +__STM32F0xx_CMSIS_DEVICE_VERSION_SUB1Ì65536Ö0 +__STM32F0xx_CMSIS_DEVICE_VERSION_SUB2Ì65536Ö0 +__STM32F0xx_HÌ65536Ö0 +__STRINGÌ131072Í(x)Ö0 +__SUSECONDS_T_TYPEÌ65536Ö0 +__SWORD_TYPEÌ65536Ö0 +__SYSCALL_SLONG_TYPEÌ65536Ö0 +__SYSCALL_ULONG_TYPEÌ65536Ö0 +__SYSCALL_WORDSIZEÌ65536Ö0 +__THROWÌ65536Ö0 +__THROWNLÌ65536Ö0 +__TIMER_T_TYPEÌ65536Ö0 +__TIME_T_TYPEÌ65536Ö0 +__U16_TYPEÌ65536Ö0 +__U32_TYPEÌ65536Ö0 +__U64_TYPEÌ65536Ö0 +__UID_T_TYPEÌ65536Ö0 +__UINT16_CÌ131072Í(c)Ö0 +__UINT16_MAX__Ì65536Ö0 +__UINT16_TYPE__Ì65536Ö0 +__UINT32_CÌ131072Í(c)Ö0 +__UINT32_MAX__Ì65536Ö0 +__UINT32_TYPE__Ì65536Ö0 +__UINT64_CÌ131072Í(c)Ö0 +__UINT64_MAX__Ì65536Ö0 +__UINT64_TYPE__Ì65536Ö0 +__UINT8_CÌ131072Í(c)Ö0 +__UINT8_MAX__Ì65536Ö0 +__UINT8_TYPE__Ì65536Ö0 +__UINTMAX_CÌ131072Í(c)Ö0 +__UINTMAX_MAX__Ì65536Ö0 +__UINTMAX_TYPE__Ì65536Ö0 +__UINTPTR_MAX__Ì65536Ö0 +__UINTPTR_TYPE__Ì65536Ö0 +__UINT_FAST16_MAX__Ì65536Ö0 +__UINT_FAST16_TYPE__Ì65536Ö0 +__UINT_FAST32_MAX__Ì65536Ö0 +__UINT_FAST32_TYPE__Ì65536Ö0 +__UINT_FAST64_MAX__Ì65536Ö0 +__UINT_FAST64_TYPE__Ì65536Ö0 +__UINT_FAST8_MAX__Ì65536Ö0 +__UINT_FAST8_TYPE__Ì65536Ö0 +__UINT_LEAST16_MAX__Ì65536Ö0 +__UINT_LEAST16_TYPE__Ì65536Ö0 +__UINT_LEAST32_MAX__Ì65536Ö0 +__UINT_LEAST32_TYPE__Ì65536Ö0 +__UINT_LEAST64_MAX__Ì65536Ö0 +__UINT_LEAST64_TYPE__Ì65536Ö0 +__UINT_LEAST8_MAX__Ì65536Ö0 +__UINT_LEAST8_TYPE__Ì65536Ö0 +__ULONG32_TYPEÌ65536Ö0 +__ULONGWORD_TYPEÌ65536Ö0 +__UQUAD_TYPEÌ65536Ö0 +__USAT16Ì131072Í(ARG1,ARG2)Ö0 +__USECONDS_T_TYPEÌ65536Ö0 +__USER_LABEL_PREFIX__Ì65536Ö0 +__USE_ATFILEÌ65536Ö0 +__USE_FILE_OFFSET64Ì65536Ö0 +__USE_FORTIFY_LEVELÌ65536Ö0 +__USE_GNUÌ65536Ö0 +__USE_ISOC11Ì65536Ö0 +__USE_ISOC95Ì65536Ö0 +__USE_ISOC99Ì65536Ö0 +__USE_ISOCXX11Ì65536Ö0 +__USE_LARGEFILEÌ65536Ö0 +__USE_LARGEFILE64Ì65536Ö0 +__USE_MISCÌ65536Ö0 +__USE_POSIXÌ65536Ö0 +__USE_POSIX199309Ì65536Ö0 +__USE_POSIX199506Ì65536Ö0 +__USE_POSIX2Ì65536Ö0 +__USE_UNIX98Ì65536Ö0 +__USE_XOPENÌ65536Ö0 +__USE_XOPEN2KÌ65536Ö0 +__USE_XOPEN2K8Ì65536Ö0 +__USE_XOPEN2K8XSIÌ65536Ö0 +__USE_XOPEN2KXSIÌ65536Ö0 +__USE_XOPEN_EXTENDEDÌ65536Ö0 +__UWORD_TYPEÌ65536Ö0 +__VERSION__Ì65536Ö0 +__Vendor_SysTickConfigÌ65536Ö0 +__WCHAR_MAXÌ65536Ö0 +__WCHAR_MAX__Ì65536Ö0 +__WCHAR_MINÌ65536Ö0 +__WCHAR_MIN__Ì65536Ö0 +__WCHAR_TYPE__Ì65536Ö0 +__WINT_MAX__Ì65536Ö0 +__WINT_MIN__Ì65536Ö0 +__WINT_TYPE__Ì65536Ö0 +__WORDSIZEÌ65536Ö0 +__WORDSIZE_TIME64_COMPAT32Ì65536Ö0 +__always_inlineÌ65536Ö0 +__amd64Ì65536Ö0 +__amd64__Ì65536Ö0 +__attribute_alloc_size__Ì131072Í(params)Ö0 +__attribute_artificial__Ì65536Ö0 +__attribute_const__Ì65536Ö0 +__attribute_deprecated__Ì65536Ö0 +__attribute_deprecated_msg__Ì131072Í(msg)Ö0 +__attribute_format_arg__Ì131072Í(x)Ö0 +__attribute_format_strfmon__Ì131072Í(a,b)Ö0 +__attribute_malloc__Ì65536Ö0 +__attribute_noinline__Ì65536Ö0 +__attribute_pure__Ì65536Ö0 +__attribute_used__Ì65536Ö0 +__attribute_warn_unused_result__Ì65536Ö0 +__bosÌ131072Í(ptr)Ö0 +__bos0Ì131072Í(ptr)Ö0 +__code_model_small__Ì65536Ö0 +__cplusplusÌ65536Ö0 +__cpp_binary_literalsÌ65536Ö0 +__cpp_exceptionsÌ65536Ö0 +__cpp_rttiÌ65536Ö0 +__cpp_runtime_arraysÌ65536Ö0 +__errordeclÌ131072Í(name,msg)Ö0 +__extern_always_inlineÌ65536Ö0 +__extern_inlineÌ65536Ö0 +__fini_array_endÌ32768Ö0Ïfuncp_t +__fini_array_startÌ32768Ö0Ïfuncp_t +__flexarrÌ65536Ö0 +__fortify_functionÌ65536Ö0 +__glibc_c99_flexarr_availableÌ65536Ö0 +__glibc_clang_has_extensionÌ131072Í(ext)Ö0 +__glibc_clang_prereqÌ131072Í(maj,min)Ö0 +__glibc_likelyÌ131072Í(cond)Ö0 +__glibc_macro_warningÌ131072Í(message)Ö0 +__glibc_macro_warning1Ì131072Í(message)Ö0 +__glibc_unlikelyÌ131072Í(cond)Ö0 +__gnu_linux__Ì65536Ö0 +__has_includeÌ131072Í(STR)Ö0 +__has_include_nextÌ131072Í(STR)Ö0 +__init_array_endÌ32768Ö0Ïfuncp_t +__init_array_startÌ32768Ö0Ïfuncp_t +__intptr_t_definedÌ65536Ö0 +__k8Ì65536Ö0 +__k8__Ì65536Ö0 +__linuxÌ65536Ö0 +__linux__Ì65536Ö0 +__long_double_tÌ65536Ö0 +__nonnullÌ131072Í(params)Ö0 +__preinit_array_endÌ32768Ö0Ïfuncp_t +__preinit_array_startÌ32768Ö0Ïfuncp_t +__ptr_tÌ65536Ö0 +__restrict_arrÌ65536Ö0 +__stub___compat_bdflushÌ65536Ö0 +__stub_chflagsÌ65536Ö0 +__stub_fattachÌ65536Ö0 +__stub_fchflagsÌ65536Ö0 +__stub_fdetachÌ65536Ö0 +__stub_getmsgÌ65536Ö0 +__stub_gttyÌ65536Ö0 +__stub_lchmodÌ65536Ö0 +__stub_putmsgÌ65536Ö0 +__stub_revokeÌ65536Ö0 +__stub_setloginÌ65536Ö0 +__stub_sigreturnÌ65536Ö0 +__stub_sstkÌ65536Ö0 +__stub_sttyÌ65536Ö0 +__unixÌ65536Ö0 +__unix__Ì65536Ö0 +__va_arg_packÌ131072Í()Ö0 +__va_arg_pack_lenÌ131072Í()Ö0 +__warnattrÌ131072Í(msg)Ö0 +__warndeclÌ131072Í(name,msg)Ö0 +__wurÌ65536Ö0 +__x86_64Ì65536Ö0 +__x86_64__Ì65536Ö0 +_dataÌ32768Ö0Ï_data_loadaddr +_data_loadaddrÌ32768Ö0 +_ebssÌ32768Ö0Ï_data_loadaddr +_edataÌ32768Ö0Ï_data_loadaddr +_stackÌ32768Ö0Ï_data_loadaddr +adc_comp_isrÌ65536Ö0 +anon_struct_0Ì2048Ö0 +blocking_handlerÌ16Í(void)Ö0Ïvoid +blocking_handlerÌ1024Í(void)Ö0Ïvoid +bus_faultÌ64Îanon_struct_0Ö0Ïvector_table_entry_t +cec_can_isrÌ65536Ö0 +debug_monitorÌ64Îanon_struct_0Ö0Ïvector_table_entry_t +dma1_channel1_isrÌ65536Ö0 +dma1_channel2_3_isrÌ65536Ö0 +dma1_channel4_5_isrÌ65536Ö0 +exti0_1_isrÌ65536Ö0 +exti2_3_isrÌ65536Ö0 +exti4_15_isrÌ65536Ö0 +flash_isrÌ65536Ö0 +funcp_tÌ4096Ö0Ïtypedef void +hard_faultÌ64Îanon_struct_0Ö0Ïvector_table_entry_t +hard_fault_handlerÌ65536Ö0 +i2c1_isrÌ65536Ö0 +i2c2_isrÌ65536Ö0 +initial_sp_valueÌ64Îanon_struct_0Ö0Ïunsigned int * +irqÌ64Îanon_struct_0Ö0Ïvector_table_entry_t +linuxÌ65536Ö0 +mainÌ1024Í(void)Ö0Ïvoid +memory_manage_faultÌ64Îanon_struct_0Ö0Ïvector_table_entry_t +nmiÌ64Îanon_struct_0Ö0Ïvector_table_entry_t +nmi_handlerÌ65536Ö0 +nopÌ131072Í()Ö0 +null_handlerÌ16Í(void)Ö0Ïvoid +null_handlerÌ1024Í(void)Ö0Ïvoid +pend_svÌ64Îanon_struct_0Ö0Ïvector_table_entry_t +pend_sv_handlerÌ65536Ö0 +pin_clearÌ131072Í(gpioport,gpios)Ö0 +pin_readÌ131072Í(gpioport,gpios)Ö0 +pin_setÌ131072Í(gpioport,gpios)Ö0 +pin_toggleÌ131072Í(gpioport,gpios)Ö0 +pin_writeÌ131072Í(gpioport,gpios)Ö0 +pvd_isrÌ65536Ö0 +rcc_isrÌ65536Ö0 +reserved_x001cÌ64Îanon_struct_0Ö0Ïvector_table_entry_t +reserved_x0034Ì64Îanon_struct_0Ö0Ïvector_table_entry_t +resetÌ64Îanon_struct_0Ö0Ïvector_table_entry_t +reset_handlerÌ16Í(void)Ö0Ïvoid +rtc_isrÌ65536Ö0 +spi1_isrÌ65536Ö0 +spi2_isrÌ65536Ö0 +sv_callÌ64Îanon_struct_0Ö0Ïvector_table_entry_t +sv_call_handlerÌ65536Ö0 +sys_tick_handlerÌ65536Ö0 +sysresetÌ16Í(void)Ö0Ïinline void +systickÌ64Îanon_struct_0Ö0Ïvector_table_entry_t +tim14_isrÌ65536Ö0 +tim15_isrÌ65536Ö0 +tim16_isrÌ65536Ö0 +tim17_isrÌ65536Ö0 +tim1_brk_up_trg_com_isrÌ65536Ö0 +tim1_cc_isrÌ65536Ö0 +tim2_isrÌ65536Ö0 +tim3_isrÌ65536Ö0 +tim6_dac_isrÌ65536Ö0 +tim7_isrÌ65536Ö0 +tsc_isrÌ65536Ö0 +unixÌ65536Ö0 +usage_faultÌ64Îanon_struct_0Ö0Ïvector_table_entry_t +usart1_isrÌ65536Ö0 +usart2_isrÌ65536Ö0 +usart3_4_isrÌ65536Ö0 +usb_isrÌ65536Ö0 +vector_tableÌ16384Ö0Ïvector_table_t +vector_table_entry_tÌ4096Ö0Ïtypedef void +vector_table_tÌ4096Ö0Ïanon_struct_0 +wwdg_isrÌ65536Ö0 diff --git a/STM32/steppers/Makefile b/STM32/steppers/Makefile new file mode 100644 index 0000000..148c4db --- /dev/null +++ b/STM32/steppers/Makefile @@ -0,0 +1,137 @@ +BINARY = steppers +BOOTPORT ?= /dev/ttyUSB0 +BOOTSPEED ?= 115200 +# MCU FAMILY +FAMILY = F0 +# MCU code +MCU = F030x4 +DEFS = -DEBUG +# change this linking script depending on particular MCU model, +# for example, if you have STM32F103VBT6, you should write: +LDSCRIPT = ld/stm32f030f.ld + +INDEPENDENT_HEADERS= + +FP_FLAGS ?= -msoft-float +ASM_FLAGS = -mthumb -mcpu=cortex-m0 -march=armv6-m -mtune=cortex-m0 +ARCH_FLAGS = $(ASM_FLAGS) $(FP_FLAGS) + +############################################################################### +# Executables +PREFIX ?= /opt/bin/arm-none-eabi + +RM := rm -f +RMDIR := rmdir +CC := $(PREFIX)-gcc +LD := $(PREFIX)-gcc +AR := $(PREFIX)-ar +AS := $(PREFIX)-as +OBJCOPY := $(PREFIX)-objcopy +OBJDUMP := $(PREFIX)-objdump +GDB := $(PREFIX)-gdb +STFLASH := $(shell which st-flash) +STBOOT := $(shell which stm32flash) + +############################################################################### +# Source files +OBJDIR = mk +LDSCRIPT ?= $(BINARY).ld +SRC := $(wildcard *.c) +OBJS := $(addprefix $(OBJDIR)/, $(SRC:%.c=%.o)) +STARTUP = $(OBJDIR)/startup.o +OBJS += $(STARTUP) +DEPS := $(OBJS:.o=.d) + +INC_DIR ?= ../inc + +INCLUDE := -I$(INC_DIR)/F0 -I$(INC_DIR)/cm +LIB_DIR := $(INC_DIR)/ld + +############################################################################### +# C flags +CFLAGS += -O2 -g -MD -D__thumb2__=1 +CFLAGS += -Wall -Werror -Wextra -Wshadow -Wimplicit-function-declaration +CFLAGS += -Wredundant-decls $(INCLUDE) +# -Wmissing-prototypes -Wstrict-prototypes +CFLAGS += -fno-common -ffunction-sections -fdata-sections + +############################################################################### +# Linker flags +LDFLAGS += --static -nostartfiles +#--specs=nano.specs +LDFLAGS += -L$(LIB_DIR) +LDFLAGS += -T$(LDSCRIPT) +LDFLAGS += -Wl,-Map=$(OBJDIR)/$(BINARY).map +LDFLAGS += -Wl,--gc-sections + +############################################################################### +# Used libraries +LDLIBS += -Wl,--start-group -lc -lgcc -Wl,--end-group +LDLIBS += $(shell $(CC) $(CFLAGS) -print-libgcc-file-name) + +DEFS += -DSTM32$(FAMILY) -DSTM32$(MCU) + +#.SUFFIXES: .elf .bin .hex .srec .list .map .images +#.SECONDEXPANSION: +#.SECONDARY: + +ELF := $(OBJDIR)/$(BINARY).elf +LIST := $(OBJDIR)/$(BINARY).list +BIN := $(BINARY).bin +HEX := $(BINARY).hex + +all: bin list + +elf: $(ELF) +bin: $(BIN) +hex: $(HEX) +list: $(LIST) + +ifneq ($(MAKECMDGOALS),clean) +-include $(DEPS) +endif + +$(OBJDIR): + mkdir $(OBJDIR) + +$(STARTUP): $(INC_DIR)/startup/vector.c + $(CC) $(CFLAGS) $(DEFS) $(INCLUDE) $(ARCH_FLAGS) -o $@ -c $< + +$(OBJDIR)/%.o: %.c + @echo " CC $<" + $(CC) $(CFLAGS) $(DEFS) $(INCLUDE) $(ARCH_FLAGS) -o $@ -c $< + +#$(OBJDIR)/%.d: %.c $(OBJDIR) +# $(CC) -MM -MG $< | sed -e 's,^\([^:]*\)\.o[ ]*:,$(@D)/\1.o $(@D)/\1.d:,' >$@ + +$(BIN): $(ELF) + @echo " OBJCOPY $(BIN)" + $(OBJCOPY) -Obinary $(ELF) $(BIN) + +$(HEX): $(ELF) + @echo " OBJCOPY $(HEX)" + $(OBJCOPY) -Oihex $(ELF) $(HEX) + +$(LIST): $(ELF) + @echo " OBJDUMP $(LIST)" + $(OBJDUMP) -S $(ELF) > $(LIST) + +$(ELF): $(OBJDIR) $(OBJS) + @echo " LD $(ELF)" + $(LD) $(LDFLAGS) $(ARCH_FLAGS) $(OBJS) $(LDLIBS) -o $(ELF) + +clean: + @echo " CLEAN" + $(RM) $(OBJS) $(DEPS) $(ELF) $(HEX) $(LIST) $(OBJDIR)/*.map + @rmdir $(OBJDIR) 2>/dev/null || true + + +flash: $(BIN) + @echo " FLASH $(BIN)" + $(STFLASH) write $(BIN) 0x8000000 + +boot: $(BIN) + @echo " LOAD $(BIN) through bootloader" + $(STBOOT) -b$(BOOTSPEED) $(BOOTPORT) -w $(BIN) + +.PHONY: clean flash boot diff --git a/STM32/steppers/Readme.md b/STM32/steppers/Readme.md new file mode 100644 index 0000000..d1c250c --- /dev/null +++ b/STM32/steppers/Readme.md @@ -0,0 +1,26 @@ +Management of two stepper motors +================================ + +Based on STM32F030F4P6 + +## Pinout + +|Pin | Type | Role | +|:---|:----:|:------------------------| +|PA0 | AIN | Steppers current | +|PA1 | AIN | Input voltage 12V | +|PA2 | AIN | EndSwitch2 of motor1 | +|PA3 | AIN | EndSwitch1 of motor1 | +|PA4 | PUPD | Tim14Ch1 - motor1 steps | +|PA5 | PUPD | Motor2 enable | +|PA6 | PUPD | Tim3Ch1 - motor2 steps | +|PA7 | PUPD | Motor2 direction | +|PA9 | OD | USART1 Tx | +|PA10| FIN | USART1 Rx | +|PA13| AIN | EndSwitch1 of motor2 | +|PA14| AIN | EndSwitch2 of motor2 | +|PB1 | PUPD | Turn off motors' power | +|PF0 | PUPD | Motor1 enable | +|PF1 | PUPD | Motor1 direction | + +## Protocol diff --git a/STM32/steppers/adc.c b/STM32/steppers/adc.c new file mode 100644 index 0000000..f468ac7 --- /dev/null +++ b/STM32/steppers/adc.c @@ -0,0 +1,149 @@ +/* + * geany_encoding=koi8-r + * adc.c + * + * Copyright 2017 Edward V. Emelianov + * + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program; if not, write to the Free Software + * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, + * MA 02110-1301, USA. + * + */ +#include "stm32f0.h" +#include "flash.h" +#include "adc.h" + +/* + * 0 - Steppers current + * 1 - Input voltage 12V + * 2 - EndSwitch2 of motor1 + * 3 - EndSwitch1 of motor1 + * 4 - EndSwitch1 of motor2 + * 5 - EndSwitch2 of motor2 + * 6 - inner temperature + * 7 - vref + */ +uint16_t ADC_array[NUMBER_OF_ADC_CHANNELS]; + +void adc_setup(){ + // AIN: PA0..3, PA13, PA14. ADC_IN16 - inner temperature. ADC_IN17 - VREFINT + /* (1) Enable the peripheral clock of the ADC */ + /* (2) Set peripheral prescaler to /2 so PCLK = HCLK/2 = 24MHz */ + RCC->APB2ENR |= RCC_APB2ENR_ADC1EN; /* (1) */ + RCC->CFGR |= RCC_CFGR_PPRE_2; /* (2) */ + /* (1) Ensure that ADEN = 0 */ + /* (2) Clear ADEN */ + /* (3) Launch the calibration by setting ADCAL */ + /* (4) Wait until ADCAL=0 */ + if ((ADC1->CR & ADC_CR_ADEN) != 0){ /* (1) */ + ADC1->CR &= (uint32_t)(~ADC_CR_ADEN); /* (2) */ + } + ADC1->CR |= ADC_CR_ADCAL; /* (3) */ + while ((ADC1->CR & ADC_CR_ADCAL) != 0){} /* (4) */ + /* (1) Enable the ADC */ + /* (2) Wait until ADC ready */ + do{ + ADC1->CR |= ADC_CR_ADEN; /* (1) */ + }while ((ADC1->ISR & ADC_ISR_ADRDY) == 0) /* (2) */; + /* (1) Select PCLK/2 by writing 01 in CKMODE */ + /* (2) Select the continuous mode */ + /* (3) Select CHSEL0..3, 13,14, 16,17 */ + /* (4) Select a sampling mode of 111 i.e. 239.5 ADC clk to be greater than 17.1us */ + /* (5) Wake-up the VREFINT and Temperature sensor (only for VBAT, Temp sensor and VRefInt) */ + ADC1->CFGR2 |= ADC_CFGR2_CKMODE_0; /* (1) */ + ADC1->CFGR1 |= ADC_CFGR1_CONT; /* (2)*/ + ADC1->CHSELR = ADC_CHSELR_CHSEL0 | ADC_CHSELR_CHSEL1 | ADC_CHSELR_CHSEL2 | + ADC_CHSELR_CHSEL3 | ADC_CHSELR_CHSEL13 | ADC_CHSELR_CHSEL14 | + ADC_CHSELR_CHSEL16 | ADC_CHSELR_CHSEL17; /* (3)*/ + ADC1->SMPR |= ADC_SMPR_SMP_0 | ADC_SMPR_SMP_1 | ADC_SMPR_SMP_2; /* (4) */ + ADC->CCR |= ADC_CCR_TSEN | ADC_CCR_VREFEN; /* (5) */ + // DMA for AIN + /* (1) Enable the peripheral clock on DMA */ + /* (2) Enable DMA transfer on ADC and circular mode */ + /* (3) Configure the peripheral data register address */ + /* (4) Configure the memory address */ + /* (5) Configure the number of DMA tranfer to be performs on DMA channel 1 */ + /* (6) Configure increment, size, interrupts and circular mode */ + /* (7) Enable DMA Channel 1 */ + RCC->AHBENR |= RCC_AHBENR_DMA1EN; /* (1) */ + ADC1->CFGR1 |= ADC_CFGR1_DMAEN | ADC_CFGR1_DMACFG; /* (2) */ + DMA1_Channel1->CPAR = (uint32_t) (&(ADC1->DR)); /* (3) */ + DMA1_Channel1->CMAR = (uint32_t)(ADC_array); /* (4) */ + DMA1_Channel1->CNDTR = NUMBER_OF_ADC_CHANNELS; /* (5) */ + DMA1_Channel1->CCR |= DMA_CCR_MINC | DMA_CCR_MSIZE_0 | DMA_CCR_PSIZE_0 | DMA_CCR_CIRC; /* (6) */ + DMA1_Channel1->CCR |= DMA_CCR_EN; /* (7) */ + ADC1->CR |= ADC_CR_ADSTART; /* start the ADC conversions */ +} + +// return MCU temperature (degrees of celsius) +uint32_t getTemp(){ + uint32_t temperature = ADC_array[6]; + temperature = ((temperature * VDD_APPLI / VDD_CALIB) - (uint32_t) *TEMP30_CAL_ADDR ) ; + temperature *= (uint32_t)(110 - 30); + temperature /= (uint32_t)(*TEMP110_CAL_ADDR - *TEMP30_CAL_ADDR); + temperature += 30; + return(temperature); +} + +//static uint32_t calval = 0; +// return Vdd * 10 (V) +uint32_t getVdd(){ + /* if(!calval){ + calval = ((uint32_t) *VREFINT_CAL_ADDR) * VDD_CALIB; + calval /= VDD_APPLI; + } */ + uint32_t vdd = ADC_array[7] * (uint32_t)33 * the_conf.v33numerator; // 3.3V + //vdd /= calval * the_conf.v33denominator; + vdd /= ((uint32_t) *VREFINT_CAL_ADDR) * the_conf.v33denominator; + return vdd; +} + +// return value of 12V * 10 (V) +uint32_t getVmot(){ + uint32_t vmot = ADC_array[1] * getVdd() * the_conf.v12numerator; + vmot >>= 12; + vmot /= the_conf.v12denominator; + return vmot; +} + +// return value of motors' current * 100 (A) +uint32_t getImot(){ + uint32_t vmot = ADC_array[0] * getVdd() * the_conf.i12numerator * 10; + vmot >>= 12; + vmot /= the_conf.i12denominator; + return vmot; +} + +// end-switches status: 0 - don't activated, 1 - activated, 2 - user button, 4 - error +// @param motnum - motor number (0,1) +// @param eswnum - switch number (0,1) +ESW_status eswStatus(int motnum, int eswnum){ + int idx; + if(motnum){ // motor 1 + if(eswnum) idx = 5; + else idx = 4; + }else{ // motor 0 + if(eswnum) idx = 3; + else idx = 2; + } + uint16_t thres = the_conf.ESW_thres, val = ADC_array[idx]; + // low sighal: 0..threshold - Hall activated + if(val < thres) return ESW_HALL; + // high signal: (4096-thres)..4096 - pullup + if(val > (uint16_t)0x1000 - thres) return ESW_RELEASED; + // middle signal: 0x800-thres..0x800+thres - user button active (47k pullup + 47k pulldown) + if(0x800 - thres < val && val < 0x800 + thres) return ESW_BUTTON; + // very strange, return err + return ESW_ERROR; +} diff --git a/STM32/steppers/adc.h b/STM32/steppers/adc.h new file mode 100644 index 0000000..073c36d --- /dev/null +++ b/STM32/steppers/adc.h @@ -0,0 +1,47 @@ +/* + * geany_encoding=koi8-r + * adc.h + * + * Copyright 2017 Edward V. Emelianov + * + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program; if not, write to the Free Software + * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, + * MA 02110-1301, USA. + * + */ + +#pragma once +#ifndef __ADC_H__ +#define __ADC_H__ + +// 8 channels (including inttemp & vrefint) +#define NUMBER_OF_ADC_CHANNELS (8) + +extern uint16_t ADC_array[]; +void adc_setup(); + +typedef enum{ + ESW_RELEASED, + ESW_HALL, + ESW_BUTTON, + ESW_ERROR +} ESW_status; + +uint32_t getTemp(); +uint32_t getVdd(); +uint32_t getVmot(); +uint32_t getImot(); +ESW_status eswStatus(int motnum, int eswnum); + +#endif // __ADC_H__ diff --git a/STM32/steppers/flash.c b/STM32/steppers/flash.c new file mode 100644 index 0000000..015b418 --- /dev/null +++ b/STM32/steppers/flash.c @@ -0,0 +1,144 @@ +/* + * geany_encoding=koi8-r + * flash.c + * + * Copyright 2017 Edward V. Emelianov + * + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program; if not, write to the Free Software + * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, + * MA 02110-1301, USA. + * + */ +#include "stm32f0.h" +#include // memcpy + +#include "flash.h" +#include "usart.h" + +// start of configuration data in flash (from 15kB, one kB size) +#define FLASH_CONF_START_ADDR ((uint32_t)0x08003C00) + +user_conf the_conf = { + .good_data_pos = 0xffffffff + ,.devID = 0 + ,.v12numerator = 1 + ,.v12denominator = 1 + ,.i12numerator = 1 + ,.i12denominator = 1 + ,.v33denominator = 1 + ,.v33numerator = 1 + ,.ESW_thres = 150 +}; + +static int maxnum = 0x800 / sizeof(user_conf); + +static int erase_flash(); + +static int get_gooddata(){ + user_conf *c = (user_conf*) FLASH_CONF_START_ADDR; + uint32_t datapos = c->good_data_pos; + if(datapos == 0xffffffff){ // virginity clear + return maxnum; + } + // have data - move it to `the_conf` + if(maxnum > 32) maxnum = 32; + int idx; + for(idx = 1; idx < maxnum; ++idx){ // find current settings index - first non-zero bit + if(datapos & 1<CR & FLASH_CR_LOCK){ + FLASH->KEYR = FLASH_FKEY1; + FLASH->KEYR = FLASH_FKEY2; + } + the_conf.good_data_pos = 0xffffffff ^ (1<SR & FLASH_SR_BSY); + FLASH->SR = FLASH_SR_EOP | FLASH_SR_PGERR | FLASH_SR_WRPERR; + FLASH->CR |= FLASH_CR_PG; + uint16_t *data = (uint16_t*) &the_conf; + uint16_t *address = (uint16_t*) &c[idx]; + uint32_t i, count = sizeof(user_conf) / 2; + for (i = 0; i < count; ++i){ + //*(volatile uint16_t*)(address + i) = (((uint8_t)data[i + 1]) << 8) | data[i]; + *(volatile uint16_t*)(address + i) = data[i]; + //while (!(FLASH->SR & FLASH_SR_EOP)); + while((FLASH->SR & FLASH_SR_BSY)); +buf[0] = '0' + i; +usart1_send_blocking(buf); + if(FLASH->SR & FLASH_SR_PGERR) ret = 1; +buf[0] = ret + '0'; +usart1_send_blocking(buf); + FLASH->SR = FLASH_SR_EOP | FLASH_SR_PGERR | FLASH_SR_WRPERR; + } + FLASH->CR &= ~(FLASH_CR_PG); + return ret; +} + + +static int erase_flash(){ + int ret = 0; + /* (1) Wait till no operation is on going */ + /* (2) Clear error & EOP bits */ + /* (3) Check that the Flash is unlocked */ + /* (4) Perform unlock sequence */ + while ((FLASH->SR & FLASH_SR_BSY) != 0){} /* (1) */ + FLASH->SR = FLASH_SR_EOP | FLASH_SR_PGERR | FLASH_SR_WRPERR; /* (2) */ + /* if (FLASH->SR & FLASH_SR_EOP){ + FLASH->SR |= FLASH_SR_EOP; + }*/ + if ((FLASH->CR & FLASH_CR_LOCK) != 0){ /* (3) */ + FLASH->KEYR = FLASH_FKEY1; /* (4) */ + FLASH->KEYR = FLASH_FKEY2; + } + /* (1) Set the PER bit in the FLASH_CR register to enable page erasing */ + /* (2) Program the FLASH_AR register to select a page to erase */ + /* (3) Set the STRT bit in the FLASH_CR register to start the erasing */ + /* (4) Wait until the EOP flag in the FLASH_SR register set */ + /* (5) Clear EOP flag by software by writing EOP at 1 */ + /* (6) Reset the PER Bit to disable the page erase */ + FLASH->CR |= FLASH_CR_PER; /* (1) */ + FLASH->AR = FLASH_CONF_START_ADDR; /* (2) */ + FLASH->CR |= FLASH_CR_STRT; /* (3) */ + while(!(FLASH->SR & FLASH_SR_EOP)); + FLASH->SR |= FLASH_SR_EOP; /* (5)*/ + if(FLASH->SR & FLASH_SR_WRPERR){ /* Check Write protection error */ + ret = 1; + FLASH->SR |= FLASH_SR_WRPERR; /* Clear the flag by software by writing it at 1*/ + } + FLASH->CR &= ~FLASH_CR_PER; /* (6) */ + return ret; +} + diff --git a/STM32/steppers/flash.h b/STM32/steppers/flash.h new file mode 100644 index 0000000..6c8840b --- /dev/null +++ b/STM32/steppers/flash.h @@ -0,0 +1,46 @@ +/* + * geany_encoding=koi8-r + * flash.h + * + * Copyright 2017 Edward V. Emelianov + * + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program; if not, write to the Free Software + * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, + * MA 02110-1301, USA. + * + */ + +#pragma once +#ifndef __FLASH_H__ +#define __FLASH_H__ + +typedef struct{ + uint32_t good_data_pos; // position of data (index of mostly left zero) + uint16_t devID; // device address (id) + uint16_t ESW_thres; // ADC threshold for end-switches/Hall sensors + // calibration values for current/voltage sensors + uint16_t v12numerator; // 12V to motors + uint16_t v12denominator; + uint16_t i12numerator; // motors' current + uint16_t i12denominator; + uint16_t v33numerator; // 3.3V (vref) + uint16_t v33denominator; +} user_conf; + +extern user_conf the_conf; + +void get_userconf(); +int store_userconf(); + +#endif // __FLASH_H__ diff --git a/STM32/steppers/ld/stm32f030f.ld b/STM32/steppers/ld/stm32f030f.ld new file mode 100644 index 0000000..f8b61f1 --- /dev/null +++ b/STM32/steppers/ld/stm32f030f.ld @@ -0,0 +1,12 @@ +/* Linker script for STM32F030f4, 16K flash, 4K RAM. */ + +/* Define memory regions. */ +MEMORY +{ + rom (rx) : ORIGIN = 0x08000000, LENGTH = 16K + ram (rwx) : ORIGIN = 0x20000000, LENGTH = 4K +} + +/* Include the common ld script. */ +INCLUDE stm32f0.ld + diff --git a/STM32/steppers/main.c b/STM32/steppers/main.c new file mode 100644 index 0000000..6cdec22 --- /dev/null +++ b/STM32/steppers/main.c @@ -0,0 +1,112 @@ +/* + * main.c + * + * Copyright 2017 Edward V. Emelianoff + * + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program; if not, write to the Free Software + * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, + * MA 02110-1301, USA. + */ + +#include "stm32f0.h" +#include "usart.h" +#include "adc.h" +#include "flash.h" +#include "proto.h" + +volatile uint32_t Tms = 0; + +/* Called when systick fires */ +void sys_tick_handler(void){ + ++Tms; +} + +/* + * PA4 (Tim14Ch1) M1STEP + * PA6 (Tim3Ch1) M2STEP + * PA5 - M2EN + * PA7 - M2DIR + * PB1 - 12V on/off + * PF0 - M1EN + * PF1 - M1DIR + */ +static void gpio_setup(void){ + // Enable clocks to the GPIO subsystems + RCC->AHBENR |= RCC_AHBENR_GPIOAEN | RCC_AHBENR_GPIOBEN | RCC_AHBENR_GPIOFEN; + // PA0..3, PA13, PA14 - AIN; PA4..7 - PUPD; + GPIOA->MODER = GPIO_MODER_MODER0_AI | GPIO_MODER_MODER1_AI | GPIO_MODER_MODER2_AI | + GPIO_MODER_MODER3_AI | GPIO_MODER_MODER13_AI | GPIO_MODER_MODER14_AI | + GPIO_MODER_MODER4_O | GPIO_MODER_MODER5_O | GPIO_MODER_MODER6_O | GPIO_MODER_MODER7_O; + GPIOA->OSPEEDR = 0; // all low speed + GPIOA->PUPDR = 0; // clear pull-down for PA14&PA13 + // PA4 - Tim14Ch1 (AF4), PA6 - Tim3Ch1 (AF1) + GPIOA->AFR[0] = (GPIOA->AFR[0] &~ (GPIO_AFRL_AFRL4 | GPIO_AFRL_AFRL6))\ + | (4 << (4 * 4)) | (1 << (6 * 4)); + // PB1 - PUPD + GPIOB->MODER = GPIO_MODER_MODER1_O; + // PF0, PF1 - PUPD + GPIOF->MODER = GPIO_MODER_MODER0_O | GPIO_MODER_MODER1_O; +} + +int main(void){ + uint32_t lastT = 0; + uint32_t ostctr = 0; + #if 0 + //def EBUG + uint32_t msgctr = 0; + #endif + char *txt = NULL; + sysreset(); + SysTick_Config(6000, 1); + gpio_setup(); + adc_setup(); + USART1_config(); + get_userconf(); + //pin_set(GPIOA, 1<<5); // clear extern LED + while (1){ + if(lastT > Tms || Tms - lastT > 499){ + #ifdef EBUG + pin_toggle(GPIOA, 1<<4); // blink by onboard LED once per second + #endif + lastT = Tms; + } + if(usart1rx()){ // usart1 received data, store in in buffer + if(usart1_getline(&txt)){ + txt = process_command(txt); + }else txt = NULL; // buffer overflow + } + #if 0 + //def EBUG + if(msgctr > Tms || Tms - msgctr > 4999){ // once per 5 seconds + msgctr = Tms; + txt = "hello"; + } + #endif + if(trbufisfull()){ + write2trbuf("ERR"); + usart1_send_blocking(gettrbuf()); + } + cleartrbuf(); + if(txt){ // text waits for sending + if(ALL_OK == usart1_send(txt)){ + txt = NULL; + } + } + if(ostctr != Tms){ + ostctr = Tms; + // + } + } +} + diff --git a/STM32/steppers/proto.c b/STM32/steppers/proto.c new file mode 100644 index 0000000..37f9cbb --- /dev/null +++ b/STM32/steppers/proto.c @@ -0,0 +1,282 @@ +/* + * geany_encoding=koi8-r + * proto.c + * + * Copyright 2017 Edward V. Emelianov + * + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program; if not, write to the Free Software + * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, + * MA 02110-1301, USA. + * + */ +#include "stm32f0.h" +#include "proto.h" +#include "adc.h" +#include "flash.h" +#include "string.h" +#include "usart.h" + +#define SENDBUF() do{usart1_send_blocking(gettrbuf()); cleartrbuf();}while(0) + +static const char *eodata = "DATAEND"; +static const char *badcmd = "BADCMD"; +static const char *allok = "ALL OK"; +static const char *err = "ERR"; + +#define EODATA ((char*)eodata) +#define BADCMD ((char*)badcmd) +#define ALLOK ((char*)allok) +#define ERR ((char*)err) + +static char *getnum(char *buf, int32_t *N); +static char *get_something(char *str); +static char *set_something(char *str); +static char *get_status(); +static char *get_conf(); +static char *get_raw_adc(); +static char *get_ADCval(char *str); +static char *setDenEn(uint8_t De, char *str); +static char *setDevId(char *str); +static char *setESWthres(char *str); +static char *get_temper(); + +#define omitwsp(str) do{register char nxt; while((nxt = *str)){if(nxt != ' ' && nxt != '\t') break; else ++str;}}while(0) + +/** + * get input buffer `cmdbuf`, parse it and change system state + * @return message to send + */ +char* process_command(char *cmdbuf){ + int32_t num; + char *str, c; + #ifdef EBUG + usart1_send_blocking(cmdbuf); + #endif + str = getnum(cmdbuf, &num); + if(!str) return NULL; // bad format + if(num != the_conf.devID && num != -1) return NULL; // other target + // OK, the command is for this device + while((c = *str)){if(c != ' ' && c != '\t') break; else ++str;} + if(!c){ // simple ping + return "ALIVE"; + } + switch (*str++){ + case 'S': // set something + return set_something(str); + break; + case 'G': // get something + return get_something(str); + break; + case 'W': // write flash + if(store_userconf()) return ERR; + else return ALLOK; + break; + } + return BADCMD; // badcmd +} + +// read `buf` and get first integer `N` in it +// @return pointer to first non-number if all OK or NULL if first symbol isn't a space or number +static char *getnum(char *buf, int32_t *N){ + char c; + int positive = -1; + int32_t val = 0; + while((c = *buf++)){ + if(c == '\t' || c == ' '){ + if(positive < 0) continue; // beginning spaces + else break; // spaces after number + } + if(c == '-'){ + if(positive < 0){ + positive = 0; + continue; + }else break; // there already was `-` or number + } + if(c < '0' || c > '9') break; + if(positive < 0) positive = 1; + val = val * 10 + (int32_t)(c - '0'); + } + if(positive != -1){ + if(positive == 0){ + if(val == 0) return NULL; // single '-' + val = -val; + } + *N = val; + }else return NULL; + return buf-1; +} + +// get conf (uint16_t) number +// @return 0 if all OK +static int getu16(char *buf, uint16_t *N){ + int32_t N32; + if(!getnum(buf, &N32)) return 1; + if(N32 > 0xffff || N32 < 0) return 1; + *N = (uint16_t) N32; + return 0; +} + +static char *get_something(char *str){ + switch(*str++){ + case 'A': // get ADC value: voltage or current + return get_ADCval(str); + break; + case 'C': // get current configuration values + return get_conf(); + break; + case 'R': // get raw ADC values + return get_raw_adc(); + break; + case 'S': // get status + return get_status(); + break; + case 'T': + return get_temper(); + break; + } + return BADCMD; +} + +static char *get_status(){ + return NULL; +} + +typedef struct{ + const char *fieldname; + const uint16_t *ptr; +} user_conf_descr; + +static const user_conf_descr descrarr[] = { + {"DEVID", &the_conf.devID}, + {"V12NUM", &the_conf.v12numerator}, + {"V12DEN", &the_conf.v12denominator}, + {"I12NUM", &the_conf.i12numerator}, + {"I12DEN", &the_conf.i12denominator}, + {"V33NUM", &the_conf.v33numerator}, + {"V33DEN", &the_conf.v33denominator}, + {"ESWTHR", &the_conf.ESW_thres}, + {NULL, NULL} +}; + +static char *get_conf(){ + const user_conf_descr *curdesc = descrarr; + write2trbuf("DATAPOS="); + put_uint(the_conf.good_data_pos); + SENDBUF(); + do{ + write2trbuf(curdesc->fieldname); + put2trbuf('='); + put_uint((uint32_t) *curdesc->ptr); + SENDBUF(); + }while((++curdesc)->fieldname); + return EODATA; +} + +static char *get_raw_adc(){ + int i; + for(i = 0; i < NUMBER_OF_ADC_CHANNELS; ++i){ + write2trbuf("ADC["); + put2trbuf('0' + i); + write2trbuf("]="); + put_uint((uint32_t) ADC_array[i]); + SENDBUF(); + } + return EODATA; +} + +static char *get_ADCval(char *str){ + uint32_t v; + switch(*str){ + case 'D': // vdd + write2trbuf("VDD="); + v = getVdd(); + break; + case 'I': // motors' current + write2trbuf("IMOT="); + v = getImot(); + break; + case 'M': // vmot + write2trbuf("VMOT="); + v = getVmot(); + break; + default: + return BADCMD; + } + put_uint(v); + SENDBUF(); + return NULL; +} + +static char *set_something(char *str){ + switch(*str++){ + case 'D': // set denominator + return setDenEn(1, str); + break; + case 'E': // set numerator + return setDenEn(0, str); + break; + case 'I': // set device ID + return setDevId(str); + break; + case 'T': // set endsw threshold + return setESWthres(str); + break; + } + return BADCMD; +} + +/** + * set denominator/numerator + * @param De == 1 for denominator, == 0 for numerator + * @param str - rest of string + */ +static char *setDenEn(uint8_t De, char *str){ + uint16_t *targ = NULL; + switch(*str++){ + case 'D': + targ = De ? &the_conf.v33denominator : &the_conf.v33numerator; + break; + case 'I': + targ = De ? &the_conf.i12denominator : &the_conf.i12numerator; + break; + case 'M': + targ = De ? &the_conf.v12denominator : &the_conf.v12numerator; + break; + default: + return BADCMD; + } + omitwsp(str); + if(getu16(str, targ)) return BADCMD; + return ALLOK; +} + +static char *setDevId(char *str){ + omitwsp(str); + if(getu16(str, &the_conf.devID)) return BADCMD; + return ALLOK; +} + +static char *setESWthres(char *str){ + omitwsp(str); + if(getu16(str, &the_conf.ESW_thres)) return BADCMD; + return ALLOK; +} + +static char *get_temper(){ + uint32_t t = getTemp(); + write2trbuf("TEMP="); + put_uint(t); + SENDBUF(); + return NULL; +} diff --git a/STM32/steppers/proto.h b/STM32/steppers/proto.h new file mode 100644 index 0000000..405d7cf --- /dev/null +++ b/STM32/steppers/proto.h @@ -0,0 +1,29 @@ +/* + * geany_encoding=koi8-r + * proto.h + * + * Copyright 2017 Edward V. Emelianov + * + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program; if not, write to the Free Software + * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, + * MA 02110-1301, USA. + * + */ +#pragma once +#ifndef __PROTO_H__ +#define __PROTO_H__ + +char* process_command(char *cmdbuf); + +#endif // __PROTO_H__ diff --git a/STM32/steppers/steppers.geany b/STM32/steppers/steppers.geany new file mode 100644 index 0000000..7185bb8 --- /dev/null +++ b/STM32/steppers/steppers.geany @@ -0,0 +1,37 @@ +[editor] +line_wrapping=false +line_break_column=100 +auto_continue_multiline=true + +[file_prefs] +final_new_line=true +ensure_convert_new_lines=true +strip_trailing_spaces=true +replace_tabs=true + +[indentation] +indent_width=4 +indent_type=0 +indent_hard_tab_width=4 +detect_indent=false +detect_indent_width=false +indent_mode=3 + +[project] +name=Steppers +base_path=/home/eddy/Docs/SAO/Zeiss-1000/Simple_photometer/STM32/ + +[long line marker] +long_line_behaviour=1 +long_line_column=100 + +[files] +current_page=4 +FILE_NAME_0=0;C;0;EUTF-8;0;1;0;%2Fhome%2Feddy%2FDocs%2FSAO%2FZeiss-1000%2FSimple_photometer%2FSTM32%2Fmain.c;0;4 +FILE_NAME_1=130;Make;0;EUTF-8;1;1;0;%2Fhome%2Feddy%2FDocs%2FSAO%2FZeiss-1000%2FSimple_photometer%2FSTM32%2FMakefile;0;4 +FILE_NAME_2=0;Markdown;0;EUTF-8;0;1;0;%2Fhome%2Feddy%2FDocs%2FSAO%2FZeiss-1000%2FSimple_photometer%2FSTM32%2FReadme.md;0;4 +FILE_NAME_3=0;C;0;EUTF-8;0;1;0;%2Fhome%2Feddy%2FDocs%2FSAO%2FZeiss-1000%2FSimple_photometer%2FSTM32%2Fusart.c;0;4 +FILE_NAME_4=0;C;0;EUTF-8;0;1;0;%2Fhome%2Feddy%2FDocs%2FSAO%2FZeiss-1000%2FSimple_photometer%2FSTM32%2Fusart.h;0;4 + +[VTE] +last_dir=/home/eddy diff --git a/STM32/steppers/usart.c b/STM32/steppers/usart.c new file mode 100644 index 0000000..436276e --- /dev/null +++ b/STM32/steppers/usart.c @@ -0,0 +1,218 @@ +/* + * usart.c + * + * Copyright 2017 Edward V. Emelianov + * + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program; if not, write to the Free Software + * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, + * MA 02110-1301, USA. + */ + +#include "usart.h" +#include // memcpy + +extern volatile uint32_t Tms; + +static int datalen[2] = {0,0}; // received data line length (including '\n') + +int linerdy = 0, // received data ready + dlen = 0, // length of data (including '\n') in current buffer + bufovr = 0, // input buffer overfull + txrdy = 1 // transmission done +; + +static int rbufno = 0; // current rbuf number +static char rbuf[2][UARTBUFSZ], tbuf[UARTBUFSZ]; // receive & transmit buffers +static char *recvdata = NULL; + +static char trbuf[UARTBUFSZ]; // auxiliary buffer for data transmission +int trbufidx = 0; +int put2trbuf(char c){ + if(trbufidx > UARTBUFSZ - 1) return 1; + trbuf[trbufidx++] = c; + return 0; +} +// write zero-terminated string +int write2trbuf(const char *str){ + while(trbufidx < UARTBUFSZ - 1 && *str){ + trbuf[trbufidx++] = *str++; + } + if(*str) return 1; // buffer overfull + trbuf[trbufidx] = 0; + return 0; // all OK +} +char *gettrbuf(){ + if(trbufidx > UARTBUFSZ - 1) trbufidx = UARTBUFSZ - 1; + trbuf[trbufidx] = 0; + return trbuf; +} + + +void USART1_config(){ + /* Enable the peripheral clock of GPIOA */ + RCC->AHBENR |= RCC_AHBENR_GPIOAEN; + /* GPIO configuration for USART1 signals */ + /* (1) Select AF mode (10) on PA9 and PA10 */ + /* (2) AF1 for USART1 signals */ + GPIOA->MODER = (GPIOA->MODER & ~(GPIO_MODER_MODER9|GPIO_MODER_MODER10))\ + | (GPIO_MODER_MODER9_1 | GPIO_MODER_MODER10_1); /* (1) */ + GPIOA->AFR[1] = (GPIOA->AFR[1] &~ (GPIO_AFRH_AFRH1 | GPIO_AFRH_AFRH2))\ + | (1 << (1 * 4)) | (1 << (2 * 4)); /* (2) */ + // Tx (PA9) in OD mode + GPIOA->OTYPER |= 1 << 9; + #ifdef EBUG + GPIOA->PUPDR = (GPIOA->PUPDR & ~GPIO_PUPDR_PUPDR9) | GPIO_PUPDR_PUPDR9_0; // set pullup for Tx + #endif + /* Enable the peripheral clock USART1 */ + RCC->APB2ENR |= RCC_APB2ENR_USART1EN; + /* Configure USART1 */ + /* (1) oversampling by 16, 115200 baud */ + /* (2) 8 data bit, 1 start bit, 1 stop bit, no parity */ + USART1->BRR = 480000 / 1152; /* (1) */ + USART1->CR1 = USART_CR1_TE | USART_CR1_RE | USART_CR1_UE; /* (2) */ + /* polling idle frame Transmission */ + while(!(USART1->ISR & USART_ISR_TC)){} + USART1->ICR |= USART_ICR_TCCF; /* clear TC flag */ + USART1->CR1 |= USART_CR1_RXNEIE; /* enable TC, TXE & RXNE interrupt */ + RCC->AHBENR |= RCC_AHBENR_DMA1EN; + DMA1_Channel2->CPAR = (uint32_t) &(USART1->TDR); // periph + DMA1_Channel2->CMAR = (uint32_t) tbuf; // mem + DMA1_Channel2->CCR |= DMA_CCR_MINC | DMA_CCR_DIR | DMA_CCR_TCIE; // 8bit, mem++, mem->per, transcompl irq + USART1->CR3 = USART_CR3_DMAT; + NVIC_SetPriority(DMA1_Channel2_3_IRQn, 3); + NVIC_EnableIRQ(DMA1_Channel2_3_IRQn); + /* Configure IT */ + /* (3) Set priority for USART1_IRQn */ + /* (4) Enable USART1_IRQn */ + NVIC_SetPriority(USART1_IRQn, 0); /* (3) */ + NVIC_EnableIRQ(USART1_IRQn); /* (4) */ +} + +void usart1_isr(){ + #ifdef CHECK_TMOUT + static uint32_t tmout = 0; + #endif + if(USART1->ISR & USART_ISR_RXNE){ // RX not emty - receive next char + #ifdef CHECK_TMOUT + if(tmout && Tms >= tmout){ // set overflow flag + bufovr = 1; + datalen[rbufno] = 0; + } + tmout = Tms + TIMEOUT_MS; + if(!tmout) tmout = 1; // prevent 0 + #endif + // read RDR clears flag + uint8_t rb = USART1->RDR; + if(datalen[rbufno] < UARTBUFSZ){ // put next char into buf + rbuf[rbufno][datalen[rbufno]++] = rb; + if(rb == '\n'){ // got newline - line ready + linerdy = 1; + dlen = datalen[rbufno]; + recvdata = rbuf[rbufno]; + recvdata[dlen-1] = 0; // change '\n' to trailing zero + // prepare other buffer + rbufno = !rbufno; + datalen[rbufno] = 0; + #ifdef CHECK_TMOUT + // clear timeout at line end + tmout = 0; + #endif + } + }else{ // buffer overrun + bufovr = 1; + datalen[rbufno] = 0; + #ifdef CHECK_TMOUT + tmout = 0; + #endif + } + } +} + +void dma1_channel2_3_isr(){ + if(DMA1->ISR & DMA_ISR_TCIF2){ // Tx + DMA1->IFCR |= DMA_IFCR_CTCIF2; // clear TC flag + txrdy = 1; + } +} + +/** + * return length of received data (without trailing zero + */ +int usart1_getline(char **line){ + if(!linerdy) return 0; + if(bufovr){ + bufovr = 0; + linerdy = 0; + return 0; + } + *line = recvdata; + linerdy = 0; + return dlen; +} + +/* +// send bu UART zero-terminated string `str` with length `len` (with substitution of trailing zero by '\n') +TXstatus usart1_send(char *str){ + if(!txrdy) return LINE_BUSY; + int len = 0; + while(len < UARTBUFSZ && str[len]) ++len; + if(len > UARTBUFSZ-1) return STR_TOO_LONG; + str[len++] = '\n'; + txrdy = 0; + DMA1_Channel2->CCR &= ~DMA_CCR_EN; + memcpy(tbuf, str, len); + DMA1_Channel2->CNDTR = len; + DMA1_Channel2->CCR |= DMA_CCR_EN; // start transmission + return ALL_OK; +}*/ + +TXstatus usart1_send(char *str){ + if(!txrdy) return LINE_BUSY; + int i; + for(i = 0; i < UARTBUFSZ; ++i){ + char c = *str++; + if(c == 0){ c = '\n'; i = UARTBUFSZ;} + USART1->TDR = c; + while(!(USART1->ISR & USART_ISR_TXE)); + } + txrdy = 1; + return ALL_OK; +} + + +/** + * Fill trbuf with integer value + * @param N - integer value + * @return 1 if buffer overflow; oterwise return 0 + */ +int put_int(int32_t N){ + if(N < 0){ + if(put2trbuf('-')) return 1; + N = -N; + } + return put_uint((uint32_t) N); +} + +int put_uint(uint32_t N){ + char buf[10]; + int L = 0; + if(N){ + while(N){ + buf[L++] = N % 10 + '0'; + N /= 10; + } + while(L--) if(put2trbuf(buf[L])) return 1; + }else if(put2trbuf('0')) return 1; + return 0; +} diff --git a/STM32/steppers/usart.h b/STM32/steppers/usart.h new file mode 100644 index 0000000..a26d3b8 --- /dev/null +++ b/STM32/steppers/usart.h @@ -0,0 +1,60 @@ +/* + * usart.h + * + * Copyright 2017 Edward V. Emelianov + * + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program; if not, write to the Free Software + * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, + * MA 02110-1301, USA. + */ +#pragma once +#ifndef __USART_H__ +#define __USART_H__ + +#include "stm32f0.h" + +// input and output buffers size +#define UARTBUFSZ (64) +// timeout between data bytes +#define TIMEOUT_MS (1500) +// check timeout +#define CHECK_TMOUT + +typedef enum{ + ALL_OK, + LINE_BUSY, + STR_TOO_LONG +} TXstatus; + +#define usart1rx() (linerdy) +#define usart1ovr() (bufovr) + +extern int linerdy, bufovr, txrdy; +extern int trbufidx; + +void USART1_config(); +int usart1_getline(char **line); +TXstatus usart1_send(char *str); +#define usart1_send_blocking(str) do{}while(LINE_BUSY == usart1_send(str)) + +#define cleartrbuf() do{trbufidx = 0;}while(0) +#define trbufisfull() (trbufidx) +int put2trbuf(char c); +int write2trbuf(const char *str); +char *gettrbuf(); +int put_int(int32_t N); +int put_uint(uint32_t N); + + +#endif // __USART_H__