Merge remote-tracking branch 'origin/master' into ieee802154

This commit is contained in:
Gregory Nutt 2017-04-14 08:57:39 -06:00
commit a7ad683c89
64 changed files with 14993 additions and 7 deletions

View File

@ -0,0 +1,146 @@
/************************************************************************************
* arch/arm/include/stm32f0/chip.h
*
* Copyright (C) 2017 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
* Alan Carvalho de Assis <acassis@gmail.com>
*
* 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 NuttX 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 OWNER 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.
*
************************************************************************************/
#ifndef __ARCH_ARM_INCLUDE_STM32F0_CHIP_H
#define __ARCH_ARM_INCLUDE_STM32F0_CHIP_H
/************************************************************************************
* Included Files
************************************************************************************/
#include <nuttx/config.h>
/************************************************************************************
* Pre-processor Definitions
************************************************************************************/
/* Get customizations for each supported chip */
#if defined(CONFIG_ARCH_CHIP_STM32F051R8)
# define STM32F051x 1 /* STM32F051x family */
# define STM32F0_FLASH_SIZE (64*1024) /* 64Kb */
# define STM32F0_SRAM_SIZE (8*1024) /* 8Kb */
# define STM32F0_CPUSRAM_SIZE (8*1024)
# undef STM32F0_HAVE_BANK0 /* No AHB SRAM bank 0 */
# undef STM32F0_HAVE_BANK1 /* No AHB SRAM bank 1 */
# define STM32F0_NETHCONTROLLERS 0 /* No Ethernet controller */
# define STM32F0_NUSBHOST 0 /* No USB host controller */
# define STM32F0_NUSBOTG 0 /* No USB OTG controller */
# define STM32F0_NUSBDEV 1 /* One USB device controller */
# define STM32F0_NUSART 2 /* Two USARTs module */
# define STM32F0_NPORTS 6 /* 6 GPIO ports, GPIOA-F */
# define STM32F0_NCAN 1 /* One CAN controller */
# define STM32F0_NI2C 2 /* Two I2C module */
# define STM32F0_NI2S 1 /* One I2S module */
# define STM32F0_NDAC 1 /* One DAC module */
# define STM32F0_NSPI 2 /* Two DAC module */
#else
# error "Unsupported STM32F0xx chip"
#endif
/* NVIC priority levels *************************************************************/
/* Each priority field holds a priority value, 0-31. The lower the value, the greater
* the priority of the corresponding interrupt. The processor implements only
* bits[7:6] of each field, bits[5:0] read as zero and ignore writes.
*/
#define NVIC_SYSH_PRIORITY_MIN 0xc0 /* All bits[7:6] set is minimum priority */
#define NVIC_SYSH_PRIORITY_DEFAULT 0x80 /* Midpoint is the default */
#define NVIC_SYSH_PRIORITY_MAX 0x00 /* Zero is maximum priority */
#define NVIC_SYSH_PRIORITY_STEP 0x40 /* Two bits of interrupt priority used */
/* If CONFIG_ARMV7M_USEBASEPRI is selected, then interrupts will be disabled
* by setting the BASEPRI register to NVIC_SYSH_DISABLE_PRIORITY so that most
* interrupts will not have execution priority. SVCall must have execution
* priority in all cases.
*
* In the normal cases, interrupts are not nest-able and all interrupts run
* at an execution priority between NVIC_SYSH_PRIORITY_MIN and
* NVIC_SYSH_PRIORITY_MAX (with NVIC_SYSH_PRIORITY_MAX reserved for SVCall).
*
* If, in addition, CONFIG_ARCH_HIPRI_INTERRUPT is defined, then special
* high priority interrupts are supported. These are not "nested" in the
* normal sense of the word. These high priority interrupts can interrupt
* normal processing but execute outside of OS (although they can "get back
* into the game" via a PendSV interrupt).
*
* In the normal course of things, interrupts must occasionally be disabled
* using the up_irq_save() inline function to prevent contention in use of
* resources that may be shared between interrupt level and non-interrupt
* level logic. Now the question arises, if CONFIG_ARCH_HIPRI_INTERRUPT,
* do we disable all interrupts (except SVCall), or do we only disable the
* "normal" interrupts. Since the high priority interrupts cannot interact
* with the OS, you may want to permit the high priority interrupts even if
* interrupts are disabled. The setting CONFIG_ARCH_INT_DISABLEALL can be
* used to select either behavior:
*
* ----------------------------+--------------+----------------------------
* CONFIG_ARCH_HIPRI_INTERRUPT | NO | YES
* ----------------------------+--------------+--------------+-------------
* CONFIG_ARCH_INT_DISABLEALL | N/A | YES | NO
* ----------------------------+--------------+--------------+-------------
* | | | SVCall
* | SVCall | SVCall | HIGH
* Disable here and below --------> MAXNORMAL ---> HIGH --------> MAXNORMAL
* | | MAXNORMAL |
* ----------------------------+--------------+--------------+-------------
*/
#if defined(CONFIG_ARCH_HIPRI_INTERRUPT) && defined(CONFIG_ARCH_INT_DISABLEALL)
# define NVIC_SYSH_MAXNORMAL_PRIORITY (NVIC_SYSH_PRIORITY_MAX + 2*NVIC_SYSH_PRIORITY_STEP)
# define NVIC_SYSH_HIGH_PRIORITY (NVIC_SYSH_PRIORITY_MAX + NVIC_SYSH_PRIORITY_STEP)
# define NVIC_SYSH_DISABLE_PRIORITY NVIC_SYSH_HIGH_PRIORITY
# define NVIC_SYSH_SVCALL_PRIORITY NVIC_SYSH_PRIORITY_MAX
#else
# define NVIC_SYSH_MAXNORMAL_PRIORITY (NVIC_SYSH_PRIORITY_MAX + NVIC_SYSH_PRIORITY_STEP)
# define NVIC_SYSH_HIGH_PRIORITY NVIC_SYSH_PRIORITY_MAX
# define NVIC_SYSH_DISABLE_PRIORITY NVIC_SYSH_MAXNORMAL_PRIORITY
# define NVIC_SYSH_SVCALL_PRIORITY NVIC_SYSH_PRIORITY_MAX
#endif
/************************************************************************************
* Public Types
************************************************************************************/
/************************************************************************************
* Public Data
************************************************************************************/
/************************************************************************************
* Public Functions
************************************************************************************/
#endif /* __ARCH_ARM_INCLUDE_STM32F0_CHIP_H */

View File

@ -0,0 +1,143 @@
/****************************************************************************
* arch/arm/include/stm32f0/irq.h
*
* Copyright (C) 2017 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
* Alan Carvalho de Assis <acassis@gmail.com>
*
* 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 NuttX 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 OWNER 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.
*
****************************************************************************/
/* This file should never be included directed but, rather, only indirectly
* through nuttx/irq.h
*/
#ifndef __ARCH_ARM_INCLUDE_STM32F0_IRQ_H
#define __ARCH_ARM_INCLUDE_STM32F0_IRQ_H
/****************************************************************************
* Included Files
****************************************************************************/
#ifndef __ASSEMBLY__
# include <stdint.h>
#endif
#include <arch/stm32f0/chip.h>
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/* IRQ numbers. The IRQ number corresponds vector number and hence map
* directly to bits in the NVIC. This does, however, waste several words of
* memory in the IRQ to handle mapping tables.
*/
/* Common Processor Exceptions (vectors 0-15) */
#define STM32F0_IRQ_RESERVED (0) /* Reserved vector (only used with CONFIG_DEBUG_FEATURES) */
/* Vector 0: Reset stack pointer value */
/* Vector 1: Reset (not handler as an IRQ) */
#define STM32F0_IRQ_NMI (2) /* Vector 2: Non-Maskable Interrupt (NMI) */
#define STM32F0_IRQ_HARDFAULT (3) /* Vector 3: Hard fault */
/* Vectors 4-10: Reserved */
#define STM32F0_IRQ_SVCALL (11) /* Vector 11: SVC call */
/* Vector 12-13: Reserved */
#define STM32F0_IRQ_PENDSV (14) /* Vector 14: Pendable system service request */
#define STM32F0_IRQ_SYSTICK (15) /* Vector 15: System tick */
/* External interrupts (vectors >= 16) */
#define STM32F0_IRQ_EXTINT (16) /* Vector number of the first external interrupt */
#define STM32F0_IRQ_WWDG (16) /* Vector 16: WWDG */
#define STM32F0_IRQ_PVD_VDDIO2 (17) /* Vector 17: PVD_VDDIO2 */
#define STM32F0_IRQ_RTC (18) /* Vector 18: RTC */
#define STM32F0_IRQ_FLASH (19) /* Vector 19: FLASH */
#define STM32F0_IRQ_RCC_CRS (20) /* Vector 20: RCC and CRS */
#define STM32F0_IRQ_EXTI0_1 (21) /* Vector 21: EXTI0_1 */
#define STM32F0_IRQ_EXTI2_3 (22) /* Vector 22: EXTI2_3 */
#define STM32F0_IRQ_EXTI4_15 (23) /* Vector 23: EXTI4_15 */
#define STM32F0_IRQ_TSC (24) /* Vector 24: TSC */
#define STM32F0_IRQ_DMA_CH1 (25) /* Vector 25: DMA_CH1 */
#define STM32F0_IRQ_DMA_CH23 (26) /* Vector 26: DMA_CH2_3 and DMA2_CH1_2 */
#define STM32F0_IRQ_DMA_CH4567 (27) /* Vector 27: DMA_CH4_5_6_7 and DMA2_CH3_4_5 */
#define STM32F0_IRQ_ADC_COMP (28) /* Vector 28: ADC_COMP */
#define STM32F0_IRQ_TIM1_BRK (29) /* Vector 29: TIM1_BRK_UP_TRG_COM */
#define STM32F0_IRQ_TIM1_CC (30) /* Vector 30: TIM1_CC */
#define STM32F0_IRQ_TIM2 (31) /* Vector 31: TIM2 */
#define STM32F0_IRQ_TIM3 (32) /* Vector 32: TIM3 */
#define STM32F0_IRQ_TIM6_DAC (33) /* Vector 33: TIM6 and DAC */
#define STM32F0_IRQ_TIM7 (34) /* Vector 34: TIM7 */
#define STM32F0_IRQ_TIM14 (35) /* Vector 35: TIM14 */
#define STM32F0_IRQ_TIM15 (36) /* Vector 36: TIM15 */
#define STM32F0_IRQ_TIM16 (37) /* Vector 37: TIM16 */
#define STM32F0_IRQ_TIM17 (38) /* Vector 38: TIM17 */
#define STM32F0_IRQ_I2C1 (39) /* Vector 39: I2C1 */
#define STM32F0_IRQ_I2C2 (40) /* Vector 40: I2C2 */
#define STM32F0_IRQ_SPI1 (41) /* Vector 41: SPI1 */
#define STM32F0_IRQ_SPI2 (42) /* Vector 42: SPI2 */
#define STM32F0_IRQ_USART1 (43) /* Vector 43: USART1 */
#define STM32F0_IRQ_USART2 (44) /* Vector 44: USART2 */
#define STM32F0_IRQ_USART345678 (45) /* Vector 45: USART3_4_5_6_7_8 */
#define STM32F0_IRQ_CEC_CAN (46) /* Vector 46: HDMI CEC and CAN */
#define STM32F0_IRQ_USB (47) /* Vector 47: USB */
#define NR_VECTORS (64) /* 64 vectors */
#define NR_IRQS (48) /* 64 interrupts but 48 IRQ numbers */
/****************************************************************************
* Public Types
****************************************************************************/
#ifndef __ASSEMBLY__
typedef void (*vic_vector_t)(uint32_t *regs);
/****************************************************************************
* Inline functions
****************************************************************************/
/****************************************************************************
* Public Data
****************************************************************************/
/****************************************************************************
* Public Function Prototypes
****************************************************************************/
#ifdef __cplusplus
extern "C"
{
#endif
#ifdef __cplusplus
}
#endif
#endif /* __ASSEMBLY__ */
#endif /* __ARCH_ARM_INCLUDE_STM32F0_IRQ_H */

1560
arch/arm/src/stm32f0/Kconfig Normal file

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,100 @@
############################################################################
# arch/arm/src/stm32f0/Make.defs
#
# Copyright (C) 2017 Gregory Nutt. All rights reserved.
# Author: Gregory Nutt <gnutt@nuttx.org>
# Alan Carvalho de Assis <acassis@gmail.com>
#
# 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 NuttX 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 OWNER 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.
#
############################################################################
HEAD_ASRC =
CMN_ASRCS = up_exception.S up_saveusercontext.S up_fullcontextrestore.S
CMN_ASRCS += up_switchcontext.S vfork.S
CMN_CSRCS = up_allocateheap.c up_assert.c up_blocktask.c up_copyfullstate.c
CMN_CSRCS += up_createstack.c up_mdelay.c up_udelay.c up_exit.c
CMN_CSRCS += up_initialize.c up_initialstate.c up_interruptcontext.c
CMN_CSRCS += up_puts.c up_modifyreg8.c up_modifyreg16.c up_modifyreg32.c
CMN_CSRCS += up_releasepending.c up_releasestack.c up_reprioritizertr.c
CMN_CSRCS += up_schedulesigaction.c up_sigdeliver.c up_stackframe.c
CMN_CSRCS += up_systemreset.c up_unblocktask.c up_usestack.c up_doirq.c
CMN_CSRCS += up_hardfault.c up_svcall.c up_vectors.c up_vfork.c
ifeq ($(CONFIG_BUILD_PROTECTED),y)
CMN_CSRCS += up_task_start.c up_pthread_start.c
ifneq ($(CONFIG_DISABLE_SIGNALS),y)
CMN_CSRCS += up_signal_dispatch.c
CMN_UASRCS += up_signal_handler.S
endif
endif
ifeq ($(CONFIG_STACK_COLORATION),y)
CMN_CSRCS += up_checkstack.c
endif
ifeq ($(CONFIG_DEBUG_FEATURES),y)
CMN_CSRCS += up_dumpnvic.c
endif
CHIP_ASRCS =
CHIP_CSRCS = stm32f0_clockconfig.c stm32f0_gpio.c stm32f0_idle.c
CHIP_CSRCS += stm32f0_irq.c stm32f0_lowputc.c stm32f0_serial.c
CHIP_CSRCS += stm32f0_start.c
# Configuration-dependent STM32F0xx files
ifneq ($(CONFIG_SCHED_TICKLESS),y)
CHIP_CSRCS += stm32f0_timerisr.c
endif
ifeq ($(CONFIG_BUILD_PROTECTED),y)
CHIP_CSRCS += stm32f0_userspace.c
endif
ifeq ($(CONFIG_STM32F0_GPIOIRQ),y)
CHIP_CSRCS += stm32f0_gpioint.c
endif
ifeq ($(CONFIG_ARCH_IRQPRIO),y)
CHIP_CSRCS += stm32f0_irqprio.c
endif
ifeq ($(CONFIG_STM32F0_SPI0),y)
CHIP_CSRCS += stm32f0_spi.c
else
ifeq ($(CONFIG_STM32F0_SPI1),y)
CHIP_CSRCS += stm32f0_spi.c
endif
endif
ifeq ($(CONFIG_PWM),y)
CHIP_CSRCS += stm32f0_pwm.c
endif

View File

@ -0,0 +1,59 @@
/************************************************************************************
* arch/arm/src/stm32f0/chip.h
*
* Copyright (C) 2017 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
* Alan Carvalho de Assis <acassis@gmail.com>
*
* 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 NuttX 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 OWNER 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.
*
************************************************************************************/
#ifndef __ARCH_ARM_SRC_STM32F0_CHIP_H
#define __ARCH_ARM_SRC_STM32F0_CHIP_H
/************************************************************************************
* Included Files
************************************************************************************/
#include <nuttx/config.h>
#include "nvic.h"
/* Include the chip capabilities file */
#include <arch/stm32f0/chip.h>
#define ARMV6M_PERIPHERAL_INTERRUPTS 32
/* Include the memory map file. Other chip hardware files should then include
* this file for the proper setup.
*/
#include "chip/stm32f0_memorymap.h"
#endif /* __ARCH_ARM_SRC_STM32F0_CHIP_H */

View File

@ -0,0 +1,127 @@
/************************************************************************************
* arch/arm/src/stm32f0/chip/stm32f0_pinmap.h
*
* Copyright (C) 2017 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
* Alan Carvalho de Assis <acassis@gmail.com>
*
* 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 NuttX 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 OWNER 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.
*
************************************************************************************/
#ifndef __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_PINMMAP_H
#define __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_PINMMAP_H
/************************************************************************************
* Included Files
************************************************************************************/
#include <nuttx/config.h>
#include "stm32f0_gpio.h"
/************************************************************************************
* Pre-processor Definitions
************************************************************************************/
/* ADC */
#define GPIO_ADC_IN0 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN0)
#define GPIO_ADC_IN1 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN1)
#define GPIO_ADC_IN2 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN2)
#define GPIO_ADC_IN3 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN3)
#define GPIO_ADC_IN4 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN4)
#define GPIO_ADC_IN5 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN5)
#define GPIO_ADC_IN6 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN6)
#define GPIO_ADC_IN7 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN7)
#define GPIO_ADC_IN8 (GPIO_ANALOG|GPIO_PORTB|GPIO_PIN0)
#define GPIO_ADC_IN9 (GPIO_ANALOG|GPIO_PORTB|GPIO_PIN1)
#define GPIO_ADC_IN10 (GPIO_ANALOG|GPIO_PORTC|GPIO_PIN0)
#define GPIO_ADC_IN11 (GPIO_ANALOG|GPIO_PORTC|GPIO_PIN1)
#define GPIO_ADC_IN12 (GPIO_ANALOG|GPIO_PORTC|GPIO_PIN2)
#define GPIO_ADC_IN13 (GPIO_ANALOG|GPIO_PORTC|GPIO_PIN3)
#define GPIO_ADC_IN14 (GPIO_ANALOG|GPIO_PORTC|GPIO_PIN4)
#define GPIO_ADC_IN15 (GPIO_ANALOG|GPIO_PORTC|GPIO_PIN5)
/* TIMERS */
/* TODO: Define TIMx pins here */
/* USART */
#if defined(CONFIG_STM32F0_USART1_REMAP)
# define GPIO_USART1_TX (GPIO_ALT|GPIO_AF0 |GPIO_PORTB|GPIO_PIN6)
# define GPIO_USART1_RX (GPIO_ALT|GPIO_AF0 |GPIO_PORTB|GPIO_PIN7)
#else
# define GPIO_USART1_TX (GPIO_ALT|GPIO_AF1 |GPIO_PORTA|GPIO_PIN9)
# define GPIO_USART1_RX (GPIO_ALT|GPIO_AF1 |GPIO_PORTA|GPIO_PIN10)
#endif
#define GPIO_USART1_CTS (GPIO_ALT|GPIO_AF1 |GPIO_PORTA|GPIO_PIN11)
#define GPIO_USART1_RTS (GPIO_ALT|GPIO_AF1 |GPIO_PORTA|GPIO_PIN12)
#define GPIO_USART1_CK (GPIO_ALT|GPIO_AF1 |GPIO_PORTA|GPIO_PIN8)
#define GPIO_USART2_CTS (GPIO_ALT|GPIO_AF1 |GPIO_PORTA|GPIO_PIN0)
#define GPIO_USART2_RTS (GPIO_ALT|GPIO_AF1 |GPIO_PORTA|GPIO_PIN1)
#define GPIO_USART2_TX (GPIO_ALT|GPIO_AF1 |GPIO_PORTA|GPIO_PIN2)
#define GPIO_USART2_RX (GPIO_ALT|GPIO_AF1 |GPIO_PORTA|GPIO_PIN3)
#define GPIO_USART2_CK (GPIO_ALT|GPIO_AF1 |GPIO_PORTA|GPIO_PIN4)
/* SPI */
#if defined(CONFIG_STM32F0_SPI1_REMAP)
# define GPIO_SPI1_NSS (GPIO_ALT|GPIO_AF0 |GPIO_PORTA|GPIO_PIN15)
# define GPIO_SPI1_SCK (GPIO_ALT|GPIO_AF0 |GPIO_PORTB|GPIO_PIN3)
# define GPIO_SPI1_MISO (GPIO_ALT|GPIO_AF0 |GPIO_PORTB|GPIO_PIN4)
# define GPIO_SPI1_MOSI (GPIO_ALT|GPIO_AF0 |GPIO_PORTB|GPIO_PIN5)
#else
# define GPIO_SPI1_NSS (GPIO_ALT|GPIO_AF0 |GPIO_PORTA|GPIO_PIN4)
# define GPIO_SPI1_SCK (GPIO_ALT|GPIO_AF0 |GPIO_PORTA|GPIO_PIN5)
# define GPIO_SPI1_MISO (GPIO_ALT|GPIO_AF0 |GPIO_PORTA|GPIO_PIN6)
# define GPIO_SPI1_MOSI (GPIO_ALT|GPIO_AF0 |GPIO_PORTA|GPIO_PIN7)
#endif
#define GPIO_SPI2_NSS (GPIO_ALT|GPIO_AF0 |GPIO_PORTB|GPIO_PIN12)
#define GPIO_SPI2_SCK (GPIO_ALT|GPIO_AF0 |GPIO_PORTB|GPIO_PIN13)
#define GPIO_SPI2_MISO (GPIO_ALT|GPIO_AF0 |GPIO_PORTB|GPIO_PIN14)
#define GPIO_SPI2_MOSI (GPIO_ALT|GPIO_AF0 |GPIO_PORTB|GPIO_PIN15)
/* I2C */
#if defined(CONFIG_STM32F0_I2C1_REMAP)
# define GPIO_I2C1_SCL (GPIO_ALT|GPIO_AF1 |GPIO_PORTB|GPIO_PIN8)
# define GPIO_I2C1_SDA (GPIO_ALT|GPIO_AF1 |GPIO_PORTB|GPIO_PIN9)
#else
# define GPIO_I2C1_SCL (GPIO_ALT|GPIO_AF1 |GPIO_PORTB|GPIO_PIN6)
# define GPIO_I2C1_SDA (GPIO_ALT|GPIO_AF1 |GPIO_PORTB|GPIO_PIN7)
#endif
#define GPIO_I2C1_SMBA (GPIO_ALT|GPIO_AF3 |GPIO_PORTB|GPIO_PIN5)
#define GPIO_I2C2_SCL (GPIO_ALT|GPIO_AF1 |GPIO_PORTB|GPIO_PIN10)
#define GPIO_I2C2_SDA (GPIO_ALT|GPIO_AF1 |GPIO_PORTB|GPIO_PIN11)
#endif /* __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_PINMMAP_H */

View File

@ -0,0 +1,157 @@
/************************************************************************************
* arch/arm/src/stm32f0/chip/stm32f05xxx_memorymap.h
*
* Copyright (C) 2017 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
* Alan Carvalho de Assis <acassis@gmail.com>
*
* 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 NuttX 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 OWNER 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.
*
************************************************************************************/
#ifndef __ARCH_ARM_SRC_STM32F0_CHIP_STM32F05XXX_MEMORYMAP_H
#define __ARCH_ARM_SRC_STM32F0_CHIP_STM32F05XXX_MEMORYMAP_H
/************************************************************************************
* Pre-processor Definitions
************************************************************************************/
/* STM32F050XXX Address Blocks *******************************************************/
#define STM32F0_CODE_BASE 0x00000000 /* 0x00000000-0x1fffffff: 512Mb code block */
#define STM32F0_SRAM_BASE 0x20000000 /* 0x20000000-0x3fffffff: 512Mb sram block */
#define STM32F0_PERIPH_BASE 0x40000000 /* 0x40000000-0x5fffffff: 512Mb peripheral block */
/* 0x60000000-0xdfffffff: Reserved */
#define STM32F0_CORTEX_BASE 0xe0000000 /* 0xe0000000-0xffffffff: 512Mb Cortex-M4 block */
#define STM32F0_REGION_MASK 0xf0000000
#define STM32F0_IS_SRAM(a) ((((uint32_t)(a)) & STM32F0_REGION_MASK) == STM32F0_SRAM_BASE)
/* Code Base Addresses **************************************************************/
#define STM32F0_BOOT_BASE 0x00000000 /* 0x00000000-0x000fffff: Aliased boot memory */
/* 0x00100000-0x07ffffff: Reserved */
#define STM32F0_FLASH_BASE 0x08000000 /* 0x08000000-0x080fffff: FLASH memory */
/* 0x08100000-0x0fffffff: Reserved */
#define STM32F0_CCMRAM_BASE 0x10000000 /* 0x10000000-0x1000ffff: 64Kb CCM data RAM */
/* 0x10010000-0x1ffeffff: Reserved */
#define STM32F0_SYSMEM_BASE 0x1fffd800 /* 0x1fff0000-0x1fff7a0f: System memory */
/* 0x1fff7a10-0x1fff7fff: Reserved */
#define STM32F0_OPTION_BASE 0x1ffff800 /* 0x1fffc000-0x1fffc007: Option bytes */
/* 0x1fffc008-0x1fffffff: Reserved */
/* System Memory Addresses **********************************************************/
#define STM32F0_SYSMEM_UID 0x1ffff7ac /* The 96-bit unique device identifier */
#define STM32F0_SYSMEM_FSIZE 0x1ffff7cc /* This bitfield indicates the size of
* the device Flash memory expressed in
* Kbytes. Example: 0x040 corresponds
* to 64 Kbytes
*/
/* Peripheral Base Addresses ********************************************************/
#define STM32F0_APB1_BASE 0x40000000 /* 0x40000000-0x40009fff: APB1 */
/* 0x4000a000-0x4000ffff: Reserved */
#define STM32F0_APB2_BASE 0x40010000 /* 0x40010000-0x40006bff: APB2 */
/* 0x40016c00-0x4001ffff: Reserved */
#define STM32F0_AHB1_BASE 0x40020000 /* 0x40020000-0x400243ff: APB1 */
/* 0x40024400-0x4007ffff: Reserved */
#define STM32F0_AHB2_BASE 0x48000000 /* 0x48000000-0x480017ff: AHB2 */
/* 0x48001800-0x4fffFfff: Reserved */
#define STM32F0_AHB3_BASE 0x50000000 /* 0x50000000-0x500007ff: AHB3 */
/* APB1 Base Addresses **************************************************************/
#define STM32F0_TIM2_BASE 0x40000000 /* 0x40000000-0x400003ff TIM2 */
#define STM32F0_TIM3_BASE 0x40000400 /* 0x40000400-0x400007ff TIM3 */
#define STM32F0_TIM6_BASE 0x40001000 /* 0x40001000-0x400013ff TIM6 */
#define STM32F0_TIM7_BASE 0x40001400 /* 0x40001400-0x400017ff TIM7 */
#define STM32F0_TIM14_BASE 0x40002000 /* 0x40002000-0x400023ff TIM14 */
#define STM32F0_RTC_BASE 0x40002800 /* 0x40002800-0x40002bff RTC */
#define STM32F0_WWDG_BASE 0x40002c00 /* 0x40002c00-0x40002fff WWDG */
#define STM32F0_IWDG_BASE 0x40003000 /* 0x40003000-0x400033ff IWDG */
#define STM32F0_SPI2_BASE 0x40003800 /* 0x40003800-0x40003bff SPI2, or */
#define STM32F0_I2S2_BASE 0x40003800 /* 0x40003800-0x40003bff I2S2 */
#define STM32F0_USART2_BASE 0x40004400 /* 0x40004400-0x400047ff USART2 */
#define STM32F0_USART3_BASE 0x40004800 /* 0x40004800-0x40004bff USART3 */
#define STM32F0_USART4_BASE 0x40004c00 /* 0x40004c00-0x40004fff USART4 */
#define STM32F0_USART5_BASE 0x40005000 /* 0x40005000-0x400053ff USART5 */
#define STM32F0_I2C1_BASE 0x40005400 /* 0x40005400-0x400057ff I2C1 */
#define STM32F0_I2C2_BASE 0x40005800 /* 0x40005800-0x40005bff I2C2 */
#define STM32F0_USB_BASE 0x40005c00 /* 0x40005c00-0x40005fff USB device FS */
#define STM32F0_USBRAM_BASE 0x40006000 /* 0x40006000-0x400063ff USB SRAM 512B */
#define STM32F0_CAN_BASE 0x40006400 /* 0x40006400-0x400067ff bxCAN */
#define STM32F0_CRS_BASE 0x40006c00 /* 0x40006c00-0x40006fff CRS */
#define STM32F0_PWR_BASE 0x40007000 /* 0x40007000-0x400073ff PWR */
#define STM32F0_DAC_BASE 0x40007400 /* 0x40007400-0x400077ff DAC */
#define STM32F0_CEC_BASE 0x40007800 /* 0x40007800-0x40007bff HDMI CEC */
/* APB2 Base Addresses **************************************************************/
#define STM32F0_SYSCFG_BASE 0x40010000 /* 0x40010000-0x400103ff SYSCFG + COMP + OPAMP */
#define STM32F0_EXTI_BASE 0x40010400 /* 0x40010400-0x400107ff EXTI */
#define STM32F0_USART6_BASE 0x40011400 /* 0x40011400-0x400117ff USART6 */
#define STM32F0_USART7_BASE 0x40011800 /* 0x40011800-0x40011bff USART7 */
#define STM32F0_USART8_BASE 0x40011c00 /* 0x40011c00-0x40011fff USART8 */
#define STM32F0_ADC_BASE 0x40012400 /* 0x40012400-0x400127ff ADC */
#define STM32F0_TIM1_BASE 0x40012c00 /* 0x40012c00-0x40012fff TIM1 */
#define STM32F0_SPI1_BASE 0x40013000 /* 0x40013000-0x400133ff SPI1 */
#define STM32F0_USART1_BASE 0x40013800 /* 0x40013800-0x40013bff USART1 */
#define STM32F0_TIM15_BASE 0x40014000 /* 0x40014000-0x400143ff TIM15 */
#define STM32F0_TIM16_BASE 0x40014400 /* 0x40014400-0x400147ff TIM16 */
#define STM32F0_TIM17_BASE 0x40014800 /* 0x40014800-0x40014bff TIM17 */
#define STM32F0_DBGMCU_BASE 0x40015800 /* 0x40015800-0x40015bff DBGMCU */
/* AHB1 Base Addresses **************************************************************/
#define STM32F0_DMA1_BASE 0x40020000 /* 0x40020000-0x400203ff: DMA1 */
#define STM32F0_DMA2_BASE 0x40020400 /* 0x40020400-0x400207ff: DMA2 */
#define STM32F0_RCC_BASE 0x40021000 /* 0x40021000-0x400213ff: Reset and Clock control RCC */
#define STM32F0_FLASHIF_BASE 0x40022000 /* 0x40022000-0x400223ff: Flash memory interface */
#define STM32F0_CRC_BASE 0x40023000 /* 0x40023000-0x400233ff: CRC */
#define STM32F0_TSC_BASE 0x40024000 /* 0x40024000-0x400243ff: TSC */
/* AHB2 Base Addresses **************************************************************/
#define STM32F0_GPIOA_BASE 0x48000000 /* 0x48000000-0x480003ff: GPIO Port A */
#define STM32F0_GPIOB_BASE 0x48000400 /* 0x48000400-0x480007ff: GPIO Port B */
#define STM32F0_GPIOC_BASE 0x48000800 /* 0x48000800-0x48000bff: GPIO Port C */
#define STM32F0_GPIOD_BASE 0X48000C00 /* 0x48000c00-0x48000fff: GPIO Port D */
#define STM32F0_GPIOE_BASE 0x48001000 /* 0x48001000-0x480013ff: GPIO Port E */
#define STM32F0_GPIOF_BASE 0x48001400 /* 0x48001400-0x480017ff: GPIO Port F */
/* Cortex-M4 Base Addresses *********************************************************/
/* Other registers -- see armv7-m/nvic.h for standard Cortex-M4 registers in this
* address range
*/
#define STM32F0_SCS_BASE 0xe000e000
#define STM32F0_DEBUGMCU_BASE 0xe0042000
#endif /* __ARCH_ARM_SRC_STM32F0_CHIP_STM32F30XXX_MEMORYMAP_H */

View File

@ -0,0 +1,195 @@
/********************************************************************************
* arch/arm/src/stm32f0/chip/stm32f0_adc.h
*
* Copyright (C) 2017 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
* Alan Carvalho de Assis <acassis@gmail.com>
*
* 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 NuttX 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 OWNER 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.
*
********************************************************************************/
#ifndef __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_ADC_H
#define __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_ADC_H
/********************************************************************************
* Included Files
********************************************************************************/
#include <nuttx/config.h>
#include "chip.h"
/********************************************************************************
* Pre-processor Definitions
********************************************************************************/
/* Register Offsets *********************************************************************************/
#define STM32F0_ADC_ISR_OFFSET 0x0000 /* ADC interrupt and status register */
#define STM32F0_ADC_IER_OFFSET 0x0004 /* ADC interrupt enable register */
#define STM32F0_ADC_CR_OFFSET 0x0008 /* ADC control register */
#define STM32F0_ADC_CFGR1_OFFSET 0x000c /* ADC configuration register 1 */
#define STM32F0_ADC_CFGR2_OFFSET 0x0010 /* ADC configuration register 2 */
#define STM32F0_ADC_SMPR_OFFSET 0x0014 /* ADC sample time register */
#define STM32F0_ADC_TR_OFFSET 0x0020 /* ADC watchdog threshold register */
#define STM32F0_ADC_CHSELR_OFFSET 0x0028 /* ADC channel selection register */
#define STM32F0_ADC_DR_OFFSET 0x0040 /* ADC regular data register */
#define STM32F0_ADC_CCR_OFFSET 0x0308 /* ADC common configuration register */
/* Register Addresses *******************************************************************************/
#define STM32F0_ADC_ISR (STM32F0_ADC_BASE+STM32F0_ADC_ISR_OFFSET)
#define STM32F0_ADC_IER (STM32F0_ADC_BASE+STM32F0_ADC_IER_OFFSET)
#define STM32F0_ADC_CR (STM32F0_ADC_BASE+STM32F0_ADC_CR_OFFSET)
#define STM32F0_ADC_CFGR1 (STM32F0_ADC_BASE+STM32F0_ADC_CFGR1_OFFSET)
#define STM32F0_ADC_CFGR2 (STM32F0_ADC_BASE+STM32F0_ADC_CFGR2_OFFSET)
#define STM32F0_ADC_SMPR (STM32F0_ADC_BASE+STM32F0_ADC_SMPR_OFFSET)
#define STM32F0_ADC_TR (STM32F0_ADC_BASE+STM32F0_ADC_TR_OFFSET)
#define STM32F0_ADC_CHSELR (STM32F0_ADC_BASE+STM32F0_ADC_CHSELR_OFFSET)
#define STM32F0_ADC_DR (STM32F0_ADC_BASE+STM32F0_ADC_DR_OFFSET)
#define STM32F0_ADC_CCR (STM32F0_ADC_BASE+STM32F0_ADC_CCR_OFFSET)
/* Register Bitfield Definitions ************************************************/
/* ADC interrupt and status register (ISR) and ADC interrupt enable register (IER) */
#define ADC_INT_ARDY (1 << 0) /* Bit 0: ADC ready */
#define ADC_INT_EOSMP (1 << 1) /* Bit 1: End of sampling flag */
#define ADC_INT_EOC (1 << 2) /* Bit 2: End of conversion */
#define ADC_INT_EOS (1 << 3) /* Bit 3: End of regular sequence flag */
#define ADC_INT_OVR (1 << 4) /* Bit 4: Overrun */
#define ADC_INT_AWD (1 << 7) /* Bit 7: Analog watchdog flag */
/* ADC control register */
#define ADC_CR_ADEN (1 << 0) /* Bit 0: ADC enable control */
#define ADC_CR_ADDIS (1 << 1) /* Bit 1: ADC disable command */
#define ADC_CR_ADSTART (1 << 2) /* Bit 2: ADC start of regular conversion */
#define ADC_CR_ADSTP (1 << 4) /* Bit 4: ADC stop of regular conversion command */
#define ADC_CR_ADCAL (1 << 31) /* Bit 31: ADC calibration */
/* ADC configuration register 1 */
#define ADC_CFGR1_DMAEN (1 << 0) /* Bit 0: Direct memory access enable */
#define ADC_CFGR1_DMACFG (1 << 1) /* Bit 1: Direct memory access configuration */
#define ADC_CFGR1_SCANDIR (1 << 2) /* Bit 2: Scan sequence direction */
#define ADC_CFGR1_RES_SHIFT (3) /* Bits 3-4: Data resolution */
#define ADC_CFGR1_RES_MASK (3 << ADC_CFGR1_RES_SHIFT)
# define ADC_CFGR1_RES_12BIT (0 << ADC_CFGR1_RES_SHIFT) /* 15 ADCCLK clyes */
# define ADC_CFGR1_RES_10BIT (1 << ADC_CFGR1_RES_SHIFT) /* 13 ADCCLK clyes */
# define ADC_CFGR1_RES_8BIT (2 << ADC_CFGR1_RES_SHIFT) /* 11 ADCCLK clyes */
# define ADC_CFGR1_RES_6BIT (3 << ADC_CFGR1_RES_SHIFT) /* 9 ADCCLK clyes */
#define ADC_CFGR1_ALIGN (1 << 5) /* Bit 5: Data Alignment */
#define ADC_CFGR1_EXTSEL_SHIFT (6) /* Bits 6-8: External trigger selection */
#define ADC_CFGR1_EXTSEL_MASK (7 << ADC_CFGR1_EXTSEL_SHIFT)
# define ADC12_CFGR1_EXTSEL_TRG0 (0 << ADC_CFGR1_EXTSEL_SHIFT)
# define ADC12_CFGR1_EXTSEL_TRG1 (1 << ADC_CFGR1_EXTSEL_SHIFT)
# define ADC12_CFGR1_EXTSEL_TRG2 (2 << ADC_CFGR1_EXTSEL_SHIFT)
# define ADC12_CFGR1_EXTSEL_TRG3 (3 << ADC_CFGR1_EXTSEL_SHIFT)
# define ADC12_CFGR1_EXTSEL_TRG4 (4 << ADC_CFGR1_EXTSEL_SHIFT)
# define ADC12_CFGR1_EXTSEL_TRG5 (5 << ADC_CFGR1_EXTSEL_SHIFT)
# define ADC12_CFGR1_EXTSEL_TRG6 (6 << ADC_CFGR1_EXTSEL_SHIFT)
# define ADC12_CFGR1_EXTSEL_TRG7 (7 << ADC_CFGR1_EXTSEL_SHIFT)
#define ADC_CFGR1_EXTEN_SHIFT (10) /* Bits 10-11: External trigger/polarity selection regular channels */
#define ADC_CFGR1_EXTEN_MASK (3 << ADC_CFGR1_EXTEN_SHIFT)
# define ADC_CFGR1_EXTEN_NONE (0 << ADC_CFGR1_EXTEN_SHIFT) /* Trigger detection disabled */
# define ADC_CFGR1_EXTEN_RISING (1 << ADC_CFGR1_EXTEN_SHIFT) /* Trigger detection on the rising edge */
# define ADC_CFGR1_EXTEN_FALLING (2 << ADC_CFGR1_EXTEN_SHIFT) /* Trigger detection on the falling edge */
# define ADC_CFGR1_EXTEN_BOTH (3 << ADC_CFGR1_EXTEN_SHIFT) /* Trigger detection on both edges */
#define ADC_CFGR1_OVRMOD (1 << 12) /* Bit 12: Overrun Mode */
#define ADC_CFGR1_CONT (1 << 13) /* Bit 13: Continuous mode for regular conversions */
#define ADC_CFGR1_WAIT (1 << 14) /* Bit 14: Wait convertion mode */
#define ADC_CFGR1_AUTOFF (1 << 15) /* Bit 15: Auto-off mode */
#define ADC_CFGR1_DISCEN (1 << 16) /* Bit 16: Discontinuous mode on regular channels */
#define ADC_CFGR1_AWDSGL (1 << 22) /* Bit 22: Enable watchdog on single/all channels */
#define ADC_CFGR1_AWDEN (1 << 23) /* Bit 23: Analog watchdog enable */
#define ADC_CFGR1_AWDCH_SHIFT (26) /* Bits 26-30: Analog watchdog 1 channel select bits */
#define ADC_CFGR1_AWDCH_MASK (31 << ADC_CFGR1_AWDCH_SHIFT)
# define ADC_CFGR1_AWDCH_DISABLED (0 << ADC_CFGR1_AWDCH_SHIFT)
/* ADC configuration register 2 */
#define ADC_CFGR2_CKMODE_SHIFT (30) /* Bits 30-31: ADC clock mode */
#define ADC_CFGR2_CKMODE_MASK (3 << ADC_CFGR2_CKMODE_SHIFT)
# define ADC_CFGR2_CKMODE_ADCCLK (0 << ADC_CFGR2_CKMODE_SHIFT) /* 00: ADCCLK (Asynchronous) generated at product level */
# define ADC_CFGR2_CKMODE_PCLKd2 (1 << ADC_CFGR2_CKMODE_SHIFT) /* 01: PCLK/2 (Synchronous clock mode) */
# define ADC_CFGR2_CKMODE_PCLKd4 (2 << ADC_CFGR2_CKMODE_SHIFT) /* 10: PCLK/4 (Synchronous clock mode) */
/* ADC sample time register */
#define ADC_SMPR_SMP_SHIFT (0) /* Bits 0-2: Sampling time selection */
#define ADC_SMPR_SMP_MASK (7 << ADC_SMPR_SMP_SHIFT)
#define ADC_SMPR_SMP_1p5 (0 << ADC_SMPR_SMP_SHIFT) /* 000: 1.5 cycles */
#define ADC_SMPR_SMP_7p5 (1 << ADC_SMPR_SMP_SHIFT) /* 001: 7.5 cycles */
#define ADC_SMPR_SMP_13p5 (2 << ADC_SMPR_SMP_SHIFT) /* 010: 13.5 cycles */
#define ADC_SMPR_SMP_28p5 (3 << ADC_SMPR_SMP_SHIFT) /* 011: 28.5 cycles */
#define ADC_SMPR_SMP_41p5 (4 << ADC_SMPR_SMP_SHIFT) /* 100: 41.5 cycles */
#define ADC_SMPR_SMP_55p5 (5 << ADC_SMPR_SMP_SHIFT) /* 101: 55.5 cycles */
#define ADC_SMPR_SMP_71p5 (6 << ADC_SMPR_SMP_SHIFT) /* 110: 71.5 cycles */
#define ADC_SMPR_SMP_239p5 (7 << ADC_SMPR_SMP_SHIFT) /* 111: 239.5 cycles */
/* ADC watchdog threshold register */
#define ADC_TR_LT_SHIFT (0) /* Bits 0-11: Analog watchdog lower threshold */
#define ADC_TR_LT_MASK (0x0fff << ADC_TR_LT_SHIFT)
#define ADC_TR_HT_SHIFT (16) /* Bits 16-27: Analog watchdog higher threshold */
#define ADC_TR_HT_MASK (0x0fff << ADC_TR_HT_SHIFT)
/* ADC channel selection register */
#define ADC_CHSELR_CHSEL0 (1 << 0) /* Select channel 0 */
#define ADC_CHSELR_CHSEL1 (1 << 1) /* Select channel 1 */
#define ADC_CHSELR_CHSEL2 (1 << 2) /* Select channel 2 */
#define ADC_CHSELR_CHSEL3 (1 << 3) /* Select channel 3 */
#define ADC_CHSELR_CHSEL4 (1 << 4) /* Select channel 4 */
#define ADC_CHSELR_CHSEL5 (1 << 5) /* Select channel 5 */
#define ADC_CHSELR_CHSEL6 (1 << 6) /* Select channel 6 */
#define ADC_CHSELR_CHSEL7 (1 << 7) /* Select channel 7 */
#define ADC_CHSELR_CHSEL8 (1 << 8) /* Select channel 8 */
#define ADC_CHSELR_CHSEL9 (1 << 9) /* Select channel 9 */
#define ADC_CHSELR_CHSEL10 (1 << 10) /* Select channel 10 */
#define ADC_CHSELR_CHSEL11 (1 << 11) /* Select channel 11 */
#define ADC_CHSELR_CHSEL12 (1 << 12) /* Select channel 12 */
#define ADC_CHSELR_CHSEL13 (1 << 13) /* Select channel 13 */
#define ADC_CHSELR_CHSEL14 (1 << 14) /* Select channel 14 */
#define ADC_CHSELR_CHSEL15 (1 << 15) /* Select channel 15 */
#define ADC_CHSELR_CHSEL16 (1 << 16) /* Select channel 16 */
#define ADC_CHSELR_CHSEL17 (1 << 17) /* Select channel 17 */
#define ADC_CHSELR_CHSEL18 (1 << 18) /* Select channel 18 */
#define ADC_DR_RDATA_SHIFT (0)
#define ADC_DR_RDATA_MASK (0xffff << ADC_DR_RDATA_SHIFT)
/* Common configuration register */
#define ADC_CCR_VREFEN (1 << 22) /* Bit 22: VREFINT enable */
#define ADC_CCR_TSEN (1 << 23) /* Bit 23: Temperature sensor enable */
#define ADC_CCR_VBATEN (1 << 24) /* Bit 22: VBAT enable */
#endif /* __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_ADC_H */

View File

@ -0,0 +1,469 @@
/************************************************************************************
* arch/arm/src/stm32f0/chip/stm32f0_can.h
*
* Copyright (C) 2017 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
* Alan Carvalho de Assis <acassis@gmail.com>
*
* 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 NuttX 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 OWNER 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.
*
************************************************************************************/
#ifndef __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_CAN_H
#define __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_CAN_H
/************************************************************************************
* Included Files
************************************************************************************/
#include <nuttx/config.h>
#include "chip.h"
/************************************************************************************
* Pre-processor Definitions
************************************************************************************/
/* 3 TX mailboxes */
#define CAN_TXMBOX1 0
#define CAN_TXMBOX2 1
#define CAN_TXMBOX3 2
/* 2 RX mailboxes */
#define CAN_RXMBOX1 0
#define CAN_RXMBOX2 1
/* Number of filters depends on silicon */
#define CAN_NFILTERS 14
/* Register Offsets *****************************************************************/
/* CAN control and status registers */
#define STM32F0_CAN_MCR_OFFSET 0x0000 /* CAN master control register */
#define STM32F0_CAN_MSR_OFFSET 0x0004 /* CAN master status register */
#define STM32F0_CAN_TSR_OFFSET 0x0008 /* CAN transmit status register */
#define STM32F0_CAN_RFR_OFFSET(m) (0x000c+((m)<<2))
#define STM32F0_CAN_RF0R_OFFSET 0x000c /* CAN receive FIFO 0 register */
#define STM32F0_CAN_RF1R_OFFSET 0x0010 /* CAN receive FIFO 1 register */
#define STM32F0_CAN_IER_OFFSET 0x0014 /* CAN interrupt enable register */
#define STM32F0_CAN_ESR_OFFSET 0x0018 /* CAN error status register */
#define STM32F0_CAN_BTR_OFFSET 0x001c /* CAN bit timing register */
/* CAN mailbox registers (3 TX and 2 RX) */
#define STM32F0_CAN_TIR_OFFSET(m) (0x0180+((m)<<4))
#define STM32F0_CAN_TI0R_OFFSET 0x0180 /* TX mailbox identifier register 0 */
#define STM32F0_CAN_TI1R_OFFSET 0x0190 /* TX mailbox identifier register 1 */
#define STM32F0_CAN_TI2R_OFFSET 0x01a0 /* TX mailbox identifier register 2 */
#define STM32F0_CAN_TDTR_OFFSET(m) (0x0184+((m)<<4))
#define STM32F0_CAN_TDT0R_OFFSET 0x0184 /* Mailbox data length control and time stamp register 0 */
#define STM32F0_CAN_TDT1R_OFFSET 0x0194 /* Mailbox data length control and time stamp register 1 */
#define STM32F0_CAN_TDT2R_OFFSET 0x01a4 /* Mailbox data length control and time stamp register 2 */
#define STM32F0_CAN_TDLR_OFFSET(m) (0x0188+((m)<<4))
#define STM32F0_CAN_TDL0R_OFFSET 0x0188 /* Mailbox data low register 0 */
#define STM32F0_CAN_TDL1R_OFFSET 0x0198 /* Mailbox data low register 1 */
#define STM32F0_CAN_TDL2R_OFFSET 0x01a8 /* Mailbox data low register 2 */
#define STM32F0_CAN_TDHR_OFFSET(m) (0x018c+((m)<<4))
#define STM32F0_CAN_TDH0R_OFFSET 0x018c /* Mailbox data high register 0 */
#define STM32F0_CAN_TDH1R_OFFSET 0x019c /* Mailbox data high register 1 */
#define STM32F0_CAN_TDH2R_OFFSET 0x01ac /* Mailbox data high register 2 */
#define STM32F0_CAN_RIR_OFFSET(m) (0x01b0+((m)<<4))
#define STM32F0_CAN_RI0R_OFFSET 0x01b0 /* Rx FIFO mailbox identifier register 0 */
#define STM32F0_CAN_RI1R_OFFSET 0x01c0 /* Rx FIFO mailbox identifier register 1 */
#define STM32F0_CAN_RDTR_OFFSET(m) (0x01b4+((m)<<4))
#define STM32F0_CAN_RDT0R_OFFSET 0x01b4 /* Rx FIFO mailbox data length control and time stamp register 0 */
#define STM32F0_CAN_RDT1R_OFFSET 0x01c4 /* Rx FIFO mailbox data length control and time stamp register 1 */
#define STM32F0_CAN_RDLR_OFFSET(m) (0x01b8+((m)<<4))
#define STM32F0_CAN_RDL0R_OFFSET 0x01b8 /* Receive FIFO mailbox data low register 0 */
#define STM32F0_CAN_RDL1R_OFFSET 0x01c8 /* Receive FIFO mailbox data low register 1 */
#define STM32F0_CAN_RDHR_OFFSET(m) (0x01bc+((m)<<4))
#define STM32F0_CAN_RDH0R_OFFSET 0x01bc /* Receive FIFO mailbox data high register 0 */
#define STM32F0_CAN_RDH1R_OFFSET 0x01cc /* Receive FIFO mailbox data high register 1 */
/* CAN filter registers */
#define STM32F0_CAN_FMR_OFFSET 0x0200 /* CAN filter master register */
#define STM32F0_CAN_FM1R_OFFSET 0x0204 /* CAN filter mode register */
#define STM32F0_CAN_FS1R_OFFSET 0x020c /* CAN filter scale register */
#define STM32F0_CAN_FFA1R_OFFSET 0x0214 /* CAN filter FIFO assignment register */
#define STM32F0_CAN_FA1R_OFFSET 0x021c /* CAN filter activation register */
/* There are 14 or 28 filter banks (depending) on the device.
* Each filter bank is composed of two 32-bit registers, CAN_FiR:
* F0R1 Offset 0x240
* F0R2 Offset 0x244
* F1R1 Offset 0x248
* F1R2 Offset 0x24c
* ...
*/
#define STM32F0_CAN_FIR_OFFSET(f,i) (0x240+((f)<<3)+(((i)-1)<<2))
/* Register Addresses ***************************************************************/
#if STM32F0_NCAN > 0
# define STM32F0_CAN1_MCR (STM32F0_CAN1_BASE+STM32F0_CAN_MCR_OFFSET)
# define STM32F0_CAN1_MSR (STM32F0_CAN1_BASE+STM32F0_CAN_MSR_OFFSET)
# define STM32F0_CAN1_TSR (STM32F0_CAN1_BASE+STM32F0_CAN_TSR_OFFSET)
# define STM32F0_CAN1_RF0R (STM32F0_CAN1_BASE+STM32F0_CAN_RF0R_OFFSET)
# define STM32F0_CAN1_RF1R (STM32F0_CAN1_BASE+STM32F0_CAN_RF1R_OFFSET)
# define STM32F0_CAN1_IER (STM32F0_CAN1_BASE+STM32F0_CAN_IER_OFFSET)
# define STM32F0_CAN1_ESR (STM32F0_CAN1_BASE+STM32F0_CAN_ESR_OFFSET)
# define STM32F0_CAN1_BTR (STM32F0_CAN1_BASE+STM32F0_CAN_BTR_OFFSET)
# define STM32F0_CAN1_TIR(m) (STM32F0_CAN1_BASE+STM32F0_CAN_TIR_OFFSET(m))
# define STM32F0_CAN1_TI0R (STM32F0_CAN1_BASE+STM32F0_CAN_TI0R_OFFSET)
# define STM32F0_CAN1_TI1R (STM32F0_CAN1_BASE+STM32F0_CAN_TI1R_OFFSET)
# define STM32F0_CAN1_TI2R (STM32F0_CAN1_BASE+STM32F0_CAN_TI2R_OFFSET)
# define STM32F0_CAN1_TDTR(m) (STM32F0_CAN1_BASE+STM32F0_CAN_TDTR_OFFSET(m))
# define STM32F0_CAN1_TDT0R (STM32F0_CAN1_BASE+STM32F0_CAN_TDT0R_OFFSET)
# define STM32F0_CAN1_TDT1R (STM32F0_CAN1_BASE+STM32F0_CAN_TDT1R_OFFSET)
# define STM32F0_CAN1_TDT2R (STM32F0_CAN1_BASE+STM32F0_CAN_TDT2R_OFFSET)
# define STM32F0_CAN1_TDLR(m) (STM32F0_CAN1_BASE+STM32F0_CAN_TDLR_OFFSET(m))
# define STM32F0_CAN1_TDL0R (STM32F0_CAN1_BASE+STM32F0_CAN_TDL0R_OFFSET)
# define STM32F0_CAN1_TDL1R (STM32F0_CAN1_BASE+STM32F0_CAN_TDL1R_OFFSET)
# define STM32F0_CAN1_TDL2R (STM32F0_CAN1_BASE+STM32F0_CAN_TDL2R_OFFSET)
# define STM32F0_CAN1_TDHR(m) (STM32F0_CAN1_BASE+STM32F0_CAN_TDHR_OFFSET(m))
# define STM32F0_CAN1_TDH0R (STM32F0_CAN1_BASE+STM32F0_CAN_TDH0R_OFFSET)
# define STM32F0_CAN1_TDH1R (STM32F0_CAN1_BASE+STM32F0_CAN_TDH1R_OFFSET)
# define STM32F0_CAN1_TDH2R (STM32F0_CAN1_BASE+STM32F0_CAN_TDH2R_OFFSET)
# define STM32F0_CAN1_RIR(m) (STM32F0_CAN1_BASE+STM32F0_CAN_RIR_OFFSET(m))
# define STM32F0_CAN1_RI0R (STM32F0_CAN1_BASE+STM32F0_CAN_RI0R_OFFSET)
# define STM32F0_CAN1_RI1R (STM32F0_CAN1_BASE+STM32F0_CAN_RI1R_OFFSET)
# define STM32F0_CAN1_RDTR(m) (STM32F0_CAN1_BASE+STM32F0_CAN_RDTR_OFFSET(m))
# define STM32F0_CAN1_RDT0R (STM32F0_CAN1_BASE+STM32F0_CAN_RDT0R_OFFSET)
# define STM32F0_CAN1_RDT1R (STM32F0_CAN1_BASE+STM32F0_CAN_RDT1R_OFFSET)
# define STM32F0_CAN1_RDLR(m) (STM32F0_CAN1_BASE+STM32F0_CAN_RDLR_OFFSET(m))
# define STM32F0_CAN1_RDL0R (STM32F0_CAN1_BASE+STM32F0_CAN_RDL0R_OFFSET)
# define STM32F0_CAN1_RDL1R (STM32F0_CAN1_BASE+STM32F0_CAN_RDL1R_OFFSET)
# define STM32F0_CAN1_RDHR(m) (STM32F0_CAN1_BASE+STM32F0_CAN_RDHR_OFFSET(m))
# define STM32F0_CAN1_RDH0R (STM32F0_CAN1_BASE+STM32F0_CAN_RDH0R_OFFSET)
# define STM32F0_CAN1_RDH1R (STM32F0_CAN1_BASE+STM32F0_CAN_RDH1R_OFFSET)
# define STM32F0_CAN1_FMR (STM32F0_CAN1_BASE+STM32F0_CAN_FMR_OFFSET)
# define STM32F0_CAN1_FM1R (STM32F0_CAN1_BASE+STM32F0_CAN_FM1R_OFFSET)
# define STM32F0_CAN1_FS1R (STM32F0_CAN1_BASE+STM32F0_CAN_FS1R_OFFSET)
# define STM32F0_CAN1_FFA1R (STM32F0_CAN1_BASE+STM32F0_CAN_FFA1R_OFFSET)
# define STM32F0_CAN1_FA1R (STM32F0_CAN1_BASE+STM32F0_CAN_FA1R_OFFSET)
# define STM32F0_CAN1_FIR(b,i) (STM32F0_CAN1_BASE+STM32F0_CAN_FIR_OFFSET(b,i))
#endif
#if STM32F0_NCAN > 1
# define STM32F0_CAN2_MCR (STM32F0_CAN2_BASE+STM32F0_CAN_MCR_OFFSET)
# define STM32F0_CAN2_MSR (STM32F0_CAN2_BASE+STM32F0_CAN_MSR_OFFSET)
# define STM32F0_CAN2_TSR (STM32F0_CAN2_BASE+STM32F0_CAN_TSR_OFFSET)
# define STM32F0_CAN2_RF0R (STM32F0_CAN2_BASE+STM32F0_CAN_RF0R_OFFSET)
# define STM32F0_CAN2_RF1R (STM32F0_CAN2_BASE+STM32F0_CAN_RF1R_OFFSET)
# define STM32F0_CAN2_IER (STM32F0_CAN2_BASE+STM32F0_CAN_IER_OFFSET)
# define STM32F0_CAN2_ESR (STM32F0_CAN2_BASE+STM32F0_CAN_ESR_OFFSET)
# define STM32F0_CAN2_BTR (STM32F0_CAN2_BASE+STM32F0_CAN_BTR_OFFSET)
# define STM32F0_CAN2_TIR(m) (STM32F0_CAN2_BASE+STM32F0_CAN_TIR_OFFSET(m))
# define STM32F0_CAN2_TI0R (STM32F0_CAN2_BASE+STM32F0_CAN_TI0R_OFFSET)
# define STM32F0_CAN2_TI1R (STM32F0_CAN2_BASE+STM32F0_CAN_TI1R_OFFSET)
# define STM32F0_CAN2_TI2R (STM32F0_CAN2_BASE+STM32F0_CAN_TI2R_OFFSET)
# define STM32F0_CAN2_TDTR(m) (STM32F0_CAN2_BASE+STM32F0_CAN_TDTR_OFFSET(m))
# define STM32F0_CAN2_TDT0R (STM32F0_CAN2_BASE+STM32F0_CAN_TDT0R_OFFSET)
# define STM32F0_CAN2_TDT1R (STM32F0_CAN2_BASE+STM32F0_CAN_TDT1R_OFFSET)
# define STM32F0_CAN2_TDT2R (STM32F0_CAN2_BASE+STM32F0_CAN_TDT2R_OFFSET)
# define STM32F0_CAN2_TDLR(m) (STM32F0_CAN2_BASE+STM32F0_CAN_TDLR_OFFSET(m))
# define STM32F0_CAN2_TDL0R (STM32F0_CAN2_BASE+STM32F0_CAN_TDL0R_OFFSET)
# define STM32F0_CAN2_TDL1R (STM32F0_CAN2_BASE+STM32F0_CAN_TDL1R_OFFSET)
# define STM32F0_CAN2_TDL2R (STM32F0_CAN2_BASE+STM32F0_CAN_TDL2R_OFFSET)
# define STM32F0_CAN2_TDHR(m) (STM32F0_CAN2_BASE+STM32F0_CAN_TDHR_OFFSET(m))
# define STM32F0_CAN2_TDH0R (STM32F0_CAN2_BASE+STM32F0_CAN_TDH0R_OFFSET)
# define STM32F0_CAN2_TDH1R (STM32F0_CAN2_BASE+STM32F0_CAN_TDH1R_OFFSET)
# define STM32F0_CAN2_TDH2R (STM32F0_CAN2_BASE+STM32F0_CAN_TDH2R_OFFSET)
# define STM32F0_CAN2_RIR(m) (STM32F0_CAN2_BASE+STM32F0_CAN_RIR_OFFSET(m))
# define STM32F0_CAN2_RI0R (STM32F0_CAN2_BASE+STM32F0_CAN_RI0R_OFFSET)
# define STM32F0_CAN2_RI1R (STM32F0_CAN2_BASE+STM32F0_CAN_RI1R_OFFSET)
# define STM32F0_CAN2_RDTR(m) (STM32F0_CAN2_BASE+STM32F0_CAN_RDTR_OFFSET(m))
# define STM32F0_CAN2_RDT0R (STM32F0_CAN2_BASE+STM32F0_CAN_RDT0R_OFFSET)
# define STM32F0_CAN2_RDT1R (STM32F0_CAN2_BASE+STM32F0_CAN_RDT1R_OFFSET)
# define STM32F0_CAN2_RDLR(m) (STM32F0_CAN2_BASE+STM32F0_CAN_RDLR_OFFSET(m))
# define STM32F0_CAN2_RDL0R (STM32F0_CAN2_BASE+STM32F0_CAN_RDL0R_OFFSET)
# define STM32F0_CAN2_RDL1R (STM32F0_CAN2_BASE+STM32F0_CAN_RDL1R_OFFSET)
# define STM32F0_CAN2_RDHR(m) (STM32F0_CAN2_BASE+STM32F0_CAN_RDHR_OFFSET(m))
# define STM32F0_CAN2_RDH0R (STM32F0_CAN2_BASE+STM32F0_CAN_RDH0R_OFFSET)
# define STM32F0_CAN2_RDH1R (STM32F0_CAN2_BASE+STM32F0_CAN_RDH1R_OFFSET)
# define STM32F0_CAN2_FMR (STM32F0_CAN2_BASE+STM32F0_CAN_FMR_OFFSET)
# define STM32F0_CAN2_FM1R (STM32F0_CAN2_BASE+STM32F0_CAN_FM1R_OFFSET)
# define STM32F0_CAN2_FS1R (STM32F0_CAN2_BASE+STM32F0_CAN_FS1R_OFFSET)
# define STM32F0_CAN2_FFA1R (STM32F0_CAN2_BASE+STM32F0_CAN_FFA1R_OFFSET)
# define STM32F0_CAN2_FA1R (STM32F0_CAN2_BASE+STM32F0_CAN_FA1R_OFFSET)
# define STM32F0_CAN2_FIR(b,i) (STM32F0_CAN2_BASE+STM32F0_CAN_FIR_OFFSET(b,i))
#endif
/* Register Bitfield Definitions ****************************************************/
/* CAN master control register */
#define CAN_MCR_INRQ (1 << 0) /* Bit 0: Initialization Request */
#define CAN_MCR_SLEEP (1 << 1) /* Bit 1: Sleep Mode Request */
#define CAN_MCR_TXFP (1 << 2) /* Bit 2: Transmit FIFO Priority */
#define CAN_MCR_RFLM (1 << 3) /* Bit 3: Receive FIFO Locked Mode */
#define CAN_MCR_NART (1 << 4) /* Bit 4: No Automatic Retransmission */
#define CAN_MCR_AWUM (1 << 5) /* Bit 5: Automatic Wakeup Mode */
#define CAN_MCR_ABOM (1 << 6) /* Bit 6: Automatic Bus-Off Management */
#define CAN_MCR_TTCM (1 << 7) /* Bit 7: Time Triggered Communication Mode Enable */
#define CAN_MCR_RESET (1 << 15) /* Bit 15: bxCAN software master reset */
#define CAN_MCR_DBF (1 << 16) /* Bit 16: Debug freeze */
/* CAN master status register */
#define CAN_MSR_INAK (1 << 0) /* Bit 0: Initialization Acknowledge */
#define CAN_MSR_SLAK (1 << 1) /* Bit 1: Sleep Acknowledge */
#define CAN_MSR_ERRI (1 << 2) /* Bit 2: Error Interrupt */
#define CAN_MSR_WKUI (1 << 3) /* Bit 3: Wakeup Interrupt */
#define CAN_MSR_SLAKI (1 << 4) /* Bit 4: Sleep acknowledge interrupt */
#define CAN_MSR_TXM (1 << 8) /* Bit 8: Transmit Mode */
#define CAN_MSR_RXM (1 << 9) /* Bit 9: Receive Mode */
#define CAN_MSR_SAMP (1 << 10) /* Bit 10: Last Sample Point */
#define CAN_MSR_RX (1 << 11) /* Bit 11: CAN Rx Signal */
/* CAN transmit status register */
#define CAN_TSR_RQCP0 (1 << 0) /* Bit 0: Request Completed Mailbox 0 */
#define CAN_TSR_TXOK0 (1 << 1) /* Bit 1 : Transmission OK of Mailbox 0 */
#define CAN_TSR_ALST0 (1 << 2) /* Bit 2 : Arbitration Lost for Mailbox 0 */
#define CAN_TSR_TERR0 (1 << 3) /* Bit 3 : Transmission Error of Mailbox 0 */
#define CAN_TSR_ABRQ0 (1 << 7) /* Bit 7 : Abort Request for Mailbox 0 */
#define CAN_TSR_RQCP1 (1 << 8) /* Bit 8 : Request Completed Mailbox 1 */
#define CAN_TSR_TXOK1 (1 << 9) /* Bit 9 : Transmission OK of Mailbox 1 */
#define CAN_TSR_ALST1 (1 << 10) /* Bit 10 : Arbitration Lost for Mailbox 1 */
#define CAN_TSR_TERR1 (1 << 11) /* Bit 11 : Transmission Error of Mailbox 1 */
#define CAN_TSR_ABRQ1 (1 << 15) /* Bit 15 : Abort Request for Mailbox 1 */
#define CAN_TSR_RQCP2 (1 << 16) /* Bit 16 : Request Completed Mailbox 2 */
#define CAN_TSR_TXOK2 (1 << 17) /* Bit 17 : Transmission OK of Mailbox 2 */
#define CAN_TSR_ALST2 (1 << 18) /* Bit 18: Arbitration Lost for Mailbox 2 */
#define CAN_TSR_TERR2 (1 << 19) /* Bit 19: Transmission Error of Mailbox 2 */
#define CAN_TSR_ABRQ2 (1 << 23) /* Bit 23: Abort Request for Mailbox 2 */
#define CAN_TSR_CODE_SHIFT (24) /* Bits 25-24: Mailbox Code */
#define CAN_TSR_CODE_MASK (3 << CAN_TSR_CODE_SHIFT)
#define CAN_TSR_TME0 (1 << 26) /* Bit 26: Transmit Mailbox 0 Empty */
#define CAN_TSR_TME1 (1 << 27) /* Bit 27: Transmit Mailbox 1 Empty */
#define CAN_TSR_TME2 (1 << 28) /* Bit 28: Transmit Mailbox 2 Empty */
#define CAN_TSR_LOW0 (1 << 29) /* Bit 29: Lowest Priority Flag for Mailbox 0 */
#define CAN_TSR_LOW1 (1 << 30) /* Bit 30: Lowest Priority Flag for Mailbox 1 */
#define CAN_TSR_LOW2 (1 << 31) /* Bit 31: Lowest Priority Flag for Mailbox 2 */
/* CAN receive FIFO 0/1 registers */
#define CAN_RFR_FMP_SHIFT (0) /* Bits 1-0: FIFO Message Pending */
#define CAN_RFR_FMP_MASK (3 << CAN_RFR_FMP_SHIFT)
#define CAN_RFR_FULL (1 << 3) /* Bit 3: FIFO 0 Full */
#define CAN_RFR_FOVR (1 << 4) /* Bit 4: FIFO 0 Overrun */
#define CAN_RFR_RFOM (1 << 5) /* Bit 5: Release FIFO 0 Output Mailbox */
/* CAN interrupt enable register */
#define CAN_IER_TMEIE (1 << 0) /* Bit 0: Transmit Mailbox Empty Interrupt Enable */
#define CAN_IER_FMPIE0 (1 << 1) /* Bit 1: FIFO Message Pending Interrupt Enable */
#define CAN_IER_FFIE0 (1 << 2) /* Bit 2: FIFO Full Interrupt Enable */
#define CAN_IER_FOVIE0 (1 << 3) /* Bit 3: FIFO Overrun Interrupt Enable */
#define CAN_IER_FMPIE1 (1 << 4) /* Bit 4: FIFO Message Pending Interrupt Enable */
#define CAN_IER_FFIE1 (1 << 5) /* Bit 5: FIFO Full Interrupt Enable */
#define CAN_IER_FOVIE1 (1 << 6) /* Bit 6: FIFO Overrun Interrupt Enable */
#define CAN_IER_EWGIE (1 << 8) /* Bit 8: Error Warning Interrupt Enable */
#define CAN_IER_EPVIE (1 << 9) /* Bit 9: Error Passive Interrupt Enable */
#define CAN_IER_BOFIE (1 << 10) /* Bit 10: Bus-Off Interrupt Enable */
#define CAN_IER_LECIE (1 << 11) /* Bit 11: Last Error Code Interrupt Enable */
#define CAN_IER_ERRIE (1 << 15) /* Bit 15: Error Interrupt Enable */
#define CAN_IER_WKUIE (1 << 16) /* Bit 16: Wakeup Interrupt Enable */
#define CAN_IER_SLKIE (1 << 17) /* Bit 17: Sleep Interrupt Enable */
/* CAN error status register */
#define CAN_ESR_EWGF (1 << 0) /* Bit 0: Error Warning Flag */
#define CAN_ESR_EPVF (1 << 1) /* Bit 1: Error Passive Flag */
#define CAN_ESR_BOFF (1 << 2) /* Bit 2: Bus-Off Flag */
#define CAN_ESR_LEC_SHIFT (4) /* Bits 6-4: Last Error Code */
#define CAN_ESR_LEC_MASK (7 << CAN_ESR_LEC_SHIFT)
# define CAN_ESR_NOERROR (0 << CAN_ESR_LEC_SHIFT) /* 000: No Error */
# define CAN_ESR_STUFFERROR (1 << CAN_ESR_LEC_SHIFT) /* 001: Stuff Error */
# define CAN_ESR_FORMERROR (2 << CAN_ESR_LEC_SHIFT) /* 010: Form Error */
# define CAN_ESR_ACKERROR (3 << CAN_ESR_LEC_SHIFT) /* 011: Acknowledgment Error */
# define CAN_ESR_BRECERROR (4 << CAN_ESR_LEC_SHIFT) /* 100: Bit recessive Error */
# define CAN_ESR_BDOMERROR (5 << CAN_ESR_LEC_SHIFT) /* 101: Bit dominant Error */
# define CAN_ESR_CRCERRPR (6 << CAN_ESR_LEC_SHIFT) /* 110: CRC Error */
# define CAN_ESR_SWERROR (7 << CAN_ESR_LEC_SHIFT) /* 111: Set by software */
#define CAN_ESR_TEC_SHIFT (16) /* Bits 23-16: LS byte of the 9-bit Transmit Error Counter */
#define CAN_ESR_TEC_MASK (0xff << CAN_ESR_TEC_SHIF)
#define CAN_ESR_REC_SHIFT (24) /* Bits 31-24: Receive Error Counter */
#define CAN_ESR_REC_MASK (0xff << CAN_ESR_REC_SHIFT)
/* CAN bit timing register */
#define CAN_BTR_BRP_SHIFT (0) /* Bits 9-0: Baud Rate Prescaler */
#define CAN_BTR_BRP_MASK (0x03ff << CAN_BTR_BRP_SHIFT)
#define CAN_BTR_TS1_SHIFT (16) /* Bits 19-16: Time Segment 1 */
#define CAN_BTR_TS1_MASK (0x0f << CAN_BTR_TS1_SHIFT)
#define CAN_BTR_TS2_SHIFT (20) /* Bits 22-20: Time Segment 2 */
#define CAN_BTR_TS2_MASK (7 << CAN_BTR_TS2_SHIFT)
#define CAN_BTR_SJW_SHIFT (24) /* Bits 25-24: Resynchronization Jump Width */
#define CAN_BTR_SJW_MASK (3 << CAN_BTR_SJW_SHIFT)
#define CAN_BTR_LBKM (1 << 30) /* Bit 30: Loop Back Mode (Debug) */
#define CAN_BTR_SILM (1 << 31) /* Bit 31: Silent Mode (Debug) */
#define CAN_BTR_BRP_MAX (1024) /* Maximum BTR value (without decrement) */
#define CAN_BTR_TSEG1_MAX (16) /* Maximum TSEG1 value (without decrement) */
#define CAN_BTR_TSEG2_MAX (8) /* Maximum TSEG2 value (without decrement) */
/* TX mailbox identifier register */
#define CAN_TIR_TXRQ (1 << 0) /* Bit 0: Transmit Mailbox Request */
#define CAN_TIR_RTR (1 << 1) /* Bit 1: Remote Transmission Request */
#define CAN_TIR_IDE (1 << 2) /* Bit 2: Identifier Extension */
#define CAN_TIR_EXID_SHIFT (3) /* Bit 3-31: Extended Identifier */
#define CAN_TIR_EXID_MASK (0x1fffffff << CAN_TIR_EXID_SHIFT)
#define CAN_TIR_STID_SHIFT (21) /* Bits 21-31: Standard Identifier */
#define CAN_TIR_STID_MASK (0x07ff << CAN_TIR_STID_SHIFT)
/* Mailbox data length control and time stamp register */
#define CAN_TDTR_DLC_SHIFT (0) /* Bits 3:0: Data Length Code */
#define CAN_TDTR_DLC_MASK (0x0f << CAN_TDTR_DLC_SHIFT)
#define CAN_TDTR_TGT (1 << 8) /* Bit 8: Transmit Global Time */
#define CAN_TDTR_TIME_SHIFT (16) /* Bits 31:16: Message Time Stamp */
#define CAN_TDTR_TIME_MASK (0xffff << CAN_TDTR_TIME_SHIFT)
/* Mailbox data low register */
#define CAN_TDLR_DATA0_SHIFT (0) /* Bits 7-0: Data Byte 0 */
#define CAN_TDLR_DATA0_MASK (0xff << CAN_TDLR_DATA0_SHIFT)
#define CAN_TDLR_DATA1_SHIFT (8) /* Bits 15-8: Data Byte 1 */
#define CAN_TDLR_DATA1_MASK (0xff << CAN_TDLR_DATA1_SHIFT)
#define CAN_TDLR_DATA2_SHIFT (16) /* Bits 23-16: Data Byte 2 */
#define CAN_TDLR_DATA2_MASK (0xff << CAN_TDLR_DATA2_SHIFT)
#define CAN_TDLR_DATA3_SHIFT (24) /* Bits 31-24: Data Byte 3 */
#define CAN_TDLR_DATA3_MASK (0xff << CAN_TDLR_DATA3_SHIFT)
/* Mailbox data high register */
#define CAN_TDHR_DATA4_SHIFT (0) /* Bits 7-0: Data Byte 4 */
#define CAN_TDHR_DATA4_MASK (0xff << CAN_TDHR_DATA4_SHIFT)
#define CAN_TDHR_DATA5_SHIFT (8) /* Bits 15-8: Data Byte 5 */
#define CAN_TDHR_DATA5_MASK (0xff << CAN_TDHR_DATA5_SHIFT)
#define CAN_TDHR_DATA6_SHIFT (16) /* Bits 23-16: Data Byte 6 */
#define CAN_TDHR_DATA6_MASK (0xff << CAN_TDHR_DATA6_SHIFT)
#define CAN_TDHR_DATA7_SHIFT (24) /* Bits 31-24: Data Byte 7 */
#define CAN_TDHR_DATA7_MASK (0xff << CAN_TDHR_DATA7_SHIFT)
/* Rx FIFO mailbox identifier register */
#define CAN_RIR_RTR (1 << 1) /* Bit 1: Remote Transmission Request */
#define CAN_RIR_IDE (1 << 2) /* Bit 2: Identifier Extension */
#define CAN_RIR_EXID_SHIFT (3) /* Bit 3-31: Extended Identifier */
#define CAN_RIR_EXID_MASK (0x1fffffff << CAN_RIR_EXID_SHIFT)
#define CAN_RIR_STID_SHIFT (21) /* Bits 21-31: Standard Identifier */
#define CAN_RIR_STID_MASK (0x07ff << CAN_RIR_STID_SHIFT)
/* Receive FIFO mailbox data length control and time stamp register */
#define CAN_RDTR_DLC_SHIFT (0) /* Bits 3:0: Data Length Code */
#define CAN_RDTR_DLC_MASK (0x0f << CAN_RDTR_DLC_SHIFT)
#define CAN_RDTR_FMI_SHIFT (8) /* Bits 15-8: Filter Match Index */
#define CAN_RDTR_FMI_MASK (0xff << CAN_RDTR_FM_SHIFT)
#define CAN_RDTR_TIME_SHIFT (16) /* Bits 31:16: Message Time Stamp */
#define CAN_RDTR_TIME_MASK (0xffff << CAN_RDTR_TIME_SHIFT)
/* Receive FIFO mailbox data low register */
#define CAN_RDLR_DATA0_SHIFT (0) /* Bits 7-0: Data Byte 0 */
#define CAN_RDLR_DATA0_MASK (0xff << CAN_RDLR_DATA0_SHIFT)
#define CAN_RDLR_DATA1_SHIFT (8) /* Bits 15-8: Data Byte 1 */
#define CAN_RDLR_DATA1_MASK (0xff << CAN_RDLR_DATA1_SHIFT)
#define CAN_RDLR_DATA2_SHIFT (16) /* Bits 23-16: Data Byte 2 */
#define CAN_RDLR_DATA2_MASK (0xff << CAN_RDLR_DATA2_SHIFT)
#define CAN_RDLR_DATA3_SHIFT (24) /* Bits 31-24: Data Byte 3 */
#define CAN_RDLR_DATA3_MASK (0xff << CAN_RDLR_DATA3_SHIFT)
/* Receive FIFO mailbox data high register */
#define CAN_RDHR_DATA4_SHIFT (0) /* Bits 7-0: Data Byte 4 */
#define CAN_RDHR_DATA4_MASK (0xff << CAN_RDHR_DATA4_SHIFT)
#define CAN_RDHR_DATA5_SHIFT (8) /* Bits 15-8: Data Byte 5 */
#define CAN_RDHR_DATA5_MASK (0xff << CAN_RDHR_DATA5_SHIFT)
#define CAN_RDHR_DATA6_SHIFT (16) /* Bits 23-16: Data Byte 6 */
#define CAN_RDHR_DATA6_MASK (0xff << CAN_RDHR_DATA6_SHIFT)
#define CAN_RDHR_DATA7_SHIFT (24) /* Bits 31-24: Data Byte 7 */
#define CAN_RDHR_DATA7_MASK (0xff << CAN_RDHR_DATA7_SHIFT)
/* CAN filter master register */
#define CAN_FMR_FINIT (1 << 0) /* Bit 0: Filter Init Mode */
/* CAN filter mode register */
#define CAN_FM1R_FBM_SHIFT (0) /* Bits 13:0: Filter Mode */
#define CAN_FM1R_FBM_MASK (0x3fff << CAN_FM1R_FBM_SHIFT)
/* CAN filter scale register */
#define CAN_FS1R_FSC_SHIFT (0) /* Bits 13:0: Filter Scale Configuration */
#define CAN_FS1R_FSC_MASK (0x3fff << CAN_FS1R_FSC_SHIFT)
/* CAN filter FIFO assignment register */
#define CAN_FFA1R_FFA_SHIFT (0) /* Bits 13:0: Filter FIFO Assignment */
#define CAN_FFA1R_FFA_MASK (0x3fff << CAN_FFA1R_FFA_SHIFT)
/* CAN filter activation register */
#define CAN_FA1R_FACT_SHIFT (0) /* Bits 13:0: Filter Active */
#define CAN_FA1R_FACT_MASK (0x3fff << CAN_FA1R_FACT_SHIFT)
#endif /* __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_CAN_H */

View File

@ -0,0 +1,138 @@
/************************************************************************************
* arch/arm/src/stm32f0/chip/stm32f0_comp.h
*
* Copyright (C) 2017 Gregory Nutt. All rights reserved.
* Author: Mateusz Szafoni <raiden00@railab.me>
* Alan Carvalho de Assis <acassis@gmail.com>
*
* 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 NuttX 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 OWNER 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.
*
************************************************************************************/
#ifndef __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_COMP_H
#define __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_COMP_H
/************************************************************************************
* Included Files
************************************************************************************/
#include <nuttx/config.h>
#include "chip.h"
/************************************************************************************
* Pre-processor Definitions
************************************************************************************/
/* Register Offsets *****************************************************************/
#define STM32F0_COMP_CSR_OFFSET 0x001c /* COMP1/COMP2 Control register */
/* Register Addresses ***************************************************************/
#define STM32F0_COMP_CSR (STM32F0_COMP_BASE+STM32F0_COMP_CSR_OFFSET)
/* Register Bitfield Definitions ****************************************************/
/* COMP control and status register */
#define COMP_CSR_COMP1EN (1 << 0) /* Bit 0: Comparator 1 enable */
#define COMP_CSR_COMP1SW1 (1 << 1) /* Bit 1: Comparator 1 non inverting input DAC switch */
#define COMP_CSR_COMP1MODE_SHIFT (2) /* Bits 2-3: Compator 1 mode */
#define COMP_CSR_COMP1MODE_MASK (3 << COMP_CSR_COMP1MODE_SHIFT)
# define COMP_CSR_COMP1MODE_HIGH (0 << COMP_CSR_COMP1MODE_SHIFT) /* 00: High Speed / full power */
# define COMP_CSR_COMP1MODE_MEDIUM (1 << COMP_CSR_COMP1MODE_SHIFT) /* 01: Medium Speed / medium power */
# define COMP_CSR_COMP1MODE_LOW (2 << COMP_CSR_COMP1MODE_SHIFT) /* 10: Low Speed / low-power */
# define COMP_CSR_COMP1MODE_VLOW (3 << COMP_CSR_COMP1MODE_SHIFT) /* 11: Very-low Speed / ultra-low power */
#define COMP_CSR_COMP1INSEL_SHIFT (4) /* Bits 4-6: Comparator 1 inverting input selection */
#define COMP_CSR_COMP1INSEL_MASK (7 << COMP_CSR_COMP1INSEL_SHIFT)
# define COMP_CSR_COMP1INSEL_1P4VREF (0 << COMP_CSR_COMP1INSEL_SHIFT) /* 000: 1/4 of Vrefint */
# define COMP_CSR_COMP1INSEL_1P2VREF (1 << COMP_CSR_COMP1INSEL_SHIFT) /* 001: 1/2 of Vrefint */
# define COMP_CSR_COMP1INSEL_3P4VREF (2 << COMP_CSR_COMP1INSEL_SHIFT) /* 010: 3/4 of Vrefint */
# define COMP_CSR_COMP1INSEL_VREF (3 << COMP_CSR_COMP1INSEL_SHIFT) /* 011: Vrefint */
# define COMP_CSR_COMP1INSEL_INM4 (4 << COMP_CSR_COMP1INSEL_SHIFT) /* 100: COMP1_INM4 (PA4 DAC_OUT1 if enabled) */
# define COMP_CSR_COMP1INSEL_INM5 (5 << COMP_CSR_COMP1INSEL_SHIFT) /* 101: COMP1_INM5 (PA5 DAC_OUT2 if present and enabled) */
# define COMP_CSR_COMP1INSEL_INM6 (6 << COMP_CSR_COMP1INSEL_SHIFT) /* 110: COMP1_INM6 (PA0) */
#define COMP_CSR_COMP1OUTSEL_SHIFT (8) /* Bits 8-10: Comparator 1 output selection*/
#define COMP_CSR_COMP1OUTSEL_MASK (7 << COMP_CSR_COMP1OUTSEL_MASK)
# define COMP_CSR_COMP1OUTSEL_NOSEL (0 << COMP_CSR_COMP1OUTSEL_MASK) /* 000: no selection */
# define COMP_CSR_COMP1OUTSEL_T1BRK (1 << COMP_CSR_COMP1OUTSEL_MASK) /* 001: Timer 1 break input */
# define COMP_CSR_COMP1OUTSEL_T1ICAP (2 << COMP_CSR_COMP1OUTSEL_MASK) /* 010: Timer 1 Input capture 1 */
# define COMP_CSR_COMP1OUTSEL_T1OCRC (3 << COMP_CSR_COMP1OUTSEL_MASK) /* 011: Timer 1 OCrefclear input */
# define COMP_CSR_COMP1OUTSEL_T2ICAP (4 << COMP_CSR_COMP1OUTSEL_MASK) /* 100: Timer 2 input capture 4 */
# define COMP_CSR_COMP1OUTSEL_T2OCRC (5 << COMP_CSR_COMP1OUTSEL_MASK) /* 101: Timer 2 OCrefclear input */
# define COMP_CSR_COMP1OUTSEL_T3ICAP (6 << COMP_CSR_COMP1OUTSEL_MASK) /* 110: Timer 3 input capture 1 */
# define COMP_CSR_COMP1OUTSEL_T3OCRC (7 << COMP_CSR_COMP1OUTSEL_MASK) /* 111: Timer 3 OCrefclear input */
#define COMP_CSR_COMP1POL (1 << 11) /* Bit 11: Comparator 1 output polarity */
#define COMP_CSR_COMP1HYST_SHIFT (12) /* Bits 12-13: Comparator 1 hysteresis */
#define COMP_CSR_COMP1HYST_MASK (3 << COMP_CSR_COMP1HYST_SHIFT)
# define COMP_CSR_COMP1HYST_NOHYST (0 << COMP_CSR_COMP1HYST_MASK) /* 00: No hysteresis */
# define COMP_CSR_COMP1HYST_LOWHYST (1 << COMP_CSR_COMP1HYST_MASK) /* 01: Low hysteresis */
# define COMP_CSR_COMP1HYST_MDHYST (2 << COMP_CSR_COMP1HYST_MASK) /* 10: Medium hysteresis */
# define COMP_CSR_COMP1HYST_HIHYST (3 << COMP_CSR_COMP1HYST_MASK) /* 11: Low hysteresis */
#define COMP_CSR_COMP1OUT (1 << 14) /* Bit 14: Comparator 1 output */
#define COMP_CSR_COMP1LOCK (1 << 15) /* Bit 15: Comparator 1 lock */
#define COMP_CSR_COMP2EN (1 << 16) /* Bit 16: Comparator 2 enable */
#define COMP_CSR_COMP2MODE_SHIFT (18) /* Bits 18-19: Compator 2 mode */
#define COMP_CSR_COMP2MODE_MASK (3 << COMP_CSR_COMP2MODE_SHIFT)
# define COMP_CSR_COMP2MODE_HIGH (0 << COMP_CSR_COMP2MODE_SHIFT) /* 00: High Speed / full power */
# define COMP_CSR_COMP2MODE_MEDIUM (1 << COMP_CSR_COMP2MODE_SHIFT) /* 01: Medium Speed / medium power */
# define COMP_CSR_COMP2MODE_LOW (2 << COMP_CSR_COMP2MODE_SHIFT) /* 10: Low Speed / low-power */
# define COMP_CSR_COMP2MODE_VLOW (3 << COMP_CSR_COMP2MODE_SHIFT) /* 11: Very-low Speed / ultra-low power */
#define COMP_CSR_COMP2INSEL_SHIFT (20) /* Bits 20-22: Comparator 2 inverting input selection */
#define COMP_CSR_COMP2INSEL_MASK (7 << COMP_CSR_COMP2INSEL_SHIFT)
# define COMP_CSR_COMP2INSEL_1P4VREF (0 << COMP_CSR_COMP2INSEL_SHIFT) /* 000: 1/4 of Vrefint */
# define COMP_CSR_COMP2INSEL_1P2VREF (1 << COMP_CSR_COMP2INSEL_SHIFT) /* 001: 1/2 of Vrefint */
# define COMP_CSR_COMP2INSEL_3P4VREF (2 << COMP_CSR_COMP2INSEL_SHIFT) /* 010: 3/4 of Vrefint */
# define COMP_CSR_COMP2INSEL_VREF (3 << COMP_CSR_COMP2INSEL_SHIFT) /* 011: Vrefint */
# define COMP_CSR_COMP2INSEL_INM4 (4 << COMP_CSR_COMP2INSEL_SHIFT) /* 100: COMP1_INM4 (PA4 DAC_OUT1 if enabled) */
# define COMP_CSR_COMP2INSEL_INM5 (5 << COMP_CSR_COMP2INSEL_SHIFT) /* 101: COMP1_INM5 (PA5 DAC_OUT2 if present and enabled) */
# define COMP_CSR_COMP2INSEL_INM6 (6 << COMP_CSR_COMP2INSEL_SHIFT) /* 110: COMP1_INM6 (PA2) */
#define COMP_CSR_WNDWEN (1 << 23) /* Bit 23: Window mode enable */
#define COMP_CSR_COMP2OUTSEL_SHIFT (24) /* Bits 24-26: Comparator 1 output selection*/
#define COMP_CSR_COMP2OUTSEL_MASK (7 << COMP_CSR_COMP2OUTSEL_MASK)
# define COMP_CSR_COMP2OUTSEL_NOSEL (0 << COMP_CSR_COMP2OUTSEL_MASK) /* 000: no selection */
# define COMP_CSR_COMP2OUTSEL_T1BRK (1 << COMP_CSR_COMP2OUTSEL_MASK) /* 001: Timer 1 break input */
# define COMP_CSR_COMP2OUTSEL_T1ICAP (2 << COMP_CSR_COMP2OUTSEL_MASK) /* 010: Timer 1 Input capture 1 */
# define COMP_CSR_COMP2OUTSEL_T1OCRC (3 << COMP_CSR_COMP2OUTSEL_MASK) /* 011: Timer 1 OCrefclear input */
# define COMP_CSR_COMP2OUTSEL_T2ICAP (4 << COMP_CSR_COMP2OUTSEL_MASK) /* 100: Timer 2 input capture 4 */
# define COMP_CSR_COMP2OUTSEL_T2OCRC (5 << COMP_CSR_COMP2OUTSEL_MASK) /* 101: Timer 2 OCrefclear input */
# define COMP_CSR_COMP2OUTSEL_T3ICAP (6 << COMP_CSR_COMP2OUTSEL_MASK) /* 110: Timer 3 input capture 1 */
# define COMP_CSR_COMP2OUTSEL_T3OCRC (7 << COMP_CSR_COMP2OUTSEL_MASK) /* 111: Timer 3 OCrefclear input */
#define COMP_CSR_COMP2POL (1 << 27) /* Bit 27: Comparator 2 output polarity */
#define COMP_CSR_COMP2HYST_SHIFT (12) /* Bits 12-13: Comparator 1 hysteresis */
#define COMP_CSR_COMP2HYST_MASK (3 << COMP_CSR_COMP2HYST_SHIFT)
# define COMP_CSR_COMP2HYST_NOHYST (0 << COMP_CSR_COMP2HYST_MASK) /* 00: No hysteresis */
# define COMP_CSR_COMP2HYST_LOWHYST (1 << COMP_CSR_COMP2HYST_MASK) /* 01: Low hysteresis */
# define COMP_CSR_COMP2HYST_MDHYST (2 << COMP_CSR_COMP2HYST_MASK) /* 10: Medium hysteresis */
# define COMP_CSR_COMP2HYST_HIHYST (3 << COMP_CSR_COMP2HYST_MASK) /* 11: Low hysteresis */
#define COMP_CSR_COMP2OUT (1 << 14) /* Bit 14: Comparator 1 output */
#define COMP_CSR_COMP2LOCK (1 << 15) /* Bit 15: Comparator 1 lock */
#endif /* __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_COMP_H */

View File

@ -0,0 +1,90 @@
/************************************************************************************
* arch/arm/src/stm32f0/chip/stm32f0_crc.h
*
* Copyright (C) 2017 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
* Alan Carvalho de Assis <acassis@gmail.com>
*
* 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 NuttX 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 OWNER 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.
*
************************************************************************************/
#ifndef __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_CRC_H
#define __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_CRC_H
/************************************************************************************
* Included Files
************************************************************************************/
#include <nuttx/config.h>
#include "chip.h"
/************************************************************************************
* Pre-processor Definitions
************************************************************************************/
/* Register Offsets *****************************************************************/
#define STM32F0_CRC_DR_OFFSET 0x0000 /* Data register */
#define STM32F0_CRC_IDR_OFFSET 0x0004 /* Independent Data register */
#define STM32F0_CRC_CR_OFFSET 0x0008 /* Control register */
#define STM32F0_CRC_INIT_OFFSET 0x0010 /* Initial CRC value register */
#define STM32F0_CRC_POL_OFFSET 0x0014 /* CRC polynomial register */
/* Register Addresses ***************************************************************/
#define STM32F0_CRC_DR (STM32F0_CRC_BASE+STM32F0_CRC_DR_OFFSET)
#define STM32F0_CRC_IDR (STM32F0_CRC_BASE+STM32F0_CRC_IDR_OFFSET)
#define STM32F0_CRC_CR (STM32F0_CRC_BASE+STM32F0_CRC_CR_OFFSET)
#define STM32F0_CRC_INIT (STM32F0_CRC_BASE+STM32F0_CRC_INIT_OFFSET)
#define STM32F0_CRC_POL (STM32F0_CRC_BASE+STM32F0_CRC_POL_OFFSET)
/* Register Bitfield Definitions ****************************************************/
/* CRC independent data register */
#define CRC_IDR_MASK 0xff /* These bits as a temporary location for one byte, not affected by RESET bit of CR */
/* CRC control register */
#define CRC_CR_RESET (1 << 0) /* This bit reset the CRC calculation unit and load CRC_DR with value of CRC_INIT */
#define CRC_CR_POLYSIZE_SHIFT 3 /* Bits 3-4: Polynomial size (for STM32F07x and STM32F09x) */
#define CRC_CR_POLYSIZE_MASK (3 << CRC_CR_POLYSIZE_SHIFT)
# define CRC_CR_POLYSIZE_32 (0 << CRC_CR_POLYSIZE_SHIFT) /* 00: 32 bit polynomial */
# define CRC_CR_POLYSIZE_16 (1 << CRC_CR_POLYSIZE_SHIFT) /* 01: 16 bit polynomial */
# define CRC_CR_POLYSIZE_8 (2 << CRC_CR_POLYSIZE_SHIFT) /* 10: 8 bit polynomial */
# define CRC_CR_POLYSIZE_7 (3 << CRC_CR_POLYSIZE_SHIFT) /* 10: 8 bit polynomial */
#define CRC_CR_REVIN_SHIFT 5 /* Bits 5-6: These bits ontrol the reversal of the bit order of the input data */
#define CRC_CR_REVIN_MASK (3 << CRC_CR_REVIN_SHIFT)
# define CRC_CR_REVIN_NONE (0 << CRC_CR_REVIN_SHIFT) /* 00: bit order is not affected */
# define CRC_CR_REVIN_BYTE (1 << CRC_CR_REVIN_SHIFT) /* 01: reversal done by byte */
# define CRC_CR_REVIN_HWORD (2 << CRC_CR_REVIN_SHIFT) /* 10: reversal done by half-word */
# define CRC_CR_REVIN_WORD (3 << CRC_CR_REVIN_SHIFT) /* 11: reversal done by word */
#define CRC_CR_REVOUT (1 << 7) /* This bit controls the reversal of the bit order of the output data */
#endif /* __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_CRC_H */

View File

@ -0,0 +1,115 @@
/************************************************************************************
* arch/arm/src/stm32f0/chip/stm32f0_crs.h
*
* Copyright (C) 2017 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
* Alan Carvalho de Assis <acassis@gmail.com>
*
* 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 NuttX 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 OWNER 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.
*
************************************************************************************/
#ifndef __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_CRS_H
#define __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_CRS_H
/************************************************************************************
* Pre-processor Definitions
************************************************************************************/
/* Register Offsets *****************************************************************/
#define STM32F0_CRS_CR_OFFSET 0x0000 /* CRS control register */
#define STM32F0_CRS_CFGR_OFFSET 0x0004 /* CRS configuration register */
#define STM32F0_CRS_ISR_OFFSET 0x0008 /* CRS interrupt and status register */
#define STM32F0_CRS_ICR_OFFSET 0x000c /* CRS interrupt flag clear register */
/* Register Addresses ***************************************************************/
#define STM32F0_CRS_CR (STM32F0_CRS_BASE+STM32F0_CRS_CR_OFFSET)
#define STM32F0_CRS_CFGR (STM32F0_CRS_BASE+STM32F0_CRS_CFGR_OFFSET)
#define STM32F0_CRS_ISR (STM32F0_CRS_BASE+STM32F0_CRS_ISR_OFFSET)
#define STM32F0_CRS_ICR (STM32F0_CRS_BASE+STM32F0_CRS_ICR_OFFSET)
/* Register Bitfield Definitions ****************************************************/
/* CRS control register */
#define CRS_CR_SYNCOKIE (1 << 0) /* Bit 0: SYNC event OK interrupt enable */
#define CRS_CR_SYNCWARNIE (1 << 1) /* Bit 1: SYNC warning interrupt enable */
#define CRS_CR_ERRIE (1 << 2) /* Bit 2: Syncronization or Trimming error interrupt enabled */
#define CRS_CR_ESYNCIE (1 << 3) /* Bit 3: Expected SYNC interrupt enable */
#define CRS_CR_CEN (1 << 5) /* Bit 5: Frequency error counter enable */
#define CRS_CR_AUTOTRIMEN (1 << 6) /* Bit 6: Automatic trimming enabled */
#define CRS_CR_SWSYNC (1 << 7) /* Bit 7: Generate sofware SYNC event */
#define CRS_CR_TRIM_SHIFT 8 /* Bits 8-13: HSI48 oscillator smooth trimming */
#define CRS_CR_TRIM_MASK (0x3f << CRS_CR_TRIM_SHIFT)
/* CRS configuration register */
#define CRS_CFGR_RELOAD_SHIFT 0 /* Bits 0-15: Counter reload value */
#define CRS_CFGR_RELOAD_MASK (0xffff << CRS_CFGR_RELOAD_SHIFT)
#define CRS_CFGR_FELIM_SHIFT 16 /* Bits 16-23: Frequency error limit */
#define CRS_CFGR_FELIM_MASK (0xff << CRS_CFGR_FELIM_SHIFT)
#define CRS_CFGR_SYNCDIV_SHIFT 24 /* Bits 24-26: SYNC divider */
#define CRS_CFGR_SYNCDIV_MASK (7 << CRS_CFGR_SYNCDIV_SHIFT)
# define CRS_CFGR_SYNCDIV_d1 (0 << CRS_CFGR_SYNCDIV_SHIFT) /* Not divided */
# define CRS_CFGR_SYNCDIV_d2 (1 << CRS_CFGR_SYNCDIV_SHIFT) /* divided by 2) */
# define CRS_CFGR_SYNCDIV_d4 (2 << CRS_CFGR_SYNCDIV_SHIFT) /* divided by 4) */
# define CRS_CFGR_SYNCDIV_d8 (3 << CRS_CFGR_SYNCDIV_SHIFT) /* divided by 8) */
# define CRS_CFGR_SYNCDIV_d16 (4 << CRS_CFGR_SYNCDIV_SHIFT) /* divided by 16) */
# define CRS_CFGR_SYNCDIV_d32 (5 << CRS_CFGR_SYNCDIV_SHIFT) /* divided by 32) */
# define CRS_CFGR_SYNCDIV_d64 (6 << CRS_CFGR_SYNCDIV_SHIFT) /* divided by 64) */
# define CRS_CFGR_SYNCDIV_d128 (6 << CRS_CFGR_SYNCDIV_SHIFT) /* divided by 128) */
#define CRS_CFGR_SYNCSRC_SHIFT 28 /* Bits 28-29: SYNC signal source selection */
#define CRS_CFGR_SYNCSRC_MASK (3 << CRS_CFGR_SYNCSRC_SHIFT)
# define CRS_CFGR_SYNCSRC_GPIO (0 << CRS_CFGR_SYNCSRC_SHIFT) /* GPIO as SYNC signal source */
# define CRS_CFGR_SYNCSRC_LSE (1 << CRS_CFGR_SYNCSRC_SHIFT) /* LSE as SYNC signal source */
# define CRS_CFGR_SYNCSRC_USBSOF (2 << CRS_CFGR_SYNCSRC_SHIFT) /* USB SOF as SYNC signal source */
#define CRS_CFGR_SYNCPOL (1 << 30) /* SYNC polarity selection */
/* CRS interrupt and status register */
#define CRS_ISR_SYNCOKF (1 << 0) /* Bit 0: SYNC event OK flag */
#define CRS_ISR_SYNCWARNF (1 << 1) /* Bit 1: SYNC warning flag */
#define CRS_ISR_ERRF (1 << 2) /* Bit 2: Errot flag */
#define CRS_ISR_ESYNCF (1 << 3) /* Bit 3: Expected SYNC flag */
#define CRS_ISR_SYNCERR (1 << 8) /* Bit 8: SYNC error */
#define CRS_ISR_SYNCMISS (1 << 9) /* Bit 9: SYNC missed */
#define CRS_ISR_TRIMOVF (1 << 10) /* Bit 10: Trimming overflow or underflow */
#define CRS_ISR_FEDIR (1 << 15) /* Bit 15: Frequency error direction */
#define CRS_ISR_FECAP_SHIFT 16 /* Bits 16-31: Frequency error capture */
#define CRS_ISR_FECAP_MASK (0xffff << CRS_ISR_FECAP_SHIFT)
/* CRS interrupt flag clear register */
#define CRS_ICR_SYNCOKC (1 << 0) /* Bit 0: SYNC event OK clear flag */
#define CRS_ICR_SYNCWARNC (1 << 1) /* Bit 1: SYNC waring clear flag */
#define CRS_ICR_ERRC (1 << 2) /* Bit 2: Error clear flag */
#define CRS_ICR_ESYNCC (1 << 3) /* Bit 3: Expected SYNC clear flag */
#endif /* __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_CRS_H */

View File

@ -0,0 +1,218 @@
/************************************************************************************
* arch/arm/src/stm32f0/chip/stm32f0_dac.h
*
* Copyright (C) 2017 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
* Alan Carvalho de Assis <acassis@gmail.com>
*
* 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 NuttX 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 OWNER 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.
*
************************************************************************************/
#ifndef __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_DAC_H
#define __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_DAC_H
/************************************************************************************
* Included Files
************************************************************************************/
#include <nuttx/config.h>
#include "chip.h"
/************************************************************************************
* Pre-processor Definitions
************************************************************************************/
/* Register Offsets *****************************************************************/
#define STM32F0_DAC_CR_OFFSET 0x0000 /* DAC control register */
#define STM32F0_DAC_SWTRIGR_OFFSET 0x0004 /* DAC software trigger register */
#define STM32F0_DAC_DHR12R1_OFFSET 0x0008 /* DAC channel 1 12-bit right-aligned data holding register */
#define STM32F0_DAC_DHR12L1_OFFSET 0x000c /* DAC channel 1 12-bit left aligned data holding register */
#define STM32F0_DAC_DHR8R1_OFFSET 0x0010 /* DAC channel 1 8-bit right aligned data holding register */
#define STM32F0_DAC_DHR12R2_OFFSET 0x0014 /* DAC channel 2 12-bit right aligned data holding register */
#define STM32F0_DAC_DHR12L2_OFFSET 0x0018 /* DAC channel 2 12-bit left aligned data holding register */
#define STM32F0_DAC_DHR8R2_OFFSET 0x001c /* DAC channel 2 8-bit right-aligned data holding register */
#define STM32F0_DAC_DHR12RD_OFFSET 0x0020 /* Dual DAC 12-bit right-aligned data holding register */
#define STM32F0_DAC_DHR12LD_OFFSET 0x0024 /* DUAL DAC 12-bit left aligned data holding register */
#define STM32F0_DAC_DHR8RD_OFFSET 0x0028 /* DUAL DAC 8-bit right aligned data holding register */
#define STM32F0_DAC_DOR1_OFFSET 0x002c /* DAC channel 1 data output register */
#define STM32F0_DAC_DOR2_OFFSET 0x0030 /* DAC channel 2 data output register */
#define STM32F0_DAC_SR_OFFSET 0x0034 /* DAC status register */
/* Register Addresses ***************************************************************/
/* DAC */
# define STM32F0_DAC1_CR (STM32F0_DAC1_BASE+STM32F0_DAC_CR_OFFSET)
# define STM32F0_DAC1_SWTRIGR (STM32F0_DAC1_BASE+STM32F0_DAC_SWTRIGR_OFFSET)
# define STM32F0_DAC1_DHR12R1 (STM32F0_DAC1_BASE+STM32F0_DAC_DHR12R1_OFFSET)
# define STM32F0_DAC1_DHR12L1 (STM32F0_DAC1_BASE+STM32F0_DAC_DHR12L1_OFFSET)
# define STM32F0_DAC1_DHR8R1 (STM32F0_DAC1_BASE+STM32F0_DAC_DHR8R1_OFFSET)
# define STM32F0_DAC1_DHR12R2 (STM32F0_DAC1_BASE+STM32F0_DAC_DHR12R2_OFFSET)
# define STM32F0_DAC1_DHR12L2 (STM32F0_DAC1_BASE+STM32F0_DAC_DHR12L2_OFFSET)
# define STM32F0_DAC1_DHR8R2 (STM32F0_DAC1_BASE+STM32F0_DAC_DHR8R2_OFFSET)
# define STM32F0_DAC1_DHR12RD (STM32F0_DAC1_BASE+STM32F0_DAC_DHR12RD_OFFSET)
# define STM32F0_DAC1_DHR12LD (STM32F0_DAC1_BASE+STM32F0_DAC_DHR12LD_OFFSET)
# define STM32F0_DAC1_DHR8RD (STM32F0_DAC1_BASE+STM32F0_DAC_DHR8RD_OFFSET)
# define STM32F0_DAC1_DOR1 (STM32F0_DAC1_BASE+STM32F0_DAC_DOR1_OFFSET)
# define STM32F0_DAC1_DOR2 (STM32F0_DAC1_BASE+STM32F0_DAC_DOR2_OFFSET)
# define STM32F0_DAC1_SR (STM32F0_DAC1_BASE+STM32F0_DAC_SR_OFFSET)
/* Register Bitfield Definitions ****************************************************/
/* DAC control register */
/* These definitions may be used with the full, 32-bit register */
#define DAC_CR_EN1 (1 << 0) /* Bit 0: DAC channel 1 enable */
#define DAC_CR_BOFF1 (1 << 1) /* Bit 1: DAC channel 1 output buffer disable */
#define DAC_CR_TEN1 (1 << 2) /* Bit 2: DAC channel 1 trigger enable */
#define DAC_CR_TSEL1_SHIFT (3) /* Bits 3-5: DAC channel 1 trigger selection */
#define DAC_CR_TSEL1_MASK (7 << DAC_CR_TSEL1_SHIFT)
# define DAC_CR_TSEL1_TIM6 (0 << DAC_CR_TSEL1_SHIFT) /* Timer 6 TRGO event */
# define DAC_CR_TSEL1_TIM3 (1 << DAC_CR_TSEL1_SHIFT) /* Timer 3 TRGO event */
# define DAC_CR_TSEL1_TIM7 (2 << DAC_CR_TSEL1_SHIFT) /* Timer 7 TRGO event */
# define DAC_CR_TSEL1_TIM15 (3 << DAC_CR_TSEL1_SHIFT) /* Timer 15 TRGO event, or */
# define DAC_CR_TSEL1_TIM2 (4 << DAC_CR_TSEL1_SHIFT) /* Timer 2 TRGO event */
# define DAC_CR_TSEL1_EXT9 (6 << DAC_CR_TSEL1_SHIFT) /* External line9 */
# define DAC_CR_TSEL1_SW (7 << DAC_CR_TSEL1_SHIFT) /* Software trigger */
#define DAC_CR_WAVE1_SHIFT (6) /* Bits 6-7: DAC channel 1 noise/triangle wave generation */
#define DAC_CR_WAVE1_MASK (3 << DAC_CR_WAVE1_SHIFT)
# define DAC_CR_WAVE1_DISABLED (0 << DAC_CR_WAVE1_SHIFT) /* Wave generation disabled */
# define DAC_CR_WAVE1_NOISE (1 << DAC_CR_WAVE1_SHIFT) /* Noise wave generation enabled */
# define DAC_CR_WAVE1_TRIANGLE (2 << DAC_CR_WAVE1_SHIFT) /* Triangle wave generation enabled */
#define DAC_CR_MAMP1_SHIFT (8) /* Bits 8-11: DAC channel 1 mask/amplitude selector */
#define DAC_CR_MAMP1_MASK (15 << DAC_CR_MAMP1_SHIFT)
# define DAC_CR_MAMP1_AMP1 (0 << DAC_CR_MAMP1_SHIFT) /* Unmask bit0 of LFSR/triangle amplitude=1 */
# define DAC_CR_MAMP1_AMP3 (1 << DAC_CR_MAMP1_SHIFT) /* Unmask bits[1:0] of LFSR/triangle amplitude=3 */
# define DAC_CR_MAMP1_AMP7 (2 << DAC_CR_MAMP1_SHIFT) /* Unmask bits[2:0] of LFSR/triangle amplitude=7 */
# define DAC_CR_MAMP1_AMP15 (3 << DAC_CR_MAMP1_SHIFT) /* Unmask bits[3:0] of LFSR/triangle amplitude=15 */
# define DAC_CR_MAMP1_AMP31 (4 << DAC_CR_MAMP1_SHIFT) /* Unmask bits[4:0] of LFSR/triangle amplitude=31 */
# define DAC_CR_MAMP1_AMP63 (5 << DAC_CR_MAMP1_SHIFT) /* Unmask bits[5:0] of LFSR/triangle amplitude=63 */
# define DAC_CR_MAMP1_AMP127 (6 << DAC_CR_MAMP1_SHIFT) /* Unmask bits[6:0] of LFSR/triangle amplitude=127 */
# define DAC_CR_MAMP1_AMP255 (7 << DAC_CR_MAMP1_SHIFT) /* Unmask bits[7:0] of LFSR/triangle amplitude=255 */
# define DAC_CR_MAMP1_AMP511 (8 << DAC_CR_MAMP1_SHIFT) /* Unmask bits[8:0] of LFSR/triangle amplitude=511 */
# define DAC_CR_MAMP1_AMP1023 (9 << DAC_CR_MAMP1_SHIFT) /* Unmask bits[9:0] of LFSR/triangle amplitude=1023 */
# define DAC_CR_MAMP1_AMP2047 (10 << DAC_CR_MAMP1_SHIFT) /* Unmask bits[10:0] of LFSR/triangle amplitude=2047 */
# define DAC_CR_MAMP1_AMP4095 (11 << DAC_CR_MAMP1_SHIFT) /* Unmask bits[11:0] of LFSR/triangle amplitude=4095 */
#define DAC_CR_DMAEN1 (1 << 12) /* Bit 12: DAC channel 1 DMA enable */
#define DAC_CR_DMAUDRIE1 (1 << 13) /* Bit 13: DAC channel 1 DMA Underrun Interrupt enable */
#define DAC_CR_EN2 (1 << 16) /* Bit 16: DAC channel 2 enable */
#define DAC_CR_BOFF2 (1 << 17) /* Bit 17: DAC channel 2 output buffer disable */
#define DAC_CR_TEN2 (1 << 18) /* Bit 18: DAC channel 2 trigger enable */
#define DAC_CR_TSEL2_SHIFT (19) /* Bits 19-21: DAC channel 2 trigger selection */
#define DAC_CR_TSEL2_MASK (7 << DAC_CR_TSEL2_SHIFT)
# define DAC_CR_TSEL2_TIM6 (0 << DAC_CR_TSEL2_SHIFT) /* Timer 6 TRGO event */
# define DAC_CR_TSEL2_TIM3 (1 << DAC_CR_TSEL2_SHIFT) /* Timer 3 TRGO event */
# define DAC_CR_TSEL2_TIM7 (2 << DAC_CR_TSEL2_SHIFT) /* Timer 7 TRGO event */
# define DAC_CR_TSEL2_TIM15 (3 << DAC_CR_TSEL2_SHIFT) /* Timer 15 TRGO event */
# define DAC_CR_TSEL2_TIM2 (4 << DAC_CR_TSEL2_SHIFT) /* Timer 2 TRGO event */
# define DAC_CR_TSEL2_EXT9 (6 << DAC_CR_TSEL2_SHIFT) /* External line9 */
# define DAC_CR_TSEL2_SW (7 << DAC_CR_TSEL2_SHIFT) /* Software trigger */
#define DAC_CR_WAVE2_SHIFT (22) /* Bit 22-23: DAC channel 2 noise/triangle wave generation enable */
#define DAC_CR_WAVE2_MASK (3 << DAC_CR_WAVE2_SHIFT)
# define DAC_CR_WAVE2_DISABLED (0 << DAC_CR_WAVE2_SHIFT) /* Wave generation disabled */
# define DAC_CR_WAVE2_NOISE (1 << DAC_CR_WAVE2_SHIFT) /* Noise wave generation enabled */
# define DAC_CR_WAVE2_TRIANGLE (2 << DAC_CR_WAVE2_SHIFT) /* Triangle wave generation enabled */
#define DAC_CR_MAMP2_SHIFT (24) /* Bit 24-27: DAC channel 2 mask/amplitude selector */
#define DAC_CR_MAMP2_MASK (15 << DAC_CR_MAMP2_SHIFT)
# define DAC_CR_MAMP2_AMP1 (0 << DAC_CR_MAMP2_SHIFT) /* Unmask bit0 of LFSR/triangle amplitude=1 */
# define DAC_CR_MAMP2_AMP3 (1 << DAC_CR_MAMP2_SHIFT) /* Unmask bits[1:0] of LFSR/triangle amplitude=3 */
# define DAC_CR_MAMP2_AMP7 (2 << DAC_CR_MAMP2_SHIFT) /* Unmask bits[2:0] of LFSR/triangle amplitude=7 */
# define DAC_CR_MAMP2_AMP15 (3 << DAC_CR_MAMP2_SHIFT) /* Unmask bits[3:0] of LFSR/triangle amplitude=15 */
# define DAC_CR_MAMP2_AMP31 (4 << DAC_CR_MAMP2_SHIFT) /* Unmask bits[4:0] of LFSR/triangle amplitude=31 */
# define DAC_CR_MAMP2_AMP63 (5 << DAC_CR_MAMP2_SHIFT) /* Unmask bits[5:0] of LFSR/triangle amplitude=63 */
# define DAC_CR_MAMP2_AMP127 (6 << DAC_CR_MAMP2_SHIFT) /* Unmask bits[6:0] of LFSR/triangle amplitude=127 */
# define DAC_CR_MAMP2_AMP255 (7 << DAC_CR_MAMP2_SHIFT) /* Unmask bits[7:0] of LFSR/triangle amplitude=255 */
# define DAC_CR_MAMP2_AMP511 (8 << DAC_CR_MAMP2_SHIFT) /* Unmask bits[8:0] of LFSR/triangle amplitude=511 */
# define DAC_CR_MAMP2_AMP1023 (9 << DAC_CR_MAMP2_SHIFT) /* Unmask bits[9:0] of LFSR/triangle amplitude=1023 */
# define DAC_CR_MAMP2_AMP2047 (10 << DAC_CR_MAMP2_SHIFT) /* Unmask bits[10:0] of LFSR/triangle amplitude=2047 */
# define DAC_CR_MAMP2_AMP4095 (11 << DAC_CR_MAMP2_SHIFT) /* Unmask bits[11:0] of LFSR/triangle amplitude=4095 */
#define DAC_CR_DMAEN2 (1 << 28) /* Bit 28: DAC channel 2 DMA enable */
#define DAC_CR_DMAUDRIE2 (1 << 29) /* Bits 29: DAC channel 2 DMA underrun interrupt enable */
/* DAC software trigger register */
#define DAC_SWTRIGR_SWTRIG(n) (1 << ((n)-1))
#define DAC_SWTRIGR_SWTRIG1 (1 << 0) /* Bit 0: DAC channel 1 software trigger */
#define DAC_SWTRIGR_SWTRIG2 (1 << 1) /* Bit 1: DAC channel 2 software trigger */
/* DAC channel 1/2 12-bit right-aligned data holding register */
#define DAC_DHR12R_MASK (0x0fff)
/* DAC channel 1/2 12-bit left aligned data holding register */
#define DAC_DHR12L_MASK (0xfff0)
/* DAC channel 1/2 8-bit right aligned data holding register */
#define DAC_DHR8R_MASK (0x00ff)
/* Dual DAC 12-bit right-aligned data holding register */
#define DAC_DHR12RD_DACC_SHIFT(n) (1 << (((n)-1) << 4))
#define DAC_DHR12RD_DACC_MASK(n) (0xfff << DAC_DHR12RD_DACC_SHIFT(n))
#define DAC_DHR12RD_DACC1_SHIFT (0) /* Bits 0-11: DAC channel 1 12-bit right-aligned data */
#define DAC_DHR12RD_DACC1_MASK (0xfff << DAC_DHR12RD_DACC2_SHIFT)
#define DAC_DHR12RD_DACC2_SHIFT (16) /* Bits 16-27: DAC channel 2 12-bit right-aligned data */
#define DAC_DHR12RD_DACC2_MASK (0xfff << DAC_DHR12RD_DACC2_SHIFT)
/* Dual DAC 12-bit left-aligned data holding register */
#define DAC_DHR12LD_DACC_SHIFT(n) ((1 << (((n)-1) << 4)) + 4)
#define DAC_DHR12LD_DACC_MASK(n) (0xfff << DAC_DHR12LD_DACC_SHIFT(n))
#define DAC_DHR12LD_DACC1_SHIFT (4) /* Bits 4-15: DAC channel 1 12-bit left-aligned data */
#define DAC_DHR12LD_DACC1_MASK (0xfff << DAC_DHR12LD_DACC1_SHIFT)
#define DAC_DHR12LD_DACC2_SHIFT (20) /* Bits 20-31: DAC channel 2 12-bit left-aligned data */
#define DAC_DHR12LD_DACC2_MASK (0xfff << DAC_DHR12LD_DACC2_SHIFT)
/* DUAL DAC 8-bit right aligned data holding register */
#define DAC_DHR8RD_DACC_SHIFT(n) (1 << (((n)-1) << 3))
#define DAC_DHR8RD_DACC_MASK(n) (0xff << DAC_DHR8RD_DACC_SHIFT(n))
#define DAC_DHR8RD_DACC1_SHIFT (0) /* Bits 0-7: DAC channel 1 8-bit right-aligned data */
#define DAC_DHR8RD_DACC1_MASK (0xff << DAC_DHR8RD_DACC1_SHIFT)
#define DAC_DHR8RD_DACC2_SHIFT (8) /* Bits 8-15: DAC channel 2 8-bit right-aligned data */
#define DAC_DHR8RD_DACC2_MASK (0xff << DAC_DHR8RD_DACC2_SHIFT)
/* DAC channel 1/2 data output register */
#define DAC_DOR_MASK (0x0fff)
/* DAC status register */
#define DAC_SR_DMAUDR(n) ((1 << (((n)-1) << 4)) + 13)
#define DAC_SR_DMAUDR1 (1 << 13) /* Bit 13: DAC channel 1 DMA underrun flag */
#define DAC_SR_DMAUDR2 (1 << 29) /* Bit 29: DAC channel 2 DMA underrun flag */
#endif /* __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_DAC_H */

View File

@ -0,0 +1,456 @@
/************************************************************************************
* arch/arm/src/stm32f0/chip/stm32f0_dma.h
*
* Copyright (C) 2017 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
* Alan Carvalho de Assis <acassis@gmail.com>
*
* 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 NuttX 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 OWNER 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.
*
************************************************************************************/
#ifndef __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_DMA_H
#define __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_DMA_H
/************************************************************************************
* Pre-processor Definitions
************************************************************************************/
/* 12 Channels Total: 7 DMA1 Channels(1-7) (and 5 DMA2 channels (1-5) if STM32F09x) */
#define DMA1 0
#define DMA2 1
#define DMA3 2
#define DMA4 3
#define DMA5 4
#define DMA6 5
#define DMA7 6
/* Register Offsets *****************************************************************/
#define STM32F0_DMA_ISR_OFFSET 0x0000 /* DMA interrupt status register */
#define STM32F0_DMA_IFCR_OFFSET 0x0004 /* DMA interrupt flag clear register */
#define STM32F0_DMACHAN_OFFSET(n) (0x0014*(n))
#define STM32F0_DMACHAN1_OFFSET 0x0000
#define STM32F0_DMACHAN2_OFFSET 0x0014
#define STM32F0_DMACHAN3_OFFSET 0x0028
#define STM32F0_DMACHAN4_OFFSET 0x003c
#define STM32F0_DMACHAN5_OFFSET 0x0050
#define STM32F0_DMACHAN6_OFFSET 0x0064
#define STM32F0_DMACHAN7_OFFSET 0x0078
#define STM32F0_DMACHAN_CCR_OFFSET 0x0008 /* DMA channel configuration register */
#define STM32F0_DMACHAN_CNDTR_OFFSET 0x000c /* DMA channel number of data register */
#define STM32F0_DMACHAN_CPAR_OFFSET 0x0010 /* DMA channel peripheral address register */
#define STM32F0_DMACHAN_CMAR_OFFSET 0x0014 /* DMA channel memory address register */
#define STM32F0_DMA_CCR_OFFSET(n) (STM32F0_DMACHAN_CCR_OFFSET+STM32F0_DMACHAN_OFFSET(n))
#define STM32F0_DMA_CNDTR_OFFSET(n) (STM32F0_DMACHAN_CNDTR_OFFSET+STM32F0_DMACHAN_OFFSET(n))
#define STM32F0_DMA_CPAR_OFFSET(n) (STM32F0_DMACHAN_CPAR_OFFSET+STM32F0_DMACHAN_OFFSET(n))
#define STM32F0_DMA_CMAR_OFFSET(n) (STM32F0_DMACHAN_CMAR_OFFSET+STM32F0_DMACHAN_OFFSET(n))
#define STM32F0_DMA_CCR1_OFFSET 0x0008 /* DMA channel 1 configuration register */
#define STM32F0_DMA_CCR2_OFFSET 0x001c /* DMA channel 2 configuration register */
#define STM32F0_DMA_CCR3_OFFSET 0x0030 /* DMA channel 3 configuration register */
#define STM32F0_DMA_CCR4_OFFSET 0x0044 /* DMA channel 4 configuration register */
#define STM32F0_DMA_CCR5_OFFSET 0x0058 /* DMA channel 5 configuration register */
#define STM32F0_DMA_CCR6_OFFSET 0x006c /* DMA channel 6 configuration register */
#define STM32F0_DMA_CCR7_OFFSET 0x0080 /* DMA channel 7 configuration register */
#define STM32F0_DMA_CNDTR1_OFFSET 0x000c /* DMA channel 1 number of data register */
#define STM32F0_DMA_CNDTR2_OFFSET 0x0020 /* DMA channel 2 number of data register */
#define STM32F0_DMA_CNDTR3_OFFSET 0x0034 /* DMA channel 3 number of data register */
#define STM32F0_DMA_CNDTR4_OFFSET 0x0048 /* DMA channel 4 number of data register */
#define STM32F0_DMA_CNDTR5_OFFSET 0x005c /* DMA channel 5 number of data register */
#define STM32F0_DMA_CNDTR6_OFFSET 0x0070 /* DMA channel 6 number of data register */
#define STM32F0_DMA_CNDTR7_OFFSET 0x0084 /* DMA channel 7 number of data register */
#define STM32F0_DMA_CPAR1_OFFSET 0x0010 /* DMA channel 1 peripheral address register */
#define STM32F0_DMA_CPAR2_OFFSET 0x0024 /* DMA channel 2 peripheral address register */
#define STM32F0_DMA_CPAR3_OFFSET 0x0038 /* DMA channel 3 peripheral address register */
#define STM32F0_DMA_CPAR4_OFFSET 0x004c /* DMA channel 4 peripheral address register */
#define STM32F0_DMA_CPAR5_OFFSET 0x0060 /* DMA channel 5 peripheral address register */
#define STM32F0_DMA_CPAR6_OFFSET 0x0074 /* DMA channel 6 peripheral address register */
#define STM32F0_DMA_CPAR7_OFFSET 0x0088 /* DMA channel 7 peripheral address register */
#define STM32F0_DMA_CMAR1_OFFSET 0x0014 /* DMA channel 1 memory address register */
#define STM32F0_DMA_CMAR2_OFFSET 0x0028 /* DMA channel 2 memory address register */
#define STM32F0_DMA_CMAR3_OFFSET 0x003c /* DMA channel 3 memory address register */
#define STM32F0_DMA_CMAR4_OFFSET 0x0050 /* DMA channel 4 memory address register */
#define STM32F0_DMA_CMAR5_OFFSET 0x0064 /* DMA channel 5 memory address register */
#define STM32F0_DMA_CMAR6_OFFSET 0x0078 /* DMA channel 6 memory address register */
#define STM32F0_DMA_CMAR7_OFFSET 0x008c /* DMA channel 7 memory address register */
#define STM32F0_DMA_CSELR_OFFSET 0x00a8 /* DMA channel selection register */
/* Register Addresses ***************************************************************/
#define STM32F0_DMA1_ISRC (STM32F0_DMA1_BASE+STM32F0_DMA_ISR_OFFSET)
#define STM32F0_DMA1_IFCR (STM32F0_DMA1_BASE+STM32F0_DMA_IFCR_OFFSET)
#define STM32F0_DMA1_CCR(n) (STM32F0_DMA1_BASE+STM32F0_DMA_CCR_OFFSET(n))
#define STM32F0_DMA1_CCR1 (STM32F0_DMA1_BASE+STM32F0_DMA_CCR1_OFFSET)
#define STM32F0_DMA1_CCR2 (STM32F0_DMA1_BASE+STM32F0_DMA_CCR2_OFFSET)
#define STM32F0_DMA1_CCR3 (STM32F0_DMA1_BASE+STM32F0_DMA_CCR3_OFFSET)
#define STM32F0_DMA1_CCR4 (STM32F0_DMA1_BASE+STM32F0_DMA_CCR4_OFFSET)
#define STM32F0_DMA1_CCR5 (STM32F0_DMA1_BASE+STM32F0_DMA_CCR5_OFFSET)
#define STM32F0_DMA1_CCR6 (STM32F0_DMA1_BASE+STM32F0_DMA_CCR6_OFFSET)
#define STM32F0_DMA1_CCR7 (STM32F0_DMA1_BASE+STM32F0_DMA_CCR7_OFFSET)
#define STM32F0_DMA1_CNDTR(n) (STM32F0_DMA1_BASE+STM32F0_DMA_CNDTR_OFFSET(n))
#define STM32F0_DMA1_CNDTR1 (STM32F0_DMA1_BASE+STM32F0_DMA_CNDTR1_OFFSET)
#define STM32F0_DMA1_CNDTR2 (STM32F0_DMA1_BASE+STM32F0_DMA_CNDTR2_OFFSET)
#define STM32F0_DMA1_CNDTR3 (STM32F0_DMA1_BASE+STM32F0_DMA_CNDTR3_OFFSET)
#define STM32F0_DMA1_CNDTR4 (STM32F0_DMA1_BASE+STM32F0_DMA_CNDTR4_OFFSET)
#define STM32F0_DMA1_CNDTR5 (STM32F0_DMA1_BASE+STM32F0_DMA_CNDTR5_OFFSET)
#define STM32F0_DMA1_CNDTR6 (STM32F0_DMA1_BASE+STM32F0_DMA_CNDTR6_OFFSET)
#define STM32F0_DMA1_CNDTR7 (STM32F0_DMA1_BASE+STM32F0_DMA_CNDTR7_OFFSET)
#define STM32F0_DMA1_CPAR(n) (STM32F0_DMA1_BASE+STM32F0_DMA_CPAR_OFFSET(n))
#define STM32F0_DMA1_CPAR1 (STM32F0_DMA1_BASE+STM32F0_DMA_CPAR1_OFFSET)
#define STM32F0_DMA1_CPAR2 (STM32F0_DMA1_BASE+STM32F0_DMA_CPAR2_OFFSET)
#define STM32F0_DMA1_CPAR3 (STM32F0_DMA1_BASE+STM32F0_DMA_CPAR3_OFFSET)
#define STM32F0_DMA1_CPAR4 (STM32F0_DMA1_BASE+STM32F0_DMA_CPAR4_OFFSET)
#define STM32F0_DMA1_CPAR5 (STM32F0_DMA1_BASE+STM32F0_DMA_CPAR5_OFFSET)
#define STM32F0_DMA1_CPAR6 (STM32F0_DMA1_BASE+STM32F0_DMA_CPAR6_OFFSET)
#define STM32F0_DMA1_CPAR7 (STM32F0_DMA1_BASE+STM32F0_DMA_CPAR7_OFFSET)
#define STM32F0_DMA1_CMAR(n) (STM32F0_DMA1_BASE+STM32F0_DMA_CMAR_OFFSET(n))
#define STM32F0_DMA1_CMAR1 (STM32F0_DMA1_BASE+STM32F0_DMA_CMAR1_OFFSET)
#define STM32F0_DMA1_CMAR2 (STM32F0_DMA1_BASE+STM32F0_DMA_CMAR2_OFFSET)
#define STM32F0_DMA1_CMAR3 (STM32F0_DMA1_BASE+STM32F0_DMA_CMAR3_OFFSET)
#define STM32F0_DMA1_CMAR4 (STM32F0_DMA1_BASE+STM32F0_DMA_CMAR4_OFFSET)
#define STM32F0_DMA1_CMAR5 (STM32F0_DMA1_BASE+STM32F0_DMA_CMAR5_OFFSET)
#define STM32F0_DMA1_CMAR6 (STM32F0_DMA1_BASE+STM32F0_DMA_CMAR6_OFFSET)
#define STM32F0_DMA1_CMAR7 (STM32F0_DMA1_BASE+STM32F0_DMA_CMAR7_OFFSET)
#define STM32F0_DMA2_ISRC (STM32F0_DMA2_BASE+STM32F0_DMA_ISR_OFFSET)
#define STM32F0_DMA2_IFCR (STM32F0_DMA2_BASE+STM32F0_DMA_IFCR_OFFSET)
#define STM32F0_DMA2_CCR(n) (STM32F0_DMA2_BASE+STM32F0_DMA_CCR_OFFSET(n))
#define STM32F0_DMA2_CCR1 (STM32F0_DMA2_BASE+STM32F0_DMA_CCR1_OFFSET)
#define STM32F0_DMA2_CCR2 (STM32F0_DMA2_BASE+STM32F0_DMA_CCR2_OFFSET)
#define STM32F0_DMA2_CCR3 (STM32F0_DMA2_BASE+STM32F0_DMA_CCR3_OFFSET)
#define STM32F0_DMA2_CCR4 (STM32F0_DMA2_BASE+STM32F0_DMA_CCR4_OFFSET)
#define STM32F0_DMA2_CCR5 (STM32F0_DMA2_BASE+STM32F0_DMA_CCR5_OFFSET)
#define STM32F0_DMA2_CCR6 (STM32F0_DMA2_BASE+STM32F0_DMA_CCR6_OFFSET)
#define STM32F0_DMA2_CCR7 (STM32F0_DMA2_BASE+STM32F0_DMA_CCR7_OFFSET)
#define STM32F0_DMA2_CNDTR(n) (STM32F0_DMA2_BASE+STM32F0_DMA_CNDTR_OFFSET(n))
#define STM32F0_DMA2_CNDTR1 (STM32F0_DMA2_BASE+STM32F0_DMA_CNDTR1_OFFSET)
#define STM32F0_DMA2_CNDTR2 (STM32F0_DMA2_BASE+STM32F0_DMA_CNDTR2_OFFSET)
#define STM32F0_DMA2_CNDTR3 (STM32F0_DMA2_BASE+STM32F0_DMA_CNDTR3_OFFSET)
#define STM32F0_DMA2_CNDTR4 (STM32F0_DMA2_BASE+STM32F0_DMA_CNDTR4_OFFSET)
#define STM32F0_DMA2_CNDTR5 (STM32F0_DMA2_BASE+STM32F0_DMA_CNDTR5_OFFSET)
#define STM32F0_DMA2_CNDTR6 (STM32F0_DMA2_BASE+STM32F0_DMA_CNDTR6_OFFSET)
#define STM32F0_DMA2_CNDTR7 (STM32F0_DMA2_BASE+STM32F0_DMA_CNDTR7_OFFSET)
#define STM32F0_DMA2_CPAR(n) (STM32F0_DMA2_BASE+STM32F0_DMA_CPAR_OFFSET(n))
#define STM32F0_DMA2_CPAR1 (STM32F0_DMA2_BASE+STM32F0_DMA_CPAR1_OFFSET)
#define STM32F0_DMA2_CPAR2 (STM32F0_DMA2_BASE+STM32F0_DMA_CPAR2_OFFSET)
#define STM32F0_DMA2_CPAR3 (STM32F0_DMA2_BASE+STM32F0_DMA_CPAR3_OFFSET)
#define STM32F0_DMA2_CPAR4 (STM32F0_DMA2_BASE+STM32F0_DMA_CPAR4_OFFSET)
#define STM32F0_DMA2_CPAR5 (STM32F0_DMA2_BASE+STM32F0_DMA_CPAR5_OFFSET)
#define STM32F0_DMA2_CPAR6 (STM32F0_DMA2_BASE+STM32F0_DMA_CPAR6_OFFSET)
#define STM32F0_DMA2_CPAR7 (STM32F0_DMA2_BASE+STM32F0_DMA_CPAR7_OFFSET)
#define STM32F0_DMA2_CMAR(n) (STM32F0_DMA2_BASE+STM32F0_DMA_CMAR_OFFSET(n))
#define STM32F0_DMA2_CMAR1 (STM32F0_DMA2_BASE+STM32F0_DMA_CMAR1_OFFSET)
#define STM32F0_DMA2_CMAR2 (STM32F0_DMA2_BASE+STM32F0_DMA_CMAR2_OFFSET)
#define STM32F0_DMA2_CMAR3 (STM32F0_DMA2_BASE+STM32F0_DMA_CMAR3_OFFSET)
#define STM32F0_DMA2_CMAR4 (STM32F0_DMA2_BASE+STM32F0_DMA_CMAR4_OFFSET)
#define STM32F0_DMA2_CMAR5 (STM32F0_DMA2_BASE+STM32F0_DMA_CMAR5_OFFSET)
#define STM32F0_DMA2_CMAR6 (STM32F0_DMA2_BASE+STM32F0_DMA_CMAR6_OFFSET)
#define STM32F0_DMA2_CMAR7 (STM32F0_DMA2_BASE+STM32F0_DMA_CMAR7_OFFSET)
/* Register Bitfield Definitions ****************************************************/
#define DMA_CHAN_SHIFT(n) ((n) << 2)
#define DMA_CHAN_MASK 0x0f
#define DMA_CHAN_GIF_BIT (1 << 0) /* Bit 0: Channel Global interrupt flag */
#define DMA_CHAN_TCIF_BIT (1 << 1) /* Bit 1: Channel Transfer Complete flag */
#define DMA_CHAN_HTIF_BIT (1 << 2) /* Bit 2: Channel Half Transfer flag */
#define DMA_CHAN_TEIF_BIT (1 << 3) /* Bit 3: Channel Transfer Error flag */
/* DMA interrupt status register */
#define DMA_ISR_CHAN_SHIFT(n) DMA_CHAN_SHIFT(n)
#define DMA_ISR_CHAN_MASK(n) (DMA_CHAN_MASK << DMA_ISR_CHAN_SHIFT(n))
#define DMA_ISR_CHAN1_SHIFT (0) /* Bits 3-0: DMA Channel 1 interrupt status */
#define DMA_ISR_CHAN1_MASK (DMA_CHAN_MASK << DMA_ISR_CHAN1_SHIFT)
#define DMA_ISR_CHAN2_SHIFT (4) /* Bits 7-4: DMA Channel 2 interrupt status */
#define DMA_ISR_CHAN2_MASK (DMA_CHAN_MASK << DMA_ISR_CHAN2_SHIFT)
#define DMA_ISR_CHAN3_SHIFT (8) /* Bits 11-8: DMA Channel 3 interrupt status */
#define DMA_ISR_CHAN3_MASK (DMA_CHAN_MASK << DMA_ISR_CHAN3_SHIFT)
#define DMA_ISR_CHAN4_SHIFT (12) /* Bits 15-12: DMA Channel 4 interrupt status */
#define DMA_ISR_CHAN4_MASK (DMA_CHAN_MASK << DMA_ISR_CHAN4_SHIFT)
#define DMA_ISR_CHAN5_SHIFT (16) /* Bits 19-16: DMA Channel 5 interrupt status */
#define DMA_ISR_CHAN5_MASK (DMA_CHAN_MASK << DMA_ISR_CHAN5_SHIFT)
#define DMA_ISR_CHAN6_SHIFT (20) /* Bits 23-20: DMA Channel 6 interrupt status */
#define DMA_ISR_CHAN6_MASK (DMA_CHAN_MASK << DMA_ISR_CHAN6_SHIFT)
#define DMA_ISR_CHAN7_SHIFT (24) /* Bits 27-24: DMA Channel 7 interrupt status */
#define DMA_ISR_CHAN7_MASK (DMA_CHAN_MASK << DMA_ISR_CHAN7_SHIFT)
#define DMA_ISR_GIF(n) (DMA_CHAN_GIF_BIT << DMA_ISR_CHAN_SHIFT(n))
#define DMA_ISR_TCIF(n) (DMA_CHAN_TCIF_BIT << DMA_ISR_CHAN_SHIFT(n))
#define DMA_ISR_HTIF(n) (DMA_CHAN_HTIF_BIT << DMA_ISR_CHAN_SHIFT(n))
#define DMA_ISR_TEIF(n) (DMA_CHAN_TEIF_BIT << DMA_ISR_CHAN_SHIFT(n))
/* DMA interrupt flag clear register */
#define DMA_IFCR_CHAN_SHIFT(n) DMA_CHAN_SHIFT(n)
#define DMA_IFCR_CHAN_MASK(n) (DMA_CHAN_MASK << DMA_IFCR_CHAN_SHIFT(n))
#define DMA_IFCR_CHAN1_SHIFT (0) /* Bits 3-0: DMA Channel 1 interrupt flag clear */
#define DMA_IFCR_CHAN1_MASK (DMA_CHAN_MASK << DMA_IFCR_CHAN1_SHIFT)
#define DMA_IFCR_CHAN2_SHIFT (4) /* Bits 7-4: DMA Channel 2 interrupt flag clear */
#define DMA_IFCR_CHAN2_MASK (DMA_CHAN_MASK << DMA_IFCR_CHAN2_SHIFT)
#define DMA_IFCR_CHAN3_SHIFT (8) /* Bits 11-8: DMA Channel 3 interrupt flag clear */
#define DMA_IFCR_CHAN3_MASK (DMA_CHAN_MASK << DMA_IFCR_CHAN3_SHIFT)
#define DMA_IFCR_CHAN4_SHIFT (12) /* Bits 15-12: DMA Channel 4 interrupt flag clear */
#define DMA_IFCR_CHAN4_MASK (DMA_CHAN_MASK << DMA_IFCR_CHAN4_SHIFT)
#define DMA_IFCR_CHAN5_SHIFT (16) /* Bits 19-16: DMA Channel 5 interrupt flag clear */
#define DMA_IFCR_CHAN5_MASK (DMA_CHAN_MASK << DMA_IFCR_CHAN5_SHIFT)
#define DMA_IFCR_CHAN6_SHIFT (20) /* Bits 23-20: DMA Channel 6 interrupt flag clear */
#define DMA_IFCR_CHAN6_MASK (DMA_CHAN_MASK << DMA_IFCR_CHAN6_SHIFT)
#define DMA_IFCR_CHAN7_SHIFT (24) /* Bits 27-24: DMA Channel 7 interrupt flag clear */
#define DMA_IFCR_CHAN7_MASK (DMA_CHAN_MASK << DMA_IFCR_CHAN7_SHIFT)
#define DMA_IFCR_ALLCHANNELS (0x0fffffff)
#define DMA_IFCR_CGIF(n) (DMA_CHAN_GIF_BIT << DMA_IFCR_CHAN_SHIFT(n))
#define DMA_IFCR_CTCIF(n) (DMA_CHAN_TCIF_BIT << DMA_IFCR_CHAN_SHIFT(n))
#define DMA_IFCR_CHTIF(n) (DMA_CHAN_HTIF_BIT << DMA_IFCR_CHAN_SHIFT(n))
#define DMA_IFCR_CTEIF(n) (DMA_CHAN_TEIF_BIT << DMA_IFCR_CHAN_SHIFT(n))
/* DMA channel configuration register */
#define DMA_CCR_EN (1 << 0) /* Bit 0: Channel enable */
#define DMA_CCR_TCIE (1 << 1) /* Bit 1: Transfer complete interrupt enable */
#define DMA_CCR_HTIE (1 << 2) /* Bit 2: Half Transfer interrupt enable */
#define DMA_CCR_TEIE (1 << 3) /* Bit 3: Transfer error interrupt enable */
#define DMA_CCR_DIR (1 << 4) /* Bit 4: Data transfer direction */
#define DMA_CCR_CIRC (1 << 5) /* Bit 5: Circular mode */
#define DMA_CCR_PINC (1 << 6) /* Bit 6: Peripheral increment mode */
#define DMA_CCR_MINC (1 << 7) /* Bit 7: Memory increment mode */
#define DMA_CCR_PSIZE_SHIFT (8) /* Bits 8-9: Peripheral size */
#define DMA_CCR_PSIZE_MASK (3 << DMA_CCR_PSIZE_SHIFT)
# define DMA_CCR_PSIZE_8BITS (0 << DMA_CCR_PSIZE_SHIFT) /* 00: 8-bits */
# define DMA_CCR_PSIZE_16BITS (1 << DMA_CCR_PSIZE_SHIFT) /* 01: 16-bits */
# define DMA_CCR_PSIZE_32BITS (2 << DMA_CCR_PSIZE_SHIFT) /* 10: 32-bits */
#define DMA_CCR_MSIZE_SHIFT (10) /* Bits 10-11: Memory size */
#define DMA_CCR_MSIZE_MASK (3 << DMA_CCR_MSIZE_SHIFT)
# define DMA_CCR_MSIZE_8BITS (0 << DMA_CCR_MSIZE_SHIFT) /* 00: 8-bits */
# define DMA_CCR_MSIZE_16BITS (1 << DMA_CCR_MSIZE_SHIFT) /* 01: 16-bits */
# define DMA_CCR_MSIZE_32BITS (2 << DMA_CCR_MSIZE_SHIFT) /* 10: 32-bits */
#define DMA_CCR_PL_SHIFT (12) /* Bits 12-13: Channel Priority level */
#define DMA_CCR_PL_MASK (3 << DMA_CCR_PL_SHIFT)
# define DMA_CCR_PRILO (0 << DMA_CCR_PL_SHIFT) /* 00: Low */
# define DMA_CCR_PRIMED (1 << DMA_CCR_PL_SHIFT) /* 01: Medium */
# define DMA_CCR_PRIHI (2 << DMA_CCR_PL_SHIFT) /* 10: High */
# define DMA_CCR_PRIVERYHI (3 << DMA_CCR_PL_SHIFT) /* 11: Very high */
#define DMA_CCR_MEM2MEM (1 << 14) /* Bit 14: Memory to memory mode */
#define DMA_CCR_ALLINTS (DMA_CCR_TEIE|DMA_CCR_HTIE|DMA_CCR_TCIE)
/* DMA channel number of data register */
#define DMA_CNDTR_NDT_SHIFT (0) /* Bits 15-0: Number of data to Transfer */
#define DMA_CNDTR_NDT_MASK (0xffff << DMA_CNDTR_NDT_SHIFT)
/* DMA Channel mapping. Each DMA channel has a mapping to one of several
* possible sources/sinks of data. The requests from peripherals assigned to a
* channel are multiplexed together before entering the DMA block. This means
* that only one request on a given channel can be enabled at once.
*
* Alternative DMA channel selections are provided with a numeric suffix like _1,
* _2, etc. Drivers, however, will use the pin selection without the numeric suffix.
* Additional definitions are required in the board.h file.
*/
/* REVISE IT: based on STM32L4 DMA Header */
#define STM32F0_DMA1_CHAN1 (0)
#define STM32F0_DMA1_CHAN2 (1)
#define STM32F0_DMA1_CHAN3 (2)
#define STM32F0_DMA1_CHAN4 (3)
#define STM32F0_DMA1_CHAN5 (4)
#define STM32F0_DMA1_CHAN6 (5)
#define STM32F0_DMA1_CHAN7 (6)
#define STM32F0_DMA2_CHAN1 (7)
#define STM32F0_DMA2_CHAN2 (8)
#define STM32F0_DMA2_CHAN3 (9)
#define STM32F0_DMA2_CHAN4 (10)
#define STM32F0_DMA2_CHAN5 (11)
#define DMACHAN_SETTING(chan, sel) ( ( ( (sel) & 0xff) << 8) | ( (chan) & 0xff) )
#define DMACHAN_SETTING_CHANNEL_MASK 0x00FF
#define DMACHAN_SETTING_CHANNEL_SHIFT (0)
#define DMACHAN_SETTING_FUNCTION_MASK 0xFF00
#define DMACHAN_SETTING_FUNCTION_SHIFT (8)
/* ADC */
#define DMACHAN_ADC1_1 DMACHAN_SETTING(STM32F0_DMA1_CHAN1, 0)
#define DMACHAN_ADC1_2 DMACHAN_SETTING(STM32F0_DMA2_CHAN3, 0)
#define DMACHAN_ADC2_1 DMACHAN_SETTING(STM32F0_DMA1_CHAN1, 0)
#define DMACHAN_ADC2_2 DMACHAN_SETTING(STM32F0_DMA2_CHAN4, 0)
#define DMACHAN_ADC3_1 DMACHAN_SETTING(STM32F0_DMA1_CHAN1, 0)
#define DMACHAN_ADC3_2 DMACHAN_SETTING(STM32F0_DMA2_CHAN5, 0)
/* AES */
#define DMACHAN_AES_IN_1 DMACHAN_SETTING(STM32F0_DMA2_CHAN1, 6)
#define DMACHAN_AES_IN_2 DMACHAN_SETTING(STM32F0_DMA2_CHAN5, 6)
#define DMACHAN_AES_OUT_1 DMACHAN_SETTING(STM32F0_DMA2_CHAN2, 6)
#define DMACHAN_AES_OUT_2 DMACHAN_SETTING(STM32F0_DMA2_CHAN3, 6)
/* DAC */
#define DMACHAN_DAC1_1 DMACHAN_SETTING(STM32F0_DMA1_CHAN3, 6)
#define DMACHAN_DAC1_2 DMACHAN_SETTING(STM32F0_DMA1_CHAN4, 5)
#define DMACHAN_DAC1_3 DMACHAN_SETTING(STM32F0_DMA2_CHAN4, 3)
#define DMACHAN_DAC2 DMACHAN_SETTING(STM32F0_DMA2_CHAN5, 3)
/* I2C */
#define DMACHAN_I2C1_RX_1 DMACHAN_SETTING(STM32F0_DMA1_CHAN7, 3)
#define DMACHAN_I2C1_RX_2 DMACHAN_SETTING(STM32F0_DMA2_CHAN6, 5)
#define DMACHAN_I2C1_TX_1 DMACHAN_SETTING(STM32F0_DMA1_CHAN6, 3)
#define DMACHAN_I2C1_TX_2 DMACHAN_SETTING(STM32F0_DMA2_CHAN7, 5)
#define DMACHAN_I2C2_RX DMACHAN_SETTING(STM32F0_DMA1_CHAN5, 3)
#define DMACHAN_I2C2_TX DMACHAN_SETTING(STM32F0_DMA1_CHAN4, 3)
#define DMACHAN_I2C3_RX DMACHAN_SETTING(STM32F0_DMA1_CHAN3, 2)
#define DMACHAN_I2C3_TX DMACHAN_SETTING(STM32F0_DMA1_CHAN2, 3)
/* QUADSPI */
#define DMACHAN_QUADSPI_1 DMACHAN_SETTING(STM32F0_DMA1_CHAN5, 5)
#define DMACHAN_QUADSPI_2 DMACHAN_SETTING(STM32F0_DMA2_CHAN7, 3)
/* SPI */
#define DMACHAN_SPI1_RX_1 DMACHAN_SETTING(STM32F0_DMA1_CHAN2, 1)
#define DMACHAN_SPI1_RX_2 DMACHAN_SETTING(STM32F0_DMA2_CHAN3, 4)
#define DMACHAN_SPI1_TX_1 DMACHAN_SETTING(STM32F0_DMA1_CHAN3, 0)
#define DMACHAN_SPI1_TX_2 DMACHAN_SETTING(STM32F0_DMA2_CHAN4, 4)
#define DMACHAN_SPI2_RX DMACHAN_SETTING(STM32F0_DMA1_CHAN4, 1)
#define DMACHAN_SPI2_TX DMACHAN_SETTING(STM32F0_DMA1_CHAN5, 1)
#define DMACHAN_SPI3_RX DMACHAN_SETTING(STM32F0_DMA2_CHAN1, 3)
#define DMACHAN_SPI3_TX DMACHAN_SETTING(STM32F0_DMA2_CHAN2, 3)
/* TIM */
#define DMACHAN_TIM1_CH1 DMACHAN_SETTING(STM32F0_DMA1_CHAN2, 7)
#define DMACHAN_TIM1_CH2 DMACHAN_SETTING(STM32F0_DMA1_CHAN3, 7)
#define DMACHAN_TIM1_CH3 DMACHAN_SETTING(STM32F0_DMA1_CHAN7, 7)
#define DMACHAN_TIM1_CH4 DMACHAN_SETTING(STM32F0_DMA1_CHAN4, 7)
#define DMACHAN_TIM1_COM DMACHAN_SETTING(STM32F0_DMA1_CHAN4, 7)
#define DMACHAN_TIM1_TRIG DMACHAN_SETTING(STM32F0_DMA1_CHAN4, 7)
#define DMACHAN_TIM1_UP DMACHAN_SETTING(STM32F0_DMA1_CHAN6, 7)
#define DMACHAN_TIM2_CH1 DMACHAN_SETTING(STM32F0_DMA1_CHAN5, 4)
#define DMACHAN_TIM2_CH2 DMACHAN_SETTING(STM32F0_DMA1_CHAN7, 4)
#define DMACHAN_TIM2_CH3 DMACHAN_SETTING(STM32F0_DMA1_CHAN1, 4)
#define DMACHAN_TIM2_CH4 DMACHAN_SETTING(STM32F0_DMA1_CHAN7, 4)
#define DMACHAN_TIM2_UP DMACHAN_SETTING(STM32F0_DMA1_CHAN2, 4)
#define DMACHAN_TIM3_CH1 DMACHAN_SETTING(STM32F0_DMA1_CHAN6, 5)
#define DMACHAN_TIM3_CH3 DMACHAN_SETTING(STM32F0_DMA1_CHAN2, 5)
#define DMACHAN_TIM3_CH4 DMACHAN_SETTING(STM32F0_DMA1_CHAN3, 5)
#define DMACHAN_TIM3_TRIG DMACHAN_SETTING(STM32F0_DMA1_CHAN6, 5)
#define DMACHAN_TIM3_UP DMACHAN_SETTING(STM32F0_DMA1_CHAN3, 5)
#define DMACHAN_TIM4_CH1 DMACHAN_SETTING(STM32F0_DMA1_CHAN1, 6)
#define DMACHAN_TIM4_CH2 DMACHAN_SETTING(STM32F0_DMA1_CHAN4, 6)
#define DMACHAN_TIM4_CH3 DMACHAN_SETTING(STM32F0_DMA1_CHAN5, 6)
#define DMACHAN_TIM4_UP DMACHAN_SETTING(STM32F0_DMA1_CHAN7, 6)
#define DMACHAN_TIM5_CH1 DMACHAN_SETTING(STM32F0_DMA2_CHAN5, 5)
#define DMACHAN_TIM5_CH2 DMACHAN_SETTING(STM32F0_DMA2_CHAN4, 5)
#define DMACHAN_TIM5_CH3 DMACHAN_SETTING(STM32F0_DMA2_CHAN2, 5)
#define DMACHAN_TIM5_CH4 DMACHAN_SETTING(STM32F0_DMA2_CHAN1, 5)
#define DMACHAN_TIM5_COM DMACHAN_SETTING(STM32F0_DMA2_CHAN1, 5)
#define DMACHAN_TIM5_TRIG DMACHAN_SETTING(STM32F0_DMA2_CHAN1, 5)
#define DMACHAN_TIM5_UP DMACHAN_SETTING(STM32F0_DMA2_CHAN2, 5)
#define DMACHAN_TIM6_UP_1 DMACHAN_SETTING(STM32F0_DMA1_CHAN3, 6)
#define DMACHAN_TIM6_UP_2 DMACHAN_SETTING(STM32F0_DMA2_CHAN4, 3)
#define DMACHAN_TIM7_UP_1 DMACHAN_SETTING(STM32F0_DMA1_CHAN4, 5)
#define DMACHAN_TIM7_UP_2 DMACHAN_SETTING(STM32F0_DMA2_CHAN5, 3)
#define DMACHAN_TIM8_CH1 DMACHAN_SETTING(STM32F0_DMA2_CHAN6, 7)
#define DMACHAN_TIM8_CH2 DMACHAN_SETTING(STM32F0_DMA2_CHAN7, 7)
#define DMACHAN_TIM8_CH3 DMACHAN_SETTING(STM32F0_DMA2_CHAN1, 7)
#define DMACHAN_TIM8_CH4 DMACHAN_SETTING(STM32F0_DMA2_CHAN2, 7)
#define DMACHAN_TIM8_COM DMACHAN_SETTING(STM32F0_DMA2_CHAN2, 7)
#define DMACHAN_TIM8_TRIG DMACHAN_SETTING(STM32F0_DMA2_CHAN2, 7)
#define DMACHAN_TIM8_UP DMACHAN_SETTING(STM32F0_DMA2_CHAN1, 7)
#define DMACHAN_TIM15_CH1 DMACHAN_SETTING(STM32F0_DMA1_CHAN5, 7)
#define DMACHAN_TIM15_COM DMACHAN_SETTING(STM32F0_DMA1_CHAN5, 7)
#define DMACHAN_TIM15_TRIG DMACHAN_SETTING(STM32F0_DMA1_CHAN5, 7)
#define DMACHAN_TIM15_UP DMACHAN_SETTING(STM32F0_DMA1_CHAN5, 7)
#define DMACHAN_TIM16_CH1_1 DMACHAN_SETTING(STM32F0_DMA1_CHAN3, 4)
#define DMACHAN_TIM16_CH1_2 DMACHAN_SETTING(STM32F0_DMA1_CHAN6, 4)
#define DMACHAN_TIM16_UP_1 DMACHAN_SETTING(STM32F0_DMA1_CHAN3, 4)
#define DMACHAN_TIM16_UP_2 DMACHAN_SETTING(STM32F0_DMA1_CHAN6, 4)
#define DMACHAN_TIM17_CH1_1 DMACHAN_SETTING(STM32F0_DMA1_CHAN1, 5)
#define DMACHAN_TIM17_CH1_2 DMACHAN_SETTING(STM32F0_DMA1_CHAN7, 5)
#define DMACHAN_TIM17_UP_1 DMACHAN_SETTING(STM32F0_DMA1_CHAN1, 5)
#define DMACHAN_TIM17_UP_2 DMACHAN_SETTING(STM32F0_DMA1_CHAN7, 5)
/* UART */
#define DMACHAN_USART1_RX_1 DMACHAN_SETTING(STM32F0_DMA1_CHAN5, 2)
#define DMACHAN_USART1_RX_2 DMACHAN_SETTING(STM32F0_DMA2_CHAN7, 2)
#define DMACHAN_USART1_TX_1 DMACHAN_SETTING(STM32F0_DMA1_CHAN4, 2)
#define DMACHAN_USART1_TX_2 DMACHAN_SETTING(STM32F0_DMA2_CHAN6, 2)
#define DMACHAN_USART2_RX DMACHAN_SETTING(STM32F0_DMA1_CHAN6, 2)
#define DMACHAN_USART2_TX DMACHAN_SETTING(STM32F0_DMA1_CHAN7, 2)
#define DMACHAN_USART3_RX DMACHAN_SETTING(STM32F0_DMA1_CHAN3, 1)
#define DMACHAN_USART3_TX DMACHAN_SETTING(STM32F0_DMA1_CHAN2, 2)
#define DMACHAN_UART5_RX DMACHAN_SETTING(STM32F0_DMA2_CHAN2, 2)
#define DMACHAN_UART5_TX DMACHAN_SETTING(STM32F0_DMA2_CHAN1, 2)
#define DMACHAN_UART4_RX DMACHAN_SETTING(STM32F0_DMA2_CHAN5, 2)
#define DMACHAN_UART4_TX DMACHAN_SETTING(STM32F0_DMA2_CHAN3, 2)
#endif /* __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_DMA_H */

View File

@ -0,0 +1,131 @@
/************************************************************************************
* arch/arm/src/stm32f0/chip/stm32f0_exti.h
*
* Copyright (C) 2017 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
* Alan Carvalho de Assis <acassis@gmail.com>
*
* 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 NuttX 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 OWNER 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.
*
************************************************************************************/
#ifndef __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_EXTI_H
#define __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_EXTI_H
/************************************************************************************
* Included Files
************************************************************************************/
#include <nuttx/config.h>
#include "chip.h"
/************************************************************************************
* Pre-processor Definitions
************************************************************************************/
#define STM32F0_NEXTI 31
#define STM32F0_EXTI_MASK 0xffffffff
#define STM32F0_EXTI_BIT(n) (1 << (n))
/* Register Offsets *****************************************************************/
#define STM32F0_EXTI_IMR_OFFSET 0x0000 /* Interrupt mask register */
#define STM32F0_EXTI_EMR_OFFSET 0x0004 /* Event mask register */
#define STM32F0_EXTI_RTSR_OFFSET 0x0008 /* Rising Trigger selection register */
#define STM32F0_EXTI_FTSR_OFFSET 0x000c /* Falling Trigger selection register */
#define STM32F0_EXTI_SWIER_OFFSET 0x0010 /* Software interrupt event register */
#define STM32F0_EXTI_PR_OFFSET 0x0014 /* Pending register */
/* Register Addresses ***************************************************************/
#define STM32F0_EXTI_IMR (STM32F0_EXTI_BASE+STM32F0_EXTI_IMR_OFFSET)
#define STM32F0_EXTI_EMR (STM32F0_EXTI_BASE+STM32F0_EXTI_EMR_OFFSET)
#define STM32F0_EXTI_RTSR (STM32F0_EXTI_BASE+STM32F0_EXTI_RTSR_OFFSET)
#define STM32F0_EXTI_FTSR (STM32F0_EXTI_BASE+STM32F0_EXTI_FTSR_OFFSET)
#define STM32F0_EXTI_SWIER (STM32F0_EXTI_BASE+STM32F0_EXTI_SWIER_OFFSET)
#define STM32F0_EXTI_PR (STM32F0_EXTI_BASE+STM32F0_EXTI_PR_OFFSET)
/* Register Bitfield Definitions ****************************************************/
/* EXTI lines > 15 are associated with internal devices: */
#define EXTI_PVD_LINE (1 << 16) /* EXTI line 16 is connected to the PVD output */
#define EXTI_RTC_ALARM (1 << 17) /* EXTI line 17 is connected to the RTC Alarm event */
#define EXTI_USB_WAKEUP (1 << 18) /* EXTI line 18 is connected to the USB wake up event */
#define EXTI_RTC_TAMPER (1 << 19) /* EXTI line 19 is connected to the RTC Tamper and TimeStamp events */
#define EXTI_RTC_WAKEUP (1 << 20) /* EXTI line 20 is connected to the RTC Wakeup event */
#define EXTI_COMP1 (1 << 21) /* EXTI line 21 is connected to the COMP1 (comparator) output */
#define EXTI_COMP2 (1 << 22) /* EXTI line 22 is connected to the COMP2 (comparator) output */
#define EXTI_I2C1 (1 << 23) /* EXTI line 23 is connected to the I2C1 wakeup */
/* EXTI line 24 is reserved (internally held low) */
#define EXTI_USART1 (1 << 25) /* EXTI line 25 is connected to the USART1 wakeup */
#define EXTI_USART2 (1 << 26) /* EXTI line 26 is connected to the USART2 wakeup */
#define EXTI_CEC (1 << 27) /* EXTI line 27 is connected to the CEC wakeup */
#define EXTI_USART3 (1 << 28) /* EXTI line 28 is connected to the USART3 wakeup */
/* EXTI line 29 is reserved (internally held low) */
/* EXTI line 30 is reserved (internally held low) */
#define EXTI_VDDIO2 (1 << 31) /* EXTI line 31 is connected to the Vddio2 supply comparator */
/* Interrupt mask register */
#define EXTI_IMR_BIT(n) STM32F0_EXTI_BIT(n) /* 1=Interrupt request from line x is not masked */
#define EXTI_IMR_SHIFT (0) /* Bits 0-X: Interrupt Mask for all lines */
#define EXTI_IMR_MASK STM32F0_EXTI_MASK
/* Event mask register */
#define EXTI_EMR_BIT(n) STM32F0_EXTI_BIT(n) /* 1=Event request from line x is not mask */
#define EXTI_EMR_SHIFT (0) /* Bits Bits 0-X: Event Mask for all lines */
#define EXTI_EMR_MASK STM32F0_EXTI_MASK
/* Rising Trigger selection register */
#define EXTI_RTSR_BIT(n) STM32F0_EXTI_BIT(n) /* 1=Rising trigger enabled (for Event and Interrupt) for input line */
#define EXTI_RTSR_SHIFT (0) /* Bits 0-X: Rising trigger event configuration bit for all lines */
#define EXTI_RTSR_MASK STM32F0_EXTI_MASK
/* Falling Trigger selection register */
#define EXTI_FTSR_BIT(n) STM32F0_EXTI_BIT(n) /* 1=Falling trigger enabled (for Event and Interrupt) for input line */
#define EXTI_FTSR_SHIFT (0) /* Bits 0-X: Falling trigger event configuration bitfor all lines */
#define EXTI_FTSR_MASK STM32F0_EXTI_MASK
/* Software interrupt event register */
#define EXTI_SWIER_BIT(n) STM32F0_EXTI_BIT(n) /* 1=Sets the corresponding pending bit in EXTI_PR */
#define EXTI_SWIER_SHIFT (0) /* Bits 0-X: Software Interrupt for all lines */
#define EXTI_SWIER_MASK STM32F0_EXTI_MASK
/* Pending register */
#define EXTI_PR_BIT(n) STM32F0_EXTI_BIT(n) /* 1=Selected trigger request occurred */
#define EXTI_PR_SHIFT (0) /* Bits 0-X: Pending bit for all lines */
#define EXTI_PR_MASK STM32F0_EXTI_MASK
#endif /* __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_EXTI_H */

View File

@ -0,0 +1,333 @@
/************************************************************************************
* arch/arm/src/stm32f0/chip/stm32f0_gpio.h
*
* Copyright (C) 2017 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
* Alan Carvalho de Assis <acassis@gmail.com>
*
* 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 NuttX 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 OWNER 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.
*
************************************************************************************/
#ifndef __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_GPIO_H
#define __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_GPIO_H
/************************************************************************************
* Pre-processor Definitions
************************************************************************************/
/* Register Offsets *****************************************************************/
#define STM32F0_GPIO_MODER_OFFSET 0x0000 /* GPIO port mode register */
#define STM32F0_GPIO_OTYPER_OFFSET 0x0004 /* GPIO port output type register */
#define STM32F0_GPIO_OSPEED_OFFSET 0x0008 /* GPIO port output speed register */
#define STM32F0_GPIO_PUPDR_OFFSET 0x000c /* GPIO port pull-up/pull-down register */
#define STM32F0_GPIO_IDR_OFFSET 0x0010 /* GPIO port input data register */
#define STM32F0_GPIO_ODR_OFFSET 0x0014 /* GPIO port output data register */
#define STM32F0_GPIO_BSRR_OFFSET 0x0018 /* GPIO port bit set/reset register */
#define STM32F0_GPIO_LCKR_OFFSET 0x001c /* GPIO port configuration lock register */
#define STM32F0_GPIO_AFRL_OFFSET 0x0020 /* GPIO alternate function low register */
#define STM32F0_GPIO_AFRH_OFFSET 0x0024 /* GPIO alternate function high register */
#define STM32F0_GPIO_BRR_OFFSET 0x0028 /* GPIO port bit reset register */
/* Register Addresses ***************************************************************/
#if STM32F0_NPORTS > 0
# define STM32F0_GPIOA_MODER (STM32F0_GPIOA_BASE+STM32F0_GPIO_MODER_OFFSET)
# define STM32F0_GPIOA_OTYPER (STM32F0_GPIOA_BASE+STM32F0_GPIO_OTYPER_OFFSET)
# define STM32F0_GPIOA_OSPEED (STM32F0_GPIOA_BASE+STM32F0_GPIO_OSPEED_OFFSET)
# define STM32F0_GPIOA_PUPDR (STM32F0_GPIOA_BASE+STM32F0_GPIO_PUPDR_OFFSET)
# define STM32F0_GPIOA_IDR (STM32F0_GPIOA_BASE+STM32F0_GPIO_IDR_OFFSET)
# define STM32F0_GPIOA_ODR (STM32F0_GPIOA_BASE+STM32F0_GPIO_ODR_OFFSET)
# define STM32F0_GPIOA_BSRR (STM32F0_GPIOA_BASE+STM32F0_GPIO_BSRR_OFFSET)
# define STM32F0_GPIOA_LCKR (STM32F0_GPIOA_BASE+STM32F0_GPIO_LCKR_OFFSET)
# define STM32F0_GPIOA_AFRL (STM32F0_GPIOA_BASE+STM32F0_GPIO_AFRL_OFFSET)
# define STM32F0_GPIOA_AFRH (STM32F0_GPIOA_BASE+STM32F0_GPIO_AFRH_OFFSET)
#endif
#if STM32F0_NPORTS > 1
# define STM32F0_GPIOB_MODER (STM32F0_GPIOB_BASE+STM32F0_GPIO_MODER_OFFSET)
# define STM32F0_GPIOB_OTYPER (STM32F0_GPIOB_BASE+STM32F0_GPIO_OTYPER_OFFSET)
# define STM32F0_GPIOB_OSPEED (STM32F0_GPIOB_BASE+STM32F0_GPIO_OSPEED_OFFSET)
# define STM32F0_GPIOB_PUPDR (STM32F0_GPIOB_BASE+STM32F0_GPIO_PUPDR_OFFSET)
# define STM32F0_GPIOB_IDR (STM32F0_GPIOB_BASE+STM32F0_GPIO_IDR_OFFSET)
# define STM32F0_GPIOB_ODR (STM32F0_GPIOB_BASE+STM32F0_GPIO_ODR_OFFSET)
# define STM32F0_GPIOB_BSRR (STM32F0_GPIOB_BASE+STM32F0_GPIO_BSRR_OFFSET)
# define STM32F0_GPIOB_LCKR (STM32F0_GPIOB_BASE+STM32F0_GPIO_LCKR_OFFSET)
# define STM32F0_GPIOB_AFRL (STM32F0_GPIOB_BASE+STM32F0_GPIO_AFRL_OFFSET)
# define STM32F0_GPIOB_AFRH (STM32F0_GPIOB_BASE+STM32F0_GPIO_AFRH_OFFSET)
#endif
#if STM32F0_NPORTS > 2
# define STM32F0_GPIOC_MODER (STM32F0_GPIOC_BASE+STM32F0_GPIO_MODER_OFFSET)
# define STM32F0_GPIOC_OTYPER (STM32F0_GPIOC_BASE+STM32F0_GPIO_OTYPER_OFFSET)
# define STM32F0_GPIOC_OSPEED (STM32F0_GPIOC_BASE+STM32F0_GPIO_OSPEED_OFFSET)
# define STM32F0_GPIOC_PUPDR (STM32F0_GPIOC_BASE+STM32F0_GPIO_PUPDR_OFFSET)
# define STM32F0_GPIOC_IDR (STM32F0_GPIOC_BASE+STM32F0_GPIO_IDR_OFFSET)
# define STM32F0_GPIOC_ODR (STM32F0_GPIOC_BASE+STM32F0_GPIO_ODR_OFFSET)
# define STM32F0_GPIOC_BSRR (STM32F0_GPIOC_BASE+STM32F0_GPIO_BSRR_OFFSET)
# define STM32F0_GPIOC_LCKR (STM32F0_GPIOC_BASE+STM32F0_GPIO_LCKR_OFFSET)
# define STM32F0_GPIOC_AFRL (STM32F0_GPIOC_BASE+STM32F0_GPIO_AFRL_OFFSET)
# define STM32F0_GPIOC_AFRH (STM32F0_GPIOC_BASE+STM32F0_GPIO_AFRH_OFFSET)
#endif
#if STM32F0_NPORTS > 3
# define STM32F0_GPIOD_MODER (STM32F0_GPIOD_BASE+STM32F0_GPIO_MODER_OFFSET)
# define STM32F0_GPIOD_OTYPER (STM32F0_GPIOD_BASE+STM32F0_GPIO_OTYPER_OFFSET)
# define STM32F0_GPIOD_OSPEED (STM32F0_GPIOD_BASE+STM32F0_GPIO_OSPEED_OFFSET)
# define STM32F0_GPIOD_PUPDR (STM32F0_GPIOD_BASE+STM32F0_GPIO_PUPDR_OFFSET)
# define STM32F0_GPIOD_IDR (STM32F0_GPIOD_BASE+STM32F0_GPIO_IDR_OFFSET)
# define STM32F0_GPIOD_ODR (STM32F0_GPIOD_BASE+STM32F0_GPIO_ODR_OFFSET)
# define STM32F0_GPIOD_BSRR (STM32F0_GPIOD_BASE+STM32F0_GPIO_BSRR_OFFSET)
# define STM32F0_GPIOD_LCKR (STM32F0_GPIOD_BASE+STM32F0_GPIO_LCKR_OFFSET)
# define STM32F0_GPIOD_AFRL (STM32F0_GPIOD_BASE+STM32F0_GPIO_AFRL_OFFSET)
# define STM32F0_GPIOD_AFRH (STM32F0_GPIOD_BASE+STM32F0_GPIO_AFRH_OFFSET)
#endif
#if STM32F0_NPORTS > 4
# define STM32F0_GPIOE_MODER (STM32F0_GPIOE_BASE+STM32F0_GPIO_MODER_OFFSET)
# define STM32F0_GPIOE_OTYPER (STM32F0_GPIOE_BASE+STM32F0_GPIO_OTYPER_OFFSET)
# define STM32F0_GPIOE_OSPEED (STM32F0_GPIOE_BASE+STM32F0_GPIO_OSPEED_OFFSET)
# define STM32F0_GPIOE_PUPDR (STM32F0_GPIOE_BASE+STM32F0_GPIO_PUPDR_OFFSET)
# define STM32F0_GPIOE_IDR (STM32F0_GPIOE_BASE+STM32F0_GPIO_IDR_OFFSET)
# define STM32F0_GPIOE_ODR (STM32F0_GPIOE_BASE+STM32F0_GPIO_ODR_OFFSET)
# define STM32F0_GPIOE_BSRR (STM32F0_GPIOE_BASE+STM32F0_GPIO_BSRR_OFFSET)
# define STM32F0_GPIOE_LCKR (STM32F0_GPIOE_BASE+STM32F0_GPIO_LCKR_OFFSET)
# define STM32F0_GPIOE_AFRL (STM32F0_GPIOE_BASE+STM32F0_GPIO_AFRL_OFFSET)
# define STM32F0_GPIOE_AFRH (STM32F0_GPIOE_BASE+STM32F0_GPIO_AFRH_OFFSET)
#endif
#if STM32F0_NPORTS > 5
# define STM32F0_GPIOF_MODER (STM32F0_GPIOF_BASE+STM32F0_GPIO_MODER_OFFSET)
# define STM32F0_GPIOF_OTYPER (STM32F0_GPIOF_BASE+STM32F0_GPIO_OTYPER_OFFSET)
# define STM32F0_GPIOF_OSPEED (STM32F0_GPIOF_BASE+STM32F0_GPIO_OSPEED_OFFSET)
# define STM32F0_GPIOF_PUPDR (STM32F0_GPIOF_BASE+STM32F0_GPIO_PUPDR_OFFSET)
# define STM32F0_GPIOF_IDR (STM32F0_GPIOF_BASE+STM32F0_GPIO_IDR_OFFSET)
# define STM32F0_GPIOF_ODR (STM32F0_GPIOF_BASE+STM32F0_GPIO_ODR_OFFSET)
# define STM32F0_GPIOF_BSRR (STM32F0_GPIOF_BASE+STM32F0_GPIO_BSRR_OFFSET)
# define STM32F0_GPIOF_LCKR (STM32F0_GPIOF_BASE+STM32F0_GPIO_LCKR_OFFSET)
# define STM32F0_GPIOF_AFRL (STM32F0_GPIOF_BASE+STM32F0_GPIO_AFRL_OFFSET)
# define STM32F0_GPIOF_AFRH (STM32F0_GPIOF_BASE+STM32F0_GPIO_AFRH_OFFSET)
#endif
/* Register Bitfield Definitions ****************************************************/
/* GPIO port mode register */
#define GPIO_MODER_INPUT (0) /* Input */
#define GPIO_MODER_OUTPUT (1) /* General purpose output mode */
#define GPIO_MODER_ALT (2) /* Alternate mode */
#define GPIO_MODER_ANALOG (3) /* Analog mode */
#define GPIO_MODER_SHIFT(n) ((n) << 1)
#define GPIO_MODER_MASK(n) (3 << GPIO_MODER_SHIFT(n))
#define GPIO_MODER0_SHIFT (0)
#define GPIO_MODER0_MASK (3 << GPIO_MODER0_SHIFT)
#define GPIO_MODER1_SHIFT (2)
#define GPIO_MODER1_MASK (3 << GPIO_MODER1_SHIFT)
#define GPIO_MODER2_SHIFT (4)
#define GPIO_MODER2_MASK (3 << GPIO_MODER2_SHIFT)
#define GPIO_MODER3_SHIFT (6)
#define GPIO_MODER3_MASK (3 << GPIO_MODER3_SHIFT)
#define GPIO_MODER4_SHIFT (8)
#define GPIO_MODER4_MASK (3 << GPIO_MODER4_SHIFT)
#define GPIO_MODER5_SHIFT (10)
#define GPIO_MODER5_MASK (3 << GPIO_MODER5_SHIFT)
#define GPIO_MODER6_SHIFT (12)
#define GPIO_MODER6_MASK (3 << GPIO_MODER6_SHIFT)
#define GPIO_MODER7_SHIFT (14)
#define GPIO_MODER7_MASK (3 << GPIO_MODER7_SHIFT)
#define GPIO_MODER8_SHIFT (16)
#define GPIO_MODER8_MASK (3 << GPIO_MODER8_SHIFT)
#define GPIO_MODER9_SHIFT (18)
#define GPIO_MODER9_MASK (3 << GPIO_MODER9_SHIFT)
#define GPIO_MODER10_SHIFT (20)
#define GPIO_MODER10_MASK (3 << GPIO_MODER10_SHIFT)
#define GPIO_MODER11_SHIFT (22)
#define GPIO_MODER11_MASK (3 << GPIO_MODER11_SHIFT)
#define GPIO_MODER12_SHIFT (24)
#define GPIO_MODER12_MASK (3 << GPIO_MODER12_SHIFT)
#define GPIO_MODER13_SHIFT (26)
#define GPIO_MODER13_MASK (3 << GPIO_MODER13_SHIFT)
#define GPIO_MODER14_SHIFT (28)
#define GPIO_MODER14_MASK (3 << GPIO_MODER14_SHIFT)
#define GPIO_MODER15_SHIFT (30)
#define GPIO_MODER15_MASK (3 << GPIO_MODER15_SHIFT)
/* GPIO port output type register */
#define GPIO_OTYPER_OD(n) (1 << (n)) /* 1=Output open-drain */
#define GPIO_OTYPER_PP(n) (0) /* 0=Ouput push-pull */
/* GPIO port output speed register */
#define GPIO_OSPEED_2MHz (0) /* x0: 2 MHz Low speed */
#define GPIO_OSPEED_10MHz (1) /* 01: 10 MHz Medium speed */
#define GPIO_OSPEED_50MHz (3) /* 11: 50 MHz High speed */
#define GPIO_OSPEED_SHIFT(n) ((n) << 1)
#define GPIO_OSPEED_MASK(n) (3 << GPIO_OSPEED_SHIFT(n))
#define GPIO_OSPEED0_SHIFT (0)
#define GPIO_OSPEED0_MASK (3 << GPIO_OSPEED0_SHIFT)
#define GPIO_OSPEED1_SHIFT (2)
#define GPIO_OSPEED1_MASK (3 << GPIO_OSPEED1_SHIFT)
#define GPIO_OSPEED2_SHIFT (4)
#define GPIO_OSPEED2_MASK (3 << GPIO_OSPEED2_SHIFT)
#define GPIO_OSPEED3_SHIFT (6)
#define GPIO_OSPEED3_MASK (3 << GPIO_OSPEED3_SHIFT)
#define GPIO_OSPEED4_SHIFT (8)
#define GPIO_OSPEED4_MASK (3 << GPIO_OSPEED4_SHIFT)
#define GPIO_OSPEED5_SHIFT (10)
#define GPIO_OSPEED5_MASK (3 << GPIO_OSPEED5_SHIFT)
#define GPIO_OSPEED6_SHIFT (12)
#define GPIO_OSPEED6_MASK (3 << GPIO_OSPEED6_SHIFT)
#define GPIO_OSPEED7_SHIFT (14)
#define GPIO_OSPEED7_MASK (3 << GPIO_OSPEED7_SHIFT)
#define GPIO_OSPEED8_SHIFT (16)
#define GPIO_OSPEED8_MASK (3 << GPIO_OSPEED8_SHIFT)
#define GPIO_OSPEED9_SHIFT (18)
#define GPIO_OSPEED9_MASK (3 << GPIO_OSPEED9_SHIFT)
#define GPIO_OSPEED10_SHIFT (20)
#define GPIO_OSPEED10_MASK (3 << GPIO_OSPEED10_SHIFT)
#define GPIO_OSPEED11_SHIFT (22)
#define GPIO_OSPEED11_MASK (3 << GPIO_OSPEED11_SHIFT)
#define GPIO_OSPEED12_SHIFT (24)
#define GPIO_OSPEED12_MASK (3 << GPIO_OSPEED12_SHIFT)
#define GPIO_OSPEED13_SHIFT (26)
#define GPIO_OSPEED13_MASK (3 << GPIO_OSPEED13_SHIFT)
#define GPIO_OSPEED14_SHIFT (28)
#define GPIO_OSPEED14_MASK (3 << GPIO_OSPEED14_SHIFT)
#define GPIO_OSPEED15_SHIFT (30)
#define GPIO_OSPEED15_MASK (3 << GPIO_OSPEED15_SHIFT)
/* GPIO port pull-up/pull-down register */
#define GPIO_PUPDR_NONE (0) /* No pull-up, pull-down */
#define GPIO_PUPDR_PULLUP (1) /* Pull-up */
#define GPIO_PUPDR_PULLDOWN (2) /* Pull-down */
#define GPIO_PUPDR_SHIFT(n) ((n) << 1)
#define GPIO_PUPDR_MASK(n) (3 << GPIO_PUPDR_SHIFT(n))
#define GPIO_PUPDR0_SHIFT (0)
#define GPIO_PUPDR0_MASK (3 << GPIO_PUPDR0_SHIFT)
#define GPIO_PUPDR1_SHIFT (2)
#define GPIO_PUPDR1_MASK (3 << GPIO_PUPDR1_SHIFT)
#define GPIO_PUPDR2_SHIFT (4)
#define GPIO_PUPDR2_MASK (3 << GPIO_PUPDR2_SHIFT)
#define GPIO_PUPDR3_SHIFT (6)
#define GPIO_PUPDR3_MASK (3 << GPIO_PUPDR3_SHIFT)
#define GPIO_PUPDR4_SHIFT (8)
#define GPIO_PUPDR4_MASK (3 << GPIO_PUPDR4_SHIFT)
#define GPIO_PUPDR5_SHIFT (10)
#define GPIO_PUPDR5_MASK (3 << GPIO_PUPDR5_SHIFT)
#define GPIO_PUPDR6_SHIFT (12)
#define GPIO_PUPDR6_MASK (3 << GPIO_PUPDR6_SHIFT)
#define GPIO_PUPDR7_SHIFT (14)
#define GPIO_PUPDR7_MASK (3 << GPIO_PUPDR7_SHIFT)
#define GPIO_PUPDR8_SHIFT (16)
#define GPIO_PUPDR8_MASK (3 << GPIO_PUPDR8_SHIFT)
#define GPIO_PUPDR9_SHIFT (18)
#define GPIO_PUPDR9_MASK (3 << GPIO_PUPDR9_SHIFT)
#define GPIO_PUPDR10_SHIFT (20)
#define GPIO_PUPDR10_MASK (3 << GPIO_PUPDR10_SHIFT)
#define GPIO_PUPDR11_SHIFT (22)
#define GPIO_PUPDR11_MASK (3 << GPIO_PUPDR11_SHIFT)
#define GPIO_PUPDR12_SHIFT (24)
#define GPIO_PUPDR12_MASK (3 << GPIO_PUPDR12_SHIFT)
#define GPIO_PUPDR13_SHIFT (26)
#define GPIO_PUPDR13_MASK (3 << GPIO_PUPDR13_SHIFT)
#define GPIO_PUPDR14_SHIFT (28)
#define GPIO_PUPDR14_MASK (3 << GPIO_PUPDR14_SHIFT)
#define GPIO_PUPDR15_SHIFT (30)
#define GPIO_PUPDR15_MASK (3 << GPIO_PUPDR15_SHIFT)
/* GPIO port input data register */
#define GPIO_IDR(n) (1 << (n))
/* GPIO port output data register */
#define GPIO_ODR(n) (1 << (n))
/* GPIO port bit set/reset register */
#define GPIO_BSRR_SET(n) (1 << (n))
#define GPIO_BSRR_RESET(n) (1 << ((n)+16))
/* GPIO port configuration lock register */
#define GPIO_LCKR(n) (1 << (n))
#define GPIO_LCKK (1 << 16) /* Lock key */
/* GPIO alternate function low/high register */
#define GPIO_AFR_SHIFT(n) ((n) << 2)
#define GPIO_AFR_MASK(n) (15 << GPIO_AFR_SHIFT(n))
#define GPIO_AFRL0_SHIFT (0)
#define GPIO_AFRL0_MASK (15 << GPIO_AFRL0_SHIFT)
#define GPIO_AFRL1_SHIFT (4)
#define GPIO_AFRL1_MASK (15 << GPIO_AFRL1_SHIFT)
#define GPIO_AFRL2_SHIFT (8)
#define GPIO_AFRL2_MASK (15 << GPIO_AFRL2_SHIFT)
#define GPIO_AFRL3_SHIFT (12)
#define GPIO_AFRL3_MASK (15 << GPIO_AFRL3_SHIFT)
#define GPIO_AFRL4_SHIFT (16)
#define GPIO_AFRL4_MASK (15 << GPIO_AFRL4_SHIFT)
#define GPIO_AFRL5_SHIFT (20)
#define GPIO_AFRL5_MASK (15 << GPIO_AFRL5_SHIFT)
#define GPIO_AFRL6_SHIFT (24)
#define GPIO_AFRL6_MASK (15 << GPIO_AFRL6_SHIFT)
#define GPIO_AFRL7_SHIFT (28)
#define GPIO_AFRL7_MASK (15 << GPIO_AFRL7_SHIFT)
#define GPIO_AFRH8_SHIFT (0)
#define GPIO_AFRH8_MASK (15 << GPIO_AFRH8_SHIFT)
#define GPIO_AFRH9_SHIFT (4)
#define GPIO_AFRH9_MASK (15 << GPIO_AFRH9_SHIFT)
#define GPIO_AFRH10_SHIFT (8)
#define GPIO_AFRH10_MASK (15 << GPIO_AFRH10_SHIFT)
#define GPIO_AFRH11_SHIFT (12)
#define GPIO_AFRH11_MASK (15 << GPIO_AFRH11_SHIFT)
#define GPIO_AFRH12_SHIFT (16)
#define GPIO_AFRH12_MASK (15 << GPIO_AFRH12_SHIFT)
#define GPIO_AFRH13_SHIFT (20)
#define GPIO_AFRH13_MASK (15 << GPIO_AFRH13_SHIFT)
#define GPIO_AFRH14_SHIFT (24)
#define GPIO_AFRH14_MASK (15 << GPIO_AFRH14_SHIFT)
#define GPIO_AFRH15_SHIFT (28)
#define GPIO_AFRH15_MASK (15 << GPIO_AFRH15_SHIFT)
/* GPIO port bit reset register */
#define GPIO_BRR(n) (1 << (n))
#endif /* __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_GPIO_H */

View File

@ -0,0 +1,238 @@
/************************************************************************************
* arch/arm/src/stm32f0/chip/stm32f0_i2c.h
*
* Copyright (C) 2017 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
* Alan Carvalho de Assis <acassis@gmail.com>
*
* 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 NuttX 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 OWNER 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.
*
************************************************************************************/
#ifndef __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_I2C_H
#define __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_I2C_H
/************************************************************************************
* Pre-processor Definitions
************************************************************************************/
/* Register Offsets *****************************************************************/
#define STM32F0_I2C_CR1_OFFSET 0x0000 /* Control register 1 (32-bit) */
#define STM32F0_I2C_CR2_OFFSET 0x0004 /* Control register 2 (32-bit) */
#define STM32F0_I2C_OAR1_OFFSET 0x0008 /* Own address register 1 (16-bit) */
#define STM32F0_I2C_OAR2_OFFSET 0x000c /* Own address register 2 (16-bit) */
#define STM32F0_I2C_TIMINGR_OFFSET 0x0010 /* Timing register */
#define STM32F0_I2C_TIMEOUTR_OFFSET 0x0014 /* Timeout register */
#define STM32F0_I2C_ISR_OFFSET 0x0018 /* Interrupt and Status register */
#define STM32F0_I2C_ICR_OFFSET 0x001c /* Interrupt clear register */
#define STM32F0_I2C_PECR_OFFSET 0x0020 /* Packet error checking register */
#define STM32F0_I2C_RXDR_OFFSET 0x0024 /* Receive data register */
#define STM32F0_I2C_TXDR_OFFSET 0x0028 /* Transmit data register */
/* Register Addresses ***************************************************************/
#if STM32F0_NI2C > 0
# define STM32F0_I2C1_CR1 (STM32F0_I2C1_BASE+STM32F0_I2C_CR1_OFFSET)
# define STM32F0_I2C1_CR2 (STM32F0_I2C1_BASE+STM32F0_I2C_CR2_OFFSET)
# define STM32F0_I2C1_OAR1 (STM32F0_I2C1_BASE+STM32F0_I2C_OAR1_OFFSET)
# define STM32F0_I2C1_OAR2 (STM32F0_I2C1_BASE+STM32F0_I2C_OAR2_OFFSET)
# define STM32F0_I2C1_TIMINGR (STM32F0_I2C1_BASE+STM32F0_I2C_TIMINGR_OFFSET)
# define STM32F0_I2C1_TIMEOUTR (STM32F0_I2C1_BASE+STM32F0_I2C_TIMEOUTR_OFFSET)
# define STM32F0_I2C1_ISR (STM32F0_I2C1_BASE+STM32F0_I2C_ISR_OFFSET)
# define STM32F0_I2C1_ICR (STM32F0_I2C1_BASE+STM32F0_I2C_ICR_OFFSET)
# define STM32F0_I2C1_PECR (STM32F0_I2C1_BASE+STM32F0_I2C_PECR_OFFSET)
# define STM32F0_I2C1_RXDR (STM32F0_I2C1_BASE+STM32F0_I2C_RXDR_OFFSET)
# define STM32F0_I2C1_TXDR (STM32F0_I2C1_BASE+STM32F0_I2C_TXDR_OFFSET)
#endif
#if STM32F0_NI2C > 1
# define STM32F0_I2C2_CR1 (STM32F0_I2C2_BASE+STM32F0_I2C_CR1_OFFSET)
# define STM32F0_I2C2_CR2 (STM32F0_I2C2_BASE+STM32F0_I2C_CR2_OFFSET)
# define STM32F0_I2C2_OAR1 (STM32F0_I2C2_BASE+STM32F0_I2C_OAR1_OFFSET)
# define STM32F0_I2C2_OAR2 (STM32F0_I2C2_BASE+STM32F0_I2C_OAR2_OFFSET)
# define STM32F0_I2C2_TIMINGR (STM32F0_I2C2_BASE+STM32F0_I2C_TIMINGR_OFFSET)
# define STM32F0_I2C2_TIMEOUTR (STM32F0_I2C2_BASE+STM32F0_I2C_TIMEOUTR_OFFSET)
# define STM32F0_I2C2_ISR (STM32F0_I2C2_BASE+STM32F0_I2C_ISR_OFFSET)
# define STM32F0_I2C2_ICR (STM32F0_I2C2_BASE+STM32F0_I2C_ICR_OFFSET)
# define STM32F0_I2C2_PECR (STM32F0_I2C2_BASE+STM32F0_I2C_PECR_OFFSET)
# define STM32F0_I2C2_RXDR (STM32F0_I2C2_BASE+STM32F0_I2C_RXDR_OFFSET)
# define STM32F0_I2C2_TXDR (STM32F0_I2C2_BASE+STM32F0_I2C_TXDR_OFFSET)
#endif
/* Register Bitfield Definitions ****************************************************/
/* Control register 1 */
#define I2C_CR1_PE (1 << 0) /* Bit 0: Peripheral Enable */
#define I2C_CR1_TXIE (1 << 1) /* Bit 1: TX Interrupt enable */
#define I2C_CR1_RXIE (1 << 2) /* Bit 2: RX Interrupt enable */
#define I2C_CR1_ADDRIE (1 << 3) /* Bit 3: Address match interrupt enable (slave) */
#define I2C_CR1_NACKIE (1 << 4) /* Bit 4: Not acknowledge received interrupt enable */
#define I2C_CR1_STOPIE (1 << 5) /* Bit 5: STOP detection interrupt enable */
#define I2C_CR1_TCIE (1 << 6) /* Bit 6: Transfer Complete interrupt enable */
#define I2C_CR1_ERRIE (1 << 7) /* Bit 7: Error interrupts enable */
#define I2C_CR1_DNF_SHIFT (8) /* Bits 8-11: Digital noise filter */
#define I2C_CR1_DNF_MASK (15 << I2C_CR1_DNF_SHIFT)
# define I2C_CR1_DNF_DISABLE (0 << I2C_CR1_DNF_SHIFT)
# define I2C_CR1_DNF(n) ((n) << I2C_CR1_DNF_SHIFT) /* Up to n * Ti2cclk, n=1..15 */
#define I2C_CR1_ANFOFF (1 << 12) /* Bit 12: Analog noise filter OFF */
#define I2C_CR1_TXDMAEN (1 << 14) /* Bit 14: DMA transmission requests enable */
#define I2C_CR1_RXDMAEN (1 << 15) /* Bit 15: DMA reception requests enable */
#define I2C_CR1_SBC (1 << 16) /* Bit 16: Slave byte control */
#define I2C_CR1_NOSTRETCH (1 << 17) /* Bit 17: Clock stretching disable */
#define I2C_CR1_WUPEN (1 << 18) /* Bit 18: Wakeup from STOP enable */
#define I2C_CR1_GCEN (1 << 19) /* Bit 19: General call enable */
#define I2C_CR1_SMBHEN (1 << 20) /* Bit 20: SMBus Host address enable */
#define I2C_CR1_SMBDEN (1 << 21) /* Bit 21: SMBus Device Default address enable */
#define I2C_CR1_ALERTEN (1 << 22) /* Bit 22: SMBus alert enable */
#define I2C_CR1_PECEN (1 << 23) /* Bit 23: PEC enable */
/* Control register 2 */
#define I2C_CR2_SADD10_SHIFT (0) /* Bits 0-9: Slave 10-bit address (master) */
#define I2C_CR2_SADD10_MASK (0x3ff << I2C_CR2_SADD10_SHIFT)
#define I2C_CR2_SADD7_SHIFT (1) /* Bits 1-7: Slave 7-bit address (master) */
#define I2C_CR2_SADD7_MASK (0x7f << I2C_CR2_SADD7_SHIFT)
#define I2C_CR2_RD_WRN (1 << 10) /* Bit 10: Transfer direction (master) */
#define I2C_CR2_ADD10 (1 << 11) /* Bit 11: 10-bit addressing mode (master) */
#define I2C_CR2_HEAD10R (1 << 12) /* Bit 12: 10-bit address header only read direction (master) */
#define I2C_CR2_START (1 << 13) /* Bit 13: Start generation */
#define I2C_CR2_STOP (1 << 14) /* Bit 14: Stop generation (master) */
#define I2C_CR2_NACK (1 << 15) /* Bit 15: NACK generation (slave) */
#define I2C_CR2_NBYTES_SHIFT (16) /* Bits 16-23: Number of bytes */
#define I2C_CR2_NBYTES_MASK (0xff << I2C_CR2_NBYTES_SHIFT)
#define I2C_CR2_RELOAD (1 << 24) /* Bit 24: NBYTES reload mode */
#define I2C_CR2_AUTOEND (1 << 25) /* Bit 25: Automatic end mode (master) */
#define I2C_CR2_PECBYTE (1 << 26) /* Bit 26: Packet error checking byte */
/* Own address register 1 */
#define I2C_OAR1_OA1_10_SHIFT (0) /* Bits 0-9: 10-bit interface address */
#define I2C_OAR1_OA1_10_MASK (0x3ff << I2C_OAR1_OA1_10_SHIFT)
#define I2C_OAR1_OA1_7_SHIFT (1) /* Bits 1-7: 7-bit interface address */
#define I2C_OAR1_OA1_7_MASK (0x7f << I2C_OAR1_OA1_7_SHIFT)
#define I2C_OAR1_OA1MODE (1 << 10) /* Bit 10: Own Address 1 10-bit mode */
#define I2C_OAR1_OA1EN (1 << 15) /* Bit 15: Own Address 1 enable */
/* Own address register 2 */
#define I2C_OAR2_OA2_SHIFT (1) /* Bits 1-7: 7-bit interface address */
#define I2C_OAR2_OA2_MASK (0x7f << I2C_OAR2_OA2_SHIFT)
#define I2C_OAR2_OA2MSK_SHIFT (8) /* Bits 8-10: Own Address 2 masks */
#define I2C_OAR2_OA2MSK_MASK (7 << I2C_OAR2_OA2MSK_SHIFT)
# define I2C_OAR2_OA2MSK_NONE (0 << I2C_OAR2_OA2MSK_SHIFT) /* No mask */
# define I2C_OAR2_OA2MSK_2_7 (1 << I2C_OAR2_OA2MSK_SHIFT) /* Only OA2[7:2] are compared */
# define I2C_OAR2_OA2MSK_3_7 (2 << I2C_OAR2_OA2MSK_SHIFT) /* Only OA2[7:3] are compared */
# define I2C_OAR2_OA2MSK_4_7 (3 << I2C_OAR2_OA2MSK_SHIFT) /* Only OA2[7:4] are compared */
# define I2C_OAR2_OA2MSK_5_7 (4 << I2C_OAR2_OA2MSK_SHIFT) /* Only OA2[7:5] are compared */
# define I2C_OAR2_OA2MSK_6_7 (5 << I2C_OAR2_OA2MSK_SHIFT) /* Only OA2[7:6] are compared */
# define I2C_OAR2_OA2MSK_7 (6 << I2C_OAR2_OA2MSK_SHIFT) /* Only OA2[7] is compared */
# define I2C_OAR2_OA2MSK_ALL (7 << I2C_OAR2_OA2MSK_SHIFT) /* All 7-bit addresses acknowledged */
#define I2C_OAR2_OA2EN (1 << 15) /* Bit 15: Own Address 2 enable */
/* Timing register */
#define I2C_TIMINGR_SCLL_SHIFT (0) /* Bits 0-7: SCL low period (master) */
#define I2C_TIMINGR_SCLL_MASK (0xff << I2C_TIMINGR_SCLL_SHIFT)
# define I2C_TIMINGR_SCLL(n) (((n)-1) << I2C_TIMINGR_SCLL_SHIFT) /* tSCLL = n x tPRESC */
#define I2C_TIMINGR_SCLH_SHIFT (8) /* Bits 8-15: SCL high period (master) */
#define I2C_TIMINGR_SCLH_MASK (0xff << I2C_TIMINGR_SCLH_SHIFT)
# define I2C_TIMINGR_SCLH(n) (((n)-1) << I2C_TIMINGR_SCLH_SHIFT) /* tSCLH = n x tPRESC */
#define I2C_TIMINGR_SDADEL_SHIFT (16) /* Bits 16-19: Data hold time */
#define I2C_TIMINGR_SDADEL_MASK (15 << I2C_TIMINGR_SDADEL_SHIFT)
# define I2C_TIMINGR_SDADEL(n) ((n) << I2C_TIMINGR_SDADEL_SHIFT) /* tSDADEL= n x tPRESC */
#define I2C_TIMINGR_SCLDEL_SHIFT (20) /* Bits 20-23: Data setup time */
#define I2C_TIMINGR_SCLDEL_MASK (15 << I2C_TIMINGR_SCLDEL_SHIFT)
# define I2C_TIMINGR_SCLDEL(n) (((n)-1) << I2C_TIMINGR_SCLDEL_SHIFT) /* tSCLDEL = n x tPRESC */
#define I2C_TIMINGR_PRESC_SHIFT (28) /* Bits 28-31: Timing prescaler */
#define I2C_TIMINGR_PRESC_MASK (15 << I2C_TIMINGR_PRESC_SHIFT)
# define I2C_TIMINGR_PRESC(n) (((n)-1) << I2C_TIMINGR_PRESC_SHIFT) /* tPRESC = n x tI2CCLK */
/* Timeout register */
#define I2C_TIMEOUTR_A_SHIFT (0) /* Bits 0-11: Bus Timeout A */
#define I2C_TIMEOUTR_A_MASK (0x0fff << I2C_TIMEOUTR_A_SHIFT)
# define I2C_TIMEOUTR_A(n) ((n) << I2C_TIMEOUTR_A_SHIFT)
#define I2C_TIMEOUTR_TIDLE (1 << 12) /* Bit 12: Idle clock timeout detection */
#define I2C_TIMEOUTR_TIMOUTEN (1 << 15) /* Bit 15: Clock timeout enable */
#define I2C_TIMEOUTR_B_SHIFT (16) /* Bits 16-27: Bus Timeout B */
#define I2C_TIMEOUTR_B_MASK (0x0fff << I2C_TIMEOUTR_B_SHIFT)
# define I2C_TIMEOUTR_B(n) ((n) << I2C_TIMEOUTR_B_SHIFT)
#define I2C_TIMEOUTR_TEXTEN (1 << 31) /* Bits 31: Extended clock timeout enable */
/* Interrupt and Status register and interrupt clear register */
/* Common interrupt bits */
#define I2C_INT_ADDR (1 << 3) /* Bit 3: Address matched (slave) */
#define I2C_INT_NACK (1 << 4) /* Bit 4: Not Acknowledge received flag */
#define I2C_INT_STOP (1 << 5) /* Bit 5: Stop detection flag */
#define I2C_INT_BERR (1 << 8) /* Bit 8: Bus error */
#define I2C_INT_ARLO (1 << 9) /* Bit 9: Arbitration lost */
#define I2C_INT_OVR (1 << 10) /* Bit 10: Overrun/Underrun (slave) */
#define I2C_INT_PECERR (1 << 11) /* Bit 11: PEC Error in reception */
#define I2C_INT_TIMEOUT (1 << 12) /* Bit 12: Timeout or tLOW detection flag */
#define I2C_INT_ALERT (1 << 13) /* Bit 13: SMBus alert */
/* Fields unique to the Interrupt and Status register */
#define I2C_ISR_TXE (1 << 0) /* Bit 0: Transmit data register empty (transmitters) */
#define I2C_ISR_TXIS (1 << 1) /* Bit 1: Transmit interrupt status (transmitters) */
#define I2C_ISR_RXNE (1 << 2) /* Bit 2: Receive data register not empty (receivers) */
#define I2C_ISR_ADDR (1 << 3) /* Bit 3: Address Match (slave mode) */
#define I2C_ISR_NACKF (1 << 4) /* Bit 4: Not Acknowledge received flag */
#define I2C_ISR_STOPF (1 << 5) /* Bit 5: Stop detection flag */
#define I2C_ISR_TC (1 << 6) /* Bit 6: Transfer Complete (master) */
#define I2C_ISR_TCR (1 << 7) /* Bit 7: Transfer Complete Reload */
#define I2C_ISR_BUSY (1 << 15) /* Bit 15: Bus busy */
#define I2C_ISR_DIR (1 << 16) /* Bit 16: Transfer direction (slave) */
#define I2C_ISR_ADDCODE_SHIFT (17) /* Bits 17-23: Address match code (slave) */
#define I2C_ISR_ADDCODE_MASK (0x7f << I2C_ISR_ADDCODE_SHIFT)
#define I2C_ISR_ERRORMASK (I2C_INT_BERR | I2C_INT_ARLO | I2C_INT_OVR | I2C_INT_PECERR | I2C_INT_TIMEOUT)
#define I2C_ICR_CLEARMASK (I2C_INT_ADDR | I2C_INT_NACK | I2C_INT_STOP | I2C_INT_BERR | I2C_INT_ARLO \
| I2C_INT_OVR | I2C_INT_PECERR | I2C_INT_TIMEOUT | I2C_INT_ALERT)
/* Packet error checking register */
#define I2C_PECR_MASK (0xff)
/* Receive data register */
#define I2C_RXDR_MASK (0xff)
/* Transmit data register */
#define I2C_TXDR_MASK (0xff)
#endif /* __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_I2C_H */

View File

@ -0,0 +1,53 @@
/************************************************************************************
* arch/arm/src/stm32f0/chip/stm32f0_memorymap.h
*
* Copyright (C) 2017 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
* Alan Carvalho de Assis <acassis@gmail.com>
*
* 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 NuttX 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 OWNER 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.
*
************************************************************************************/
#ifndef __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_MEMORYMAP_H
#define __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_MEMORYMAP_H
/************************************************************************************
* Included Files
************************************************************************************/
#include <nuttx/config.h>
#include "chip.h"
#if defined(CONFIG_STM32F0_STM32F05X)
# include "chip/stm32f05xxx_memorymap.h"
#else
# error "Unsupported STM32 memory map"
#endif
#endif /* __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_MEMORYMAP_H */

View File

@ -0,0 +1,98 @@
/************************************************************************************
* arch/arm/src/stm32f0/chip/stm32f0_pwr.h
*
* Copyright (C) 2017 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
* Alan Carvalho de Assis <acassis@gmail.com>
*
* 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 NuttX 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 OWNER 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.
*
************************************************************************************/
#ifndef __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_PWR_H
#define __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_PWR_H
/************************************************************************************
* Included Files
************************************************************************************/
#include <nuttx/config.h>
#include "chip.h"
/************************************************************************************
* Pre-processor Definitions
************************************************************************************/
/* Register Offsets *****************************************************************/
#define STM32F0_PWR_CR_OFFSET 0x0000 /* Power control register */
#define STM32F0_PWR_CSR_OFFSET 0x0004 /* Power control/status register */
/* Register Addresses ***************************************************************/
#define STM32F0_PWR_CR (STM32F0_PWR_BASE+STM32F0_PWR_CR_OFFSET)
#define STM32F0_PWR_CSR (STM32F0_PWR_BASE+STM32F0_PWR_CSR_OFFSET)
/* Register Bitfield Definitions ****************************************************/
/* Power control register */
#define PWR_CR_LPDS (1 << 0) /* Bit 0: Low-Power Deepsleep/sleep; low power run */
#define PWR_CR_PDDS (1 << 1) /* Bit 1: Power Down Deepsleep */
#define PWR_CR_CWUF (1 << 2) /* Bit 2: Clear Wakeup Flag */
#define PWR_CR_CSBF (1 << 3) /* Bit 3: Clear Standby Flag */
#define PWR_CR_PVDE (1 << 4) /* Bit 4: Power Voltage Detector Enable */
#define PWR_CR_PLS_SHIFT (5) /* Bits 7-5: PVD Level Selection */
#define PWR_CR_PLS_MASK (7 << PWR_CR_PLS_SHIFT)
# define PWR_CR_2p2V (0 << PWR_CR_PLS_SHIFT) /* 000: 2.2V */
# define PWR_CR_2p3V (1 << PWR_CR_PLS_SHIFT) /* 001: 2.3V */
# define PWR_CR_2p4V (2 << PWR_CR_PLS_SHIFT) /* 010: 2.4V */
# define PWR_CR_2p5V (3 << PWR_CR_PLS_SHIFT) /* 011: 2.5V */
# define PWR_CR_2p6V (4 << PWR_CR_PLS_SHIFT) /* 100: 2.6V */
# define PWR_CR_2p7V (5 << PWR_CR_PLS_SHIFT) /* 101: 2.7V */
# define PWR_CR_2p8V (6 << PWR_CR_PLS_SHIFT) /* 110: 2.8V */
# define PWR_CR_2p9V (7 << PWR_CR_PLS_SHIFT) /* 111: 2.9V */
#define PWR_CR_DBP (1 << 8) /* Bit 8: Disable Backup Domain write protection */
/* Power control/status register */
#define PWR_CSR_WUF (1 << 0) /* Bit 0: Wakeup Flag */
#define PWR_CSR_SBF (1 << 1) /* Bit 1: Standby Flag */
#define PWR_CSR_PVDO (1 << 2) /* Bit 2: PVD Output */
#define PWR_CSR_VREFINTRDY (1 << 3) /* Bit 3: Internal voltage reference (VREFINT) ready flag */
#define PWR_CSR_EWUP1 (1 << 8) /* Bit 8: Enable WKUP1 pin */
#define PWR_CSR_EWUP2 (1 << 9) /* Bit 9: Enable WKUP2 pin */
#define PWR_CSR_EWUP3 (1 << 10) /* Bit 10: Enable WKUP3 pin */
#define PWR_CSR_EWUP4 (1 << 11) /* Bit 11: Enable WKUP4 pin */
#define PWR_CSR_EWUP5 (1 << 12) /* Bit 12: Enable WKUP5 pin */
#define PWR_CSR_EWUP6 (1 << 13) /* Bit 13: Enable WKUP6 pin */
#define PWR_CSR_EWUP7 (1 << 14) /* Bit 14: Enable WKUP7 pin */
#define PWR_CSR_EWUP8 (1 << 15) /* Bit 15: Enable WKUP8 pin */
#endif /* __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_PWR_H */

View File

@ -0,0 +1,348 @@
/************************************************************************************
* arch/arm/src/stm32f0/chip/stm32f0_rcc.h
*
* Copyright (C) 2017 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
* Alan Carvalho de Assis <acassis@gmail.com>
*
* 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 NuttX 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 OWNER 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.
*
************************************************************************************/
#ifndef __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_RCC_H
#define __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_RCC_H
/************************************************************************************
* Pre-processor Definitions
************************************************************************************/
/* Register Offsets *****************************************************************/
#define STM32F0_RCC_CR_OFFSET 0x0000 /* Clock control register */
#define STM32F0_RCC_CFGR_OFFSET 0x0004 /* Clock configuration register */
#define STM32F0_RCC_CIR_OFFSET 0x0008 /* Clock interrupt register */
#define STM32F0_RCC_APB2RSTR_OFFSET 0x000c /* APB2 Peripheral reset register */
#define STM32F0_RCC_APB1RSTR_OFFSET 0x0010 /* APB1 Peripheral reset register */
#define STM32F0_RCC_AHBENR_OFFSET 0x0014 /* AHB Peripheral Clock enable register */
#define STM32F0_RCC_APB2ENR_OFFSET 0x0018 /* APB2 Peripheral Clock enable register */
#define STM32F0_RCC_APB1ENR_OFFSET 0x001c /* APB1 Peripheral Clock enable register */
#define STM32F0_RCC_BDCR_OFFSET 0x0020 /* Backup domain control register */
#define STM32F0_RCC_CSR_OFFSET 0x0024 /* Control/status register */
#define STM32F0_RCC_AHBRSTR_OFFSET 0x0028 /* AHB Reset register */
#define STM32F0_RCC_CFGR2_OFFSET 0x002c /* Clock configuration register 2 */
/* Register Addresses ***************************************************************/
#define STM32F0_RCC_CR (STM32F0_RCC_BASE+STM32F0_RCC_CR_OFFSET)
#define STM32F0_RCC_CFGR (STM32F0_RCC_BASE+STM32F0_RCC_CFGR_OFFSET)
#define STM32F0_RCC_CIR (STM32F0_RCC_BASE+STM32F0_RCC_CIR_OFFSET)
#define STM32F0_RCC_APB2RSTR (STM32F0_RCC_BASE+STM32F0_RCC_APB2RSTR_OFFSET)
#define STM32F0_RCC_APB1RSTR (STM32F0_RCC_BASE+STM32F0_RCC_APB1RSTR_OFFSET)
#define STM32F0_RCC_AHBENR (STM32F0_RCC_BASE+STM32F0_RCC_AHBENR_OFFSET)
#define STM32F0_RCC_APB2ENR (STM32F0_RCC_BASE+STM32F0_RCC_APB2ENR_OFFSET)
#define STM32F0_RCC_APB1ENR (STM32F0_RCC_BASE+STM32F0_RCC_APB1ENR_OFFSET)
#define STM32F0_RCC_BDCR (STM32F0_RCC_BASE+STM32F0_RCC_BDCR_OFFSET)
#define STM32F0_RCC_CSR (STM32F0_RCC_BASE+STM32F0_RCC_CSR_OFFSET)
#define STM32F0_RCC_AHBRSTR (STM32F0_RCC_BASE+STM32F0_RCC_AHBRSTR_OFFSET)
#define STM32F0_RCC_CFGR2 (STM32F0_RCC_BASE+STM32F0_RCC_CFGR2_OFFSET)
/* Register Bitfield Definitions ****************************************************/
/* Clock control register */
#define RCC_CR_HSION (1 << 0) /* Bit 0: Internal High Speed clock enable */
#define RCC_CR_HSIRDY (1 << 1) /* Bit 1: Internal High Speed clock ready flag */
#define RCC_CR_HSITRIM_SHIFT (3) /* Bits 7-3: Internal High Speed clock trimming */
#define RCC_CR_HSITRIM_MASK (0x1f << RCC_CR_HSITRIM_SHIFT)
#define RCC_CR_HSICAL_SHIFT (8) /* Bits 15-8: Internal High Speed clock Calibration */
#define RCC_CR_HSICAL_MASK (0xff << RCC_CR_HSICAL_SHIFT)
#define RCC_CR_HSEON (1 << 16) /* Bit 16: External High Speed clock enable */
#define RCC_CR_HSERDY (1 << 17) /* Bit 17: External High Speed clock ready flag */
#define RCC_CR_HSEBYP (1 << 18) /* Bit 18: External High Speed clock Bypass */
#define RCC_CR_CSSON (1 << 19) /* Bit 19: Clock Security System enable */
#define RCC_CR_PLLON (1 << 24) /* Bit 24: PLL enable */
#define RCC_CR_PLLRDY (1 << 25) /* Bit 25: PLL clock ready flag */
/* Clock configuration register */
#define RCC_CFGR_SW_SHIFT (0) /* Bits 1-0: System clock Switch */
#define RCC_CFGR_SW_MASK (3 << RCC_CFGR_SW_SHIFT)
# define RCC_CFGR_SW_HSI (0 << RCC_CFGR_SW_SHIFT) /* 00: HSI selected as system clock */
# define RCC_CFGR_SW_HSE (1 << RCC_CFGR_SW_SHIFT) /* 01: HSE selected as system clock */
# define RCC_CFGR_SW_PLL (2 << RCC_CFGR_SW_SHIFT) /* 10: PLL selected as system clock */
# define RCC_CFGR_SW_HSI48 (3 << RCC_CFGR_SW_SHIFT) /* 11: HSI48 selected as system clock */
#define RCC_CFGR_SWS_SHIFT (2) /* Bits 3-2: System Clock Switch Status */
#define RCC_CFGR_SWS_MASK (3 << RCC_CFGR_SWS_SHIFT)
# define RCC_CFGR_SWS_HSI (0 << RCC_CFGR_SWS_SHIFT) /* 00: HSI oscillator used as system clock */
# define RCC_CFGR_SWS_HSE (1 << RCC_CFGR_SWS_SHIFT) /* 01: HSE oscillator used as system clock */
# define RCC_CFGR_SWS_PLL (2 << RCC_CFGR_SWS_SHIFT) /* 10: PLL used as system clock */
# define RCC_CFGR_SWS_HSI48 (3 << RCC_CFGR_SWS_SHIFT) /* 11: HSI48 used as system clock */
#define RCC_CFGR_HPRE_SHIFT (4) /* Bits 7-4: AHB prescaler */
#define RCC_CFGR_HPRE_MASK (0x0f << RCC_CFGR_HPRE_SHIFT)
# define RCC_CFGR_HPRE_SYSCLK (0 << RCC_CFGR_HPRE_SHIFT) /* 0xxx: SYSCLK not divided */
# define RCC_CFGR_HPRE_SYSCLKd2 (8 << RCC_CFGR_HPRE_SHIFT) /* 1000: SYSCLK divided by 2 */
# define RCC_CFGR_HPRE_SYSCLKd4 (9 << RCC_CFGR_HPRE_SHIFT) /* 1001: SYSCLK divided by 4 */
# define RCC_CFGR_HPRE_SYSCLKd8 (10 << RCC_CFGR_HPRE_SHIFT) /* 1010: SYSCLK divided by 8 */
# define RCC_CFGR_HPRE_SYSCLKd16 (11 << RCC_CFGR_HPRE_SHIFT) /* 1011: SYSCLK divided by 16 */
# define RCC_CFGR_HPRE_SYSCLKd64 (12 << RCC_CFGR_HPRE_SHIFT) /* 1100: SYSCLK divided by 64 */
# define RCC_CFGR_HPRE_SYSCLKd128 (13 << RCC_CFGR_HPRE_SHIFT) /* 1101: SYSCLK divided by 128 */
# define RCC_CFGR_HPRE_SYSCLKd256 (14 << RCC_CFGR_HPRE_SHIFT) /* 1110: SYSCLK divided by 256 */
# define RCC_CFGR_HPRE_SYSCLKd512 (15 << RCC_CFGR_HPRE_SHIFT) /* 1111: SYSCLK divided by 512 */
#define RCC_CFGR_PPRE1_SHIFT (8) /* Bits 10-8: APB Low speed prescaler (APB1) */
#define RCC_CFGR_PPRE1_MASK (7 << RCC_CFGR_PPRE1_SHIFT)
# define RCC_CFGR_PPRE1_HCLK (0 << RCC_CFGR_PPRE1_SHIFT) /* 0xx: HCLK not divided */
# define RCC_CFGR_PPRE1_HCLKd2 (4 << RCC_CFGR_PPRE1_SHIFT) /* 100: HCLK divided by 2 */
# define RCC_CFGR_PPRE1_HCLKd4 (5 << RCC_CFGR_PPRE1_SHIFT) /* 101: HCLK divided by 4 */
# define RCC_CFGR_PPRE1_HCLKd8 (6 << RCC_CFGR_PPRE1_SHIFT) /* 110: HCLK divided by 8 */
# define RCC_CFGR_PPRE1_HCLKd16 (7 << RCC_CFGR_PPRE1_SHIFT) /* 111: HCLK divided by 16 */
/* Bits 13-11: Reserve. Keep the reset value */
#define RCC_CFGR_ADCPRE (1 << 14) /* Bit 14: ADC prescaler, Obsolete use ADC_CFGR2 */
#define RCC_CFGR_PLLSRC_SHIFT (15) /* Bit 15: PLL input clock source */
#define RCC_CFGR_PLLSRC_MASK (3 << RCC_CFGR_PLLSRC_SHIFT)
# define RCC_CFGR_PLLSRC_HSId2 (0 << RCC_CFGR_PLLSRC_SHIFT) /* 00: HSI/2 as PLL input clock */
# define RCC_CFGR_PLLSRC_HS1_PREDIV (1 << RCC_CFGR_PLLSRC_SHIFT) /* 01: HSE/PREDIV as PLL input clock */
# define RCC_CFGR_PLLSRC_HSE_PREDIV (2 << RCC_CFGR_PLLSRC_SHIFT) /* 10: HSE/PREDIV as PLL input clock */
# define RCC_CFGR_PLLSRC_HSI48_PREDIV (3 << RCC_CFGR_PLLSRC_SHIFT) /* 11: HSI48/PREDIV as PLL input clock */
#define RCC_CFGR_PLLXTPRE (1 << 17) /* Bit 17: HSE divider for PLL entry */
#define RCC_CFGR_PLLMUL_SHIFT (18) /* Bits 21-18: PLL Multiplication Factor */
#define RCC_CFGR_PLLMUL_MASK (0x0f << RCC_CFGR_PLLMUL_SHIFT)
# define RCC_CFGR_PLLMUL_CLKx2 (0 << RCC_CFGR_PLLMUL_SHIFT) /* 0000: PLL input clock x 2 */
# define RCC_CFGR_PLLMUL_CLKx3 (1 << RCC_CFGR_PLLMUL_SHIFT) /* 0001: PLL input clock x 3 */
# define RCC_CFGR_PLLMUL_CLKx4 (2 << RCC_CFGR_PLLMUL_SHIFT) /* 0010: PLL input clock x 4 */
# define RCC_CFGR_PLLMUL_CLKx5 (3 << RCC_CFGR_PLLMUL_SHIFT) /* 0011: PLL input clock x 5 */
# define RCC_CFGR_PLLMUL_CLKx6 (4 << RCC_CFGR_PLLMUL_SHIFT) /* 0100: PLL input clock x 6 */
# define RCC_CFGR_PLLMUL_CLKx7 (5 << RCC_CFGR_PLLMUL_SHIFT) /* 0101: PLL input clock x 7 */
# define RCC_CFGR_PLLMUL_CLKx8 (6 << RCC_CFGR_PLLMUL_SHIFT) /* 0110: PLL input clock x 8 */
# define RCC_CFGR_PLLMUL_CLKx9 (7 << RCC_CFGR_PLLMUL_SHIFT) /* 0111: PLL input clock x 9 */
# define RCC_CFGR_PLLMUL_CLKx10 (8 << RCC_CFGR_PLLMUL_SHIFT) /* 1000: PLL input clock x 10 */
# define RCC_CFGR_PLLMUL_CLKx11 (9 << RCC_CFGR_PLLMUL_SHIFT) /* 1001: PLL input clock x 11 */
# define RCC_CFGR_PLLMUL_CLKx12 (10 << RCC_CFGR_PLLMUL_SHIFT) /* 1010: PLL input clock x 12 */
# define RCC_CFGR_PLLMUL_CLKx13 (11 << RCC_CFGR_PLLMUL_SHIFT) /* 1011: PLL input clock x 13 */
# define RCC_CFGR_PLLMUL_CLKx14 (12 << RCC_CFGR_PLLMUL_SHIFT) /* 1100: PLL input clock x 14 */
# define RCC_CFGR_PLLMUL_CLKx15 (13 << RCC_CFGR_PLLMUL_SHIFT) /* 1101: PLL input clock x 15 */
# define RCC_CFGR_PLLMUL_CLKx16 (14 << RCC_CFGR_PLLMUL_SHIFT) /* 111x: PLL input clock x 16 */
/* Bit 22-23: Reserved */
#define RCC_CFGR_MCO_SHIFT (24) /* Bits 27-24: Microcontroller Clock Output */
#define RCC_CFGR_MCO_MASK (15 << RCC_CFGR_MCO_SHIFT)
# define RCC_CFGR_NOCLK (0 << RCC_CFGR_MCO_SHIFT) /* 0000: No clock */
# define RCC_CFGR_HSI14 (1 << RCC_CFGR_MCO_SHIFT) /* 0001: Internal RC 14MHz oscillator */
# define RCC_CFGR_LSI (2 << RCC_CFGR_MCO_SHIFT) /* 0010: Internal Low Speed (LSI) oscillator */
# define RCC_CFGR_LSE (2 << RCC_CFGR_MCO_SHIFT) /* 0011: External Low Speed (LSE) oscillator */
# define RCC_CFGR_SYSCLK (4 << RCC_CFGR_MCO_SHIFT) /* 0100: System clock selected */
# define RCC_CFGR_INTCLK (5 << RCC_CFGR_MCO_SHIFT) /* 0101: Internal 8 MHz RC oscillator clock selected */
# define RCC_CFGR_EXTCLK (6 << RCC_CFGR_MCO_SHIFT) /* 0110: External 4-32 MHz oscillator clock selected */
# define RCC_CFGR_PLLCLKd2 (7 << RCC_CFGR_MCO_SHIFT) /* 0111: PLL clock selected (divided by 1 or 2 depending on PLLNODIV */
# define RCC_CFGR_PLL2CLK (8 << RCC_CFGR_MCO_SHIFT) /* 1000: Internal RC 48MHz (HSI48) oscillator */
#define RCC_CFGR_MCOPRE_SHIFT (28) /* Bits 28-30: Microcontroller Clock Output Prescaler, not available on STM32F05x */
#define RCC_CFGR_MCOPRE_MASK (3 << RCC_CFGR_MCOPRE_SHIFT)
# define RCC_CFGR_MCOPRE_div1 (0 << RCC_CFGR_MCOPRE_SHIFT) /* 000: MCO is divided by 1 */
# define RCC_CFGR_MCOPRE_div2 (1 << RCC_CFGR_MCOPRE_SHIFT) /* 001: MCO is divided by 2 */
# define RCC_CFGR_MCOPRE_div4 (2 << RCC_CFGR_MCOPRE_SHIFT) /* 010: MCO is divided by 4 */
# define RCC_CFGR_MCOPRE_div8 (3 << RCC_CFGR_MCOPRE_SHIFT) /* 011: MCO is divided by 8 */
# define RCC_CFGR_MCOPRE_div16 (4 << RCC_CFGR_MCOPRE_SHIFT) /* 100: MCO is divided by 16 */
# define RCC_CFGR_MCOPRE_div32 (5 << RCC_CFGR_MCOPRE_SHIFT) /* 101: MCO is divided by 32 */
# define RCC_CFGR_MCOPRE_div64 (6 << RCC_CFGR_MCOPRE_SHIFT) /* 110: MCO is divided by 64 */
# define RCC_CFGR_MCOPRE_div128 (7 << RCC_CFGR_MCOPRE_SHIFT) /* 111: MCO is divided by 128 */
/* Clock interrupt register */
#define RCC_CIR_LSIRDYF (1 << 0) /* Bit 0: LSI Ready Interrupt flag */
#define RCC_CIR_LSERDYF (1 << 1) /* Bit 1: LSE Ready Interrupt flag */
#define RCC_CIR_HSIRDYF (1 << 2) /* Bit 2: HSI Ready Interrupt flag */
#define RCC_CIR_HSERDYF (1 << 3) /* Bit 3: HSE Ready Interrupt flag */
#define RCC_CIR_PLLRDYF (1 << 4) /* Bit 4: PLL Ready Interrupt flag */
#define RCC_CIR_HSI14RDYF (1 << 5) /* Bit 5: HSI14 Ready Interrupt flag */
#define RCC_CIR_HSI48RDYF (1 << 6) /* Bit 6: HSI48 Ready Interrupt flag */
#define RCC_CIR_CSSF (1 << 7) /* Bit 7: Clock Security System Interrupt flag */
#define RCC_CIR_LSIRDYIE (1 << 8) /* Bit 8: LSI Ready Interrupt Enable */
#define RCC_CIR_LSERDYIE (1 << 9) /* Bit 9: LSE Ready Interrupt Enable */
#define RCC_CIR_HSIRDYIE (1 << 10) /* Bit 10: HSI Ready Interrupt Enable */
#define RCC_CIR_HSERDYIE (1 << 11) /* Bit 11: HSE Ready Interrupt Enable */
#define RCC_CIR_PLLRDYIE (1 << 12) /* Bit 12: PLL Ready Interrupt Enable */
#define RCC_CIR_HSI14RDYIE (1 << 13) /* Bit 13: HSI14 Ready Interrupt Enable */
#define RCC_CIR_HSI48RDYIE (1 << 14) /* Bit 14: HSI48 Ready Interrupt Enable */
#define RCC_CIR_LSIRDYC (1 << 16) /* Bit 16: LSI Ready Interrupt Clear */
#define RCC_CIR_LSERDYC (1 << 17) /* Bit 17: LSE Ready Interrupt Clear */
#define RCC_CIR_HSIRDYC (1 << 18) /* Bit 18: HSI Ready Interrupt Clear */
#define RCC_CIR_HSERDYC (1 << 19) /* Bit 19: HSE Ready Interrupt Clear */
#define RCC_CIR_PLLRDYC (1 << 20) /* Bit 20: PLL Ready Interrupt Clear */
#define RCC_CIR_HSI14RDYC (1 << 21) /* Bit 21: HSI14 Ready Interrupt Clear */
#define RCC_CIR_HSI48RDYC (1 << 22) /* Bit 22: HSI48 Ready Interrupt Clear */
#define RCC_CIR_CSSC (1 << 23) /* Bit 23: Clock Security System Interrupt Clear */
/* APB2 Peripheral reset register */
#define RCC_APB2RSTR_SYSCFGRST (1 << 0) /* Bit 0: SYSCFG reset */
#define RCC_APB2RSTR_USART6RST (1 << 5) /* Bit 5: USART6 reset */
#define RCC_APB2RSTR_USART7RST (1 << 6) /* Bit 6: USART7 reset */
#define RCC_APB2RSTR_USART8RST (1 << 7) /* Bit 7: USART8 reset */
#define RCC_APB2RSTR_ADCRST (1 << 9) /* Bit 9: ADC interface reset */
#define RCC_APB2RSTR_TIM1RST (1 << 11) /* Bit 11: TIM1 Timer reset */
#define RCC_APB2RSTR_SPI1RST (1 << 12) /* Bit 12: SPI 1 reset */
#define RCC_APB2RSTR_USART1RST (1 << 14) /* Bit 14: USART1 reset */
#define RCC_APB2RSTR_TIM15RST (1 << 16) /* Bit 16: TIM15 reset */
#define RCC_APB2RSTR_TIM16RST (1 << 17) /* Bit 17: TIM16 reset */
#define RCC_APB2RSTR_TIM17RST (1 << 18) /* Bit 18: TIM17 reset */
#define RCC_APB2RSTR_DBGMCURST (1 << 22) /* Bit 22: Debug MCU reset */
/* APB1 Peripheral reset register */
#define RCC_APB1RSTR_TIM2RST (1 << 0) /* Bit 0: Timer 2 reset */
#define RCC_APB1RSTR_TIM3RST (1 << 1) /* Bit 1: Timer 3 reset */
#define RCC_APB1RSTR_TIM6RST (1 << 4) /* Bit 4: Timer 6 reset */
#define RCC_APB1RSTR_TIM7RST (1 << 5) /* Bit 5: Timer 7 reset */
#define RCC_APB1RSTR_TIM14RST (1 << 8) /* Bit 8: TIM14 reset */
#define RCC_APB1RSTR_WWDGRST (1 << 11) /* Bit 11: Window Watchdog reset */
#define RCC_APB1RSTR_SPI2RST (1 << 14) /* Bit 14: SPI 2 reset */
#define RCC_APB1RSTR_USART2RST (1 << 17) /* Bit 17: USART 2 reset */
#define RCC_APB1RSTR_USART3RST (1 << 18) /* Bit 18: USART 3 reset */
#define RCC_APB1RSTR_UART4RST (1 << 19) /* Bit 19: UART 4 reset */
#define RCC_APB1RSTR_UART5RST (1 << 20) /* Bit 20: UART 5 reset */
#define RCC_APB1RSTR_I2C1RST (1 << 21) /* Bit 21: I2C 1 reset */
#define RCC_APB1RSTR_I2C2RST (1 << 22) /* Bit 22: I2C 2 reset */
#define RCC_APB1RSTR_USBRST (1 << 23) /* Bit 23: USB reset */
#define RCC_APB1RSTR_CAN1RST (1 << 25) /* Bit 25: CAN1 reset */
#define RCC_APB1RSTR_CRSRST (1 << 27) /* Bit 27: CRS / Backup interface reset */
#define RCC_APB1RSTR_PWRRST (1 << 28) /* Bit 28: Power interface reset */
#define RCC_APB1RSTR_DACRST (1 << 29) /* Bit 29: DAC interface reset */
#define RCC_APB1RSTR_CECRST (1 << 30) /* Bit 30: CEC reset */
/* AHB Peripheral Clock enable register */
#define RCC_AHBENR_DMA1EN (1 << 0) /* Bit 0: DMA1 clock enable */
#define RCC_AHBENR_DMA2EN (1 << 1) /* Bit 1: DMA2 clock enable */
#define RCC_AHBENR_SRAMEN (1 << 2) /* Bit 2: SRAM interface clock enable */
#define RCC_AHBENR_FLITFEN (1 << 4) /* Bit 4: FLITF clock enable */
#define RCC_AHBENR_CRCEN (1 << 6) /* Bit 6: CRC clock enable */
#define RCC_AHBENR_IOPAEN (1 << 17) /* Bit 17: I/O port A clock enable */
#define RCC_AHBENR_IOPBEN (1 << 18) /* Bit 18: I/O port B clock enable */
#define RCC_AHBENR_IOPCEN (1 << 19) /* Bit 19: I/O port C clock enable */
#define RCC_AHBENR_IOPDEN (1 << 20) /* Bit 20: I/O port D clock enable */
#define RCC_AHBENR_IOPEEN (1 << 21) /* Bit 21: I/O port E clock enable */
#define RCC_AHBENR_IOPFEN (1 << 22) /* Bit 22: I/O port F clock enable */
#define RCC_AHBENR_TSCEN (1 << 24) /* Bit 24: Touch sensing controller clock enable */
/* APB2 Peripheral Clock enable register */
#define RCC_APB2ENR_SYSCFGCOMPEN (1 << 0) /* Bit 0: SYSCFG & COMP clock enable */
#define RCC_APB2ENR_USART6EN (1 << 5) /* Bit 5: USART6 clock enable */
#define RCC_APB2ENR_USART7EN (1 << 6) /* Bit 6: USART7 clock enable */
#define RCC_APB2ENR_USART8EN (1 << 7) /* Bit 7: USART8 & COMP clock enable */
#define RCC_APB2ENR_ADCEN (1 << 9) /* Bit 10: ADC interface clock enable */
#define RCC_APB2ENR_TIM1EN (1 << 11) /* Bit 11: TIM1 Timer clock enable */
#define RCC_APB2ENR_SPI1EN (1 << 12) /* Bit 12: SPI 1 clock enable */
#define RCC_APB2ENR_USART1EN (1 << 14) /* Bit 14: USART1 clock enable */
#define RCC_APB2ENR_TIM15EN (1 << 16) /* Bit 16: TIM15 clock enable */
#define RCC_APB2ENR_TIM16EN (1 << 17) /* Bit 17: TIM16 clock enable */
#define RCC_APB2ENR_TIM17EN (1 << 18) /* Bit 18: TIM17 clock enable */
#define RCC_APB2ENR_DBGMCUEN (1 << 22) /* Bit 18: Debug MCU clock enable */
/* APB1 Peripheral Clock enable register */
#define RCC_APB1ENR_TIM2EN (1 << 0) /* Bit 0: Timer 2 clock enable */
#define RCC_APB1ENR_TIM3EN (1 << 1) /* Bit 1: Timer 3 clock enable */
#define RCC_APB1ENR_TIM4EN (1 << 2) /* Bit 2: Timer 4 clock enable */
#define RCC_APB1ENR_TIM6EN (1 << 4) /* Bit 4: Timer 6 clock enable */
#define RCC_APB1ENR_TIM7EN (1 << 5) /* Bit 5: Timer 7 clock enable */
#define RCC_APB1ENR_TIM14EN (1 << 8) /* Bit 8: Timer 14 clock enable */
#define RCC_APB1ENR_WWDGEN (1 << 11) /* Bit 11: Window Watchdog clock enable */
#define RCC_APB1ENR_SPI2EN (1 << 14) /* Bit 14: SPI 2 clock enable */
#define RCC_APB1ENR_USART2EN (1 << 17) /* Bit 17: USART 2 clock enable */
#define RCC_APB1ENR_USART3EN (1 << 18) /* Bit 18: USART 3 clock enable */
#define RCC_APB1ENR_UART4EN (1 << 19) /* Bit 19: UART 4 clock enable */
#define RCC_APB1ENR_UART5EN (1 << 20) /* Bit 20: UART 5 clock enable */
#define RCC_APB1ENR_I2C1EN (1 << 21) /* Bit 21: I2C 1 clock enable */
#define RCC_APB1ENR_I2C2EN (1 << 22) /* Bit 22: I2C 2 clock enable */
#define RCC_APB1ENR_USBEN (1 << 23) /* Bit 23: USB clock enable */
#define RCC_APB1ENR_CANEN (1 << 25) /* Bit 25: CAN clock enable */
#define RCC_APB1ENR_CRSEN (1 << 27) /* Bit 27: CRS / Backup interface clock enable */
#define RCC_APB1ENR_PWREN (1 << 28) /* Bit 28: Power interface clock enable */
#define RCC_APB1ENR_DACEN (1 << 29) /* Bit 29: DAC interface clock enable */
#define RCC_APB1ENR_CECEN (1 << 30) /* Bit 30: CEC clock enable */
/* RTC domain control register */
#define RCC_BDCR_LSEON (1 << 0) /* Bit 0: External Low Speed oscillator enable */
#define RCC_BDCR_LSERDY (1 << 1) /* Bit 1: External Low Speed oscillator Ready */
#define RCC_BDCR_LSEBYP (1 << 2) /* Bit 2: External Low Speed oscillator Bypass */
#define RCC_BDCR_RTCSEL_SHIFT (8) /* Bits 9:8: RTC clock source selection */
#define RCC_BDCR_RTCSEL_MASK (3 << RCC_BDCR_RTCSEL_SHIFT)
# define RCC_BDCR_RTCSEL_NOCLK (0 << RCC_BDCR_RTCSEL_SHIFT) /* 00: No clock */
# define RCC_BDCR_RTCSEL_LSE (1 << RCC_BDCR_RTCSEL_SHIFT) /* 01: LSE oscillator clock used as RTC clock */
# define RCC_BDCR_RTCSEL_LSI (2 << RCC_BDCR_RTCSEL_SHIFT) /* 10: LSI oscillator clock used as RTC clock */
# define RCC_BDCR_RTCSEL_HSE (3 << RCC_BDCR_RTCSEL_SHIFT) /* 11: HSE oscillator clock divided by 128 used as RTC clock */
#define RCC_BDCR_RTCEN (1 << 15) /* Bit 15: RTC clock enable */
#define RCC_BDCR_BDRST (1 << 16) /* Bit 16: Backup domain software reset */
/* Control/status register */
#define RCC_CSR_LSION (1 << 0) /* Bit 0: Internal Low Speed oscillator enable */
#define RCC_CSR_LSIRDY (1 << 1) /* Bit 1: Internal Low Speed oscillator Ready */
#define RCC_CSR_V18PWRRSTF (1 << 23) /* Bit 23: Reset flag of the 1.8V domain */
#define RCC_CSR_RMVF (1 << 24) /* Bit 24: Remove reset flag */
#define RCC_CSR_OBLRSTF (1 << 25) /* Bit 24: Option byte loader reset flag */
#define RCC_CSR_PINRSTF (1 << 26) /* Bit 26: PIN reset flag */
#define RCC_CSR_PORRSTF (1 << 27) /* Bit 27: POR/PDR reset flag */
#define RCC_CSR_SFTRSTF (1 << 28) /* Bit 28: Software Reset flag */
#define RCC_CSR_IWDGRSTF (1 << 29) /* Bit 29: Independent Watchdog reset flag */
#define RCC_CSR_WWDGRSTF (1 << 30) /* Bit 30: Window watchdog reset flag */
#define RCC_CSR_LPWRRSTF (1 << 31) /* Bit 31: Low-Power reset flag */
/* AHB peripheral reset register */
#define RCC_AHBRSTR_IOPARST (1 << 17) /* Bit 17: I/O port A reset */
#define RCC_AHBRSTR_IOPBRST (1 << 18) /* Bit 18: I/O port B reset */
#define RCC_AHBRSTR_IOPCRST (1 << 19) /* Bit 19: I/O port C reset */
#define RCC_AHBRSTR_IOPDRST (1 << 20) /* Bit 20: I/O port D reset */
#define RCC_AHBRSTR_IOPERST (1 << 21) /* Bit 21: I/O port E reset */
#define RCC_AHBRSTR_IOPFRST (1 << 22) /* Bit 22: I/O port F reset */
#define RCC_AHBRSTR_TSCRST (1 << 24) /* Bit 24: Touch sensing reset */
/* Clock configuration register 2 */
#define RCC_CFGR2_PREDIV1_SHIFT (0)
#define RCC_CFGR2_PREDIV1_MASK (0x0f << RCC_CFGR2_PREDIV1_SHIFT)
# define RCC_CFGR2_PREDIV1d1 (0 << RCC_CFGR2_PREDIV1_SHIFT)
# define RCC_CFGR2_PREDIV1d2 (1 << RCC_CFGR2_PREDIV1_SHIFT)
# define RCC_CFGR2_PREDIV1d3 (2 << RCC_CFGR2_PREDIV1_SHIFT)
# define RCC_CFGR2_PREDIV1d4 (3 << RCC_CFGR2_PREDIV1_SHIFT)
# define RCC_CFGR2_PREDIV1d5 (4 << RCC_CFGR2_PREDIV1_SHIFT)
# define RCC_CFGR2_PREDIV1d6 (5 << RCC_CFGR2_PREDIV1_SHIFT)
# define RCC_CFGR2_PREDIV1d7 (6 << RCC_CFGR2_PREDIV1_SHIFT)
# define RCC_CFGR2_PREDIV1d8 (7 << RCC_CFGR2_PREDIV1_SHIFT)
# define RCC_CFGR2_PREDIV1d9 (8 << RCC_CFGR2_PREDIV1_SHIFT)
# define RCC_CFGR2_PREDIV1d10 (9 << RCC_CFGR2_PREDIV1_SHIFT)
# define RCC_CFGR2_PREDIV1d11 (10 << RCC_CFGR2_PREDIV1_SHIFT)
# define RCC_CFGR2_PREDIV1d12 (11 << RCC_CFGR2_PREDIV1_SHIFT)
# define RCC_CFGR2_PREDIV1d13 (12 << RCC_CFGR2_PREDIV1_SHIFT)
# define RCC_CFGR2_PREDIV1d14 (13 << RCC_CFGR2_PREDIV1_SHIFT)
# define RCC_CFGR2_PREDIV1d15 (14 << RCC_CFGR2_PREDIV1_SHIFT)
# define RCC_CFGR2_PREDIV1d16 (15 << RCC_CFGR2_PREDIV1_SHIFT)
#endif /* __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_RCC_H */

View File

@ -0,0 +1,330 @@
/************************************************************************************
* arch/arm/src/stm32f0/chip/stm32f0_rtcc.h.h
*
* Copyright (C) 2017 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
* Alan Carvalho de Assis <acassis@gmail.com>
*
* 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 NuttX 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 OWNER 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.
*
************************************************************************************/
#ifndef __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_RTCC_H
#define __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_RTCC_H
/************************************************************************************
* Pre-processor Definitions
************************************************************************************/
/* Register Offsets *****************************************************************/
#define STM32F0_RTC_TR_OFFSET 0x0000 /* RTC time register */
#define STM32F0_RTC_DR_OFFSET 0x0004 /* RTC date register */
#define STM32F0_RTC_CR_OFFSET 0x0008 /* RTC control register */
#define STM32F0_RTC_ISR_OFFSET 0x000c /* RTC initialization and status register */
#define STM32F0_RTC_PRER_OFFSET 0x0010 /* RTC prescaler register */
#define STM32F0_RTC_WUTR_OFFSET 0x0014 /* RTC wakeup timer register */
#define STM32F0_RTC_ALRMAR_OFFSET 0x001c /* RTC alarm A register */
#define STM32F0_RTC_WPR_OFFSET 0x0024 /* RTC write protection register */
#define STM32F0_RTC_SSR_OFFSET 0x0028 /* RTC sub second register */
#define STM32F0_RTC_SHIFTR_OFFSET 0x002c /* RTC shift control register */
#define STM32F0_RTC_TSTR_OFFSET 0x0030 /* RTC time stamp time register */
#define STM32F0_RTC_TSDR_OFFSET 0x0034 /* RTC time stamp date register */
#define STM32F0_RTC_TSSSR_OFFSET 0x0038 /* RTC timestamp sub second register */
#define STM32F0_RTC_CALR_OFFSET 0x003c /* RTC calibration register */
#define STM32F0_RTC_TAFCR_OFFSET 0x0040 /* RTC tamper and alternate function configuration register */
#define STM32F0_RTC_ALRMASSR_OFFSET 0x0044 /* RTC alarm A sub second register */
#define STM32F0_RTC_BKR_OFFSET(n) (0x0050+((n)<<2))
#define STM32F0_RTC_BK0R_OFFSET 0x0050 /* RTC backup register 0 */
#define STM32F0_RTC_BK1R_OFFSET 0x0054 /* RTC backup register 1 */
#define STM32F0_RTC_BK2R_OFFSET 0x0058 /* RTC backup register 2 */
#define STM32F0_RTC_BK3R_OFFSET 0x005c /* RTC backup register 3 */
#define STM32F0_RTC_BK4R_OFFSET 0x0060 /* RTC backup register 4 */
/* Register Addresses ***************************************************************/
#define STM32F0_RTC_TR (STM32F0_RTC_BASE+STM32F0_RTC_TR_OFFSET)
#define STM32F0_RTC_DR (STM32F0_RTC_BASE+STM32F0_RTC_DR_OFFSET)
#define STM32F0_RTC_CR (STM32F0_RTC_BASE+STM32F0_RTC_CR_OFFSET)
#define STM32F0_RTC_ISR (STM32F0_RTC_BASE+STM32F0_RTC_ISR_OFFSET)
#define STM32F0_RTC_PRER (STM32F0_RTC_BASE+STM32F0_RTC_PRER_OFFSET)
#define STM32F0_RTC_WUTR (STM32F0_RTC_BASE+STM32F0_RTC_WUTR_OFFSET)
#define STM32F0_RTC_ALRMAR (STM32F0_RTC_BASE+STM32F0_RTC_ALRMAR_OFFSET)
#define STM32F0_RTC_WPR (STM32F0_RTC_BASE+STM32F0_RTC_WPR_OFFSET)
#define STM32F0_RTC_SSR (STM32F0_RTC_BASE+STM32F0_RTC_SSR_OFFSET)
#define STM32F0_RTC_SHIFTR (STM32F0_RTC_BASE+STM32F0_RTC_SHIFTR_OFFSET)
#define STM32F0_RTC_TSTR (STM32F0_RTC_BASE+STM32F0_RTC_TSTR_OFFSET)
#define STM32F0_RTC_TSDR (STM32F0_RTC_BASE+STM32F0_RTC_TSDR_OFFSET)
#define STM32F0_RTC_TSSSR (STM32F0_RTC_BASE+STM32F0_RTC_TSSSR_OFFSET)
#define STM32F0_RTC_CALR (STM32F0_RTC_BASE+STM32F0_RTC_CALR_OFFSET)
#define STM32F0_RTC_TAFCR (STM32F0_RTC_BASE+STM32F0_RTC_TAFCR_OFFSET)
#define STM32F0_RTC_ALRMASSR (STM32F0_RTC_BASE+STM32F0_RTC_ALRMASSR_OFFSET)
#define STM32F0_RTC_BKR(n) (STM32F0_RTC_BASE+STM32F0_RTC_BKR_OFFSET(n))
#define STM32F0_RTC_BK0R (STM32F0_RTC_BASE+STM32F0_RTC_BK0R_OFFSET)
#define STM32F0_RTC_BK1R (STM32F0_RTC_BASE+STM32F0_RTC_BK1R_OFFSET)
#define STM32F0_RTC_BK2R (STM32F0_RTC_BASE+STM32F0_RTC_BK2R_OFFSET)
#define STM32F0_RTC_BK3R (STM32F0_RTC_BASE+STM32F0_RTC_BK3R_OFFSET)
#define STM32F0_RTC_BK4R (STM32F0_RTC_BASE+STM32F0_RTC_BK4R_OFFSET)
#ifdef CONFIG_STM32F0_STM32F30XX
# define STM32F0_RTC_BKCOUNT 16
#elif defined(CONFIG_STM32F0_STM32L15XX)
# define STM32F0_RTC_BKCOUNT 32
#else
# define STM32F0_RTC_BKCOUNT 20
#endif
/* Register Bitfield Definitions ****************************************************/
/* RTC time register */
#define RTC_TR_SU_SHIFT (0) /* Bits 0-3: Second units in BCD format */
#define RTC_TR_SU_MASK (15 << RTC_TR_SU_SHIFT)
#define RTC_TR_ST_SHIFT (4) /* Bits 4-6: Second tens in BCD format */
#define RTC_TR_ST_MASK (7 << RTC_TR_ST_SHIFT)
#define RTC_TR_MNU_SHIFT (8) /* Bit 8-11: Minute units in BCD format */
#define RTC_TR_MNU_MASK (15 << RTC_TR_MNU_SHIFT)
#define RTC_TR_MNT_SHIFT (12) /* Bits 12-14: Minute tens in BCD format */
#define RTC_TR_MNT_MASK (7 << RTC_TR_MNT_SHIFT)
#define RTC_TR_HU_SHIFT (16) /* Bit 16-19: Hour units in BCD format */
#define RTC_TR_HU_MASK (15 << RTC_TR_HU_SHIFT)
#define RTC_TR_HT_SHIFT (20) /* Bits 20-21: Hour tens in BCD format */
#define RTC_TR_HT_MASK (3 << RTC_TR_HT_SHIFT)
#define RTC_TR_PM (1 << 22) /* Bit 22: AM/PM notation */
#define RTC_TR_RESERVED_BITS (0xff808080)
/* RTC date register */
#define RTC_DR_DU_SHIFT (0) /* Bits 0-3: Date units in BCD format */
#define RTC_DR_DU_MASK (15 << RTC_DR_DU_SHIFT)
#define RTC_DR_DT_SHIFT (4) /* Bits 4-5: Date tens in BCD format */
#define RTC_DR_DT_MASK (3 << RTC_DR_DT_SHIFT)
#define RTC_DR_MU_SHIFT (8) /* Bits 8-11: Month units in BCD format */
#define RTC_DR_MU_MASK (15 << RTC_DR_MU_SHIFT)
#define RTC_DR_MT (1 << 12) /* Bit 12: Month tens in BCD format */
#define RTC_DR_WDU_SHIFT (13) /* Bits 13-15: Week day units */
#define RTC_DR_WDU_MASK (7 << RTC_DR_WDU_SHIFT)
# define RTC_DR_WDU_MONDAY (1 << RTC_DR_WDU_SHIFT)
# define RTC_DR_WDU_TUESDAY (2 << RTC_DR_WDU_SHIFT)
# define RTC_DR_WDU_WEDNESDAY (3 << RTC_DR_WDU_SHIFT)
# define RTC_DR_WDU_THURSDAY (4 << RTC_DR_WDU_SHIFT)
# define RTC_DR_WDU_FRIDAY (5 << RTC_DR_WDU_SHIFT)
# define RTC_DR_WDU_SATURDAY (6 << RTC_DR_WDU_SHIFT)
# define RTC_DR_WDU_SUNDAY (7 << RTC_DR_WDU_SHIFT)
#define RTC_DR_YU_SHIFT (16) /* Bits 16-19: Year units in BCD format */
#define RTC_DR_YU_MASK (15 << RTC_DR_YU_SHIFT)
#define RTC_DR_YT_SHIFT (20) /* Bits 20-23: Year tens in BCD format */
#define RTC_DR_YT_MASK (15 << RTC_DR_YT_SHIFT)
#define RTC_DR_RESERVED_BITS (0xff0000c0)
/* RTC control register */
#define RTC_CR_WUCKSEL_SHIFT (0) /* Bits 0-2: Wakeup clock selection */
#define RTC_CR_WUCKSEL_MASK (7 << RTC_CR_WUCKSEL_SHIFT)
# define RTC_CR_WUCKSEL_RTCDIV16 (0 << RTC_CR_WUCKSEL_SHIFT) /* 000: RTC/16 clock is selected */
# define RTC_CR_WUCKSEL_RTCDIV8 (1 << RTC_CR_WUCKSEL_SHIFT) /* 001: RTC/8 clock is selected */
# define RTC_CR_WUCKSEL_RTCDIV4 (2 << RTC_CR_WUCKSEL_SHIFT) /* 010: RTC/4 clock is selected */
# define RTC_CR_WUCKSEL_RTCDIV2 (3 << RTC_CR_WUCKSEL_SHIFT) /* 011: RTC/2 clock is selected */
# define RTC_CR_WUCKSEL_CKSPRE (4 << RTC_CR_WUCKSEL_SHIFT) /* 10x: ck_spre clock is selected */
# define RTC_CR_WUCKSEL_CKSPREADD (6 << RTC_CR_WUCKSEL_SHIFT) /* 11x: ck_spr clock and 216 added WUT counter */
#define RTC_CR_TSEDGE (1 << 3) /* Bit 3: Timestamp event active edge */
#define RTC_CR_REFCKON (1 << 4) /* Bit 4: Reference clock detection enable (50 or 60 Hz) */
#define RTC_CR_BYPSHAD (1 << 5) /* Bit 5: Bypass the shadow registers */
#define RTC_CR_FMT (1 << 6) /* Bit 6: Hour format */
#define RTC_CR_ALRAE (1 << 8) /* Bit 8: Alarm A enable */
#define RTC_CR_WUTE (1 << 10) /* Bit 10: Wakeup timer enable */
#define RTC_CR_TSE (1 << 11) /* Bit 11: Time stamp enable */
#define RTC_CR_ALRAIE (1 << 12) /* Bit 12: Alarm A interrupt enable */
#define RTC_CR_WUTIE (1 << 14) /* Bit 14: Wakeup timer interrupt enable */
#define RTC_CR_TSIE (1 << 15) /* Bit 15: Timestamp interrupt enable */
#define RTC_CR_ADD1H (1 << 16) /* Bit 16: Add 1 hour (summer time change) */
#define RTC_CR_SUB1H (1 << 17) /* Bit 17: Subtract 1 hour (winter time change) */
#define RTC_CR_BKP (1 << 18) /* Bit 18: Backup */
#define RTC_CR_COSEL (1 << 19) /* Bit 19 : Calibration output selection */
#define RTC_CR_POL (1 << 20) /* Bit 20: Output polarity */
#define RTC_CR_OSEL_SHIFT (21) /* Bits 21-22: Output selection */
#define RTC_CR_OSEL_MASK (3 << RTC_CR_OSEL_SHIFT)
# define RTC_CR_OSEL_DISABLED (0 << RTC_CR_OSEL_SHIFT) /* 00: Output disabled */
# define RTC_CR_OSEL_ALRMA (1 << RTC_CR_OSEL_SHIFT) /* 01: Alarm A output enabled */
# define RTC_CR_OSEL_ALRMB (2 << RTC_CR_OSEL_SHIFT) /* 10: Alarm B output enabled */
# define RTC_CR_OSEL_WUT (3 << RTC_CR_OSEL_SHIFT) /* 11: Wakeup output enabled */
#define RTC_CR_COE (1 << 23) /* Bit 23: Calibration output enable */
/* RTC initialization and status register */
#define RTC_ISR_ALRAWF (1 << 0) /* Bit 0: Alarm A write flag */
#define RTC_ISR_WUTWF (1 << 2) /* Bit 2: Wakeup timer write flag */
#define RTC_ISR_SHPF (1 << 3) /* Bit 3: Shift operation pending */
#define RTC_ISR_INITS (1 << 4) /* Bit 4: Initialization status flag */
#define RTC_ISR_RSF (1 << 5) /* Bit 5: Registers synchronization flag */
#define RTC_ISR_INITF (1 << 6) /* Bit 6: Initialization flag */
#define RTC_ISR_INIT (1 << 7) /* Bit 7: Initialization mode */
#define RTC_ISR_ALRAF (1 << 8) /* Bit 8: Alarm A flag */
#define RTC_ISR_WUTF (1 << 10) /* Bit 10: Wakeup timer flag */
#define RTC_ISR_TSF (1 << 11) /* Bit 11: Timestamp flag */
#define RTC_ISR_TSOVF (1 << 12) /* Bit 12: Timestamp overflow flag */
#define RTC_ISR_TAMP1F (1 << 13) /* Bit 13: Tamper detection flag */
#define RTC_ISR_TAMP2F (1 << 14) /* Bit 14: TAMPER2 detection flag */
#define RTC_ISR_TAMP3F (1 << 15) /* Bit 15: TAMPER3 detection flag */
#define RTC_ISR_RECALPF (1 << 16) /* Bit 16: Recalibration pending Flag */
#define RTC_ISR_ALLFLAGS (0x00017fff)
/* RTC prescaler register */
#define RTC_PRER_PREDIV_S_SHIFT (0) /* Bits 0-14: Synchronous prescaler factor */
#define RTC_PRER_PREDIV_S_MASK (0x7fff << RTC_PRER_PREDIV_S_SHIFT)
#define RTC_PRER_PREDIV_A_SHIFT (16) /* Bits 16-22: Asynchronous prescaler factor */
#define RTC_PRER_PREDIV_A_MASK (0x7f << RTC_PRER_PREDIV_A_SHIFT)
/* RTC wakeup timer register */
#define RTC_WUTR_MASK (0xffff) /* Bits 15:0 Wakeup auto-reload value bits */
/* RTC alarm A register */
#define RTC_ALRMR_SU_SHIFT (0) /* Bits 0-3: Second units in BCD format. */
#define RTC_ALRMR_SU_MASK (15 << RTC_ALRMR_SU_SHIFT)
#define RTC_ALRMR_ST_SHIFT (4) /* Bits 4-6: Second tens in BCD format. */
#define RTC_ALRMR_ST_MASK (7 << RTC_ALRMR_ST_SHIFT)
#define RTC_ALRMR_MSK1 (1 << 7) /* Bit 7 : Alarm A seconds mask */
#define RTC_ALRMR_MNU_SHIFT (8) /* Bits 8-11: Minute units in BCD format. */
#define RTC_ALRMR_MNU_MASK (15 << RTC_ALRMR_MNU_SHIFT)
#define RTC_ALRMR_MNT_SHIFT (12) /* Bits 12-14: Minute tens in BCD format. */
#define RTC_ALRMR_MNT_MASK (7 << RTC_ALRMR_MNT_SHIFT)
#define RTC_ALRMR_MSK2 (1 << 15) /* Bit 15 : Alarm A minutes mask */
#define RTC_ALRMR_HU_SHIFT (16) /* Bits 16-19: Hour units in BCD format. */
#define RTC_ALRMR_HU_MASK (15 << RTC_ALRMR_HU_SHIFT)
#define RTC_ALRMR_HT_SHIFT (20) /* Bits 20-21: Hour tens in BCD format. */
#define RTC_ALRMR_HT_MASK (3 << RTC_ALRMR_HT_SHIFT)
#define RTC_ALRMR_PM (1 << 22) /* Bit 22 : AM/PM notation */
#define RTC_ALRMR_MSK3 (1 << 23) /* Bit 23 : Alarm A hours mask */
#define RTC_ALRMR_DU_SHIFT (24) /* Bits 24-27: Date units or day in BCD format. */
#define RTC_ALRMR_DU_MASK (15 << RTC_ALRMR_DU_SHIFT)
#define RTC_ALRMR_DT_SHIFT (28) /* Bits 28-29: Date tens in BCD format. */
#define RTC_ALRMR_DT_MASK (3 << RTC_ALRMR_DT_SHIFT)
#define RTC_ALRMR_WDSEL (1 << 30) /* Bit 30: Week day selection */
#define RTC_ALRMR_MSK4 (1 << 31) /* Bit 31: Alarm A date mask */
/* RTC write protection register */
#define RTC_WPR_MASK (0xff) /* Bits 0-7: Write protection key */
/* RTC sub second register */
#define RTC_SSR_MASK (0xffff) /* Bits 0-15: Sub second value */
/* RTC shift control register */
#define RTC_SHIFTR_SUBFS_SHIFT (0) /* Bits 0-14: Subtract a fraction of a second */
#define RTC_SHIFTR_SUBFS_MASK (0x7fff << RTC_SHIFTR_SUBFS_SHIFT)
#define RTC_SHIFTR_ADD1S (1 << 31) /* Bit 31: Add one second */
/* RTC time stamp time register */
#define RTC_TSTR_SU_SHIFT (0) /* Bits 0-3: Second units in BCD format. */
#define RTC_TSTR_SU_MASK (15 << RTC_TSTR_SU_SHIFT)
#define RTC_TSTR_ST_SHIFT (4) /* Bits 4-6: Second tens in BCD format. */
#define RTC_TSTR_ST_MASK (7 << RTC_TSTR_ST_SHIFT)
#define RTC_TSTR_MNU_SHIFT (8) /* Bits 8-11: Minute units in BCD format. */
#define RTC_TSTR_MNU_MASK (15 << RTC_TSTR_MNU_SHIFT)
#define RTC_TSTR_MNT_SHIFT (12) /* Bits 12-14: Minute tens in BCD format. */
#define RTC_TSTR_MNT_MASK (7 << RTC_TSTR_MNT_SHIFT)
#define RTC_TSTR_HU_SHIFT (16) /* Bits 16-19: Hour units in BCD format. */
#define RTC_TSTR_HU_MASK (15 << RTC_TSTR_HU_SHIFT)
#define RTC_TSTR_HT_SHIFT (20) /* Bits 20-21: Hour tens in BCD format. */
#define RTC_TSTR_HT_MASK (3 << RTC_TSTR_HT_SHIFT)
#define RTC_TSTR_PM (1 << 22) /* Bit 22: AM/PM notation */
/* RTC time stamp date register */
#define RTC_TSDR_DU_SHIFT (0) /* Bit 0-3: Date units in BCD format */
#define RTC_TSDR_DU_MASK (15 << RTC_TSDR_DU_SHIFT) /* */
#define RTC_TSDR_DT_SHIFT (4) /* Bits 4-5: Date tens in BCD format */
#define RTC_TSDR_DT_MASK (3 << RTC_TSDR_DT_SHIFT)
#define RTC_TSDR_MU_SHIFT (8) /* Bits 8-11: Month units in BCD format */
#define RTC_TSDR_MU_MASK (xx << RTC_TSDR_MU_SHIFT)
#define RTC_TSDR_MT (1 << 12) /* Bit 12: Month tens in BCD format */
#define RTC_TSDR_WDU_SHIFT (13) /* Bits 13-15: Week day units */
#define RTC_TSDR_WDU_MASK (7 << RTC_TSDR_WDU_SHIFT)
/* RTC timestamp sub second register */
#define RTC_TSSSR_MASK (0xffff) /* Bits 0-15: Sub second value */
/* RTC calibration register */
#define RTC_CALR_CALM_SHIFT (0) /* Bits 0-8: Calibration minus */
#define RTC_CALR_CALM_MASK (0x1ff << RTC_CALR_CALM_SHIFT)
#define RTC_CALR_CALW16 (1 << 13) /* Bit 13: Use a 16-second calibration cycle period */
#define RTC_CALR_CALW8 (1 << 14) /* Bit 14: Use an 8-second calibration cycle period */
#define RTC_CALR_CALP (1 << 15) /* Bit 15: Increase frequency of RTC by 488.5 ppm */
/* RTC tamper and alternate function configuration register */
#define RTC_TAFCR_TAMP1E (1 << 0) /* Bit 0: RTC_TAMP1 input detection enable */
#define RTC_TAFCR_TAMP1TRG (1 << 1) /* Bit 1: Active level for RTC_TAMP1 input */
#define RTC_TAFCR_TAMPIE (1 << 2) /* Bit 2: Tamper interrupt enable */
#define RTC_TAFCR_TAMP3E (1 << 5) /* Bit 5: RTC_TAMP3 detection enable */
#define RTC_TAFCR_TAMP3TRG (1 << 6) /* Bit 6: Active level for RTC_TAMP3 input */
#define RTC_TAFCR_TAMPTS (1 << 7) /* Bit 7: Activate timestamp on tamper detection event */
#define RTC_TAFCR_TAMPFREQ_SHIFT (8) /* Bits 8-10: Tamper sampling frequency */
#define RTC_TAFCR_TAMPFREQ_MASK (7 << RTC_TAFCR_TAMPFREQ_SHIFT)
# define RTC_TAFCR_TAMPFREQ_DIV32768 (0 << RTC_TAFCR_TAMPFREQ_SHIFT) /* RTCCLK / 32768 (1 Hz) */
# define RTC_TAFCR_TAMPFREQ_DIV16384 (1 << RTC_TAFCR_TAMPFREQ_SHIFT) /* RTCCLK / 16384 (2 Hz) */
# define RTC_TAFCR_TAMPFREQ_DIV8192 (2 << RTC_TAFCR_TAMPFREQ_SHIFT) /* RTCCLK / 8192 (4 Hz) */
# define RTC_TAFCR_TAMPFREQ_DIV4096 (3 << RTC_TAFCR_TAMPFREQ_SHIFT) /* RTCCLK / 4096 (8 Hz) */
# define RTC_TAFCR_TAMPFREQ_DIV2048 (4 << RTC_TAFCR_TAMPFREQ_SHIFT) /* RTCCLK / 2048 (16 Hz) */
# define RTC_TAFCR_TAMPFREQ_DIV1024 (5 << RTC_TAFCR_TAMPFREQ_SHIFT) /* RTCCLK / 1024 (32 Hz) */
# define RTC_TAFCR_TAMPFREQ_DIV512 (6 << RTC_TAFCR_TAMPFREQ_SHIFT) /* RTCCLK / 512 (64 Hz) */
# define RTC_TAFCR_TAMPFREQ_DIV256 (7 << RTC_TAFCR_TAMPFREQ_SHIFT) /* RTCCLK / 256 (128 Hz) */
#define RTC_TAFCR_TAMPFLT_SHIFT (11) /* Bits 11-12: RTC_TAMPx filter count */
#define RTC_TAFCR_TAMPFLT_MASK (3 << RTC_TAFCR_TAMPFLT_SHIFT)
#define RTC_TAFCR_TAMPPRCH_SHIFT (13) /* Bits 13-14: RTC_TAMPx precharge duration */
#define RTC_TAFCR_TAMPPRCH_MASK (3 << RTC_TAFCR_TAMPPRCH_SHIFT)
# define RTC_TAFCR_TAMPPRCH_1CYCLE (0 << RTC_TAFCR_TAMPPRCH_SHIFT) /* 1 RTCCLK cycle */
# define RTC_TAFCR_TAMPPRCH_2CYCLES (1 << RTC_TAFCR_TAMPPRCH_SHIFT) /* 2 RTCCLK cycles */
# define RTC_TAFCR_TAMPPRCH_4CYCLES (2 << RTC_TAFCR_TAMPPRCH_SHIFT) /* 4 RTCCLK cycles */
# define RTC_TAFCR_TAMPPRCH_5CYCLES (3 << RTC_TAFCR_TAMPPRCH_SHIFT) /* 8 RTCCLK cycles */
#define RTC_TAFCR_TAMPPUDIS (1 << 15) /* Bit 15: RTC_TAMPx pull-up disable */
#define RTC_TAFCR_PC13VALUE (1 << 18) /* Bit 18: RTC_ALARM output type/PC13 value */
#define RTC_TAFCR_PC13MODE (1 << 19) /* Bit 19: PC13 mode */
#define RTC_TAFCR_PC14VALUE (1 << 20) /* Bit 20: PC14 value */
#define RTC_TAFCR_PC14MODE (1 << 21) /* Bit 21: PC14 mode */
#define RTC_TAFCR_PC15VALUE (1 << 22) /* Bit 22: PC15 value */
#define RTC_TAFCR_PC15MODE (1 << 23) /* Bit 23: PC15 mode */
/* RTC alarm A sub second register */
#define RTC_ALRMSSR_SS_SHIFT (0) /* Bits 0-14: Sub second value */
#define RTC_ALRMSSR_SS_MASK (0x7fff << RTC_ALRMSSR_SS_SHIFT)
#define RTC_ALRMSSR_MASKSS_SHIFT (24) /* Bits 24-27: Mask the most-significant bits starting at this bit */
#define RTC_ALRMSSR_MASKSS_MASK (0xf << RTC_ALRMSSR_MASKSS_SHIFT)
#endif /* __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_RTCC_H */

View File

@ -0,0 +1,252 @@
/************************************************************************************
* arch/arm/src/stm32f0/chip/stm32f0_spi.h
*
* Copyright (C) 2017 Gregory Nutt. All rights reserved.
* Authors: Gregory Nutt <gnutt@nuttx.org>
*
* 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 NuttX 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 OWNER 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.
*
************************************************************************************/
#ifndef __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_SPI_H
#define __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_SPI_H
/************************************************************************************
* Included Files
************************************************************************************/
#include <nuttx/config.h>
#include "chip.h"
/************************************************************************************
* Pre-processor Definitions
************************************************************************************/
/* Maximum allowed speed as per data sheet for all SPIs (both pclk1 and pclk2)*/
#define STM32F0_SPI_CLK_MAX 50000000UL
/* Register Offsets *****************************************************************/
#define STM32F0_SPI_CR1_OFFSET 0x0000 /* SPI Control Register 1 (16-bit) */
#define STM32F0_SPI_CR2_OFFSET 0x0004 /* SPI control register 2 (16-bit) */
#define STM32F0_SPI_SR_OFFSET 0x0008 /* SPI status register (16-bit) */
#define STM32F0_SPI_DR_OFFSET 0x000c /* SPI data register (16-bit) */
#define STM32F0_SPI_CRCPR_OFFSET 0x0010 /* SPI CRC polynomial register (16-bit) */
#define STM32F0_SPI_RXCRCR_OFFSET 0x0014 /* SPI Rx CRC register (16-bit) */
#define STM32F0_SPI_TXCRCR_OFFSET 0x0018 /* SPI Tx CRC register (16-bit) */
#define STM32F0_SPI_I2SCFGR_OFFSET 0x001c /* I2S configuration register */
#define STM32F0_SPI_I2SPR_OFFSET 0x0020 /* I2S prescaler register */
/* Register Addresses ***************************************************************/
#if STM32F0_NSPI > 0
# define STM32F0_SPI1_CR1 (STM32F0_SPI1_BASE+STM32F0_SPI_CR1_OFFSET)
# define STM32F0_SPI1_CR2 (STM32F0_SPI1_BASE+STM32F0_SPI_CR2_OFFSET)
# define STM32F0_SPI1_SR (STM32F0_SPI1_BASE+STM32F0_SPI_SR_OFFSET)
# define STM32F0_SPI1_DR (STM32F0_SPI1_BASE+STM32F0_SPI_DR_OFFSET)
# define STM32F0_SPI1_CRCPR (STM32F0_SPI1_BASE+STM32F0_SPI_CRCPR_OFFSET)
# define STM32F0_SPI1_RXCRCR (STM32F0_SPI1_BASE+STM32F0_SPI_RXCRCR_OFFSET)
# define STM32F0_SPI1_TXCRCR (STM32F0_SPI1_BASE+STM32F0_SPI_TXCRCR_OFFSET)
#endif
#if STM32F0_NSPI > 1
# define STM32F0_SPI2_CR1 (STM32F0_SPI2_BASE+STM32F0_SPI_CR1_OFFSET)
# define STM32F0_SPI2_CR2 (STM32F0_SPI2_BASE+STM32F0_SPI_CR2_OFFSET)
# define STM32F0_SPI2_SR (STM32F0_SPI2_BASE+STM32F0_SPI_SR_OFFSET)
# define STM32F0_SPI2_DR (STM32F0_SPI2_BASE+STM32F0_SPI_DR_OFFSET)
# define STM32F0_SPI2_CRCPR (STM32F0_SPI2_BASE+STM32F0_SPI_CRCPR_OFFSET)
# define STM32F0_SPI2_RXCRCR (STM32F0_SPI2_BASE+STM32F0_SPI_RXCRCR_OFFSET)
# define STM32F0_SPI2_TXCRCR (STM32F0_SPI2_BASE+STM32F0_SPI_TXCRCR_OFFSET)
# define STM32F0_SPI2_I2SCFGR (STM32F0_SPI2_BASE+STM32F0_SPI_I2SCFGR_OFFSET)
# define STM32F0_SPI2_I2SPR (STM32F0_SPI2_BASE+STM32F0_SPI_I2SPR_OFFSET)
#endif
#if STM32F0_NSPI > 2
# define STM32F0_SPI3_CR1 (STM32F0_SPI3_BASE+STM32F0_SPI_CR1_OFFSET)
# define STM32F0_SPI3_CR2 (STM32F0_SPI3_BASE+STM32F0_SPI_CR2_OFFSET)
# define STM32F0_SPI3_SR (STM32F0_SPI3_BASE+STM32F0_SPI_SR_OFFSET)
# define STM32F0_SPI3_DR (STM32F0_SPI3_BASE+STM32F0_SPI_DR_OFFSET)
# define STM32F0_SPI3_CRCPR (STM32F0_SPI3_BASE+STM32F0_SPI_CRCPR_OFFSET)
# define STM32F0_SPI3_RXCRCR (STM32F0_SPI3_BASE+STM32F0_SPI_RXCRCR_OFFSET)
# define STM32F0_SPI3_TXCRCR (STM32F0_SPI3_BASE+STM32F0_SPI_TXCRCR_OFFSET)
# define STM32F0_SPI3_I2SCFGR (STM32F0_SPI3_BASE+STM32F0_SPI_I2SCFGR_OFFSET)
# define STM32F0_SPI3_I2SPR (STM32F0_SPI3_BASE+STM32F0_SPI_I2SPR_OFFSET)
#endif
#if STM32F0_NSPI > 3
# define STM32F0_SPI4_CR1 (STM32F0_SPI4_BASE+STM32F0_SPI_CR1_OFFSET)
# define STM32F0_SPI4_CR2 (STM32F0_SPI4_BASE+STM32F0_SPI_CR2_OFFSET)
# define STM32F0_SPI4_SR (STM32F0_SPI4_BASE+STM32F0_SPI_SR_OFFSET)
# define STM32F0_SPI4_DR (STM32F0_SPI4_BASE+STM32F0_SPI_DR_OFFSET)
# define STM32F0_SPI4_CRCPR (STM32F0_SPI4_BASE+STM32F0_SPI_CRCPR_OFFSET)
# define STM32F0_SPI4_RXCRCR (STM32F0_SPI4_BASE+STM32F0_SPI_RXCRCR_OFFSET)
# define STM32F0_SPI4_TXCRCR (STM32F0_SPI4_BASE+STM32F0_SPI_TXCRCR_OFFSET)
# define STM32F0_SPI4_I2SCFGR (STM32F0_SPI4_BASE+STM32F0_SPI_I2SCFGR_OFFSET)
# define STM32F0_SPI4_I2SPR (STM32F0_SPI4_BASE+STM32F0_SPI_I2SPR_OFFSET)
#endif
#if STM32F0_NSPI > 4
# define STM32F0_SPI5_CR1 (STM32F0_SPI5_BASE+STM32F0_SPI_CR1_OFFSET)
# define STM32F0_SPI5_CR2 (STM32F0_SPI5_BASE+STM32F0_SPI_CR2_OFFSET)
# define STM32F0_SPI5_SR (STM32F0_SPI5_BASE+STM32F0_SPI_SR_OFFSET)
# define STM32F0_SPI5_DR (STM32F0_SPI5_BASE+STM32F0_SPI_DR_OFFSET)
# define STM32F0_SPI5_CRCPR (STM32F0_SPI5_BASE+STM32F0_SPI_CRCPR_OFFSET)
# define STM32F0_SPI5_RXCRCR (STM32F0_SPI5_BASE+STM32F0_SPI_RXCRCR_OFFSET)
# define STM32F0_SPI5_TXCRCR (STM32F0_SPI5_BASE+STM32F0_SPI_TXCRCR_OFFSET)
# define STM32F0_SPI5_I2SCFGR (STM32F0_SPI5_BASE+STM32F0_SPI_I2SCFGR_OFFSET)
# define STM32F0_SPI5_I2SPR (STM32F0_SPI5_BASE+STM32F0_SPI_I2SPR_OFFSET)
#endif
#if STM32F0_NSPI > 5
# define STM32F0_SPI6_CR1 (STM32F0_SPI6_BASE+STM32F0_SPI_CR1_OFFSET)
# define STM32F0_SPI6_CR2 (STM32F0_SPI6_BASE+STM32F0_SPI_CR2_OFFSET)
# define STM32F0_SPI6_SR (STM32F0_SPI6_BASE+STM32F0_SPI_SR_OFFSET)
# define STM32F0_SPI6_DR (STM32F0_SPI6_BASE+STM32F0_SPI_DR_OFFSET)
# define STM32F0_SPI6_CRCPR (STM32F0_SPI6_BASE+STM32F0_SPI_CRCPR_OFFSET)
# define STM32F0_SPI6_RXCRCR (STM32F0_SPI6_BASE+STM32F0_SPI_RXCRCR_OFFSET)
# define STM32F0_SPI6_TXCRCR (STM32F0_SPI6_BASE+STM32F0_SPI_TXCRCR_OFFSET)
# define STM32F0_SPI6_I2SCFGR (STM32F0_SPI6_BASE+STM32F0_SPI_I2SCFGR_OFFSET)
# define STM32F0_SPI6_I2SPR (STM32F0_SPI6_BASE+STM32F0_SPI_I2SPR_OFFSET)
#endif
/* Register Bitfield Definitions ****************************************************/
/* SPI Control Register 1 */
#define SPI_CR1_CPHA (1 << 0) /* Bit 0: Clock Phase */
#define SPI_CR1_CPOL (1 << 1) /* Bit 1: Clock Polarity */
#define SPI_CR1_MSTR (1 << 2) /* Bit 2: Master Selection */
#define SPI_CR1_BR_SHIFT (3) /* Bits 5:3 Baud Rate Control */
#define SPI_CR1_BR_MASK (7 << SPI_CR1_BR_SHIFT)
# define SPI_CR1_FPCLCKd2 (0 << SPI_CR1_BR_SHIFT) /* 000: fPCLK/2 */
# define SPI_CR1_FPCLCKd4 (1 << SPI_CR1_BR_SHIFT) /* 001: fPCLK/4 */
# define SPI_CR1_FPCLCKd8 (2 << SPI_CR1_BR_SHIFT) /* 010: fPCLK/8 */
# define SPI_CR1_FPCLCKd16 (3 << SPI_CR1_BR_SHIFT) /* 011: fPCLK/16 */
# define SPI_CR1_FPCLCKd32 (4 << SPI_CR1_BR_SHIFT) /* 100: fPCLK/32 */
# define SPI_CR1_FPCLCKd64 (5 << SPI_CR1_BR_SHIFT) /* 101: fPCLK/64 */
# define SPI_CR1_FPCLCKd128 (6 << SPI_CR1_BR_SHIFT) /* 110: fPCLK/128 */
# define SPI_CR1_FPCLCKd256 (7 << SPI_CR1_BR_SHIFT) /* 111: fPCLK/256 */
#define SPI_CR1_SPE (1 << 6) /* Bit 6: SPI Enable */
#define SPI_CR1_LSBFIRST (1 << 7) /* Bit 7: Frame Format */
#define SPI_CR1_SSI (1 << 8) /* Bit 8: Internal slave select */
#define SPI_CR1_SSM (1 << 9) /* Bit 9: Software slave management */
#define SPI_CR1_RXONLY (1 << 10) /* Bit 10: Receive only */
#define SPI_CR1_CRCL (1 << 11) /* Bit 11: CRC length */
#define SPI_CR1_CRCNEXT (1 << 12) /* Bit 12: Transmit CRC next */
#define SPI_CR1_CRCEN (1 << 13) /* Bit 13: Hardware CRC calculation enable */
#define SPI_CR1_BIDIOE (1 << 14) /* Bit 14: Output enable in bidirectional mode */
#define SPI_CR1_BIDIMODE (1 << 15) /* Bit 15: Bidirectional data mode enable */
/* SPI Control Register 2 */
#define SPI_CR2_RXDMAEN (1 << 0) /* Bit 0: Rx Buffer DMA Enable */
#define SPI_CR2_TXDMAEN (1 << 1) /* Bit 1: Tx Buffer DMA Enable */
#define SPI_CR2_SSOE (1 << 2) /* Bit 2: SS Output Enable */
#define SPI_CR2_NSSP (1 << 3) /* Bit 3 NSSP: NSS pulse management */
#define SPI_CR2_FRF (1 << 4) /* Bit 4: Frame format */
#define SPI_CR2_ERRIE (1 << 5) /* Bit 5: Error interrupt enable */
#define SPI_CR2_RXNEIE (1 << 6) /* Bit 6: RX buffer not empty interrupt enable */
#define SPI_CR2_TXEIE (1 << 7) /* Bit 7: Tx buffer empty interrupt enable */
#define SPI_CR2_DS_SHIFT (8) /* Bits 8-11: Data size */
#define SPI_CR2_DS_MASK (0xf << SPI_CR2_DS_SHIFT)
# define SPI_CR2_DS_VAL(bits) (((bits)-1) << SPI_CR2_DS_SHIFT)
# define SPI_CR2_DS_4BIT SPI_CR2_DS_VAL(4)
# define SPI_CR2_DS_5BIT SPI_CR2_DS_VAL(5)
# define SPI_CR2_DS_6BIT SPI_CR2_DS_VAL(6)
# define SPI_CR2_DS_7BIT SPI_CR2_DS_VAL(7)
# define SPI_CR2_DS_8BIT SPI_CR2_DS_VAL(8)
# define SPI_CR2_DS_9BIT SPI_CR2_DS_VAL(9)
# define SPI_CR2_DS_10BIT SPI_CR2_DS_VAL(10)
# define SPI_CR2_DS_11BIT SPI_CR2_DS_VAL(11)
# define SPI_CR2_DS_12BIT SPI_CR2_DS_VAL(12)
# define SPI_CR2_DS_13BIT SPI_CR2_DS_VAL(13)
# define SPI_CR2_DS_14BIT SPI_CR2_DS_VAL(14)
# define SPI_CR2_DS_15BIT SPI_CR2_DS_VAL(15)
# define SPI_CR2_DS_16BIT SPI_CR2_DS_VAL(16)
#define SPI_CR2_FRXTH (1 << 12) /* Bit 12: FIFO reception threshold */
#define SPI_CR2_LDMARX (1 << 13) /* Bit 13: Last DMA transfer for receptione */
#define SPI_CR2_LDMATX (1 << 14) /* Bit 14: Last DMA transfer for transmission */
/* SPI status register */
#define SPI_SR_RXNE (1 << 0) /* Bit 0: Receive buffer not empty */
#define SPI_SR_TXE (1 << 1) /* Bit 1: Transmit buffer empty */
#define SPI_SR_CHSIDE (1 << 2) /* Bit 2: Channel side (i2s) */
#define SPI_SR_UDR (1 << 3) /* Bit 3: Underrun flag (i2s) */
#define SPI_SR_CRCERR (1 << 4) /* Bit 4: CRC error flag */
#define SPI_SR_MODF (1 << 5) /* Bit 5: Mode fault */
#define SPI_SR_OVR (1 << 6) /* Bit 6: Overrun flag */
#define SPI_SR_BSY (1 << 7) /* Bit 7: Busy flag */
#define SPI_SR_FRE (1 << 8) /* Bit 8: Frame format error */
#define SPI_SR_FRLVL_SHIFT (9) /* Bits 9-10: FIFO reception level */
#define SPI_SR_FRLVL_MASK (3 << SPI_SR_FRLVL_SHIFT)
# define SPI_SR_FRLVL_EMPTY (0 << SPI_SR_FRLVL_SHIFT) /* FIFO empty */
# define SPI_SR_FRLVL_QUARTER (1 << SPI_SR_FRLVL_SHIFT) /* 1/4 FIFO */
# define SPI_SR_FRLVL_HALF (2 << SPI_SR_FRLVL_SHIFT) /* 1/2 FIFO */
# define SPI_SR_FRLVL_FULL (3 << SPI_SR_FRLVL_SHIFT) /* FIFO full */
#define SPI_SR_FTLVL_SHIFT (11) /* Bits 11-12: FIFO transmission level */
#define SPI_SR_FTLVL_MASK (3 << SPI_SR_FTLVL_SHIFT)
# define SPI_SR_FTLVL_EMPTY (0 << SPI_SR_FTLVL_SHIFT) /* FIFO empty */
# define SPI_SR_FTLVL_QUARTER (1 << SPI_SR_FTLVL_SHIFT) /* 1/4 FIFO */
# define SPI_SR_FTLVL_HALF (2 << SPI_SR_FTLVL_SHIFT) /* 1/2 FIFO */
# define SPI_SR_FTLVL_FULL (3 << SPI_SR_FTLVL_SHIFT) /* FIFO full */
/* I2S configuration register */
#define SPI_I2SCFGR_CHLEN (1 << 0) /* Bit 0: Channel length (number of bits per audio channel) */
#define SPI_I2SCFGR_DATLEN_SHIFT (1) /* Bit 1-2: Data length to be transferred */
#define SPI_I2SCFGR_DATLEN_MASK (3 << SPI_I2SCFGR_DATLEN_SHIFT)
# define SPI_I2SCFGR_DATLEN_16BIT (0 << SPI_I2SCFGR_DATLEN_SHIFT) /* 00: 16-bit data length */
# define SPI_I2SCFGR_DATLEN_24BIT (1 << SPI_I2SCFGR_DATLEN_SHIFT) /* 01: 24-bit data length */
# define SPI_I2SCFGR_DATLEN_32BIT (2 << SPI_I2SCFGR_DATLEN_SHIFT) /* 10: 32-bit data length */
#define SPI_I2SCFGR_CKPOL (1 << 3) /* Bit 3: Steady state clock polarity */
#define SPI_I2SCFGR_I2SSTD_SHIFT (4) /* Bit 4-5: I2S standard selection */
#define SPI_I2SCFGR_I2SSTD_MASK (3 << SPI_I2SCFGR_I2SSTD_SHIFT)
# define SPI_I2SCFGR_I2SSTD_PHILLIPS (0 << SPI_I2SCFGR_I2SSTD_SHIFT) /* 00: I2S Phillips standard. */
# define SPI_I2SCFGR_I2SSTD_MSB (1 << SPI_I2SCFGR_I2SSTD_SHIFT) /* 01: MSB justified standard (left justified) */
# define SPI_I2SCFGR_I2SSTD_LSB (2 << SPI_I2SCFGR_I2SSTD_SHIFT) /* 10: LSB justified standard (right justified) */
# define SPI_I2SCFGR_I2SSTD_PCM (3 << SPI_I2SCFGR_I2SSTD_SHIFT) /* 11: PCM standard */
#define SPI_I2SCFGR_PCMSYNC (1 << 7) /* Bit 7: PCM frame synchronization */
#define SPI_I2SCFGR_I2SCFG_SHIFT (8) /* Bit 8-9: I2S configuration mode */
#define SPI_I2SCFGR_I2SCFG_MASK (3 << SPI_I2SCFGR_I2SCFG_SHIFT)
# define SPI_I2SCFGR_I2SCFG_STX (0 << SPI_I2SCFGR_I2SCFG_SHIFT) /* 00: Slave - transmit */
# define SPI_I2SCFGR_I2SCFG_SRX (1 << SPI_I2SCFGR_I2SCFG_SHIFT) /* 01: Slave - receive */
# define SPI_I2SCFGR_I2SCFG_MTX (2 << SPI_I2SCFGR_I2SCFG_SHIFT) /* 10: Master - transmit */
# define SPI_I2SCFGR_I2SCFG_MRX (3 << SPI_I2SCFGR_I2SCFG_SHIFT) /* 11: Master - receive */
#define SPI_I2SCFGR_I2SE (1 << 10) /* Bit 10: I2S Enable */
#define SPI_I2SCFGR_I2SMOD (1 << 11) /* Bit 11: I2S mode selection */
/* I2S prescaler register */
#define SPI_I2SPR_I2SDIV_SHIFT (0) /* Bit 0-7: I2S Linear prescaler */
#define SPI_I2SPR_I2SDIV_MASK (0xff << SPI_I2SPR_I2SDIV_SHIFT)
#define SPI_I2SPR_ODD (1 << 8) /* Bit 8: Odd factor for the prescaler */
#define SPI_I2SPR_MCKOE (1 << 9) /* Bit 9: Master clock output enable */
#endif /* __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_SPI_H */

View File

@ -0,0 +1,391 @@
/****************************************************************************************************
* arch/arm/src/stm32f0/chip/stm32f0_syscfg.h
*
* Copyright (C) 2017 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
* Alan Carvalho de Assis <acassis@gmail.com>
*
* 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 NuttX 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 OWNER 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.
*
****************************************************************************************************/
#ifndef __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_SYSCFG_H
#define __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_SYSCFG_H
/****************************************************************************************************
* Included Files
****************************************************************************************************/
#include <nuttx/config.h>
#include "chip.h"
/****************************************************************************************************
* Pre-processor Definitions
****************************************************************************************************/
/* Register Offsets *********************************************************************************/
#define STM32F0_SYSCFG_CFGR1_OFFSET 0x0000 /* SYSCFG configuration register 1 */
#define STM32F0_SYSCFG_EXTICR_OFFSET(p) (0x0008 + ((p) & 0x000c)) /* Registers are displaced by 4! */
#define STM32F0_SYSCFG_EXTICR1_OFFSET 0x0008 /* SYSCFG external interrupt configuration register 1 */
#define STM32F0_SYSCFG_EXTICR2_OFFSET 0x000c /* SYSCFG external interrupt configuration register 2 */
#define STM32F0_SYSCFG_EXTICR3_OFFSET 0x0010 /* SYSCFG external interrupt configuration register 3 */
#define STM32F0_SYSCFG_EXTICR4_OFFSET 0x0014 /* SYSCFG external interrupt configuration register 4 */
#define STM32F0_SYSCFG_CFGR2_OFFSET 0x0018 /* SYSCFG configuration register 2 */
#define STM32F0_SYSCFG_ITLINE0_OFFSET 0x0080 /* SYSCFG interrupt line 0 status register (STM32F09x) */
#define STM32F0_SYSCFG_ITLINE1_OFFSET 0x0084 /* SYSCFG interrupt line 1 status register (STM32F09x) */
#define STM32F0_SYSCFG_ITLINE2_OFFSET 0x0088 /* SYSCFG interrupt line 2 status register (STM32F09x) */
#define STM32F0_SYSCFG_ITLINE3_OFFSET 0x008c /* SYSCFG interrupt line 3 status register (STM32F09x) */
#define STM32F0_SYSCFG_ITLINE4_OFFSET 0x0090 /* SYSCFG interrupt line 4 status register (STM32F09x) */
#define STM32F0_SYSCFG_ITLINE5_OFFSET 0x0094 /* SYSCFG interrupt line 5 status register (STM32F09x) */
#define STM32F0_SYSCFG_ITLINE6_OFFSET 0x0098 /* SYSCFG interrupt line 6 status register (STM32F09x) */
#define STM32F0_SYSCFG_ITLINE7_OFFSET 0x009c /* SYSCFG interrupt line 7 status register (STM32F09x) */
#define STM32F0_SYSCFG_ITLINE8_OFFSET 0x00a0 /* SYSCFG interrupt line 8 status register (STM32F09x) */
#define STM32F0_SYSCFG_ITLINE9_OFFSET 0x00a4 /* SYSCFG interrupt line 9 status register (STM32F09x) */
#define STM32F0_SYSCFG_ITLINE10_OFFSET 0x00a8 /* SYSCFG interrupt line 10 status register (STM32F09x) */
#define STM32F0_SYSCFG_ITLINE11_OFFSET 0x00ac /* SYSCFG interrupt line 11 status register (STM32F09x) */
#define STM32F0_SYSCFG_ITLINE12_OFFSET 0x00b0 /* SYSCFG interrupt line 12 status register (STM32F09x) */
#define STM32F0_SYSCFG_ITLINE13_OFFSET 0x00b4 /* SYSCFG interrupt line 13 status register (STM32F09x) */
#define STM32F0_SYSCFG_ITLINE14_OFFSET 0x00b8 /* SYSCFG interrupt line 14 status register (STM32F09x) */
#define STM32F0_SYSCFG_ITLINE15_OFFSET 0x00bc /* SYSCFG interrupt line 15 status register (STM32F09x) */
#define STM32F0_SYSCFG_ITLINE16_OFFSET 0x00c0 /* SYSCFG interrupt line 16 status register (STM32F09x) */
#define STM32F0_SYSCFG_ITLINE17_OFFSET 0x00c4 /* SYSCFG interrupt line 17 status register (STM32F09x) */
#define STM32F0_SYSCFG_ITLINE18_OFFSET 0x00c8 /* SYSCFG interrupt line 18 status register (STM32F09x) */
#define STM32F0_SYSCFG_ITLINE19_OFFSET 0x00cc /* SYSCFG interrupt line 19 status register (STM32F09x) */
#define STM32F0_SYSCFG_ITLINE20_OFFSET 0x00d0 /* SYSCFG interrupt line 20 status register (STM32F09x) */
#define STM32F0_SYSCFG_ITLINE21_OFFSET 0x00d4 /* SYSCFG interrupt line 21 status register (STM32F09x) */
#define STM32F0_SYSCFG_ITLINE22_OFFSET 0x00d8 /* SYSCFG interrupt line 22 status register (STM32F09x) */
#define STM32F0_SYSCFG_ITLINE23_OFFSET 0x00dc /* SYSCFG interrupt line 23 status register (STM32F09x) */
#define STM32F0_SYSCFG_ITLINE24_OFFSET 0x00e0 /* SYSCFG interrupt line 24 status register (STM32F09x) */
#define STM32F0_SYSCFG_ITLINE25_OFFSET 0x00e4 /* SYSCFG interrupt line 25 status register (STM32F09x) */
#define STM32F0_SYSCFG_ITLINE26_OFFSET 0x00e8 /* SYSCFG interrupt line 26 status register (STM32F09x) */
#define STM32F0_SYSCFG_ITLINE27_OFFSET 0x00ec /* SYSCFG interrupt line 27 status register (STM32F09x) */
#define STM32F0_SYSCFG_ITLINE28_OFFSET 0x00f0 /* SYSCFG interrupt line 28 status register (STM32F09x) */
#define STM32F0_SYSCFG_ITLINE29_OFFSET 0x00f4 /* SYSCFG interrupt line 29 status register (STM32F09x) */
#define STM32F0_SYSCFG_ITLINE30_OFFSET 0x00f8 /* SYSCFG interrupt line 30 status register (STM32F09x) */
/* Register Addresses *******************************************************************************/
#define STM32F0_SYSCFG_CFGR1 (STM32F0_SYSCFG_BASE+STM32F0_SYSCFG_CFGR1_OFFSET)
#define STM32F0_SYSCFG_EXTICR(p) (STM32F0_SYSCFG_BASE+STM32F0_SYSCFG_EXTICR_OFFSET(p))
#define STM32F0_SYSCFG_EXTICR1 (STM32F0_SYSCFG_BASE+STM32F0_SYSCFG_EXTICR1_OFFSET)
#define STM32F0_SYSCFG_EXTICR2 (STM32F0_SYSCFG_BASE+STM32F0_SYSCFG_EXTICR2_OFFSET)
#define STM32F0_SYSCFG_EXTICR3 (STM32F0_SYSCFG_BASE+STM32F0_SYSCFG_EXTICR3_OFFSET)
#define STM32F0_SYSCFG_EXTICR4 (STM32F0_SYSCFG_BASE+STM32F0_SYSCFG_EXTICR4_OFFSET)
#define STM32F0_SYSCFG_CFGR2 (STM32F0_SYSCFG_BASE+STM32F0_SYSCFG_CFGR2_OFFSET)
#define STM32F0_SYSCFG_ITLINE0 (STM32F0_SYSCFG_BASE+STM32F0_SYSCFG_ITLINE0_OFFSET)
#define STM32F0_SYSCFG_ITLINE1 (STM32F0_SYSCFG_BASE+STM32F0_SYSCFG_ITLINE1_OFFSET)
#define STM32F0_SYSCFG_ITLINE2 (STM32F0_SYSCFG_BASE+STM32F0_SYSCFG_ITLINE2_OFFSET)
#define STM32F0_SYSCFG_ITLINE3 (STM32F0_SYSCFG_BASE+STM32F0_SYSCFG_ITLINE3_OFFSET)
#define STM32F0_SYSCFG_ITLINE4 (STM32F0_SYSCFG_BASE+STM32F0_SYSCFG_ITLINE4_OFFSET)
#define STM32F0_SYSCFG_ITLINE5 (STM32F0_SYSCFG_BASE+STM32F0_SYSCFG_ITLINE5_OFFSET)
#define STM32F0_SYSCFG_ITLINE6 (STM32F0_SYSCFG_BASE+STM32F0_SYSCFG_ITLINE6_OFFSET)
#define STM32F0_SYSCFG_ITLINE7 (STM32F0_SYSCFG_BASE+STM32F0_SYSCFG_ITLINE7_OFFSET)
#define STM32F0_SYSCFG_ITLINE8 (STM32F0_SYSCFG_BASE+STM32F0_SYSCFG_ITLINE8_OFFSET)
#define STM32F0_SYSCFG_ITLINE9 (STM32F0_SYSCFG_BASE+STM32F0_SYSCFG_ITLINE9_OFFSET)
#define STM32F0_SYSCFG_ITLINE10 (STM32F0_SYSCFG_BASE+STM32F0_SYSCFG_ITLINE10_OFFSET)
#define STM32F0_SYSCFG_ITLINE11 (STM32F0_SYSCFG_BASE+STM32F0_SYSCFG_ITLINE11_OFFSET)
#define STM32F0_SYSCFG_ITLINE12 (STM32F0_SYSCFG_BASE+STM32F0_SYSCFG_ITLINE12_OFFSET)
#define STM32F0_SYSCFG_ITLINE13 (STM32F0_SYSCFG_BASE+STM32F0_SYSCFG_ITLINE13_OFFSET)
#define STM32F0_SYSCFG_ITLINE14 (STM32F0_SYSCFG_BASE+STM32F0_SYSCFG_ITLINE14_OFFSET)
#define STM32F0_SYSCFG_ITLINE15 (STM32F0_SYSCFG_BASE+STM32F0_SYSCFG_ITLINE15_OFFSET)
#define STM32F0_SYSCFG_ITLINE16 (STM32F0_SYSCFG_BASE+STM32F0_SYSCFG_ITLINE16_OFFSET)
#define STM32F0_SYSCFG_ITLINE17 (STM32F0_SYSCFG_BASE+STM32F0_SYSCFG_ITLINE17_OFFSET)
#define STM32F0_SYSCFG_ITLINE18 (STM32F0_SYSCFG_BASE+STM32F0_SYSCFG_ITLINE18_OFFSET)
#define STM32F0_SYSCFG_ITLINE19 (STM32F0_SYSCFG_BASE+STM32F0_SYSCFG_ITLINE19_OFFSET)
#define STM32F0_SYSCFG_ITLINE20 (STM32F0_SYSCFG_BASE+STM32F0_SYSCFG_ITLINE20_OFFSET)
#define STM32F0_SYSCFG_ITLINE21 (STM32F0_SYSCFG_BASE+STM32F0_SYSCFG_ITLINE21_OFFSET)
#define STM32F0_SYSCFG_ITLINE22 (STM32F0_SYSCFG_BASE+STM32F0_SYSCFG_ITLINE22_OFFSET)
#define STM32F0_SYSCFG_ITLINE23 (STM32F0_SYSCFG_BASE+STM32F0_SYSCFG_ITLINE23_OFFSET)
#define STM32F0_SYSCFG_ITLINE24 (STM32F0_SYSCFG_BASE+STM32F0_SYSCFG_ITLINE24_OFFSET)
#define STM32F0_SYSCFG_ITLINE25 (STM32F0_SYSCFG_BASE+STM32F0_SYSCFG_ITLINE25_OFFSET)
#define STM32F0_SYSCFG_ITLINE26 (STM32F0_SYSCFG_BASE+STM32F0_SYSCFG_ITLINE26_OFFSET)
#define STM32F0_SYSCFG_ITLINE27 (STM32F0_SYSCFG_BASE+STM32F0_SYSCFG_ITLINE27_OFFSET)
#define STM32F0_SYSCFG_ITLINE28 (STM32F0_SYSCFG_BASE+STM32F0_SYSCFG_ITLINE28_OFFSET)
#define STM32F0_SYSCFG_ITLINE29 (STM32F0_SYSCFG_BASE+STM32F0_SYSCFG_ITLINE29_OFFSET)
#define STM32F0_SYSCFG_ITLINE30 (STM32F0_SYSCFG_BASE+STM32F0_SYSCFG_ITLINE30_OFFSET)
/* Register Bitfield Definitions ********************************************************************/
/* SYSCFG memory remap register */
#define SYSCFG_CFGR1_MEMMODE_SHIFT (0) /* Bits 1:0 MEM_MODE: Memory mapping selection */
#define SYSCFG_CFGR1_MEMMODE_MASK (3 << SYSCFG_CFGR1_MEMMODE_SHIFT)
# define SYSCFG_CFGR1_MEMMODE_FLASH (0 << SYSCFG_CFGR1_MEMMODE_SHIFT) /* 00: Main Flash at 0x00000000 */
# define SYSCFG_CFGR1_MEMMODE_SYSTEM (1 << SYSCFG_CFGR1_MEMMODE_SHIFT) /* 01: System Flash at 0x00000000 */
# define SYSCFG_CFGR1_MEMMODE_SRAM (3 << SYSCFG_CFGR1_MEMMODE_SHIFT) /* 11: Embedded SRAM at 0x00000000 */
#define SYSCFG_CFGR1_PA11_PA12_RMP (1 << 4) /* Bit 4: PA11 and PA12 remapping bit for small packages */
#define SYSCFG_CFGR1_IRMOD_SHIFT (6) /* Bits 6-7: IR Modulation Envelope signal selection */
#define SYSCFG_CFGR1_IRMOD_MASK (3 << SYSCFG_CFGR1_IRMOD_SHIFT)
# define SYSCFG_CFGR1_IRMOD_TIM16 (0 << SYSCFG_CFGR1_IRMOD_SHIFT) /* 00: TIM16 selected */
# define SYSCFG_CFGR1_IRMOD_USART1 (1 << SYSCFG_CFGR1_IRMOD_SHIFT) /* 01: USART1 selected */
# define SYSCFG_CFGR1_IRMOD_USART4 (2 << SYSCFG_CFGR1_IRMOD_SHIFT) /* 10: USART1 selected */
#define SYSCFG_CFGR1_ADC_DMARMP (1 << 8) /* Bit 8: ADC DMA remapping bit. Only STM32F03x/F04x/F05x/F07x */
#define SYSCFG_CFGR1_USART1_TXDMARMP (1 << 9) /* Bit 9: USART1_TX_DMA request remapping bit. Only STM32F03x/F04x/F05x/F07x */
#define SYSCFG_CFGR1_USART1_RXDMARMP (1 << 10) /* Bit 10: USART1_TX_DMA request remapping bit. Only STM32F03x/F04x/F05x/F07x */
#define SYSCFG_CFGR1_TIM16_DMARMP (1 << 11) /* Bit 11: TIM16 DMA request remapping bit */
#define SYSCFG_CFGR1_TIM17_DMARMP (1 << 12) /* Bit 12: TIM17 DMA request remapping bit */
#define SYSCFG_CFGR1_TIM16_DMARMP2 (1 << 13) /* Bit 13: TIM16 alternate DMA request remapping bit */
#define SYSCFG_CFGR1_TIM17_DMARMP2 (1 << 14) /* Bit 14: TIM17 alternate DMA request remapping bit */
#define SYSCFG_CFGR1_I2C_PBXFMP_SHIFT (16) /* Bits 16-19: Fast Mode Plus (FM+) driving capability */
#define SYSCFG_CFGR1_I2C_PBXFMP_MASK (15 << SYSCFG_CFGR1_I2C_PBXFMP_SHIFT)
#define SYSCFG_CFGR1_I2C1_FMP (1 << 20) /* Bit 20: I2C1 fast mode Plus driving capability */
#define SYSCFG_CFGR1_I2C2_FMP (1 << 21) /* Bit 21: I2C2 fast mode Plus driving capability */
#define SYSCFG_CFGR1_I2C_PAXFMP_SHIFT (22) /* Bits 22-23: Fast Mode Plus (FM+) driving capability */
#define SYSCFG_CFGR1_I2C_PAXFMP_MASK (3 << SYSCFG_CFGR1_I2C_PAXFMP_SHIFT)
#define SYSCFG_CFGR1_SPI2_DMARMP (1 << 24) /* Bit 24: SPI2 DMA request remapping bit. */
#define SYSCFG_CFGR1_USART2_DMARMP (1 << 25) /* Bit 25: USART2 DMA request remapping bit. */
#define SYSCFG_CFGR1_USART3_DMARMP (1 << 26) /* Bit 26: USART3 DMA request remapping bit. */
#define SYSCFG_CFGR1_I2C1_DMARMP (1 << 27) /* Bit 27: I2C1 DMA request remapping bit. */
#define SYSCFG_CFGR1_TIM1_DMARMP (1 << 28) /* Bit 28: TIM1 DMA request remapping bit. */
#define SYSCFG_CFGR1_TIM2_DMARMP (1 << 29) /* Bit 29: TIM2 DMA request remapping bit. */
#define SYSCFG_CFGR1_TIM3_DMARMP (1 << 30) /* Bit 30: TIM3 DMA request remapping bit. */
/* SYSCFG external interrupt configuration register 1-4 */
#define SYSCFG_EXTICR_PORTA (0) /* 0000: PA[x] pin */
#define SYSCFG_EXTICR_PORTB (1) /* 0001: PB[x] pin */
#define SYSCFG_EXTICR_PORTC (2) /* 0010: PC[x] pin */
#define SYSCFG_EXTICR_PORTD (3) /* 0011: PD[x] pin */
#define SYSCFG_EXTICR_PORTE (4) /* 0100: PE[x] pin */
#define SYSCFG_EXTICR_PORTF (5) /* 0101: PF[x] pin */
#define SYSCFG_EXTICR_PORT_MASK (15)
#define SYSCFG_EXTICR_EXTI_SHIFT(g) (((g) & 3) << 2)
#define SYSCFG_EXTICR_EXTI_MASK(g) (SYSCFG_EXTICR_PORT_MASK << (SYSCFG_EXTICR_EXTI_SHIFT(g)))
#define SYSCFG_EXTICR1_EXTI0_SHIFT (0) /* Bits 0-3: EXTI 0 coinfiguration */
#define SYSCFG_EXTICR1_EXTI0_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR1_EXTI0_SHIFT)
#define SYSCFG_EXTICR1_EXTI1_SHIFT (4) /* Bits 4-7: EXTI 1 coinfiguration */
#define SYSCFG_EXTICR1_EXTI1_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR1_EXTI1_SHIFT)
#define SYSCFG_EXTICR1_EXTI2_SHIFT (8) /* Bits 8-11: EXTI 2 coinfiguration */
#define SYSCFG_EXTICR1_EXTI2_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR1_EXTI2_SHIFT)
#define SYSCFG_EXTICR1_EXTI3_SHIFT (12) /* Bits 12-15: EXTI 3 coinfiguration */
#define SYSCFG_EXTICR1_EXTI3_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR1_EXTI3_SHIFT)
#define SYSCFG_EXTICR2_EXTI4_SHIFT (0) /* Bits 0-3: EXTI 4 coinfiguration */
#define SYSCFG_EXTICR2_EXTI4_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR2_EXTI4_SHIFT)
#define SYSCFG_EXTICR2_EXTI5_SHIFT (4) /* Bits 4-7: EXTI 5 coinfiguration */
#define SYSCFG_EXTICR2_EXTI5_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR2_EXTI5_SHIFT)
#define SYSCFG_EXTICR2_EXTI6_SHIFT (8) /* Bits 8-11: EXTI 6 coinfiguration */
#define SYSCFG_EXTICR2_EXTI6_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR2_EXTI6_SHIFT)
#define SYSCFG_EXTICR2_EXTI7_SHIFT (12) /* Bits 12-15: EXTI 7 coinfiguration */
#define SYSCFG_EXTICR2_EXTI7_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR2_EXTI7_SHIFT)
#define SYSCFG_EXTICR3_EXTI8_SHIFT (0) /* Bits 0-3: EXTI 8 coinfiguration */
#define SYSCFG_EXTICR3_EXTI8_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR3_EXTI8_SHIFT)
#define SYSCFG_EXTICR3_EXTI9_SHIFT (4) /* Bits 4-7: EXTI 9 coinfiguration */
#define SYSCFG_EXTICR3_EXTI9_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR3_EXTI9_SHIFT)
#define SYSCFG_EXTICR3_EXTI10_SHIFT (8) /* Bits 8-11: EXTI 10 coinfiguration */
#define SYSCFG_EXTICR3_EXTI10_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR3_EXTI10_SHIFT)
#define SYSCFG_EXTICR3_EXTI11_SHIFT (12) /* Bits 12-15: EXTI 11 coinfiguration */
#define SYSCFG_EXTICR3_EXTI11_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR3_EXTI11_SHIFT)
#define SYSCFG_EXTICR4_EXTI12_SHIFT (0) /* Bits 0-3: EXTI 12 coinfiguration */
#define SYSCFG_EXTICR4_EXTI12_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR4_EXTI12_SHIFT)
#define SYSCFG_EXTICR4_EXTI13_SHIFT (4) /* Bits 4-7: EXTI 13 coinfiguration */
#define SYSCFG_EXTICR4_EXTI13_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR4_EXTI13_SHIFT)
#define SYSCFG_EXTICR4_EXTI14_SHIFT (8) /* Bits 8-11: EXTI 14 coinfiguration */
#define SYSCFG_EXTICR4_EXTI14_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR4_EXTI14_SHIFT)
#define SYSCFG_EXTICR4_EXTI15_SHIFT (12) /* Bits 12-15: EXTI 15 coinfiguration */
#define SYSCFG_EXTICR4_EXTI15_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR4_EXTI15_SHIFT)
/* SYSCFG configuration register 2 */
#define SYSCFG_CFGR2_LOCKUPLOCK (1 << 0) /* Bit 0: Cortex-M0 Hardfault output bit enable */
#define SYSCFG_CFGR2_SRAM_PARITYLOCK (1 << 1) /* Bit 1: RAM parity lock */
#define SYSCFG_CFGR2_PVDLOCK (1 << 2) /* Bit 2: PVD lock enable */
#define SYSCFG_CFGR2_SRAM_PEF (1 << 8) /* Bit 8: SRAM parity error */
/* SYSCFG interrupt line 0 status register */
#define SYSCFG_ITLINE0_WWDG (1 << 0) /* Bit 0: Window Watchdog interrupt pending flag */
/* SYSCFG interrupt line 1 status register */
#define SYSCFG_ITLINE1_PVDOUT (1 << 0) /* Bit 0: PVD supply monitoring interrupt request pending (EXTI line 16) */
#define SYSCFG_ITLINE1_VDDIO2 (1 << 0) /* Bit 1: VDDIO2 supply monitoring interrupt request pending (EXTI line 31) */
/* SYSCFG interrupt line 2 status register */
#define SYSCFG_ITLINE2_RTC_WAKEUP (1 << 0) /* Bit 0: RTC Wake Up interrupt request pending (EXTI line 20) */
#define SYSCFG_ITLINE2_RTC_TSTAMP (1 << 1) /* Bit 1: RTC Tamper and TimeStamp interrupt request pending (EXTI line 19) */
#define SYSCFG_ITLINE2_RTC_ALRA (1 << 2) /* Bit 2: RTC Alarm interrupt request pending (EXTI line 17) */
/* SYSCFG interrupt line 3 status register */
#define SYSCFG_ITLINE3_FLASH_ITF (1 << 0) /* Bit 0: Flash interface interrupt request pending */
/* SYSCFG interrupt line 4 status register */
#define SYSCFG_ITLINE4_RCC (1 << 0) /* Bit 0: Reset and clock control interrupt request pending */
#define SYSCFG_ITLINE4_CRS (1 << 1) /* Bit 1: Clock recovery system interrupt request pending */
/* SYSCFG interrupt line 5 status register */
#define SYSCFG_ITLINE5_EXTI0 (1 << 0) /* Bit 0: EXTI line 0 interrupt request pending */
#define SYSCFG_ITLINE5_EXTI1 (1 << 1) /* Bit 1: EXTI line 1 interrupt request pending */
/* SYSCFG interrupt line 6 status register */
#define SYSCFG_ITLINE6_EXTI2 (1 << 0) /* Bit 0: EXTI line 2 interrupt request pending */
#define SYSCFG_ITLINE6_EXTI3 (1 << 1) /* Bit 1: EXTI line 3 interrupt request pending */
/* SYSCFG interrupt line 7 status register */
#define SYSCFG_ITLINE7_EXTI4 (1 << 0) /* Bit 0: EXTI line 4 interrupt request pending */
#define SYSCFG_ITLINE7_EXTI5 (1 << 1) /* Bit 1: EXTI line 5 interrupt request pending */
#define SYSCFG_ITLINE7_EXTI6 (1 << 2) /* Bit 2: EXTI line 6 interrupt request pending */
#define SYSCFG_ITLINE7_EXTI7 (1 << 3) /* Bit 3: EXTI line 7 interrupt request pending */
#define SYSCFG_ITLINE7_EXTI8 (1 << 4) /* Bit 4: EXTI line 8 interrupt request pending */
#define SYSCFG_ITLINE7_EXTI9 (1 << 5) /* Bit 5: EXTI line 9 interrupt request pending */
#define SYSCFG_ITLINE7_EXTI10 (1 << 6) /* Bit 6: EXTI line 10 interrupt request pending */
#define SYSCFG_ITLINE7_EXTI11 (1 << 7) /* Bit 7: EXTI line 11 interrupt request pending */
#define SYSCFG_ITLINE7_EXTI12 (1 << 8) /* Bit 8: EXTI line 12 interrupt request pending */
#define SYSCFG_ITLINE7_EXTI13 (1 << 9) /* Bit 9: EXTI line 13 interrupt request pending */
#define SYSCFG_ITLINE7_EXTI14 (1 << 10) /* Bit 10: EXTI line 14 interrupt request pending */
#define SYSCFG_ITLINE7_EXTI15 (1 << 11) /* Bit 11: EXTI line 15 interrupt request pending */
/* SYSCFG interrupt line 8 status register */
#define SYSCFG_ITLINE8_TCS_MCE (1 << 0) /* Bit 0: Touch sensing controller max count error interrupt request pending */
#define SYSCFG_ITLINE8_TCS_EOA (1 << 1) /* Bit 1: Touch sensing controller end of acquisition interrupt request pending */
/* SYSCFG interrupt line 9 status register */
#define SYSCFG_ITLINE9_DMA1_CH1 (1 << 0) /* Bit 0: DMA1 channel 1 interrupt request pending */
/* SYSCFG interrupt line 10 status register */
#define SYSCFG_ITLINE10_DMA1_CH2 (1 << 0) /* Bit 0: DMA1 channel 2 interrupt request pending */
#define SYSCFG_ITLINE10_DMA1_CH3 (1 << 1) /* Bit 1: DMA1 channel 3 interrupt request pending */
#define SYSCFG_ITLINE10_DMA2_CH1 (1 << 2) /* Bit 0: DMA2 channel 1 interrupt request pending */
#define SYSCFG_ITLINE10_DMA2_CH2 (1 << 3) /* Bit 1: DMA2 channel 2 interrupt request pending */
/* SYSCFG interrupt line 11 status register */
#define SYSCFG_ITLINE11_DMA1_CH4 (1 << 0) /* Bit 0: DMA1 channel 4 interrupt request pending */
#define SYSCFG_ITLINE11_DMA1_CH5 (1 << 1) /* Bit 1: DMA1 channel 5 interrupt request pending */
#define SYSCFG_ITLINE11_DMA1_CH6 (1 << 2) /* Bit 2: DMA1 channel 6 interrupt request pending */
#define SYSCFG_ITLINE11_DMA1_CH7 (1 << 3) /* Bit 3: DMA1 channel 7 interrupt request pending */
#define SYSCFG_ITLINE11_DMA2_CH3 (1 << 4) /* Bit 4: DMA2 channel 3 interrupt request pending */
#define SYSCFG_ITLINE11_DMA2_CH4 (1 << 5) /* Bit 5: DMA2 channel 4 interrupt request pending */
#define SYSCFG_ITLINE11_DMA2_CH5 (1 << 6) /* Bit 6: DMA2 channel 5 interrupt request pending */
/* SYSCFG interrupt line 12 status register */
#define SYSCFG_ITLINE12_ADC (1 << 0) /* Bit 0: ADC interrupt request pending */
#define SYSCFG_ITLINE12_COMP1 (1 << 1) /* Bit 1: Comparator 1 interrupt request pending */
#define SYSCFG_ITLINE12_COMP2 (1 << 2) /* Bit 2: Comparator 2 interrupt request pending */
/* SYSCFG interrupt line 13 status register */
#define SYSCFG_ITLINE13_TIM1_CCU (1 << 0) /* Bit 0: TIM1 commutation interrupt request pending */
#define SYSCFG_ITLINE13_TIM1_TRG (1 << 1) /* Bit 1: TIM1 triggerinterrupt request pending */
#define SYSCFG_ITLINE13_TIM1_UPD (1 << 2) /* Bit 2: TIM1 update interrupt request pending */
#define SYSCFG_ITLINE13_TIM1_BRK (1 << 3) /* Bit 3: TIM1 break interrupt request pending */
/* SYSCFG interrupt line 14 status register */
#define SYSCFG_ITLINE14_TIM1_CC (1 << 0) /* Bit 0: TIM1 capture compare interrupt request pending */
/* SYSCFG interrupt line 15 status register */
#define SYSCFG_ITLINE15_TIM2 (1 << 0) /* Bit 0: Timer 2 interrupt request pending */
/* SYSCFG interrupt line 16 status register */
#define SYSCFG_ITLINE16_TIM3 (1 << 0) /* Bit 0: Timer 3 interrupt request pending */
/* SYSCFG interrupt line 17 status register */
#define SYSCFG_ITLINE17_TIM6 (1 << 0) /* Bit 0: Timer 6 interrupt request pending */
#define SYSCFG_ITLINE17_DAC (1 << 1) /* Bit 1: DAC underrun interrupt request pending */
/* SYSCFG interrupt line 18 status register */
#define SYSCFG_ITLINE18_TIM7 (1 << 0) /* Bit 0: Timer 7 interrupt request pending */
/* SYSCFG interrupt line 19 status register */
#define SYSCFG_ITLINE19_TIM14 (1 << 0) /* Bit 0: Timer 14 interrupt request pending */
/* SYSCFG interrupt line 20 status register */
#define SYSCFG_ITLINE20_TIM15 (1 << 0) /* Bit 0: Timer 15 interrupt request pending */
/* SYSCFG interrupt line 21 status register */
#define SYSCFG_ITLINE21_TIM16 (1 << 0) /* Bit 0: Timer 16 interrupt request pending */
/* SYSCFG interrupt line 22 status register */
#define SYSCFG_ITLINE22_TIM17 (1 << 0) /* Bit 0: Timer 17 interrupt request pending */
/* SYSCFG interrupt line 23 status register */
#define SYSCFG_ITLINE23_I2C1 (1 << 0) /* Bit 0: I2C1 interrupt request pending, combined with EXTI line 23 */
/* SYSCFG interrupt line 24 status register */
#define SYSCFG_ITLINE24_I2C2 (1 << 0) /* Bit 0: I2C2 interrupt request pending */
/* SYSCFG interrupt line 25 status register */
#define SYSCFG_ITLINE25_SPI1 (1 << 0) /* Bit 0: SPI1 interrupt request pending */
/* SYSCFG interrupt line 26 status register */
#define SYSCFG_ITLINE26_SPI2 (1 << 0) /* Bit 0: SPI2 interrupt request pending */
/* SYSCFG interrupt line 27 status register */
#define SYSCFG_ITLINE27_USART1 (1 << 0) /* Bit 0: USART1 interrupt request pending */
/* SYSCFG interrupt line 28 status register */
#define SYSCFG_ITLINE28_USART2 (1 << 0) /* Bit 0: USART2 interrupt request pending */
/* SYSCFG interrupt line 29 status register */
#define SYSCFG_ITLINE29_USART3 (1 << 0) /* Bit 0: USART3 interrupt request pending */
#define SYSCFG_ITLINE29_USART4 (1 << 1) /* Bit 1: USART4 interrupt request pending */
#define SYSCFG_ITLINE29_USART5 (1 << 2) /* Bit 2: USART5 interrupt request pending */
#define SYSCFG_ITLINE29_USART6 (1 << 3) /* Bit 3: USART6 interrupt request pending */
#define SYSCFG_ITLINE29_USART7 (1 << 4) /* Bit 4: USART7 interrupt request pending */
#define SYSCFG_ITLINE29_USART8 (1 << 5) /* Bit 5: USART8 interrupt request pending */
/* SYSCFG interrupt line 30 status register */
#define SYSCFG_ITLINE30_CEC (1 << 0) /* Bit 0: CEC interrupt request pending, combined with EXTI line 27 */
#define SYSCFG_ITLINE30_CAN (1 << 1) /* Bit 1: CAN interrupt request pending */
#endif /* __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_SYSCFG_H */

View File

@ -0,0 +1,52 @@
/****************************************************************************************************
* arch/arm/src/stm32f0/chip/stm32f0_tim.h
*
* Copyright (C) 2017 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
* Alan Carvalho de Assis <acassis@gmail.com>
*
* 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 NuttX 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 OWNER 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.
*
****************************************************************************************************/
#ifndef __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_TIM_H
#define __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_TIM_H
/****************************************************************************************************
* Pre-processor Definitions
****************************************************************************************************/
/* TODO: Define the TIMx registers here */
/* Register Offsets *********************************************************************************/
/* Basic Timers - TIM6 and TIM7 */
/* Register Bitfield Definitions ********************************************************************/
#endif /* __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_TIM_H */

View File

@ -0,0 +1,358 @@
/************************************************************************************
* arch/arm/src/stm32f0/chip/stm32f0_uart.h
*
* Copyright (C) 2017 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
* Alan Carvalho de Assis <acassis@gmail.com>
*
* 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 NuttX 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 OWNER 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.
*
************************************************************************************/
#ifndef __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_UART_H
#define __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_UART_H
/************************************************************************************
* Included Files
************************************************************************************/
#include <nuttx/config.h>
#include "chip.h"
/************************************************************************************
* Pre-processor Definitions
************************************************************************************/
/* Register Offsets *****************************************************************/
#define STM32F0_USART_CR1_OFFSET 0x0000 /* Control register 1 */
#define STM32F0_USART_CR2_OFFSET 0x0004 /* Control register 2 */
#define STM32F0_USART_CR3_OFFSET 0x0008 /* Control register 3 */
#define STM32F0_USART_BRR_OFFSET 0x000c /* Baud Rate register */
#define STM32F0_USART_GTPR_OFFSET 0x0010 /* Guard time and prescaler register */
#define STM32F0_USART_RTOR_OFFSET 0x0014 /* Receiver timeout register */
#define STM32F0_USART_RQR_OFFSET 0x0018 /* Request register */
#define STM32F0_USART_ISR_OFFSET 0x001c /* Interrupot and status register */
#define STM32F0_USART_ICR_OFFSET 0x0020 /* Interrupt flag clear register */
#define STM32F0_USART_RDR_OFFSET 0x0024 /* Receive Data register */
#define STM32F0_USART_TDR_OFFSET 0x0028 /* Transmit Data register */
/* Register Addresses ***************************************************************/
#if STM32F0_NUSART > 0
# define STM32F0_USART1_CR1 (STM32F0_USART1_BASE+STM32F0_USART_CR1_OFFSET)
# define STM32F0_USART1_CR2 (STM32F0_USART1_BASE+STM32F0_USART_CR2_OFFSET)
# define STM32F0_USART1_CR3 (STM32F0_USART1_BASE+STM32F0_USART_CR3_OFFSET)
# define STM32F0_USART1_BRR (STM32F0_USART1_BASE+STM32F0_USART_BRR_OFFSET)
# define STM32F0_USART1_GTPR (STM32F0_USART1_BASE+STM32F0_USART_GTPR_OFFSET)
# define STM32F0_USART1_RTOR (STM32F0_USART1_BASE+STM32F0_USART_RTOR_OFFSET)
# define STM32F0_USART1_RQR (STM32F0_USART1_BASE+STM32F0_USART_RQR_OFFSET)
# define STM32F0_USART1_ISR (STM32F0_USART1_BASE+STM32F0_USART_ISR_OFFSET)
# define STM32F0_USART1_ICR (STM32F0_USART1_BASE+STM32F0_USART_ICR_OFFSET)
# define STM32F0_USART1_RDR (STM32F0_USART1_BASE+STM32F0_USART_RDR_OFFSET)
# define STM32F0_USART1_TDR (STM32F0_USART1_BASE+STM32F0_USART_TDR_OFFSET)
#endif
#if STM32F0_NUSART > 1
# define STM32F0_USART2_CR1 (STM32F0_USART2_BASE+STM32F0_USART_CR1_OFFSET)
# define STM32F0_USART2_CR2 (STM32F0_USART2_BASE+STM32F0_USART_CR2_OFFSET)
# define STM32F0_USART2_CR3 (STM32F0_USART2_BASE+STM32F0_USART_CR3_OFFSET)
# define STM32F0_USART2_BRR (STM32F0_USART2_BASE+STM32F0_USART_BRR_OFFSET)
# define STM32F0_USART2_GTPR (STM32F0_USART2_BASE+STM32F0_USART_GTPR_OFFSET)
# define STM32F0_USART2_RTOR (STM32F0_USART2_BASE+STM32F0_USART_RTOR_OFFSET)
# define STM32F0_USART2_RQR (STM32F0_USART2_BASE+STM32F0_USART_RQR_OFFSET)
# define STM32F0_USART2_ISR (STM32F0_USART2_BASE+STM32F0_USART_ISR_OFFSET)
# define STM32F0_USART2_ICR (STM32F0_USART2_BASE+STM32F0_USART_ICR_OFFSET)
# define STM32F0_USART2_RDR (STM32F0_USART2_BASE+STM32F0_USART_RDR_OFFSET)
# define STM32F0_USART2_TDR (STM32F0_USART2_BASE+STM32F0_USART_TDR_OFFSET)
#endif
#if STM32F0_NUSART > 2
# define STM32F0_USART3_CR1 (STM32F0_USART3_BASE+STM32F0_USART_CR1_OFFSET)
# define STM32F0_USART3_CR2 (STM32F0_USART3_BASE+STM32F0_USART_CR2_OFFSET)
# define STM32F0_USART3_CR3 (STM32F0_USART3_BASE+STM32F0_USART_CR3_OFFSET)
# define STM32F0_USART3_BRR (STM32F0_USART3_BASE+STM32F0_USART_BRR_OFFSET)
# define STM32F0_USART3_GTPR (STM32F0_USART3_BASE+STM32F0_USART_GTPR_OFFSET)
# define STM32F0_USART3_RTOR (STM32F0_USART3_BASE+STM32F0_USART_RTOR_OFFSET)
# define STM32F0_USART3_RQR (STM32F0_USART3_BASE+STM32F0_USART_RQR_OFFSET)
# define STM32F0_USART3_ISR (STM32F0_USART3_BASE+STM32F0_USART_ISR_OFFSET)
# define STM32F0_USART3_ICR (STM32F0_USART3_BASE+STM32F0_USART_ICR_OFFSET)
# define STM32F0_USART3_RDR (STM32F0_USART3_BASE+STM32F0_USART_RDR_OFFSET)
# define STM32F0_USART3_TDR (STM32F0_USART3_BASE+STM32F0_USART_TDR_OFFSET)
#endif
#if STM32F0_NUSART > 3
# define STM32F0_UART4_CR1 (STM32F0_UART4_BASE+STM32F0_USART_CR1_OFFSET)
# define STM32F0_UART4_CR2 (STM32F0_UART4_BASE+STM32F0_USART_CR2_OFFSET)
# define STM32F0_UART4_CR3 (STM32F0_UART4_BASE+STM32F0_USART_CR3_OFFSET)
# define STM32F0_UART4_BRR (STM32F0_UART4_BASE+STM32F0_USART_BRR_OFFSET)
# define STM32F0_UART4_GTPR (STM32F0_UART4_BASE+STM32F0_USART_GTPR_OFFSET)
# define STM32F0_UART4_RTOR (STM32F0_UART4_BASE+STM32F0_USART_RTOR_OFFSET)
# define STM32F0_UART4_RQR (STM32F0_UART4_BASE+STM32F0_USART_RQR_OFFSET)
# define STM32F0_UART4_ISR (STM32F0_UART4_BASE+STM32F0_USART_ISR_OFFSET)
# define STM32F0_UART4_ICR (STM32F0_UART4_BASE+STM32F0_USART_ICR_OFFSET)
# define STM32F0_UART4_RDR (STM32F0_UART4_BASE+STM32F0_USART_RDR_OFFSET)
# define STM32F0_UART4_TDR (STM32F0_UART4_BASE+STM32F0_USART_TDR_OFFSET)
#endif
#if STM32F0_NUSART > 4
# define STM32F0_UART5_CR1 (STM32F0_UART5_BASE+STM32F0_USART_CR1_OFFSET)
# define STM32F0_UART5_CR2 (STM32F0_UART5_BASE+STM32F0_USART_CR2_OFFSET)
# define STM32F0_UART5_CR3 (STM32F0_UART5_BASE+STM32F0_USART_CR3_OFFSET)
# define STM32F0_UART5_BRR (STM32F0_UART5_BASE+STM32F0_USART_BRR_OFFSET)
# define STM32F0_UART5_GTPR (STM32F0_UART5_BASE+STM32F0_USART_GTPR_OFFSET)
# define STM32F0_UART5_RTOR (STM32F0_UART5_BASE+STM32F0_USART_RTOR_OFFSET)
# define STM32F0_UART5_RQR (STM32F0_UART5_BASE+STM32F0_USART_RQR_OFFSET)
# define STM32F0_UART5_ISR (STM32F0_UART5_BASE+STM32F0_USART_ISR_OFFSET)
# define STM32F0_UART5_ICR (STM32F0_UART5_BASE+STM32F0_USART_ICR_OFFSET)
# define STM32F0_UART5_RDR (STM32F0_UART5_BASE+STM32F0_USART_RDR_OFFSET)
# define STM32F0_UART5_TDR (STM32F0_UART5_BASE+STM32F0_USART_TDR_OFFSET)
#endif
#if STM32F0_NUSART > 5
# define STM32F0_UART6_CR1 (STM32F0_UART6_BASE+STM32F0_USART_CR1_OFFSET)
# define STM32F0_UART6_CR2 (STM32F0_UART6_BASE+STM32F0_USART_CR2_OFFSET)
# define STM32F0_UART6_CR3 (STM32F0_UART6_BASE+STM32F0_USART_CR3_OFFSET)
# define STM32F0_UART6_BRR (STM32F0_UART6_BASE+STM32F0_USART_BRR_OFFSET)
# define STM32F0_UART6_GTPR (STM32F0_UART6_BASE+STM32F0_USART_GTPR_OFFSET)
# define STM32F0_UART6_RTOR (STM32F0_UART6_BASE+STM32F0_USART_RTOR_OFFSET)
# define STM32F0_UART6_RQR (STM32F0_UART6_BASE+STM32F0_USART_RQR_OFFSET)
# define STM32F0_UART6_ISR (STM32F0_UART6_BASE+STM32F0_USART_ISR_OFFSET)
# define STM32F0_UART6_ICR (STM32F0_UART6_BASE+STM32F0_USART_ICR_OFFSET)
# define STM32F0_UART6_RDR (STM32F0_UART6_BASE+STM32F0_USART_RDR_OFFSET)
# define STM32F0_UART6_TDR (STM32F0_UART6_BASE+STM32F0_USART_TDR_OFFSET)
#endif
#if STM32F0_NUSART > 6
# define STM32F0_UART7_CR1 (STM32F0_UART7_BASE+STM32F0_USART_CR1_OFFSET)
# define STM32F0_UART7_CR2 (STM32F0_UART7_BASE+STM32F0_USART_CR2_OFFSET)
# define STM32F0_UART7_CR3 (STM32F0_UART7_BASE+STM32F0_USART_CR3_OFFSET)
# define STM32F0_UART7_BRR (STM32F0_UART7_BASE+STM32F0_USART_BRR_OFFSET)
# define STM32F0_UART7_GTPR (STM32F0_UART7_BASE+STM32F0_USART_GTPR_OFFSET)
# define STM32F0_UART7_RTOR (STM32F0_UART7_BASE+STM32F0_USART_RTOR_OFFSET)
# define STM32F0_UART7_RQR (STM32F0_UART7_BASE+STM32F0_USART_RQR_OFFSET)
# define STM32F0_UART7_ISR (STM32F0_UART7_BASE+STM32F0_USART_ISR_OFFSET)
# define STM32F0_UART7_ICR (STM32F0_UART7_BASE+STM32F0_USART_ICR_OFFSET)
# define STM32F0_UART7_RDR (STM32F0_UART7_BASE+STM32F0_USART_RDR_OFFSET)
# define STM32F0_UART7_TDR (STM32F0_UART7_BASE+STM32F0_USART_TDR_OFFSET)
#endif
#if STM32F0_NUSART > 7
# define STM32F0_UART8_CR1 (STM32F0_UART8_BASE+STM32F0_USART_CR1_OFFSET)
# define STM32F0_UART8_CR2 (STM32F0_UART8_BASE+STM32F0_USART_CR2_OFFSET)
# define STM32F0_UART8_CR3 (STM32F0_UART8_BASE+STM32F0_USART_CR3_OFFSET)
# define STM32F0_UART8_BRR (STM32F0_UART8_BASE+STM32F0_USART_BRR_OFFSET)
# define STM32F0_UART8_GTPR (STM32F0_UART8_BASE+STM32F0_USART_GTPR_OFFSET)
# define STM32F0_UART8_RTOR (STM32F0_UART8_BASE+STM32F0_USART_RTOR_OFFSET)
# define STM32F0_UART8_RQR (STM32F0_UART8_BASE+STM32F0_USART_RQR_OFFSET)
# define STM32F0_UART8_ISR (STM32F0_UART8_BASE+STM32F0_USART_ISR_OFFSET)
# define STM32F0_UART8_ICR (STM32F0_UART8_BASE+STM32F0_USART_ICR_OFFSET)
# define STM32F0_UART8_RDR (STM32F0_UART8_BASE+STM32F0_USART_RDR_OFFSET)
# define STM32F0_UART8_TDR (STM32F0_UART8_BASE+STM32F0_USART_TDR_OFFSET)
#endif
/* Register Bitfield Definitions ****************************************************/
/* Control register 1 */
#define USART_CR1_UE (1 << 0) /* Bit 0: USART Enable */
#define USART_CR1_UESM (1 << 1) /* Bit 1: USART Enable in Stop mode*/
#define USART_CR1_RE (1 << 2) /* Bit 2: Receiver Enable */
#define USART_CR1_TE (1 << 3) /* Bit 3: Transmitter Enable */
#define USART_CR1_IDLEIE (1 << 4) /* Bit 4: IDLE Interrupt Enable */
#define USART_CR1_RXNEIE (1 << 5) /* Bit 5: RXNE Interrupt Enable */
#define USART_CR1_TCIE (1 << 6) /* Bit 6: Transmission Complete Interrupt Enable */
#define USART_CR1_TXEIE (1 << 7) /* Bit 7: TXE Interrupt Enable */
#define USART_CR1_PEIE (1 << 8) /* Bit 8: PE Interrupt Enable */
#define USART_CR1_PS (1 << 9) /* Bit 9: Parity Selection */
#define USART_CR1_PCE (1 << 10) /* Bit 10: Parity Control Enable */
#define USART_CR1_WAKE (1 << 11) /* Bit 11: Wakeup method */
#define USART_CR1_M0 (1 << 12) /* Bit 12: word length */
#define USART_CR1_MME (1 << 13) /* Bit 13: Mute mode enable */
#define USART_CR1_CMIE (1 << 14) /* Bit 14: Character match interrupt enable */
#define USART_CR1_OVER8 (1 << 15) /* Bit 15: Oversampling mode */
#define USART_CR1_DEDT_SHIFT (16) /* Bits 16..20 DE deactivation delay */
#define USART_CR1_DEDT_MASK (0x1f << USART_CR1_DEDT_SHIFT)
#define USART_CR1_DEAT_SHIFT (21) /* Bits 21..25 DE activation delay */
#define USART_CR1_DEAT_MASK (0x1f << USART_CR1_DEAT_SHIFT)
#define USART_CR1_RTOIE (1 << 26) /* Bit 26: Receiver timeout interrupt enable */
#define USART_CR1_EOBIE (1 << 27) /* Bit 27: End of block interrupt enable */
#define USART_CR1_M1 (1 << 28) /* Bit 12: word length */
#define USART_CR1_ALLINTS (USART_CR1_IDLEIE|USART_CR1_RXNEIE| \
USART_CR1_TCIE|USART_CR1_TXEIE|USART_CR1_PEIE|USART_CR1_CMIE| \
USART_CR1_RTOIE|USART_CR1_EOBIE)
/* Control register 2 */
#define USART_CR2_ADDM7 (1 << 4) /* Bit 4: */
#define USART_CR2_LBDL (1 << 5) /* Bit 5: LIN Break Detection Length */
#define USART_CR2_LBDIE (1 << 6) /* Bit 6: LIN Break Detection Interrupt Enable */
#define USART_CR2_LBCL (1 << 8) /* Bit 8: Last Bit Clock pulse */
#define USART_CR2_CPHA (1 << 9) /* Bit 9: Clock Phase */
#define USART_CR2_CPOL (1 << 10) /* Bit 10: Clock Polarity */
#define USART_CR2_CLKEN (1 << 11) /* Bit 11: Clock Enable */
#define USART_CR2_STOP_SHIFT (12) /* Bits 13-12: STOP bits */
#define USART_CR2_STOP_MASK (3 << USART_CR2_STOP_SHIFT)
# define USART_CR2_STOP1 (0 << USART_CR2_STOP_SHIFT) /* 00: 1 Stop bit */
# define USART_CR2_STOP0p5 (1 << USART_CR2_STOP_SHIFT) /* 01: 0.5 Stop bit */
# define USART_CR2_STOP2 (2 << USART_CR2_STOP_SHIFT) /* 10: 2 Stop bits */
# define USART_CR2_STOP1p5 (3 << USART_CR2_STOP_SHIFT) /* 11: 1.5 Stop bit */
#define USART_CR2_LINEN (1 << 14) /* Bit 14: LIN mode enable */
#define USART_CR2_SWAP (1 << 15) /* Bit 15: Swap TX/RX pins */
#define USART_CR2_RXINV (1 << 16) /* Bit 16: RX pin active level inversion */
#define USART_CR2_TXINV (1 << 17) /* Bit 17: TX pin active level inversion */
#define USART_CR2_DATAINV (1 << 18) /* Bit 18: Binary data inversion */
#define USART_CR2_MSBFIRST (1 << 19) /* Bit 19: Most significant bit first */
#define USART_CR2_ABREN (1 << 20) /* Bit 20: Auto Baud rate enable */
#define USART_CR2_ABRMOD_SHIFT (21) /* Bits 21-22: Autobaud rate mode*/
#define USART_CR2_ABRMOD_MASK (3 << USART_CR2_ABRMOD_SHIFT)
#define USART_CR2_ABRMOD_START (0 << USART_CR2_ABRMOD_SHIFT) /* 00: Start bit */
#define USART_CR2_ABRMOD_EDGES (1 << USART_CR2_ABRMOD_SHIFT) /* 01: Falling-to-falling edge -> frame must start with 10xxxxxx */
#define USART_CR2_ABRMOD_7F (2 << USART_CR2_ABRMOD_SHIFT) /* 10: 0x7F */
#define USART_CR2_ABRMOD_55 (3 << USART_CR2_ABRMOD_SHIFT) /* 11: 0x55 */
#define USART_CR2_RTOEN (1 << 23) /* Bit 23: Receiver timeout enable */
#define USART_CR2_ADD_SHIFT (24) /* Bits 24-31: Address of the USART node */
#define USART_CR2_ADD_MASK (0xff << USART_CR2_ADD_SHIFT)
/* Control register 3 */
#define USART_CR3_EIE (1 << 0) /* Bit 0: Error Interrupt Enable */
#define USART_CR3_IREN (1 << 1) /* Bit 1: IrDA mode Enable */
#define USART_CR3_IRLP (1 << 2) /* Bit 2: IrDA Low-Power */
#define USART_CR3_HDSEL (1 << 3) /* Bit 3: Half-Duplex Selection */
#define USART_CR3_NACK (1 << 4) /* Bit 4: Smartcard NACK enable */
#define USART_CR3_SCEN (1 << 5) /* Bit 5: Smartcard mode enable */
#define USART_CR3_DMAR (1 << 6) /* Bit 6: DMA Enable Receiver */
#define USART_CR3_DMAT (1 << 7) /* Bit 7: DMA Enable Transmitter */
#define USART_CR3_RTSE (1 << 8) /* Bit 8: RTS Enable */
#define USART_CR3_CTSE (1 << 9) /* Bit 9: CTS Enable */
#define USART_CR3_CTSIE (1 << 10) /* Bit 10: CTS Interrupt Enable */
#define USART_CR3_ONEBIT (1 << 11) /* Bit 11: One sample bit method Enable */
#define USART_CR3_OVRDIS (1 << 12) /* Bit 12: Overrun Disable */
#define USART_CR3_DDRE (1 << 13) /* Bit 13: DMA disable on Reception error */
#define USART_CR3_DEM (1 << 14) /* Bit 14: Driver Enable mode */
#define USART_CR3_DEP (1 << 15) /* Bit 15: Driver Enable polarity selection */
#define USART_CR3_SCARCNT2_SHIFT (17) /* Bits 17-19: Smart card auto retry count */
#define USART_CR3_SCARCNT2_MASK (7 << USART_CR3_SCARCNT2_SHIFT)
#define USART_CR3_WUS_SHIFT (20) /* Bits 20-21: Wakeup from Stop mode interrupt flag selection */
#define USART_CR3_WUS_MASK (3 << USART_CR3_WUS_SHIFT)
#define USART_CR3_WUS_ADDRESS (0 << USART_CR3_WUS_SHIFT) /* 00: WUF active on address match */
#define USART_CR3_WUS_START (2 << USART_CR3_WUS_SHIFT) /* 10: WUF active on Start bit detection */
#define USART_CR3_WUS_RXNE (3 << USART_CR3_WUS_SHIFT) /* 11: WUF active on RXNE */
#define USART_CR3_WUFIE (1 << 22) /* Bit 22: Wakeup from Stop mode interrupt enable */
/* Baud Rate Register */
#define USART_BRR_FRAC_SHIFT (0) /* Bits 3-0: fraction of USARTDIV */
#define USART_BRR_FRAC_MASK (0x0f << USART_BRR_FRAC_SHIFT)
#define USART_BRR_MANT_SHIFT (4) /* Bits 15-4: mantissa of USARTDIV */
#define USART_BRR_MANT_MASK (0x0fff << USART_BRR_MANT_SHIFT)
/* Guard time and prescaler register */
#define USART_GTPR_PSC_SHIFT (0) /* Bits 0-7: Prescaler value */
#define USART_GTPR_PSC_MASK (0xff << USART_GTPR_PSC_SHIFT)
#define USART_GTPR_GT_SHIFT (8) /* Bits 8-15: Guard time value */
#define USART_GTPR_GT_MASK (0xff << USART_GTPR_GT_SHIFT)
/* Receiver timeout register */
#define USART_RTOR_RTO_SHIFT (0) /* Bits 0-23: Receiver timeout value */
#define USART_RTOR_RTO_MASK (0xffffff << USART_RTOR_RTO_SHIFT)
#define USART_RTOR_BLEN_SHIFT (24) /* Bits 24-31: Block length */
#define USART_RTOR_BLEN_MASK (0xff << USART_RTOR_BLEN_SHIFT)
/* Request Register */
#define USART_RQR_ABRRQ (1 << 0) /* Bit 0: Auto baud rate request */
#define USART_RQR_SBKRQ (1 << 1) /* Bit 1: Send Break */
#define USART_RQR_MMRQ (1 << 2) /* Bit 2: Mute mode request */
#define USART_RQR_RXFRQ (1 << 3) /* Bit 3: Receive data flush request */
#define USART_RQR_TXFRQ (1 << 4) /* Bit 4: Transmit data flush request */
/* Interrupt and Status register */
#define USART_ISR_PE (1 << 0) /* Bit 0: Parity Error */
#define USART_ISR_FE (1 << 1) /* Bit 1: Framing Error */
#define USART_ISR_NF (1 << 2) /* Bit 2: Noise Error Flag */
#define USART_ISR_ORE (1 << 3) /* Bit 3: OverRun Error */
#define USART_ISR_IDLE (1 << 4) /* Bit 4: IDLE line detected */
#define USART_ISR_RXNE (1 << 5) /* Bit 5: Read Data Register Not Empty */
#define USART_ISR_TC (1 << 6) /* Bit 6: Transmission Complete */
#define USART_ISR_TXE (1 << 7) /* Bit 7: Transmit Data Register Empty */
#define USART_ISR_LBDF (1 << 8) /* Bit 8: LIN Break Detection Flag */
#define USART_ISR_CTSIF (1 << 9) /* Bit 9: CTS Interrupt flag */
#define USART_ISR_CTS (1 << 10) /* Bit 9: CTS Flag */
#define USART_ISR_RTOF (1 << 11) /* Bit 10: Receiver timeout Flag */
#define USART_ISR_EOBF (1 << 12) /* Bit 11: End of block Flag */
#define USART_ISR_ABRE (1 << 13) /* Bit 12: Auto baud rate Error */
#define USART_ISR_ABRF (1 << 15) /* Bit 14: Auto baud rate Flag */
#define USART_ISR_BUSY (1 << 16) /* Bit 15: Busy Flag */
#define USART_ISR_CMF (1 << 17) /* Bit 16: Character match Flag */
#define USART_ISR_SBKF (1 << 18) /* Bit 17: Send break Flag */
#define USART_ISR_RWU (1 << 19) /* Bit 18: Receiver wakeup from Mute mode */
#define USART_ISR_WUF (1 << 20) /* Bit 19: Wakeup from Stop mode Flag */
#define USART_ISR_TEACK (1 << 21) /* Bit 20: Transmit enable acknowledge Flag */
#define USART_ISR_REACK (1 << 22) /* Bit 21: Receive enable acknowledge Flag */
/* ICR */
#define USART_ICR_PECF (1 << 0) /* Bit 0: Parity error clear flag */
#define USART_ICR_FECF (1 << 1) /* Bit 1: Framing error clear flag */
#define USART_ICR_NCF (1 << 2) /* Bit 2: Noise detected clear flag */
#define USART_ICR_ORECF (1 << 3) /* Bit 3: Overrun error clear flag */
#define USART_ICR_IDLECF (1 << 4) /* Bit 4: Idle line detected clear flag */
#define USART_ICR_TCCF (1 << 6) /* Bit 6: Transmission complete clear flag */
#define USART_ICR_LBDCF (1 << 8) /* Bit 8: LIN break detection clear flag */
#define USART_ICR_CTSCF (1 << 9) /* Bit 9: CTS clear flag */
#define USART_ICR_RTOCF (1 << 11) /* Bit 11: Receiver timeout clear flag */
#define USART_ICR_EOBCF (1 << 12) /* Bit 12: End of block clear flag */
#define USART_ICR_CMCF (1 << 17) /* Bit 17: Character match clear flag */
#define USART_ICR_WUCF (1 << 20) /* Bit 20: Wakeup from Stop mode clear flag */
/* Receive Data register */
#define USART_RDR_SHIFT (0) /* Bits 8:0: Data value */
#define USART_RDR_MASK (0xff << USART_RDR_SHIFT)
/* Transmit Data register */
#define USART_TDR_SHIFT (0) /* Bits 8:0: Data value */
#define USART_TDR_MASK (0xff << USART_TDR_SHIFT)
#endif /* __ARCH_ARM_STC_STM32F0_CHIP_STM32F0_UART_H */

View File

@ -0,0 +1,263 @@
/************************************************************************************
* arch/arm/src/stm32f0/chip/stm32f0_usbdev.h
*
* Copyright (C) 2017 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
* Alan Carvalho de Assis <acassis@gmail.com>
*
* 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 NuttX 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 OWNER 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.
*
************************************************************************************/
#ifndef __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_USBDEV_H
#define __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_USBDEV_H
/************************************************************************************
* Included Files
************************************************************************************/
#include <nuttx/config.h>
#include <chip.h>
/************************************************************************************
* Pre-processor Definitions
************************************************************************************/
/* Register Offsets *****************************************************************/
/* Endpoint Registers */
#define STM32F0_USB_EPR_OFFSET(n) ((n) << 2) /* USB endpoint n register (16-bits) */
#define STM32F0_USB_EP0R_OFFSET 0x0000 /* USB endpoint 0 register (16-bits) */
#define STM32F0_USB_EP1R_OFFSET 0x0004 /* USB endpoint 1 register (16-bits) */
#define STM32F0_USB_EP2R_OFFSET 0x0008 /* USB endpoint 2 register (16-bits) */
#define STM32F0_USB_EP3R_OFFSET 0x000c /* USB endpoint 3 register (16-bits) */
#define STM32F0_USB_EP4R_OFFSET 0x0010 /* USB endpoint 4 register (16-bits) */
#define STM32F0_USB_EP5R_OFFSET 0x0014 /* USB endpoint 5 register (16-bits) */
#define STM32F0_USB_EP6R_OFFSET 0x0018 /* USB endpoint 6 register (16-bits) */
#define STM32F0_USB_EP7R_OFFSET 0x001c /* USB endpoint 7 register (16-bits) */
/* Common Registers */
#define STM32F0_USB_CNTR_OFFSET 0x0040 /* USB control register (16-bits) */
#define STM32F0_USB_ISTR_OFFSET 0x0044 /* USB interrupt status register (16-bits) */
#define STM32F0_USB_FNR_OFFSET 0x0048 /* USB frame number register (16-bits) */
#define STM32F0_USB_DADDR_OFFSET 0x004c /* USB device address (16-bits) */
#define STM32F0_USB_BTABLE_OFFSET 0x0050 /* Buffer table address (16-bits) */
#define STM32F0_USB_LPMCSR_OFFSET 0x0054 /* LPM control and status register */
#define STM32F0_USB_BCDR_OFFSET 0x0058 /* Battery charging detector */
/* Buffer Descriptor Table (Relatative to BTABLE address) */
#define STM32F0_USB_ADDR_TX_WOFFSET (0) /* Transmission buffer address n (16-bits) */
#define STM32F0_USB_COUNT_TX_WOFFSET (2) /* Transmission byte count n (16-bits) */
#define STM32F0_USB_ADDR_RX_WOFFSET (4) /* Reception buffer address n (16-bits) */
#define STM32F0_USB_COUNT_RX_WOFFSET (6) /* Reception byte count n (16-bits) */
#define STM32F0_USB_BTABLE_RADDR(ep,o) ((((uint32_t)getreg16(STM32F0_USB_BTABLE) + ((ep) << 3)) + (o)) << 1)
#define STM32F0_USB_ADDR_TX_OFFSET(ep) STM32F0_USB_BTABLE_RADDR(ep,STM32F0_USB_ADDR_TX_WOFFSET)
#define STM32F0_USB_COUNT_TX_OFFSET(ep) STM32F0_USB_BTABLE_RADDR(ep,STM32F0_USB_COUNT_TX_WOFFSET)
#define STM32F0_USB_ADDR_RX_OFFSET(ep) STM32F0_USB_BTABLE_RADDR(ep,STM32F0_USB_ADDR_RX_WOFFSET)
#define STM32F0_USB_COUNT_RX_OFFSET(ep) STM32F0_USB_BTABLE_RADDR(ep,STM32F0_USB_COUNT_RX_WOFFSET)
/* Register Addresses ***************************************************************/
/* Endpoint Registers */
#define STM32F0_USB_EPR(n) (STM32F0_USB_BASE+STM32F0_USB_EPR_OFFSET(n))
#define STM32F0_USB_EP0R (STM32F0_USB_BASE+STM32F0_USB_EP0R_OFFSET)
#define STM32F0_USB_EP1R (STM32F0_USB_BASE+STM32F0_USB_EP1R_OFFSET)
#define STM32F0_USB_EP2R (STM32F0_USB_BASE+STM32F0_USB_EP2R_OFFSET)
#define STM32F0_USB_EP3R (STM32F0_USB_BASE+STM32F0_USB_EP3R_OFFSET)
#define STM32F0_USB_EP4R (STM32F0_USB_BASE+STM32F0_USB_EP4R_OFFSET)
#define STM32F0_USB_EP5R (STM32F0_USB_BASE+STM32F0_USB_EP5R_OFFSET)
#define STM32F0_USB_EP6R (STM32F0_USB_BASE+STM32F0_USB_EP6R_OFFSET)
#define STM32F0_USB_EP7R (STM32F0_USB_BASE+STM32F0_USB_EP7R_OFFSET)
/* Common Registers */
#define STM32F0_USB_CNTR (STM32F0_USB_BASE+STM32F0_USB_CNTR_OFFSET)
#define STM32F0_USB_ISTR (STM32F0_USB_BASE+STM32F0_USB_ISTR_OFFSET)
#define STM32F0_USB_FNR (STM32F0_USB_BASE+STM32F0_USB_FNR_OFFSET)
#define STM32F0_USB_DADDR (STM32F0_USB_BASE+STM32F0_USB_DADDR_OFFSET)
#define STM32F0_USB_BTABLE (STM32F0_USB_BASE+STM32F0_USB_BTABLE_OFFSET)
#define STM32F0_USB_LPMCSR_OFFSET (STM32F0_USB_BASE+STM32F0_USB_LPMCSR_OFFSET)
#define STM32F0_USB_BCDR_OFFSET (STM32F0_USB_BASE+STM32F0_USB_BCDR_OFFSET)
/* Buffer Descriptor Table (Relatative to BTABLE address) */
#define STM32F0_USB_BTABLE_ADDR(ep,o) (STM32F0_USBRAM_BASE+STM32F0_USB_BTABLE_RADDR(ep,o))
#define STM32F0_USB_ADDR_TX(ep) STM32F0_USB_BTABLE_ADDR(ep,STM32F0_USB_ADDR_TX_WOFFSET)
#define STM32F0_USB_COUNT_TX(ep) STM32F0_USB_BTABLE_ADDR(ep,STM32F0_USB_COUNT_TX_WOFFSET)
#define STM32F0_USB_ADDR_RX(ep) STM32F0_USB_BTABLE_ADDR(ep,STM32F0_USB_ADDR_RX_WOFFSET)
#define STM32F0_USB_COUNT_RX(ep) STM32F0_USB_BTABLE_ADDR(ep,STM32F0_USB_COUNT_RX_WOFFSET)
/* Register Bitfield Definitions ****************************************************/
/* USB endpoint register */
#define USB_EPR_EA_SHIFT (0) /* Bits 3:0 [3:0]: Endpoint Address */
#define USB_EPR_EA_MASK (0X0f << USB_EPR_EA_SHIFT)
#define USB_EPR_STATTX_SHIFT (4) /* Bits 5-4: Status bits, for transmission transfers */
#define USB_EPR_STATTX_MASK (3 << USB_EPR_STATTX_SHIFT)
# define USB_EPR_STATTX_DIS (0 << USB_EPR_STATTX_SHIFT) /* EndPoint TX DISabled */
# define USB_EPR_STATTX_STALL (1 << USB_EPR_STATTX_SHIFT) /* EndPoint TX STALLed */
# define USB_EPR_STATTX_NAK (2 << USB_EPR_STATTX_SHIFT) /* EndPoint TX NAKed */
# define USB_EPR_STATTX_VALID (3 << USB_EPR_STATTX_SHIFT) /* EndPoint TX VALID */
# define USB_EPR_STATTX_DTOG1 (1 << USB_EPR_STATTX_SHIFT) /* EndPoint TX Data Toggle bit1 */
# define USB_EPR_STATTX_DTOG2 (2 << USB_EPR_STATTX_SHIFT) /* EndPoint TX Data Toggle bit2 */
#define USB_EPR_DTOG_TX (1 << 6) /* Bit 6: Data Toggle, for transmission transfers */
#define USB_EPR_CTR_TX (1 << 7) /* Bit 7: Correct Transfer for transmission */
#define USB_EPR_EP_KIND (1 << 8) /* Bit 8: Endpoint Kind */
#define USB_EPR_EPTYPE_SHIFT (9) /* Bits 10-9: Endpoint type */
#define USB_EPR_EPTYPE_MASK (3 << USB_EPR_EPTYPE_SHIFT)
# define USB_EPR_EPTYPE_BULK (0 << USB_EPR_EPTYPE_SHIFT) /* EndPoint BULK */
# define USB_EPR_EPTYPE_CONTROL (1 << USB_EPR_EPTYPE_SHIFT) /* EndPoint CONTROL */
# define USB_EPR_EPTYPE_ISOC (2 << USB_EPR_EPTYPE_SHIFT) /* EndPoint ISOCHRONOUS */
# define USB_EPR_EPTYPE_INTERRUPT (3 << USB_EPR_EPTYPE_SHIFT) /* EndPoint INTERRUPT */
#define USB_EPR_SETUP (1 << 11) /* Bit 11: Setup transaction completed */
#define USB_EPR_STATRX_SHIFT (12) /* Bits 13-12: Status bits, for reception transfers */
#define USB_EPR_STATRX_MASK (3 << USB_EPR_STATRX_SHIFT)
# define USB_EPR_STATRX_DIS (0 << USB_EPR_STATRX_SHIFT) /* EndPoint RX DISabled */
# define USB_EPR_STATRX_STALL (1 << USB_EPR_STATRX_SHIFT) /* EndPoint RX STALLed */
# define USB_EPR_STATRX_NAK (2 << USB_EPR_STATRX_SHIFT) /* EndPoint RX NAKed */
# define USB_EPR_STATRX_VALID (3 << USB_EPR_STATRX_SHIFT) /* EndPoint RX VALID */
# define USB_EPR_STATRX_DTOG1 (1 << USB_EPR_STATRX_SHIFT) /* EndPoint RX Data TOGgle bit1 */
# define USB_EPR_STATRX_DTOG2 (2 << USB_EPR_STATRX_SHIFT) /* EndPoint RX Data TOGgle bit1 */
#define USB_EPR_DTOG_RX (1 << 14) /* Bit 14: Data Toggle, for reception transfers */
#define USB_EPR_CTR_RX (1 << 15) /* Bit 15: Correct Transfer for reception */
/* USB control register */
#define USB_CNTR_FRES (1 << 0) /* Bit 0: Force USB Reset */
#define USB_CNTR_PDWN (1 << 1) /* Bit 1: Power down */
#define USB_CNTR_LPMODE (1 << 2) /* Bit 2: Low-power mode */
#define USB_CNTR_FSUSP (1 << 3) /* Bit 3: Force suspend */
#define USB_CNTR_RESUME (1 << 4) /* Bit 4: Resume request */
#define USB_CNTR_L1RESUME (1 << 5) /* Bit 5: LPM L1 Resume request */
#define USB_CNTR_L1REQM (1 << 7) /* Bit 6: LPM L1 state request interrupt mask */
#define USB_CNTR_ESOFM (1 << 8) /* Bit 8: Expected Start Of Frame Interrupt Mask */
#define USB_CNTR_SOFM (1 << 9) /* Bit 9: Start Of Frame Interrupt Mask */
#define USB_CNTR_RESETM (1 << 10) /* Bit 10: USB Reset Interrupt Mask */
#define USB_CNTR_SUSPM (1 << 11) /* Bit 11: Suspend mode Interrupt Mask */
#define USB_CNTR_WKUPM (1 << 12) /* Bit 12: Wakeup Interrupt Mask */
#define USB_CNTR_ERRM (1 << 13) /* Bit 13: Error Interrupt Mask */
#define USB_CNTR_PMAOVRNM (1 << 14) /* Bit 14: Packet Memory Area Over / Underrun Interrupt Mask */
#define USB_CNTR_CTRM (1 << 15) /* Bit 15: Correct Transfer Interrupt Mask */
#define USB_CNTR_ALLINTS (USB_CNTR_ESOFM|USB_CNTR_SOFM|USB_CNTR_RESETM|USB_CNTR_SUSPM|\
USB_CNTR_WKUPM|USB_CNTR_ERRM|USB_CNTR_DMAOVRNM|USB_CNTR_CTRM)
/* USB interrupt status register */
#define USB_ISTR_EPID_SHIFT (0) /* Bits 3-0: Endpoint Identifier */
#define USB_ISTR_EPID_MASK (0x0f << USB_ISTR_EPID_SHIFT)
#define USB_ISTR_DIR (1 << 4) /* Bit 4: Direction of transaction */
#define USB_ISTR_L1REQ (1 << 7) /* Bit 7: LPM L1 state request */
#define USB_ISTR_ESOF (1 << 8) /* Bit 8: Expected Start Of Frame */
#define USB_ISTR_SOF (1 << 9) /* Bit 9: Start Of Frame */
#define USB_ISTR_RESET (1 << 10) /* Bit 10: USB RESET request */
#define USB_ISTR_SUSP (1 << 11) /* Bit 11: Suspend mode request */
#define USB_ISTR_WKUP (1 << 12) /* Bit 12: Wake up */
#define USB_ISTR_ERR (1 << 13) /* Bit 13: Error */
#define USB_ISTR_PMAOVRN (1 << 14) /* Bit 14: Packet Memory Area Over / Underrun */
#define USB_ISTR_CTR (1 << 15) /* Bit 15: Correct Transfer */
#define USB_ISTR_ALLINTS (USB_ISTR_ESOF|USB_ISTR_SOF|USB_ISTR_RESET|USB_ISTR_SUSP|\
USB_ISTR_WKUP|USB_ISTR_ERR|USB_ISTR_DMAOVRN|USB_ISTR_CTR)
/* USB frame number register */
#define USB_FNR_FN_SHIFT (0) /* Bits 10-0: Frame Number */
#define USB_FNR_FN_MASK (0x07ff << USB_FNR_FN_SHIFT)
#define USB_FNR_LSOF_SHIFT (11) /* Bits 12-11: Lost SOF */
#define USB_FNR_LSOF_MASK (3 << USB_FNR_LSOF_SHIFT)
#define USB_FNR_LCK (1 << 13) /* Bit 13: Locked */
#define USB_FNR_RXDM (1 << 14) /* Bit 14: Receive Data - Line Status */
#define USB_FNR_RXDP (1 << 15) /* Bit 15: Receive Data + Line Status */
/* USB device address */
#define USB_DADDR_ADD_SHIFT (0) /* Bits 6-0: Device Address */
#define USB_DADDR_ADD_MASK (0x7f << USB_DADDR_ADD_SHIFT)
#define USB_DADDR_EF (1 << 7) /* Bit 7: Enable Function */
/* Buffer table address */
#define USB_BTABLE_SHIFT (3) /* Bits 15:3: Buffer Table */
#define USB_BTABLE_MASK (0x1fff << USB_BTABLE_SHIFT)
/* LPM control and status register */
#define USB_LPMCSR_LPMEN (1 << 0) /* Bit 0: LPM support enable */
#define USB_LPMCSR_LPMACK (1 << 1) /* Bit 1: LPM Token acknowledge enable */
#define USB_LPMCSR_REMWAKE (1 << 3) /* Bit 3: bRemoteWake value */
#define USB_LPMCSR_BESL_OFFSET (4) /* Bits 4-7: BESL value */
#define USB_LPMCSR_BESL_MASK (0xf << USB_LPMCSR_BESL_OFFSET)
/* Battery charging detector */
#define USB_BCDR_BCDEN (1 << 0) /* Bit 0: Battery charging detector (BCD) enable */
#define USB_BCDR_DCDEN (1 << 1) /* Bit 1: Data contact detection (DCD) mode enable */
#define USB_BCDR_PDEN (1 << 2) /* Bit 2: Primary detection (PD) mode enable */
#define USB_BCDR_SDEN (1 << 3) /* Bit 3: Secondary detection (SD) mode enable */
#define USB_BCDR_DCDET (1 << 4) /* Bit 4: Data contact detection (DCD) status */
#define USB_BCDR_PDET (1 << 5) /* Bit 5: Primary detection (PD) status */
#define USB_BCDR_SDET (1 << 6) /* Bit 6: Secondary detection (SD) status */
#define USB_BCDR_PS2DET (1 << 7) /* Bit 7: DM pull-up detection status */
#define USB_BCDR_DPPU (1 << 15) /* Bit 15: DP pull-up control */
/* Transmission buffer address */
#define USB_ADDR_TX_ZERO (1 << 0) /* Bit 0 Must always be written as 0 */
#define USB_ADDR_TX_SHIFT (1) /* Bits 15-1: Transmission Buffer Address */
#define USB_ADDR_TX_MASK (0x7fff << USB_ADDR_ADDR_TX_SHIFT)
/* Transmission byte count */
#define USB_COUNT_TX_SHIFT (0) /* Bits 0-9: Transmission Byte Count */
#define USB_COUNT_TX_MASK (0x03ff << USB_COUNT_COUNT_TX_SHIFT)
#define USB_COUNT_NUMBLOCK_OFFSET (10) /* Bits 10-14: Number of blocks */
#define USB_COUNT_NUMBLOCK_MASK (1 << USB_COUNT_NUMBLOCK_OFFSET)
#define USB_COUNT_BLSIZE (1 << 15) /* Bit 15: Block size */
/* Reception buffer address */
#define USB_ADDR_RX_ZERO (1 << 0) /* Bit 0 This bit must always be written as 0 */
#define USB_ADDR_RX_SHIFT (1) /* Bits 15:1 ADDRn_RX[15:1]: Reception Buffer Address */
#define USB_ADDR_RX_MASK (0x7fff << USB_ADDR_RX_SHIFT)
/* Reception byte count */
#define USB_COUNT_RX_BL_SIZE (1 << 15) /* Bit 15: BLock SIZE. */
#define USB_COUNT_RX_NUM_BLOCK_SHIFT (10) /* Bits 14-10: Number of blocks */
#define USB_COUNT_RX_NUM_BLOCK_MASK (0x1f << USB_COUNT_RX_NUM_BLOCK_SHIFT)
#define USB_COUNT_RX_SHIFT (0) /* Bits 9-0: Reception Byte Count */
#define USB_COUNT_RX_MASK (0x03ff << USB_COUNT_RX_SHIFT)
#endif /* __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_USBDEV_H */

View File

@ -0,0 +1,142 @@
/************************************************************************************
* arch/arm/src/stm32f0/chip/stm32f0_wdg.h
*
* Copyright (C) 2017 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
* Alan Carvalho de Assis <acassis@gmail.com>
*
* 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 NuttX 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 OWNER 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.
*
************************************************************************************/
#ifndef __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_WDG_H
#define __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_WDG_H
/************************************************************************************
* Included Files
************************************************************************************/
#include <nuttx/config.h>
#include "chip.h"
/************************************************************************************
* Pre-processor Definitions
************************************************************************************/
/* Register Offsets *****************************************************************/
#define STM32F0_IWDG_KR_OFFSET 0x0000 /* Key register (32-bit) */
#define STM32F0_IWDG_PR_OFFSET 0x0004 /* Prescaler register (32-bit) */
#define STM32F0_IWDG_RLR_OFFSET 0x0008 /* Reload register (32-bit) */
#define STM32F0_IWDG_SR_OFFSET 0x000c /* Status register (32-bit) */
#define STM32F0_IWDG_WINR_OFFSET 0x0010 /* Window register (32-bit) */
#define STM32F0_WWDG_CR_OFFSET 0x0000 /* Control Register (32-bit) */
#define STM32F0_WWDG_CFR_OFFSET 0x0004 /* Configuration register (32-bit) */
#define STM32F0_WWDG_SR_OFFSET 0x0008 /* Status register (32-bit) */
/* Register Addresses ***************************************************************/
#define STM32F0_IWDG_KR (STM32F0_IWDG_BASE+STM32F0_IWDG_KR_OFFSET)
#define STM32F0_IWDG_PR (STM32F0_IWDG_BASE+STM32F0_IWDG_PR_OFFSET)
#define STM32F0_IWDG_RLR (STM32F0_IWDG_BASE+STM32F0_IWDG_RLR_OFFSET)
#define STM32F0_IWDG_SR (STM32F0_IWDG_BASE+STM32F0_IWDG_SR_OFFSET)
#define STM32F0_IWDG_WINR (STM32F0_IWDG_BASE+STM32F0_IWDG_WINR_OFFSET)
#define STM32F0_WWDG_CR (STM32F0_WWDG_BASE+STM32F0_WWDG_CR_OFFSET)
#define STM32F0_WWDG_CFR (STM32F0_WWDG_BASE+STM32F0_WWDG_CFR_OFFSET)
#define STM32F0_WWDG_SR (STM32F0_WWDG_BASE+STM32F0_WWDG_SR_OFFSET)
/* Register Bitfield Definitions ****************************************************/
/* Key register (32-bit) */
#define IWDG_KR_KEY_SHIFT (0) /* Bits 15-0: Key value (write only, read 0000h) */
#define IWDG_KR_KEY_MASK (0xffff << IWDG_KR_KEY_SHIFT)
#define IWDG_KR_KEY_ENABLE (0x5555) /* Enable register access */
#define IWDG_KR_KEY_DISABLE (0x0000) /* Disable register access */
#define IWDG_KR_KEY_RELOAD (0xaaaa) /* Reload the counter */
#define IWDG_KR_KEY_START (0xcccc) /* Start the watchdog */
/* Prescaler register (32-bit) */
#define IWDG_PR_SHIFT (0) /* Bits 2-0: Prescaler divider */
#define IWDG_PR_MASK (7 << IWDG_PR_SHIFT)
# define IWDG_PR_DIV4 (0 << IWDG_PR_SHIFT) /* 000: divider /4 */
# define IWDG_PR_DIV8 (1 << IWDG_PR_SHIFT) /* 001: divider /8 */
# define IWDG_PR_DIV16 (2 << IWDG_PR_SHIFT) /* 010: divider /16 */
# define IWDG_PR_DIV32 (3 << IWDG_PR_SHIFT) /* 011: divider /32 */
# define IWDG_PR_DIV64 (4 << IWDG_PR_SHIFT) /* 100: divider /64 */
# define IWDG_PR_DIV128 (5 << IWDG_PR_SHIFT) /* 101: divider /128 */
# define IWDG_PR_DIV256 (6 << IWDG_PR_SHIFT) /* 11x: divider /256 */
/* Reload register (32-bit) */
#define IWDG_RLR_RL_SHIFT (0) /* Bits11:0 RL[11:0]: Watchdog counter reload value */
#define IWDG_RLR_RL_MASK (0x0fff << IWDG_RLR_RL_SHIFT)
#define IWDG_RLR_MAX (0xfff)
/* Status register (32-bit) */
#define IWDG_SR_PVU (1 << 0) /* Bit 0: Watchdog prescaler value update */
#define IWDG_SR_RVU (1 << 1) /* Bit 1: Watchdog counter reload value update */
#define IWDG_SR_WVU (1 << 2) /* Bit 2: Watchdog counter window value update */
/* Window register (32-bit) */
#define IWDG_WINR_SHIFT (0)
#define IWDG_WINR_MASK (0x0fff << IWDG_WINR_SHIFT)
/* Control Register (32-bit) */
#define WWDG_CR_T_SHIFT (0) /* Bits 6:0 T[6:0]: 7-bit counter (MSB to LSB) */
#define WWDG_CR_T_MASK (0x7f << WWDG_CR_T_SHIFT)
# define WWDG_CR_T_MAX (0x3f << WWDG_CR_T_SHIFT)
# define WWDG_CR_T_RESET (0x40 << WWDG_CR_T_SHIFT)
#define WWDG_CR_WDGA (1 << 7) /* Bit 7: Activation bit */
/* Configuration register (32-bit) */
#define WWDG_CFR_W_SHIFT (0) /* Bits 6:0 W[6:0] 7-bit window value */
#define WWDG_CFR_W_MASK (0x7f << WWDG_CFR_W_SHIFT)
#define WWDG_CFR_WDGTB_SHIFT (7) /* Bits 8:7 [1:0]: Timer Base */
#define WWDG_CFR_WDGTB_MASK (3 << WWDG_CFR_WDGTB_SHIFT)
# define WWDG_CFR_PCLK1 (0 << WWDG_CFR_WDGTB_SHIFT) /* 00: CK Counter Clock (PCLK1 div 4096) div 1 */
# define WWDG_CFR_PCLK1d2 (1 << WWDG_CFR_WDGTB_SHIFT) /* 01: CK Counter Clock (PCLK1 div 4096) div 2 */
# define WWDG_CFR_PCLK1d4 (2 << WWDG_CFR_WDGTB_SHIFT) /* 10: CK Counter Clock (PCLK1 div 4096) div 4 */
# define WWDG_CFR_PCLK1d8 (3 << WWDG_CFR_WDGTB_SHIFT) /* 11: CK Counter Clock (PCLK1 div 4096) div 8 */
#define WWDG_CFR_EWI (1 << 9) /* Bit 9: Early Wakeup Interrupt */
/* Status register (32-bit) */
#define WWDG_SR_EWIF (1 << 0) /* Bit 0: Early Wakeup Interrupt Flag */
#endif /* __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_WDG_H */

View File

@ -0,0 +1,113 @@
/****************************************************************************
* arch/arm/src/stm32f0/stm32f0_clockconfig.c
*
* Copyright (C) 2017 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
* Alan Carvalho de Assis <acassis@gmail.com>
*
* 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 NuttX 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 OWNER 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.
*
****************************************************************************/
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <stdint.h>
#include <debug.h>
#include <nuttx/arch.h>
#include <arch/board/board.h>
#include "up_arch.h"
#include "up_internal.h"
#include "stm32f0_rcc.h"
#include "stm32f0_clockconfig.h"
#include "chip/stm32f0_syscfg.h"
#include "chip/stm32f0_gpio.h"
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: stm32f0_clockconfig
*
* Description:
* Called to initialize the STM32F0xx. This does whatever setup is needed
* to put the SoC in a usable state. This includes the initialization of
* clocking using the settings in board.h.
*
****************************************************************************/
void stm32f0_clockconfig(void)
{
int regval;
/* Verify if PLL is already setup, if so define to use HSI mode */
if ((getreg32(STM32F0_RCC_CFGR) & RCC_CFGR_SWS_MASK) == RCC_CFGR_SWS_PLL)
{
/* Select HSI mode */
regval = getreg32(STM32F0_RCC_CFGR);
regval &= (uint32_t) (~RCC_CFGR_SW_MASK);
putreg32(regval, STM32F0_RCC_CFGR);
while ((getreg32(STM32F0_RCC_CFGR) & RCC_CFGR_SWS_MASK) != RCC_CFGR_SWS_HSI) ;
}
/* Disable the PLL */
regval = getreg32(STM32F0_RCC_CR);
regval &= (uint32_t)(~RCC_CR_PLLON);
putreg32(regval, STM32F0_RCC_CR);
while ((getreg32(STM32F0_RCC_CR) & RCC_CR_PLLRDY) != 0) ;
/* Configure the PLL. Multiple x6 to get 48MHz */
regval = getreg32(STM32F0_RCC_CFGR);
regval &= (RCC_CFGR_PLLMUL_CLKx6 | ~RCC_CFGR_PLLMUL_MASK);
putreg32(regval, STM32F0_RCC_CFGR);
/* Enable the PLL */
regval = getreg32(STM32F0_RCC_CR);
regval |= RCC_CR_PLLON;
putreg32(regval, STM32F0_RCC_CR);
while ((getreg32(STM32F0_RCC_CR) & RCC_CR_PLLRDY) == 0) ;
/* Configure to use the PLL */
regval = getreg32(STM32F0_RCC_CFGR);
regval |= (uint32_t) (RCC_CFGR_SW_PLL);
putreg32(regval, STM32F0_RCC_CFGR);
while ((getreg32(STM32F0_RCC_CFGR) & RCC_CFGR_SW_MASK) != RCC_CFGR_SW_PLL) ;
}

View File

@ -0,0 +1,77 @@
/************************************************************************************
* arch/arm/src/stm32f0/stm32f0_clockconfig.h
*
* Copyright (C) 2017 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
* Alan Carvalho de Assis <acassis@gmail.com>
*
* 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 NuttX 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 OWNER 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.
*
************************************************************************************/
#ifndef __ARCH_ARM_SRC_STM32F0_STM32F0_CLOCKCONFIG_H
#define __ARCH_ARM_SRC_STM32F0_STM32F0_CLOCKCONFIG_H
/************************************************************************************
* Included Files
************************************************************************************/
#include <nuttx/config.h>
/************************************************************************************
* Public Data
************************************************************************************/
#ifndef __ASSEMBLY__
#ifdef __cplusplus
extern "C"
{
#endif
/************************************************************************************
* Public Functions
************************************************************************************/
/************************************************************************************
* Name: stm32f0_clockconfig
*
* Description:
* Called to initialize the STM32F0XX. This does whatever setup is needed to put
* the MCU in a usable state. This includes the initialization of clocking using
* the settings in board.h.
*
************************************************************************************/
void stm32f0_clockconfig(void);
#ifdef __cplusplus
}
#endif
#endif /* __ASSEMBLY__ */
#endif /* __ARCH_ARM_SRC_STM32F0_STM32F0_CLOCKCONFIG_H */

View File

@ -0,0 +1,428 @@
/****************************************************************************
* arch/arm/src/stm32f0/stm32f0_gpio.c
*
* Copyright (C) 2017 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
* Alan Carvalho de Assis <acassis@gmail.com>
*
* 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 NuttX 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 OWNER 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.
*
****************************************************************************/
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <sys/types.h>
#include <stdint.h>
#include <stdbool.h>
#include <errno.h>
#include <debug.h>
#include <arch/irq.h>
#include <arch/stm32f0/chip.h>
#include "up_arch.h"
#include "chip.h"
#include "stm32f0_gpio.h"
#include "chip/stm32f0_syscfg.h"
/****************************************************************************
* Public Data
****************************************************************************/
/* Base addresses for each GPIO block */
const uint32_t g_gpiobase[STM32F0_NPORTS] =
{
#if STM32F0_NPORTS > 0
STM32F0_GPIOA_BASE,
#endif
#if STM32F0_NPORTS > 1
STM32F0_GPIOB_BASE,
#endif
#if STM32F0_NPORTS > 2
STM32F0_GPIOC_BASE,
#endif
#if STM32F0_NPORTS > 3
STM32F0_GPIOD_BASE,
#endif
#if STM32F0_NPORTS > 4
STM32F0_GPIOE_BASE,
#endif
#if STM32F0_NPORTS > 5
STM32F0_GPIOF_BASE,
#endif
};
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Function: stm32f0_gpioinit
*
* Description:
* Based on configuration within the .config file, it does:
* - Remaps positions of alternative functions.
*
* Typically called from stm32f0_start().
*
* Assumptions:
* This function is called early in the initialization sequence so that
* no mutual exlusion is necessary.
*
****************************************************************************/
void stm32f0_gpioinit(void)
{
}
/****************************************************************************
* Name: stm32f0_configgpio
*
* Description:
* Configure a GPIO pin based on bit-encoded description of the pin.
* Once it is configured as Alternative (GPIO_ALT|GPIO_CNF_AFPP|...)
* function, it must be unconfigured with stm32f0_unconfiggpio() with
* the same cfgset first before it can be set to non-alternative function.
*
* Returns:
* OK on success
* A negated errono valu on invalid port, or when pin is locked as ALT
* function.
*
* To-Do: Auto Power Enable
****************************************************************************/
int stm32f0_configgpio(uint32_t cfgset)
{
uintptr_t base;
uint32_t regval;
uint32_t setting;
unsigned int regoffset;
unsigned int port;
unsigned int pin;
unsigned int pos;
unsigned int pinmode;
irqstate_t flags;
/* Verify that this hardware supports the select GPIO port */
port = (cfgset & GPIO_PORT_MASK) >> GPIO_PORT_SHIFT;
if (port >= STM32F0_NPORTS)
{
return -EINVAL;
}
/* Get the port base address */
base = g_gpiobase[port];
/* Get the pin number and select the port configuration register for that
* pin
*/
pin = (cfgset & GPIO_PIN_MASK) >> GPIO_PIN_SHIFT;
/* Set up the mode register (and remember whether the pin mode) */
switch (cfgset & GPIO_MODE_MASK)
{
default:
case GPIO_INPUT: /* Input mode */
pinmode = GPIO_MODER_INPUT;
break;
case GPIO_OUTPUT: /* General purpose output mode */
stm32f0_gpiowrite(cfgset, (cfgset & GPIO_OUTPUT_SET) != 0); /* Set the initial output value */
pinmode = GPIO_MODER_OUTPUT;
break;
case GPIO_ALT: /* Alternate function mode */
pinmode = GPIO_MODER_ALT;
break;
case GPIO_ANALOG: /* Analog mode */
pinmode = GPIO_MODER_ANALOG;
break;
}
/* Interrupts must be disabled from here on out so that we have mutually
* exclusive access to all of the GPIO configuration registers.
*/
flags = enter_critical_section();
/* Now apply the configuration to the mode register */
regval = getreg32(base + STM32F0_GPIO_MODER_OFFSET);
regval &= ~GPIO_MODER_MASK(pin);
regval |= ((uint32_t)pinmode << GPIO_MODER_SHIFT(pin));
putreg32(regval, base + STM32F0_GPIO_MODER_OFFSET);
/* Set up the pull-up/pull-down configuration (all but analog pins) */
setting = GPIO_PUPDR_NONE;
if (pinmode != GPIO_MODER_ANALOG)
{
switch (cfgset & GPIO_PUPD_MASK)
{
default:
case GPIO_FLOAT: /* No pull-up, pull-down */
break;
case GPIO_PULLUP: /* Pull-up */
setting = GPIO_PUPDR_PULLUP;
break;
case GPIO_PULLDOWN: /* Pull-down */
setting = GPIO_PUPDR_PULLDOWN;
break;
}
}
regval = getreg32(base + STM32F0_GPIO_PUPDR_OFFSET);
regval &= ~GPIO_PUPDR_MASK(pin);
regval |= (setting << GPIO_PUPDR_SHIFT(pin));
putreg32(regval, base + STM32F0_GPIO_PUPDR_OFFSET);
/* Set the alternate function (Only alternate function pins) */
if (pinmode == GPIO_MODER_ALT)
{
setting = (cfgset & GPIO_AF_MASK) >> GPIO_AF_SHIFT;
}
else
{
setting = 0;
}
if (pin < 8)
{
regoffset = STM32F0_GPIO_AFRL_OFFSET;
pos = pin;
}
else
{
regoffset = STM32F0_GPIO_AFRH_OFFSET;
pos = pin - 8;
}
regval = getreg32(base + regoffset);
regval &= ~GPIO_AFR_MASK(pos);
regval |= (setting << GPIO_AFR_SHIFT(pos));
putreg32(regval, base + regoffset);
/* Set speed (Only outputs and alternate function pins) */
if (pinmode == GPIO_MODER_OUTPUT || pinmode == GPIO_MODER_ALT)
{
switch (cfgset & GPIO_SPEED_MASK)
{
default:
case GPIO_SPEED_2MHz: /* 2 MHz Low speed output */
setting = GPIO_OSPEED_2MHz;
break;
case GPIO_SPEED_10MHz: /* 10 MHz Medium speed output */
setting = GPIO_OSPEED_10MHz;
break;
case GPIO_SPEED_50MHz: /* 50 MHz High speed output */
setting = GPIO_OSPEED_50MHz;
break;
}
}
else
{
setting = 0;
}
regval = getreg32(base + STM32F0_GPIO_OSPEED_OFFSET);
regval &= ~GPIO_OSPEED_MASK(pin);
regval |= (setting << GPIO_OSPEED_SHIFT(pin));
putreg32(regval, base + STM32F0_GPIO_OSPEED_OFFSET);
/* Set push-pull/open-drain (Only outputs and alternate function pins) */
regval = getreg32(base + STM32F0_GPIO_OTYPER_OFFSET);
setting = GPIO_OTYPER_OD(pin);
if ((pinmode == GPIO_MODER_OUTPUT || pinmode == GPIO_MODER_ALT) &&
(cfgset & GPIO_OPENDRAIN) != 0)
{
regval |= setting;
}
else
{
regval &= ~setting;
}
putreg32(regval, base + STM32F0_GPIO_OTYPER_OFFSET);
/* Otherwise, it is an input pin. Should it configured as an EXTI interrupt? */
if ((cfgset & GPIO_EXTI) != 0)
{
#if 0
/* "In STM32 F1 the selection of the EXTI line source is performed through
* the EXTIx bits in the AFIO_EXTICRx registers, while in F2 series this
* selection is done through the EXTIx bits in the SYSCFG_EXTICRx registers.
*
* "Only the mapping of the EXTICRx registers has been changed, without any
* changes to the meaning of the EXTIx bits. However, the range of EXTI
* bits values has been extended to 0b1000 to support the two ports added
* in F2, port H and I (in F1 series the maximum value is 0b0110)."
*/
uint32_t regaddr;
int shift;
/* Set the bits in the SYSCFG EXTICR register */
regaddr = STM32F0_SYSCFG_EXTICR(pin);
regval = getreg32(regaddr);
shift = SYSCFG_EXTICR_EXTI_SHIFT(pin);
regval &= ~(SYSCFG_EXTICR_PORT_MASK << shift);
regval |= (((uint32_t)port) << shift);
putreg32(regval, regaddr);
#endif
}
leave_critical_section(flags);
return OK;
}
/****************************************************************************
* Name: stm32f0_unconfiggpio
*
* Description:
* Unconfigure a GPIO pin based on bit-encoded description of the pin, set it
* into default HiZ state (and possibly mark it's unused) and unlock it whether
* it was previsouly selected as alternative function (GPIO_ALT|GPIO_CNF_AFPP|...).
*
* This is a safety function and prevents hardware from schocks, as unexpected
* write to the Timer Channel Output GPIO to fixed '1' or '0' while it should
* operate in PWM mode could produce excessive on-board currents and trigger
* over-current/alarm function.
*
* Returns:
* OK on success
* A negated errno value on invalid port
*
* To-Do: Auto Power Disable
****************************************************************************/
int stm32f0_unconfiggpio(uint32_t cfgset)
{
/* Reuse port and pin number and set it to default HiZ INPUT */
cfgset &= GPIO_PORT_MASK | GPIO_PIN_MASK;
cfgset |= GPIO_INPUT | GPIO_FLOAT;
/* To-Do: Mark its unuse for automatic power saving options */
return stm32f0_configgpio(cfgset);
}
/****************************************************************************
* Name: stm32f0_gpiowrite
*
* Description:
* Write one or zero to the selected GPIO pin
*
****************************************************************************/
void stm32f0_gpiowrite(uint32_t pinset, bool value)
{
uint32_t base;
uint32_t bit;
unsigned int port;
unsigned int pin;
port = (pinset & GPIO_PORT_MASK) >> GPIO_PORT_SHIFT;
if (port < STM32F0_NPORTS)
{
/* Get the port base address */
base = g_gpiobase[port];
/* Get the pin number */
pin = (pinset & GPIO_PIN_MASK) >> GPIO_PIN_SHIFT;
/* Set or clear the output on the pin */
if (value)
{
bit = GPIO_BSRR_SET(pin);
}
else
{
bit = GPIO_BSRR_RESET(pin);
}
putreg32(bit, base + STM32F0_GPIO_BSRR_OFFSET);
}
}
/****************************************************************************
* Name: stm32f0_gpioread
*
* Description:
* Read one or zero from the selected GPIO pin
*
****************************************************************************/
bool stm32f0_gpioread(uint32_t pinset)
{
uint32_t base;
unsigned int port;
unsigned int pin;
port = (pinset & GPIO_PORT_MASK) >> GPIO_PORT_SHIFT;
if (port < STM32F0_NPORTS)
{
/* Get the port base address */
base = g_gpiobase[port];
/* Get the pin number and return the input state of that pin */
pin = (pinset & GPIO_PIN_MASK) >> GPIO_PIN_SHIFT;
return ((getreg32(base + STM32F0_GPIO_IDR_OFFSET) & (1 << pin)) != 0);
}
return 0;
}

View File

@ -0,0 +1,379 @@
/************************************************************************************
* arch/arm/src/stm32f0/stm32f0_gpio.h
*
* Copyright (C) 2009, 2011-2012, 2015 Gregory Nutt. All rights reserved.
* Copyright (C) 2015-2016 Sebastien Lorquet. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
* Alan Carvalho de Assis <acassis@gmail.com>
* Sebastien Lorquet <sebastien@lorquet.fr>
*
* 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 NuttX 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 OWNER 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.
*
************************************************************************************/
#ifndef __ARCH_ARM_SRC_STM32F0_STM32F0_GPIO_H
#define __ARCH_ARM_SRC_STM32F0_STM32F0_GPIO_H
/************************************************************************************
* Included Files
************************************************************************************/
#include <nuttx/config.h>
#ifndef __ASSEMBLY__
# include <stdint.h>
# include <stdbool.h>
#endif
#include <nuttx/irq.h>
#include <arch/stm32f0/chip.h>
#include "chip.h"
#if defined(CONFIG_STM32F0_STM32F05X)
# include "chip/stm32f05xr_pinmap.h"
#else
# error "Unsupported STM32F0 chip"
#endif
/************************************************************************************
* Pre-Processor Declarations
************************************************************************************/
/* Bit-encoded input to stm32f0_configgpio() */
/* Each port bit of the general-purpose I/O (GPIO) ports can be individually configured
* by software in several modes:
*
* - Input floating
* - Input pull-up
* - Input-pull-down
* - Output open-drain with pull-up or pull-down capability
* - Output push-pull with pull-up or pull-down capability
* - Alternate function push-pull with pull-up or pull-down capability
* - Alternate function open-drain with pull-up or pull-down capability
* - Analog
*
* 20-bit Encoding: 1111 1111 1100 0000 0000
* 9876 5432 1098 7654 3210
* ---- ---- ---- ---- ----
* Inputs: MMUU .... ...X PPPP BBBB
* Outputs: MMUU .... FFOV PPPP BBBB
* Alternate Functions: MMUU AAAA FFO. PPPP BBBB
* Analog: MM.. .... .... PPPP BBBB
*/
/* Mode:
*
* 1111 1111 1100 0000 0000
* 9876 5432 1098 7654 3210
* ---- ---- ---- ---- ----
* MM.. .... .... .... ....
*/
#define GPIO_MODE_SHIFT (18) /* Bits 18-19: GPIO port mode */
#define GPIO_MODE_MASK (3 << GPIO_MODE_SHIFT)
# define GPIO_INPUT (0 << GPIO_MODE_SHIFT) /* Input mode */
# define GPIO_OUTPUT (1 << GPIO_MODE_SHIFT) /* General purpose output mode */
# define GPIO_ALT (2 << GPIO_MODE_SHIFT) /* Alternate function mode */
# define GPIO_ANALOG (3 << GPIO_MODE_SHIFT) /* Analog mode */
/* Input/output pull-ups/downs (not used with analog):
*
* 1111 1111 1100 0000 0000
* 9876 5432 1098 7654 3210
* ---- ---- ---- ---- ----
* ..UU .... .... .... ....
*/
#define GPIO_PUPD_SHIFT (16) /* Bits 16-17: Pull-up/pull down */
#define GPIO_PUPD_MASK (3 << GPIO_PUPD_SHIFT)
# define GPIO_FLOAT (0 << GPIO_PUPD_SHIFT) /* No pull-up, pull-down */
# define GPIO_PULLUP (1 << GPIO_PUPD_SHIFT) /* Pull-up */
# define GPIO_PULLDOWN (2 << GPIO_PUPD_SHIFT) /* Pull-down */
/* Alternate Functions:
*
* 1111 1111 1100 0000 0000
* 9876 5432 1098 7654 3210
* ---- ---- ---- ---- ----
* .... AAAA .... .... ....
*/
#define GPIO_AF_SHIFT (12) /* Bits 12-15: Alternate function */
#define GPIO_AF_MASK (15 << GPIO_AF_SHIFT)
# define GPIO_AF(n) ((n) << GPIO_AF_SHIFT)
# define GPIO_AF0 (0 << GPIO_AF_SHIFT)
# define GPIO_AF1 (1 << GPIO_AF_SHIFT)
# define GPIO_AF2 (2 << GPIO_AF_SHIFT)
# define GPIO_AF3 (3 << GPIO_AF_SHIFT)
# define GPIO_AF4 (4 << GPIO_AF_SHIFT)
# define GPIO_AF5 (5 << GPIO_AF_SHIFT)
# define GPIO_AF6 (6 << GPIO_AF_SHIFT)
# define GPIO_AF7 (7 << GPIO_AF_SHIFT)
# define GPIO_AF8 (8 << GPIO_AF_SHIFT)
# define GPIO_AF9 (9 << GPIO_AF_SHIFT)
# define GPIO_AF10 (10 << GPIO_AF_SHIFT)
# define GPIO_AF11 (11 << GPIO_AF_SHIFT)
# define GPIO_AF12 (12 << GPIO_AF_SHIFT)
# define GPIO_AF13 (13 << GPIO_AF_SHIFT)
# define GPIO_AF14 (14 << GPIO_AF_SHIFT)
# define GPIO_AF15 (15 << GPIO_AF_SHIFT)
/* Output/Alt function frequency selection:
*
* 1111 1111 1100 0000 0000
* 9876 5432 1098 7654 3210
* ---- ---- ---- ---- ----
* .... .... FF.. .... ....
*/
#define GPIO_SPEED_SHIFT (10) /* Bits 10-11: GPIO frequency selection */
#define GPIO_SPEED_MASK (3 << GPIO_SPEED_SHIFT)
# define GPIO_SPEED_2MHz (0 << GPIO_SPEED_SHIFT) /* 2 MHz Low speed output */
# define GPIO_SPEED_10MHz (1 << GPIO_SPEED_SHIFT) /* 10 MHz Medium speed output */
# define GPIO_SPEED_50MHz (2 << GPIO_SPEED_SHIFT) /* 50 MHz High speed output */
/* Output/Alt function type selection:
*
* 1111 1111 1100 0000 0000
* 9876 5432 1098 7654 3210
* ---- ---- ---- ---- ----
* .... .... ..O. .... ....
*/
#define GPIO_OPENDRAIN (1 << 9) /* Bit9: 1=Open-drain output */
#define GPIO_PUSHPULL (0) /* Bit9: 0=Push-pull output */
/* If the pin is a GPIO digital output, then this identifies the initial output value.
* If the pin is an input, this bit is overloaded to provide the qualifier to
* distinquish input pull-up and -down:
*
* 1111 1111 1100 0000 0000
* 9876 5432 1098 7654 3210
* ---- ---- ---- ---- ----
* .... .... ...V .... ....
*/
#define GPIO_OUTPUT_SET (1 << 8) /* Bit 8: If output, inital value of output */
#define GPIO_OUTPUT_CLEAR (0)
/* External interrupt selection (GPIO inputs only):
*
* 1111 1111 1100 0000 0000
* 9876 5432 1098 7654 3210
* ---- ---- ---- ---- ----
* .... .... ...X .... ....
*/
#define GPIO_EXTI (1 << 8) /* Bit 8: Configure as EXTI interrupt */
/* This identifies the GPIO port:
*
* 1111 1111 1100 0000 0000
* 9876 5432 1098 7654 3210
* ---- ---- ---- ---- ----
* .... .... .... PPPP ....
*/
#define GPIO_PORT_SHIFT (4) /* Bit 4-7: Port number */
#define GPIO_PORT_MASK (15 << GPIO_PORT_SHIFT)
# define GPIO_PORTA (0 << GPIO_PORT_SHIFT) /* GPIOA */
# define GPIO_PORTB (1 << GPIO_PORT_SHIFT) /* GPIOB */
# define GPIO_PORTC (2 << GPIO_PORT_SHIFT) /* GPIOC */
# define GPIO_PORTD (3 << GPIO_PORT_SHIFT) /* GPIOD */
# define GPIO_PORTE (4 << GPIO_PORT_SHIFT) /* GPIOE */
# define GPIO_PORTF (5 << GPIO_PORT_SHIFT) /* GPIOF */
# define GPIO_PORTG (6 << GPIO_PORT_SHIFT) /* GPIOG */
# define GPIO_PORTH (7 << GPIO_PORT_SHIFT) /* GPIOH */
/* This identifies the bit in the port:
*
* 1111 1111 1100 0000 0000
* 9876 5432 1098 7654 3210
* ---- ---- ---- ---- ----
* .... .... .... .... BBBB
*/
#define GPIO_PIN_SHIFT (0) /* Bits 0-3: GPIO number: 0-15 */
#define GPIO_PIN_MASK (15 << GPIO_PIN_SHIFT)
# define GPIO_PIN0 (0 << GPIO_PIN_SHIFT)
# define GPIO_PIN1 (1 << GPIO_PIN_SHIFT)
# define GPIO_PIN2 (2 << GPIO_PIN_SHIFT)
# define GPIO_PIN3 (3 << GPIO_PIN_SHIFT)
# define GPIO_PIN4 (4 << GPIO_PIN_SHIFT)
# define GPIO_PIN5 (5 << GPIO_PIN_SHIFT)
# define GPIO_PIN6 (6 << GPIO_PIN_SHIFT)
# define GPIO_PIN7 (7 << GPIO_PIN_SHIFT)
# define GPIO_PIN8 (8 << GPIO_PIN_SHIFT)
# define GPIO_PIN9 (9 << GPIO_PIN_SHIFT)
# define GPIO_PIN10 (10 << GPIO_PIN_SHIFT)
# define GPIO_PIN11 (11 << GPIO_PIN_SHIFT)
# define GPIO_PIN12 (12 << GPIO_PIN_SHIFT)
# define GPIO_PIN13 (13 << GPIO_PIN_SHIFT)
# define GPIO_PIN14 (14 << GPIO_PIN_SHIFT)
# define GPIO_PIN15 (15 << GPIO_PIN_SHIFT)
/************************************************************************************
* Public Data
************************************************************************************/
#ifndef __ASSEMBLY__
#undef EXTERN
#if defined(__cplusplus)
#define EXTERN extern "C"
extern "C"
{
#else
#define EXTERN extern
#endif
/* Base addresses for each GPIO block */
EXTERN const uint32_t g_gpiobase[STM32F0_NPORTS];
/************************************************************************************
* Public Function Prototypes
************************************************************************************/
/************************************************************************************
* Name: stm32f0_configgpio
*
* Description:
* Configure a GPIO pin based on bit-encoded description of the pin.
* Once it is configured as Alternative (GPIO_ALT|GPIO_CNF_AFPP|...)
* function, it must be unconfigured with stm32f0_unconfiggpio() with
* the same cfgset first before it can be set to non-alternative function.
*
* Returns:
* OK on success
* ERROR on invalid port, or when pin is locked as ALT function.
*
************************************************************************************/
int stm32f0_configgpio(uint32_t cfgset);
/************************************************************************************
* Name: stm32f0_unconfiggpio
*
* Description:
* Unconfigure a GPIO pin based on bit-encoded description of the pin, set it
* into default HiZ state (and possibly mark it's unused) and unlock it whether
* it was previsouly selected as alternative function (GPIO_ALT|GPIO_CNF_AFPP|...).
*
* This is a safety function and prevents hardware from schocks, as unexpected
* write to the Timer Channel Output GPIO to fixed '1' or '0' while it should
* operate in PWM mode could produce excessive on-board currents and trigger
* over-current/alarm function.
*
* Returns:
* OK on success
* ERROR on invalid port
*
************************************************************************************/
int stm32f0_unconfiggpio(uint32_t cfgset);
/************************************************************************************
* Name: stm32f0_gpiowrite
*
* Description:
* Write one or zero to the selected GPIO pin
*
************************************************************************************/
void stm32f0_gpiowrite(uint32_t pinset, bool value);
/************************************************************************************
* Name: stm32f0_gpioread
*
* Description:
* Read one or zero from the selected GPIO pin
*
************************************************************************************/
bool stm32f0_gpioread(uint32_t pinset);
/************************************************************************************
* Name: stm32f0_gpiosetevent
*
* Description:
* Sets/clears GPIO based event and interrupt triggers.
*
* Input Parameters:
* pinset - GPIO pin configuration
* risingedge - Enables interrupt on rising edges
* fallingedge - Enables interrupt on falling edges
* event - Generate event when set
* func - When non-NULL, generate interrupt
* arg - Argument passed to the interrupt callback
*
* Returned Value:
* Zero (OK) is returned on success, otherwise a negated errno value is returned
* to indicate the nature of the failure.
*
************************************************************************************/
int stm32f0_gpiosetevent(uint32_t pinset, bool risingedge, bool fallingedge,
bool event, xcpt_t func, void *arg);
/************************************************************************************
* Function: stm32f0_dumpgpio
*
* Description:
* Dump all GPIO registers associated with the provided base address
*
************************************************************************************/
#ifdef CONFIG_DEBUG_FEATURES
int stm32f0_dumpgpio(uint32_t pinset, const char *msg);
#else
# define stm32f0_dumpgpio(p,m)
#endif
/************************************************************************************
* Function: stm32f0_gpioinit
*
* Description:
* Based on configuration within the .config file, it does:
* - Remaps positions of alternative functions.
*
* Typically called from stm32f0_start().
*
************************************************************************************/
void stm32f0_gpioinit(void);
#undef EXTERN
#if defined(__cplusplus)
}
#endif
#endif /* __ASSEMBLY__ */
#endif /* __ARCH_ARM_SRC_STM32F0_STM32F0_GPIO_H */

View File

@ -0,0 +1,111 @@
/****************************************************************************
* arch/arm/src/stm32f0/stm32f0_idle.c
*
* Copyright (C) 2017 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
* Alan Carvalho de Assis <acassis@gmail.com>
*
* 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 NuttX 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 OWNER 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.
*
****************************************************************************/
/****************************************************************************
* Included Files
****************************************************************************/
#include <arch/board/board.h>
#include <nuttx/config.h>
#include <nuttx/arch.h>
#include "up_internal.h"
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/* Does the board support an IDLE LED to indicate that the board is in the
* IDLE state?
*/
#if defined(CONFIG_ARCH_LEDS) && defined(LED_IDLE)
# define BEGIN_IDLE() board_autoled_on(LED_IDLE)
# define END_IDLE() board_autoled_off(LED_IDLE)
#else
# define BEGIN_IDLE()
# define END_IDLE()
#endif
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: up_idle
*
* Description:
* up_idle() is the logic that will be executed when their is no other
* ready-to-run task. This is processor idle time and will continue until
* some interrupt occurs to cause a context switch from the idle task.
*
* Processing in this state may be processor-specific. e.g., this is where
* power management operations might be performed.
*
****************************************************************************/
void up_idle(void)
{
#if defined(CONFIG_SUPPRESS_INTERRUPTS) || defined(CONFIG_SUPPRESS_TIMER_INTS)
/* If the system is idle and there are no timer interrupts, then process
* "fake" timer interrupts. Hopefully, something will wake up.
*/
sched_process_timer();
#else
/* If the g_dma_inprogress is zero, then there is no DMA in progress. This
* value is needed in the IDLE loop to determine if the IDLE loop should
* go into lower power power consumption modes. According to the LPC17xx
* User Manual: "The DMA controller can continue to work in Sleep mode, and
* has access to the peripheral SRAMs and all peripheral registers. The
* flash memory and the Main SRAM are not available in Sleep mode, they are
* disabled in order to save power."
*/
#ifdef CONFIG_STM32F0_GPDMA
if (g_dma_inprogress == 0)
#endif
{
/* Sleep until an interrupt occurs in order to save power */
BEGIN_IDLE();
asm("WFI");
END_IDLE();
}
#endif
}

View File

@ -0,0 +1,341 @@
/****************************************************************************
* arch/arm/src/stm32f0/stm32f0_irq.c
*
* Copyright (C) 2017 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
* Alan Carvalho de Assis <acassis@gmail.com>
*
* 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 NuttX 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 OWNER 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.
*
****************************************************************************/
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <stdint.h>
#include <debug.h>
#include <nuttx/irq.h>
#include <nuttx/arch.h>
#include <arch/irq.h>
#include "nvic.h"
#include "up_arch.h"
#include "up_internal.h"
//#include "stm32f0_irq.h"
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/* Get a 32-bit version of the default priority */
#define DEFPRIORITY32 \
(NVIC_SYSH_PRIORITY_DEFAULT << 24 | NVIC_SYSH_PRIORITY_DEFAULT << 16 | \
NVIC_SYSH_PRIORITY_DEFAULT << 8 | NVIC_SYSH_PRIORITY_DEFAULT)
/****************************************************************************
* Public Data
****************************************************************************/
/* g_current_regs[] holds a references to the current interrupt level
* register storage structure. If is non-NULL only during interrupt
* processing. Access to g_current_regs[] must be through the macro
* CURRENT_REGS for portability.
*/
volatile uint32_t *g_current_regs[1];
/****************************************************************************
* Private Functions
****************************************************************************/
/****************************************************************************
* Name: stm32f0_dumpnvic
*
* Description:
* Dump some interesting NVIC registers
*
****************************************************************************/
#if defined(CONFIG_DEBUG_IRQ_INFO)
static void stm32f0_dumpnvic(const char *msg, int irq)
{
irqstate_t flags;
flags = enter_critical_section();
irqinfo("NVIC (%s, irq=%d):\n", msg, irq);
irqinfo(" ISER: %08x ICER: %08x\n",
getreg32(ARMV6M_NVIC_ISER), getreg32(ARMV6M_NVIC_ICER));
irqinfo(" ISPR: %08x ICPR: %08x\n",
getreg32(ARMV6M_NVIC_ISPR), getreg32(ARMV6M_NVIC_ICPR));
irqinfo(" IRQ PRIO: %08x %08x %08x %08x\n",
getreg32(ARMV6M_NVIC_IPR0), getreg32(ARMV6M_NVIC_IPR1),
getreg32(ARMV6M_NVIC_IPR2), getreg32(ARMV6M_NVIC_IPR3));
irqinfo(" %08x %08x %08x %08x\n",
getreg32(ARMV6M_NVIC_IPR4), getreg32(ARMV6M_NVIC_IPR5),
getreg32(ARMV6M_NVIC_IPR6), getreg32(ARMV6M_NVIC_IPR7));
irqinfo("SYSCON:\n");
irqinfo(" CPUID: %08x\n",
getreg32(ARMV6M_SYSCON_CPUID));
irqinfo(" ICSR: %08x AIRCR: %08x\n",
getreg32(ARMV6M_SYSCON_ICSR), getreg32(ARMV6M_SYSCON_AIRCR));
irqinfo(" SCR: %08x CCR: %08x\n",
getreg32(ARMV6M_SYSCON_SCR), getreg32(ARMV6M_SYSCON_CCR));
irqinfo(" SHPR2: %08x SHPR3: %08x\n",
getreg32(ARMV6M_SYSCON_SHPR2), getreg32(ARMV6M_SYSCON_SHPR3));
leave_critical_section(flags);
}
#else
# define stm32f0_dumpnvic(msg, irq)
#endif
/****************************************************************************
* Name: stm32f0_nmi, stm32f0_busfault, stm32f0_usagefault, stm32f0_pendsv,
* stm32f0_dbgmonitor, stm32f0_pendsv, stm32f0_reserved
*
* Description:
* Handlers for various execptions. None are handled and all are fatal
* error conditions. The only advantage these provided over the default
* unexpected interrupt handler is that they provide a diagnostic output.
*
****************************************************************************/
#ifdef CONFIG_DEBUG_FEATURES
static int stm32f0_nmi(int irq, FAR void *context, FAR void *arg)
{
(void)up_irq_save();
_err("PANIC!!! NMI received\n");
PANIC();
return 0;
}
static int stm32f0_pendsv(int irq, FAR void *context, FAR void *arg)
{
(void)up_irq_save();
_err("PANIC!!! PendSV received\n");
PANIC();
return 0;
}
static int stm32f0_reserved(int irq, FAR void *context, FAR void *arg)
{
(void)up_irq_save();
_err("PANIC!!! Reserved interrupt\n");
PANIC();
return 0;
}
#endif
/****************************************************************************
* Name: stm32f0_clrpend
*
* Description:
* Clear a pending interrupt at the NVIC.
*
****************************************************************************/
static inline void stm32f0_clrpend(int irq)
{
/* This will be called on each interrupt exit whether the interrupt can be
* enambled or not. So this assertion is necessarily lame.
*/
DEBUGASSERT((unsigned)irq < NR_IRQS);
/* Check for an external interrupt */
if (irq >= STM32F0_IRQ_EXTINT && irq < (STM32F0_IRQ_EXTINT + 32))
{
/* Set the appropriate bit in the ISER register to enable the
* interrupt
*/
putreg32((1 << (irq - STM32F0_IRQ_EXTINT)), ARMV6M_NVIC_ICPR);
}
}
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: up_irqinitialize
****************************************************************************/
void up_irqinitialize(void)
{
uint32_t regaddr;
int i;
/* Disable all interrupts */
putreg32(0xffffffff, ARMV6M_NVIC_ICER);
/* Set all interrupts (and exceptions) to the default priority */
putreg32(DEFPRIORITY32, ARMV6M_SYSCON_SHPR2);
putreg32(DEFPRIORITY32, ARMV6M_SYSCON_SHPR3);
/* Now set all of the interrupt lines to the default priority */
for (i = 0; i < 8; i++)
{
regaddr = ARMV6M_NVIC_IPR(i);
putreg32(DEFPRIORITY32, regaddr);
}
/* currents_regs is non-NULL only while processing an interrupt */
CURRENT_REGS = NULL;
/* Attach the SVCall and Hard Fault exception handlers. The SVCall
* exception is used for performing context switches; The Hard Fault
* must also be caught because a SVCall may show up as a Hard Fault
* under certain conditions.
*/
irq_attach(STM32F0_IRQ_SVCALL, up_svcall, NULL);
irq_attach(STM32F0_IRQ_HARDFAULT, up_hardfault, NULL);
/* Attach all other processor exceptions (except reset and sys tick) */
#ifdef CONFIG_DEBUG_FEATURES
irq_attach(STM32F0_IRQ_NMI, stm32f0_nmi, NULL);
irq_attach(STM32F0_IRQ_PENDSV, stm32f0_pendsv, NULL);
irq_attach(STM32F0_IRQ_RESERVED, stm32f0_reserved, NULL);
#endif
stm32f0_dumpnvic("initial", NR_IRQS);
/* Initialize logic to support a second level of interrupt decoding for
* configured pin interrupts.
*/
#ifdef CONFIG_STM32F0_GPIOIRQ
stm32f0_gpioirqinitialize();
#endif
#ifndef CONFIG_SUPPRESS_INTERRUPTS
/* And finally, enable interrupts */
up_irq_enable();
#endif
}
/****************************************************************************
* Name: up_disable_irq
*
* Description:
* Disable the IRQ specified by 'irq'
*
****************************************************************************/
void up_disable_irq(int irq)
{
DEBUGASSERT((unsigned)irq < NR_IRQS);
/* Check for an external interrupt */
if (irq >= STM32F0_IRQ_EXTINT && irq < (STM32F0_IRQ_EXTINT + 32))
{
/* Set the appropriate bit in the ICER register to disable the
* interrupt
*/
putreg32((1 << (irq - STM32F0_IRQ_EXTINT)), ARMV6M_NVIC_ICER);
}
/* Handle processor exceptions. Only SysTick can be disabled */
else if (irq == STM32F0_IRQ_SYSTICK)
{
modifyreg32(ARMV6M_SYSTICK_CSR, SYSTICK_CSR_ENABLE, 0);
}
stm32f0_dumpnvic("disable", irq);
}
/****************************************************************************
* Name: up_enable_irq
*
* Description:
* Enable the IRQ specified by 'irq'
*
****************************************************************************/
void up_enable_irq(int irq)
{
/* This will be called on each interrupt exit whether the interrupt can be
* enabled or not. So this assertion is necessarily lame.
*/
DEBUGASSERT((unsigned)irq < NR_IRQS);
/* Check for external interrupt */
if (irq >= STM32F0_IRQ_EXTINT && irq < (STM32F0_IRQ_EXTINT + 32))
{
/* Set the appropriate bit in the ISER register to enable the
* interrupt
*/
putreg32((1 << (irq - STM32F0_IRQ_EXTINT)), ARMV6M_NVIC_ISER);
}
/* Handle processor exceptions. Only SysTick can be disabled */
else if (irq == STM32F0_IRQ_SYSTICK)
{
modifyreg32(ARMV6M_SYSTICK_CSR, 0, SYSTICK_CSR_ENABLE);
}
stm32f0_dumpnvic("enable", irq);
}
/****************************************************************************
* Name: up_ack_irq
*
* Description:
* Acknowledge the IRQ
*
****************************************************************************/
void up_ack_irq(int irq)
{
stm32f0_clrpend(irq);
}

View File

@ -0,0 +1,367 @@
/****************************************************************************
* arch/arm/src/stm32f0/stm32f0_lowputc.c
*
* Copyright (C) 2009, 2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
* Alan Carvalho de Assis <acassis@gmail.com>
*
* 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 NuttX 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 OWNER 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.
*
****************************************************************************/
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <stdint.h>
#include <arch/board/board.h>
#include "up_internal.h"
#include "up_arch.h"
#include "chip.h"
#include "stm32f0_rcc.h"
#include "stm32f0_gpio.h"
#include "stm32f0_uart.h"
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/* Select USART parameters for the selected console */
#ifdef HAVE_CONSOLE
# if defined(CONFIG_USART1_SERIAL_CONSOLE)
# define STM32F0_CONSOLE_BASE STM32F0_USART1_BASE
# define STM32F0_APBCLOCK STM32F0_PCLK2_FREQUENCY
# define STM32F0_CONSOLE_APBREG STM32F0_RCC_APB2ENR
# define STM32F0_CONSOLE_APBEN RCC_APB2ENR_USART1EN
# define STM32F0_CONSOLE_BAUD CONFIG_USART1_BAUD
# define STM32F0_CONSOLE_BITS CONFIG_USART1_BITS
# define STM32F0_CONSOLE_PARITY CONFIG_USART1_PARITY
# define STM32F0_CONSOLE_2STOP CONFIG_USART1_2STOP
# define STM32F0_CONSOLE_TX GPIO_USART1_TX
# define STM32F0_CONSOLE_RX GPIO_USART1_RX
# ifdef CONFIG_USART1_RS485
# define STM32F0_CONSOLE_RS485_DIR GPIO_USART1_RS485_DIR
# if (CONFIG_USART1_RS485_DIR_POLARITY == 0)
# define STM32F0_CONSOLE_RS485_DIR_POLARITY false
# else
# define STM32F0_CONSOLE_RS485_DIR_POLARITY true
# endif
# endif
# elif defined(CONFIG_USART2_SERIAL_CONSOLE)
# define STM32F0_CONSOLE_BASE STM32F0_USART2_BASE
# define STM32F0_APBCLOCK STM32F0_PCLK1_FREQUENCY
# define STM32F0_CONSOLE_APBREG STM32F0_RCC_APB1ENR1
# define STM32F0_CONSOLE_APBEN RCC_APB1ENR1_USART2EN
# define STM32F0_CONSOLE_BAUD CONFIG_USART2_BAUD
# define STM32F0_CONSOLE_BITS CONFIG_USART2_BITS
# define STM32F0_CONSOLE_PARITY CONFIG_USART2_PARITY
# define STM32F0_CONSOLE_2STOP CONFIG_USART2_2STOP
# define STM32F0_CONSOLE_TX GPIO_USART2_TX
# define STM32F0_CONSOLE_RX GPIO_USART2_RX
# ifdef CONFIG_USART2_RS485
# define STM32F0_CONSOLE_RS485_DIR GPIO_USART2_RS485_DIR
# if (CONFIG_USART2_RS485_DIR_POLARITY == 0)
# define STM32F0_CONSOLE_RS485_DIR_POLARITY false
# else
# define STM32F0_CONSOLE_RS485_DIR_POLARITY true
# endif
# endif
# elif defined(CONFIG_USART3_SERIAL_CONSOLE)
# define STM32F0_CONSOLE_BASE STM32F0_USART3_BASE
# define STM32F0_APBCLOCK STM32F0_PCLK1_FREQUENCY
# define STM32F0_CONSOLE_APBREG STM32F0_RCC_APB1ENR1
# define STM32F0_CONSOLE_APBEN RCC_APB1ENR1_USART3EN
# define STM32F0_CONSOLE_BAUD CONFIG_USART3_BAUD
# define STM32F0_CONSOLE_BITS CONFIG_USART3_BITS
# define STM32F0_CONSOLE_PARITY CONFIG_USART3_PARITY
# define STM32F0_CONSOLE_2STOP CONFIG_USART3_2STOP
# define STM32F0_CONSOLE_TX GPIO_USART3_TX
# define STM32F0_CONSOLE_RX GPIO_USART3_RX
# ifdef CONFIG_USART3_RS485
# define STM32F0_CONSOLE_RS485_DIR GPIO_USART3_RS485_DIR
# if (CONFIG_USART3_RS485_DIR_POLARITY == 0)
# define STM32F0_CONSOLE_RS485_DIR_POLARITY false
# else
# define STM32F0_CONSOLE_RS485_DIR_POLARITY true
# endif
# endif
# elif defined(CONFIG_UART4_SERIAL_CONSOLE)
# define STM32F0_CONSOLE_BASE STM32F0_UART4_BASE
# define STM32F0_APBCLOCK STM32F0_PCLK1_FREQUENCY
# define STM32F0_CONSOLE_APBREG STM32F0_RCC_APB1ENR1
# define STM32F0_CONSOLE_APBEN RCC_APB1ENR1_UART4EN
# define STM32F0_CONSOLE_BAUD CONFIG_UART4_BAUD
# define STM32F0_CONSOLE_BITS CONFIG_UART4_BITS
# define STM32F0_CONSOLE_PARITY CONFIG_UART4_PARITY
# define STM32F0_CONSOLE_2STOP CONFIG_UART4_2STOP
# define STM32F0_CONSOLE_TX GPIO_UART4_TX
# define STM32F0_CONSOLE_RX GPIO_UART4_RX
# ifdef CONFIG_UART4_RS485
# define STM32F0_CONSOLE_RS485_DIR GPIO_UART4_RS485_DIR
# if (CONFIG_UART4_RS485_DIR_POLARITY == 0)
# define STM32F0_CONSOLE_RS485_DIR_POLARITY false
# else
# define STM32F0_CONSOLE_RS485_DIR_POLARITY true
# endif
# endif
# elif defined(CONFIG_UART5_SERIAL_CONSOLE)
# define STM32F0_CONSOLE_BASE STM32F0_UART5_BASE
# define STM32F0_APBCLOCK STM32F0_PCLK1_FREQUENCY
# define STM32F0_CONSOLE_APBREG STM32F0_RCC_APB1ENR1
# define STM32F0_CONSOLE_APBEN RCC_APB1ENR1_UART5EN
# define STM32F0_CONSOLE_BAUD CONFIG_UART5_BAUD
# define STM32F0_CONSOLE_BITS CONFIG_UART5_BITS
# define STM32F0_CONSOLE_PARITY CONFIG_UART5_PARITY
# define STM32F0_CONSOLE_2STOP CONFIG_UART5_2STOP
# define STM32F0_CONSOLE_TX GPIO_UART5_TX
# define STM32F0_CONSOLE_RX GPIO_UART5_RX
# ifdef CONFIG_UART5_RS485
# define STM32F0_CONSOLE_RS485_DIR GPIO_UART5_RS485_DIR
# if (CONFIG_UART5_RS485_DIR_POLARITY == 0)
# define STM32F0_CONSOLE_RS485_DIR_POLARITY false
# else
# define STM32F0_CONSOLE_RS485_DIR_POLARITY true
# endif
# endif
# endif
/* CR1 settings */
# if STM32F0_CONSOLE_BITS == 9
# define USART_CR1_M0_VALUE USART_CR1_M0
# define USART_CR1_M1_VALUE 0
# elif STM32F0_CONSOLE_BITS == 7
# define USART_CR1_M0_VALUE 0
# define USART_CR1_M1_VALUE USART_CR1_M1
# else /* 8 bits */
# define USART_CR1_M0_VALUE 0
# define USART_CR1_M1_VALUE 0
# endif
# if STM32F0_CONSOLE_PARITY == 1 /* odd parity */
# define USART_CR1_PARITY_VALUE (USART_CR1_PCE|USART_CR1_PS)
# elif STM32F0_CONSOLE_PARITY == 2 /* even parity */
# define USART_CR1_PARITY_VALUE USART_CR1_PCE
# else /* no parity */
# define USART_CR1_PARITY_VALUE 0
# endif
# define USART_CR1_CLRBITS \
(USART_CR1_UESM | USART_CR1_RE | USART_CR1_TE | USART_CR1_PS | \
USART_CR1_PCE | USART_CR1_WAKE | USART_CR1_M0 | USART_CR1_M1 | \
USART_CR1_MME | USART_CR1_OVER8 | USART_CR1_DEDT_MASK | \
USART_CR1_DEAT_MASK | USART_CR1_ALLINTS)
# define USART_CR1_SETBITS (USART_CR1_M0_VALUE|USART_CR1_M1_VALUE|USART_CR1_PARITY_VALUE)
/* CR2 settings */
# if STM32F0_CONSOLE_2STOP != 0
# define USART_CR2_STOP2_VALUE USART_CR2_STOP2
# else
# define USART_CR2_STOP2_VALUE 0
# endif
# define USART_CR2_CLRBITS \
(USART_CR2_ADDM7 | USART_CR2_LBDL | USART_CR2_LBDIE | USART_CR2_LBCL | \
USART_CR2_CPHA | USART_CR2_CPOL | USART_CR2_CLKEN | USART_CR2_STOP_MASK | \
USART_CR2_LINEN | USART_CR2_SWAP | USART_CR2_RXINV | USART_CR2_TXINV | \
USART_CR2_DATAINV | USART_CR2_MSBFIRST | USART_CR2_ABREN | \
USART_CR2_ABRMOD_MASK | USART_CR2_RTOEN | USART_CR2_ADD_MASK)
# define USART_CR2_SETBITS USART_CR2_STOP2_VALUE
/* CR3 settings */
# define USART_CR3_CLRBITS \
(USART_CR3_EIE | USART_CR3_IREN | USART_CR3_IRLP | USART_CR3_HDSEL | \
USART_CR3_NACK | USART_CR3_SCEN | USART_CR3_DMAR | USART_CR3_DMAT | \
USART_CR3_RTSE | USART_CR3_CTSE | USART_CR3_CTSIE | USART_CR3_ONEBIT | \
USART_CR3_OVRDIS | USART_CR3_DDRE | USART_CR3_DEM | USART_CR3_DEP | \
USART_CR3_SCARCNT2_MASK | USART_CR3_WUS_MASK | USART_CR3_WUFIE)
# define USART_CR3_SETBITS 0
# undef USE_OVER8
/* Calculate USART BAUD rate divider */
/* Baud rate for standard USART (SPI mode included):
*
* In case of oversampling by 16, the equation is:
* baud = fCK / UARTDIV
* UARTDIV = fCK / baud
*
* In case of oversampling by 8, the equation is:
*
* baud = 2 * fCK / UARTDIV
* UARTDIV = 2 * fCK / baud
*/
# define STM32F0_USARTDIV8 \
(((STM32F0_APBCLOCK << 1) + (STM32F0_CONSOLE_BAUD >> 1)) / STM32F0_CONSOLE_BAUD)
# define STM32F0_USARTDIV16 \
((STM32F0_APBCLOCK + (STM32F0_CONSOLE_BAUD >> 1)) / STM32F0_CONSOLE_BAUD)
/* Use oversamply by 8 only if the divisor is small. But what is small? */
# if STM32F0_USARTDIV8 > 100
# define STM32F0_BRR_VALUE STM32F0_USARTDIV16
# else
# define USE_OVER8 1
# define STM32F0_BRR_VALUE \
((STM32F0_USARTDIV8 & 0xfff0) | ((STM32F0_USARTDIV8 & 0x000f) >> 1))
# endif
#endif /* HAVE_CONSOLE */
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: up_lowputc
*
* Description:
* Output one byte on the serial console
*
****************************************************************************/
void up_lowputc(char ch)
{
#ifdef HAVE_CONSOLE
/* Wait until the TX data register is empty */
while ((getreg32(STM32F0_CONSOLE_BASE + STM32F0_USART_ISR_OFFSET) & USART_ISR_TXE) == 0);
#ifdef STM32F0_CONSOLE_RS485_DIR
stm32f0_gpiowrite(STM32F0_CONSOLE_RS485_DIR, STM32F0_CONSOLE_RS485_DIR_POLARITY);
#endif
/* Then send the character */
putreg32((uint32_t)ch, STM32F0_CONSOLE_BASE + STM32F0_USART_TDR_OFFSET);
#ifdef STM32F0_CONSOLE_RS485_DIR
while ((getreg32(STM32F0_CONSOLE_BASE + STM32F0_USART_ISR_OFFSET) & USART_ISR_TC) == 0);
stm32f0_gpiowrite(STM32F0_CONSOLE_RS485_DIR, !STM32F0_CONSOLE_RS485_DIR_POLARITY);
#endif
#endif /* HAVE_CONSOLE */
}
/****************************************************************************
* Name: stm32f0_lowsetup
*
* Description:
* This performs basic initialization of the USART used for the serial
* console. Its purpose is to get the console output availabe as soon
* as possible.
*
****************************************************************************/
void stm32f0_lowsetup(void)
{
#if defined(HAVE_UART)
#if defined(HAVE_CONSOLE) && !defined(CONFIG_SUPPRESS_UART_CONFIG)
uint32_t cr;
#endif
#if defined(HAVE_CONSOLE)
/* Enable USART APB1/2 clock */
modifyreg32(STM32F0_CONSOLE_APBREG, 0, STM32F0_CONSOLE_APBEN);
#endif
/* Enable the console USART and configure GPIO pins needed for rx/tx.
*
* NOTE: Clocking for selected U[S]ARTs was already provided in stm32f0_rcc.c
*/
#ifdef STM32F0_CONSOLE_TX
stm32f0_configgpio(STM32F0_CONSOLE_TX);
#endif
#ifdef STM32F0_CONSOLE_RX
stm32f0_configgpio(STM32F0_CONSOLE_RX);
#endif
#ifdef STM32F0_CONSOLE_RS485_DIR
stm32f0_configgpio(STM32F0_CONSOLE_RS485_DIR);
stm32f0_gpiowrite(STM32F0_CONSOLE_RS485_DIR, !STM32F0_CONSOLE_RS485_DIR_POLARITY);
#endif
/* Enable and configure the selected console device */
#if defined(HAVE_CONSOLE) && !defined(CONFIG_SUPPRESS_UART_CONFIG)
/* Configure CR2 */
cr = getreg32(STM32F0_CONSOLE_BASE + STM32F0_USART_CR2_OFFSET);
cr &= ~USART_CR2_CLRBITS;
cr |= USART_CR2_SETBITS;
putreg32(cr, STM32F0_CONSOLE_BASE + STM32F0_USART_CR2_OFFSET);
/* Configure CR1 */
cr = getreg32(STM32F0_CONSOLE_BASE + STM32F0_USART_CR1_OFFSET);
cr &= ~USART_CR1_CLRBITS;
cr |= USART_CR1_SETBITS;
putreg32(cr, STM32F0_CONSOLE_BASE + STM32F0_USART_CR1_OFFSET);
/* Configure CR3 */
cr = getreg32(STM32F0_CONSOLE_BASE + STM32F0_USART_CR3_OFFSET);
cr &= ~USART_CR3_CLRBITS;
cr |= USART_CR3_SETBITS;
putreg32(cr, STM32F0_CONSOLE_BASE + STM32F0_USART_CR3_OFFSET);
/* Configure the USART Baud Rate */
putreg32(STM32F0_BRR_VALUE, STM32F0_CONSOLE_BASE + STM32F0_USART_BRR_OFFSET);
/* Select oversampling by 8 */
cr = getreg32(STM32F0_CONSOLE_BASE + STM32F0_USART_CR1_OFFSET);
#ifdef USE_OVER8
cr |= USART_CR1_OVER8;
putreg32(cr, STM32F0_CONSOLE_BASE + STM32F0_USART_CR1_OFFSET);
#endif
/* Enable Rx, Tx, and the USART */
cr |= (USART_CR1_UE | USART_CR1_TE | USART_CR1_RE);
putreg32(cr, STM32F0_CONSOLE_BASE + STM32F0_USART_CR1_OFFSET);
#endif /* HAVE_CONSOLE && !CONFIG_SUPPRESS_UART_CONFIG */
#endif /* HAVE_UART */
}

View File

@ -0,0 +1,80 @@
/************************************************************************************
* arch/arm/src/stm32f0/stm32f0_lowputc.h
*
* Copyright (C) 2017 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
* Alan Carvalho de Assis <acassis@gmail.com>
*
* 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 NuttX 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 OWNER 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.
*
************************************************************************************/
#ifndef __ARCH_ARM_SRC_STM32F0_STM32F0_LOWPUTC_H
#define __ARCH_ARM_SRC_STM32F0_STM32F0_LOWPUTC_H
/************************************************************************************
* Included Files
************************************************************************************/
#include <nuttx/config.h>
#include "chip.h"
/************************************************************************************
* Public Function Prototypes
************************************************************************************/
#ifndef __ASSEMBLY__
#undef EXTERN
#if defined(__cplusplus)
#define EXTERN extern "C"
extern "C"
{
#else
#define EXTERN extern
#endif
/************************************************************************************
* Name: stm32f0_lowsetup
*
* Description:
* Called at the very beginning of _start. Performs low level initialization
* of serial console.
*
************************************************************************************/
void stm32f0_lowsetup(void);
#undef EXTERN
#if defined(__cplusplus)
}
#endif
#endif /* __ASSEMBLY__ */
#endif /* __ARCH_ARM_SRC_STM32F0_STM32F0_LOWPUTC_H */

View File

@ -0,0 +1,51 @@
/************************************************************************************
* arch/arm/src/stm32f0/stm32f0_rcc.h
*
* Copyright (C) 2017 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.orgr>
* Alan Carvalho de Assis <acassis@gmail.com>
*
* 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 NuttX 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 OWNER 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.
*
************************************************************************************/
#ifndef __ARCH_ARM_SRC_STM32F0_STM32F0_RRC_H
#define __ARCH_ARM_SRC_STM32F0_STM32F0_RRC_H
/************************************************************************************
* Included Files
************************************************************************************/
#include <nuttx/config.h>
#include "up_arch.h"
#include "chip.h"
#include "chip/stm32f0_rcc.h"
#endif /* __ARCH_ARM_SRC_STM32F0_STM32F0_RCC_H */

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,83 @@
/************************************************************************************
* arch/arm/src/stm32f0/stm32f0_serial.h
*
* Copyright (C) 2017 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
* Alan Carvalho de Assis <acassis@gmail.com>
*
* 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 NuttX 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 OWNER 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.
*
************************************************************************************/
#ifndef __ARCH_ARM_SRC_STM32F0_STM32F0_SERIAL_H
#define __ARCH_ARM_SRC_STM32F0_STM32F0_SERIAL_H
/************************************************************************************
* Included Files
************************************************************************************/
#include <nuttx/config.h>
#include <arch/board/board.h>
#include "chip/stm32f0_uart.h"
#include "chip/stm32f0_syscfg.h"
#include "stm32f0_gpio.h"
/************************************************************************************
* Pre-processor Definitions
************************************************************************************/
/* Configuration *********************************************************************/
/* Are any UARTs enabled? */
#undef HAVE_UART
#if defined(CONFIG_STM32F0_UART0)
# define HAVE_UART 1
#endif
/* Is there a serial console? There should be at most one defined. It could be on
* any UARTn, n=0,1,2,3
*/
#if defined(CONFIG_UART0_SERIAL_CONSOLE) && defined(CONFIG_STM32F0_UART0)
# define HAVE_SERIAL_CONSOLE 1
#else
# undef CONFIG_UART0_SERIAL_CONSOLE
# undef HAVE_SERIAL_CONSOLE
#endif
/* We cannot allow the DLM/DLL divisor to become to small or will will lose too
* much accuracy. This following is a "fudge factor" that represents the minimum
* value of the divisor that we will permit.
*/
#define UART_MINDL 32
#endif /* __ARCH_ARM_SRC_STM32F0_STM32F0_SERIAL_H */

View File

@ -0,0 +1,171 @@
/****************************************************************************
* arch/arm/src/stm32f0/stm32f0_start.c
*
* Copyright (C) 2017 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
* Alan Carvalho de Assis <acassis@gmail.com>
*
* 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 NuttX 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 OWNER 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.
*
****************************************************************************/
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <stdint.h>
#include <assert.h>
#include <debug.h>
#include <nuttx/init.h>
#include <arch/board/board.h>
#include "up_arch.h"
#include "up_internal.h"
#include "stm32f0_clockconfig.h"
#include "stm32f0_lowputc.h"
#ifdef CONFIG_ARCH_FPU
# include "nvic.h"
#endif
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
#define IDLE_STACK ((uint32_t)&_ebss+CONFIG_IDLETHREAD_STACKSIZE-4)
#define HEAP_BASE ((uint32_t)&_ebss+CONFIG_IDLETHREAD_STACKSIZE)
/****************************************************************************
* Public Data
****************************************************************************/
const uint32_t g_idle_topstack = IDLE_STACK;
/****************************************************************************
* Private Functions
****************************************************************************/
/****************************************************************************
* Name: showprogress
*
* Description:
* Print a character on the UART to show boot status.
*
****************************************************************************/
#ifdef CONFIG_DEBUG_FEATURES
# define showprogress(c) up_lowputc(c)
#else
# define showprogress(c)
#endif
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: _start
*
* Description:
* This is the reset entry point.
*
****************************************************************************/
void __start(void)
{
const uint32_t *src;
uint32_t *dest;
/* Configure the uart so that we can get debug output as soon as possible */
stm32f0_clockconfig();
stm32f0_lowsetup();
showprogress('A');
/* Clear .bss. We'll do this inline (vs. calling memset) just to be
* certain that there are no issues with the state of global variables.
*/
for (dest = &_sbss; dest < &_ebss; )
{
*dest++ = 0;
}
showprogress('B');
/* Move the initialized data section from his temporary holding spot in
* FLASH into the correct place in SRAM. The correct place in SRAM is
* give by _sdata and _edata. The temporary location is in FLASH at the
* end of all of the other read-only data (.text, .rodata) at _eronly.
*/
for (src = &_eronly, dest = &_sdata; dest < &_edata; )
{
*dest++ = *src++;
}
showprogress('C');
/* Perform early serial initialization */
#ifdef USE_EARLYSERIALINIT
up_earlyserialinit();
#endif
showprogress('D');
/* For the case of the separate user-/kernel-space build, perform whatever
* platform specific initialization of the user memory is required.
* Normally this just means initializing the user space .data and .bss
* segments.
*/
#ifdef CONFIG_BUILD_PROTECTED
stm32f0_userspace();
showprogress('E');
#endif
/* Initialize onboard resources */
stm32f0_boardinitialize();
showprogress('F');
/* Then start NuttX */
showprogress('\r');
showprogress('\n');
os_start();
/* Shouldn't get here */
for (; ; );
}

View File

@ -0,0 +1,165 @@
/****************************************************************************
* arch/arm/src/stm32f0/stm32f0_timerisr.c
*
* Copyright (C) 2017 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
* Alan Carvalho de Assis <acassis@gmail.com>
*
* 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 NuttX 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 OWNER 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.
*
****************************************************************************/
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <stdint.h>
#include <time.h>
#include <debug.h>
#include <nuttx/arch.h>
#include <arch/board/board.h>
#include "nvic.h"
#include "clock/clock.h"
#include "up_internal.h"
#include "up_arch.h"
#include "chip.h"
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/* "The CLKSOURCE bit in SysTick Control and Status register selects either
* the core clock (when CLKSOURCE = 1) or a divide-by-16 of the core clock
* (when CLKSOURCE = 0). ..."
*/
#if defined(CONFIG_STM32F0_SYSTICK_CORECLK)
# define SYSTICK_CLOCK STM32F0_MCLK /* Core clock */
#elif defined(CONFIG_STM32F0_SYSTICK_CORECLK_DIV16)
# define SYSTICK_CLOCK (STM32F0_MCLK / 16) /* Core clock divided by 16 */
#endif
/* The desired timer interrupt frequency is provided by the definition
* CLK_TCK (see include/time.h). CLK_TCK defines the desired number of
* system clock ticks per second. That value is a user configurable setting
* that defaults to 100 (100 ticks per second = 10 MS interval).
*
* Then, for example, if the external high speed crystal is the SysTick
* clock source and BOARD_XTALHI_FREQUENCY is 12MHz and CLK_TCK is 100, then
* the reload value would be:
*
* SYSTICK_RELOAD = (12,000,000 / 100) - 1
* = 119,999
* = 0x1d4bf
*
* Which fits within the maximum 24-bit reload value.
*/
#define SYSTICK_RELOAD ((SYSTICK_CLOCK / CLK_TCK) - 1)
/* The size of the reload field is 24 bits. Verify that the reload value
* will fit in the reload register.
*/
#if SYSTICK_RELOAD > 0x00ffffff
# error SYSTICK_RELOAD exceeds the range of the RELOAD register
#endif
/****************************************************************************
* Private Functions
****************************************************************************/
/****************************************************************************
* Function: stm32f0_timerisr
*
* Description:
* The timer ISR will perform a variety of services for various portions
* of the systems.
*
****************************************************************************/
static int stm32f0_timerisr(int irq, uint32_t *regs, FAR void *arg)
{
/* Process timer interrupt */
sched_process_timer();
return 0;
}
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Function: arm_timer_initialize
*
* Description:
* This function is called during start-up to initialize
* the timer interrupt.
*
****************************************************************************/
void arm_timer_initialize(void)
{
uint32_t regval;
/* Set the SysTick interrupt to the default priority */
regval = getreg32(ARMV6M_SYSCON_SHPR3);
regval &= ~SYSCON_SHPR3_PRI_15_MASK;
regval |= (NVIC_SYSH_PRIORITY_DEFAULT << SYSCON_SHPR3_PRI_15_SHIFT);
putreg32(regval, ARMV6M_SYSCON_SHPR3);
/* Configure SysTick to interrupt at the requested rate */
putreg32(SYSTICK_RELOAD, ARMV6M_SYSTICK_RVR);
/* Attach the timer interrupt vector */
(void)irq_attach(STM32F0_IRQ_SYSTICK, (xcpt_t)stm32f0_timerisr, NULL);
/* Enable SysTick interrupts. "The CLKSOURCE bit in SysTick Control and
* Status register selects either the core clock (when CLKSOURCE = 1) or
* a divide-by-16 of the core clock (when CLKSOURCE = 0). ..."
*/
#ifdef CONFIG_STM32F0_SYSTICK_CORECLK
putreg32((SYSTICK_CSR_CLKSOURCE | SYSTICK_CSR_TICKINT | SYSTICK_CSR_ENABLE),
ARMV6M_SYSTICK_CSR);
#else
putreg32((SYSTICK_CSR_TICKINT | SYSTICK_CSR_ENABLE), ARMV6M_SYSTICK_CSR);
#endif
/* And enable the timer interrupt */
up_enable_irq(STM32F0_IRQ_SYSTICK);
}

View File

@ -0,0 +1,434 @@
/************************************************************************************
* arch/arm/src/stm32/stm32f0_uart.h
*
* Copyright (C) 2017 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
* Alan Carvalho de Assis <acassis@gmail.com>
*
* 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 NuttX 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 OWNER 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.
*
************************************************************************************/
#ifndef __ARCH_ARM_STC_STM32F0_STM32F0_UART_H
#define __ARCH_ARM_STC_STM32F0_STM32F0_UART_H
/************************************************************************************
* Included Files
************************************************************************************/
#include <nuttx/config.h>
#include "chip.h"
#include "chip/stm32f0_uart.h"
/************************************************************************************
* Pre-processor Definitions
************************************************************************************/
/* Make sure that we have not enabled more U[S]ARTs than are supported by the
* device.
*/
#if STM32F0_NUSART < 8 || !defined(CONFIG_STM32F0_HAVE_USART8)
# undef CONFIG_STM32F0_USART8
#endif
#if STM32F0_NUSART < 7 || !defined(CONFIG_STM32F0_HAVE_USART7)
# undef CONFIG_STM32F0_USART7
#endif
#if STM32F0_NUSART < 6 || !defined(CONFIG_STM32F0_HAVE_USART6)
# undef CONFIG_STM32F0_USART6
#endif
#if STM32F0_NUSART < 5 || !defined(CONFIG_STM32F0_HAVE_USART5)
# undef CONFIG_STM32F0_USART5
#endif
#if STM32F0_NUSART < 4 || !defined(CONFIG_STM32F0_HAVE_USART4)
# undef CONFIG_STM32F0_USART4
#endif
#if STM32F0_NUSART < 3 || !defined(CONFIG_STM32F0_HAVE_USART3)
# undef CONFIG_STM32F0_USART3
#endif
#if STM32F0_NUSART < 2
# undef CONFIG_STM32F0_USART2
#endif
#if STM32F0_NUSART < 1
# undef CONFIG_STM32F0_USART1
#endif
/* Is there a USART enabled? */
#if defined(CONFIG_STM32F0_USART1) || defined(CONFIG_STM32F0_USART2) || \
defined(CONFIG_STM32F0_USART3) || defined(CONFIG_STM32F0_USART4) || \
defined(CONFIG_STM32F0_USART5)
# define HAVE_USART 1
#endif
/* Sanity checks */
#if !defined(CONFIG_STM32F0_USART1)
# undef CONFIG_STM32F0_USART1_SERIALDRIVER
# undef CONFIG_STM32F0_USART1_1WIREDRIVER
#endif
#if !defined(CONFIG_STM32F0_USART2)
# undef CONFIG_STM32F0_USART2_SERIALDRIVER
# undef CONFIG_STM32F0_USART2_1WIREDRIVER
#endif
#if !defined(CONFIG_STM32F0_USART3)
# undef CONFIG_STM32F0_USART3_SERIALDRIVER
# undef CONFIG_STM32F0_USART3_1WIREDRIVER
#endif
#if !defined(CONFIG_STM32F0_USART4)
# undef CONFIG_STM32F0_USART4_SERIALDRIVER
# undef CONFIG_STM32F0_USART4_1WIREDRIVER
#endif
#if !defined(CONFIG_STM32F0_USART5)
# undef CONFIG_STM32F0_USART5_SERIALDRIVER
# undef CONFIG_STM32F0_USART5_1WIREDRIVER
#endif
#if !defined(CONFIG_STM32F0_USART6)
# undef CONFIG_STM32F0_USART6_SERIALDRIVER
# undef CONFIG_STM32F0_USART6_1WIREDRIVER
#endif
#if !defined(CONFIG_STM32F0_USART7)
# undef CONFIG_STM32F0_USART7_SERIALDRIVER
# undef CONFIG_STM32F0_USART7_1WIREDRIVER
#endif
#if !defined(CONFIG_STM32F0_USART8)
# undef CONFIG_STM32F0_USART8_SERIALDRIVER
# undef CONFIG_STM32F0_USART8_1WIREDRIVER
#endif
/* Check 1-Wire and U(S)ART conflicts */
#if defined(CONFIG_STM32F0_USART1_1WIREDRIVER) && defined(CONFIG_STM32F0_USART1_SERIALDRIVER)
# error Both CONFIG_STM32F0_USART1_1WIREDRIVER and CONFIG_STM32F0_USART1_SERIALDRIVER defined
# undef CONFIG_STM32F0_USART1_1WIREDRIVER
#endif
#if defined(CONFIG_STM32F0_USART2_1WIREDRIVER) && defined(CONFIG_STM32F0_USART2_SERIALDRIVER)
# error Both CONFIG_STM32F0_USART2_1WIREDRIVER and CONFIG_STM32F0_USART2_SERIALDRIVER defined
# undef CONFIG_STM32F0_USART2_1WIREDRIVER
#endif
#if defined(CONFIG_STM32F0_USART3_1WIREDRIVER) && defined(CONFIG_STM32F0_USART3_SERIALDRIVER)
# error Both CONFIG_STM32F0_USART3_1WIREDRIVER and CONFIG_STM32F0_USART3_SERIALDRIVER defined
# undef CONFIG_STM32F0_USART3_1WIREDRIVER
#endif
#if defined(CONFIG_STM32F0_USART4_1WIREDRIVER) && defined(CONFIG_STM32F0_USART4_SERIALDRIVER)
# error Both CONFIG_STM32F0_USART4_1WIREDRIVER and CONFIG_STM32F0_USART4_SERIALDRIVER defined
# undef CONFIG_STM32F0_USART4_1WIREDRIVER
#endif
#if defined(CONFIG_STM32F0_USART5_1WIREDRIVER) && defined(CONFIG_STM32F0_USART5_SERIALDRIVER)
# error Both CONFIG_STM32F0_USART5_1WIREDRIVER and CONFIG_STM32F0_USART5_SERIALDRIVER defined
# undef CONFIG_STM32F0_USART5_1WIREDRIVER
#endif
#if defined(CONFIG_STM32F0_USART6_1WIREDRIVER) && defined(CONFIG_STM32F0_USART6_SERIALDRIVER)
# error Both CONFIG_STM32F0_USART6_1WIREDRIVER and CONFIG_STM32F0_USART6_SERIALDRIVER defined
# undef CONFIG_STM32F0_USART6_1WIREDRIVER
#endif
#if defined(CONFIG_STM32F0_USART7_1WIREDRIVER) && defined(CONFIG_STM32F0_USART7_SERIALDRIVER)
# error Both CONFIG_STM32F0_USART7_1WIREDRIVER and CONFIG_STM32F0_USART7_SERIALDRIVER defined
# undef CONFIG_STM32F0_USART7_1WIREDRIVER
#endif
#if defined(CONFIG_STM32F0_USART8_1WIREDRIVER) && defined(CONFIG_STM32F0_USART8_SERIALDRIVER)
# error Both CONFIG_STM32F0_USART8_1WIREDRIVER and CONFIG_STM32F0_USART8_SERIALDRIVER defined
# undef CONFIG_STM32F0_USART8_1WIREDRIVER
#endif
/* Is the serial driver enabled? */
#if defined(CONFIG_STM32F0_USART1_SERIALDRIVER) || defined(CONFIG_STM32F0_USART2_SERIALDRIVER) || \
defined(CONFIG_STM32F0_USART3_SERIALDRIVER) || defined(CONFIG_STM32F0_USART4_SERIALDRIVER) || \
defined(CONFIG_STM32F0_USART5_SERIALDRIVER) || defined(CONFIG_STM32F0_USART6_SERIALDRIVER) || \
defined(CONFIG_STM32F0_USART7_SERIALDRIVER) || defined(CONFIG_STM32F0_USART8_SERIALDRIVER)
# define HAVE_SERIALDRIVER 1
#endif
/* Is the 1-Wire driver? */
#if defined(CONFIG_STM32F0_USART1_1WIREDRIVER) || defined(CONFIG_STM32F0_USART2_1WIREDRIVER) || \
defined(CONFIG_STM32F0_USART3_1WIREDRIVER) || defined(CONFIG_STM32F0_USART4_1WIREDRIVER) || \
defined(CONFIG_STM32F0_USART5_1WIREDRIVER) || defined(CONFIG_STM32F0_USART6_1WIREDRIVER) || \
defined(CONFIG_STM32F0_USART7_1WIREDRIVER) || defined(CONFIG_STM32F0_USART8_1WIREDRIVER)
# define HAVE_1WIREDRIVER 1
#endif
/* Is there a serial console? */
#if defined(CONFIG_USART1_SERIAL_CONSOLE) && defined(CONFIG_STM32F0_USART1_SERIALDRIVER)
# undef CONFIG_USART2_SERIAL_CONSOLE
# undef CONFIG_USART3_SERIAL_CONSOLE
# undef CONFIG_USART4_SERIAL_CONSOLE
# undef CONFIG_USART5_SERIAL_CONSOLE
# undef CONFIG_USART6_SERIAL_CONSOLE
# undef CONFIG_USART7_SERIAL_CONSOLE
# undef CONFIG_USART8_SERIAL_CONSOLE
# define CONSOLE_USART 1
# define HAVE_CONSOLE 1
#elif defined(CONFIG_USART2_SERIAL_CONSOLE) && defined(CONFIG_STM32F0_USART2_SERIALDRIVER)
# undef CONFIG_USART1_SERIAL_CONSOLE
# undef CONFIG_USART3_SERIAL_CONSOLE
# undef CONFIG_USART4_SERIAL_CONSOLE
# undef CONFIG_USART5_SERIAL_CONSOLE
# undef CONFIG_USART6_SERIAL_CONSOLE
# undef CONFIG_USART7_SERIAL_CONSOLE
# undef CONFIG_USART8_SERIAL_CONSOLE
# define CONSOLE_USART 2
# define HAVE_CONSOLE 1
#elif defined(CONFIG_USART3_SERIAL_CONSOLE) && defined(CONFIG_STM32F0_USART3_SERIALDRIVER)
# undef CONFIG_USART1_SERIAL_CONSOLE
# undef CONFIG_USART2_SERIAL_CONSOLE
# undef CONFIG_USART4_SERIAL_CONSOLE
# undef CONFIG_USART5_SERIAL_CONSOLE
# undef CONFIG_USART6_SERIAL_CONSOLE
# undef CONFIG_USART7_SERIAL_CONSOLE
# undef CONFIG_USART8_SERIAL_CONSOLE
# define CONSOLE_USART 3
# define HAVE_CONSOLE 1
#elif defined(CONFIG_USART4_SERIAL_CONSOLE) && defined(CONFIG_STM32F0_USART4_SERIALDRIVER)
# undef CONFIG_USART1_SERIAL_CONSOLE
# undef CONFIG_USART2_SERIAL_CONSOLE
# undef CONFIG_USART3_SERIAL_CONSOLE
# undef CONFIG_USART5_SERIAL_CONSOLE
# undef CONFIG_USART6_SERIAL_CONSOLE
# undef CONFIG_USART7_SERIAL_CONSOLE
# undef CONFIG_USART8_SERIAL_CONSOLE
# define CONSOLE_USART 4
# define HAVE_CONSOLE 1
#elif defined(CONFIG_USART5_SERIAL_CONSOLE) && defined(CONFIG_STM32F0_USART5_SERIALDRIVER)
# undef CONFIG_USART1_SERIAL_CONSOLE
# undef CONFIG_USART2_SERIAL_CONSOLE
# undef CONFIG_USART3_SERIAL_CONSOLE
# undef CONFIG_USART4_SERIAL_CONSOLE
# undef CONFIG_USART6_SERIAL_CONSOLE
# undef CONFIG_USART7_SERIAL_CONSOLE
# undef CONFIG_USART8_SERIAL_CONSOLE
# define CONSOLE_USART 5
# define HAVE_CONSOLE 1
#elif defined(CONFIG_USART6_SERIAL_CONSOLE) && defined(CONFIG_STM32F0_USART6_SERIALDRIVER)
# undef CONFIG_USART1_SERIAL_CONSOLE
# undef CONFIG_USART2_SERIAL_CONSOLE
# undef CONFIG_USART3_SERIAL_CONSOLE
# undef CONFIG_USART4_SERIAL_CONSOLE
# undef CONFIG_USART5_SERIAL_CONSOLE
# undef CONFIG_USART7_SERIAL_CONSOLE
# undef CONFIG_USART8_SERIAL_CONSOLE
# define CONSOLE_USART 6
# define HAVE_CONSOLE 1
#elif defined(CONFIG_USART7_SERIAL_CONSOLE) && defined(CONFIG_STM32F0_USART7_SERIALDRIVER)
# undef CONFIG_USART1_SERIAL_CONSOLE
# undef CONFIG_USART2_SERIAL_CONSOLE
# undef CONFIG_USART3_SERIAL_CONSOLE
# undef CONFIG_USART4_SERIAL_CONSOLE
# undef CONFIG_USART5_SERIAL_CONSOLE
# undef CONFIG_USART6_SERIAL_CONSOLE
# undef CONFIG_USART5_SERIAL_CONSOLE
# undef CONFIG_USART8_SERIAL_CONSOLE
# define CONSOLE_USART 7
# define HAVE_CONSOLE 1
#elif defined(CONFIG_USART8_SERIAL_CONSOLE) && defined(CONFIG_STM32F0_USART8_SERIALDRIVER)
# undef CONFIG_USART1_SERIAL_CONSOLE
# undef CONFIG_USART2_SERIAL_CONSOLE
# undef CONFIG_USART3_SERIAL_CONSOLE
# undef CONFIG_USART4_SERIAL_CONSOLE
# undef CONFIG_USART6_SERIAL_CONSOLE
# undef CONFIG_USART6_SERIAL_CONSOLE
# undef CONFIG_USART7_SERIAL_CONSOLE
# define CONSOLE_USART 8
# define HAVE_CONSOLE 1
#else
# undef CONFIG_USART1_SERIAL_CONSOLE
# undef CONFIG_USART2_SERIAL_CONSOLE
# undef CONFIG_USART3_SERIAL_CONSOLE
# undef CONFIG_USART4_SERIAL_CONSOLE
# undef CONFIG_USART5_SERIAL_CONSOLE
# undef CONFIG_USART6_SERIAL_CONSOLE
# undef CONFIG_USART7_SERIAL_CONSOLE
# undef CONFIG_USART8_SERIAL_CONSOLE
# define CONSOLE_USART 0
# undef HAVE_CONSOLE
#endif
/* DMA support is only provided if CONFIG_ARCH_DMA is in the NuttX configuration */
#if !defined(HAVE_SERIALDRIVER) || !defined(CONFIG_ARCH_DMA)
# undef CONFIG_USART1_RXDMA
# undef CONFIG_USART2_RXDMA
# undef CONFIG_USART3_RXDMA
# undef CONFIG_USART4_RXDMA
# undef CONFIG_USART5_RXDMA
# undef CONFIG_USART6_RXDMA
# undef CONFIG_USART7_RXDMA
# undef CONFIG_USART8_RXDMA
#endif
/* Disable the DMA configuration on all unused USARTs */
#ifndef CONFIG_STM32F0_USART1_SERIALDRIVER
# undef CONFIG_USART1_RXDMA
#endif
#ifndef CONFIG_STM32F0_USART2_SERIALDRIVER
# undef CONFIG_USART2_RXDMA
#endif
#ifndef CONFIG_STM32F0_USART3_SERIALDRIVER
# undef CONFIG_USART3_RXDMA
#endif
#ifndef CONFIG_STM32F0_USART4_SERIALDRIVER
# undef CONFIG_USART4_RXDMA
#endif
#ifndef CONFIG_STM32F0_USART5_SERIALDRIVER
# undef CONFIG_USART5_RXDMA
#endif
#ifndef CONFIG_STM32F0_USART6_SERIALDRIVER
# undef CONFIG_USART6_RXDMA
#endif
#ifndef CONFIG_STM32F0_USART7_SERIALDRIVER
# undef CONFIG_USART7_RXDMA
#endif
#ifndef CONFIG_STM32F0_USART8_SERIALDRIVER
# undef CONFIG_USART8_RXDMA
#endif
/* Is DMA available on any (enabled) USART? */
#undef SERIAL_HAVE_DMA
#if defined(CONFIG_USART1_RXDMA) || defined(CONFIG_USART2_RXDMA) || \
defined(CONFIG_USART3_RXDMA) || defined(CONFIG_USART4_RXDMA) || \
defined(CONFIG_USART5_RXDMA) || defined(CONFIG_USART6_RXDMA) || \
defined(CONFIG_USART7_RXDMA) || defined(CONFIG_USART8_RXDMA)
# define SERIAL_HAVE_DMA 1
#endif
/* Is DMA used on the console USART? */
#undef SERIAL_HAVE_CONSOLE_DMA
#if defined(CONFIG_USART1_SERIAL_CONSOLE) && defined(CONFIG_USART1_RXDMA)
# define SERIAL_HAVE_CONSOLE_DMA 1
#elif defined(CONFIG_USART2_SERIAL_CONSOLE) && defined(CONFIG_USART2_RXDMA)
# define SERIAL_HAVE_CONSOLE_DMA 1
#elif defined(CONFIG_USART3_SERIAL_CONSOLE) && defined(CONFIG_USART3_RXDMA)
# define SERIAL_HAVE_CONSOLE_DMA 1
#elif defined(CONFIG_USART4_SERIAL_CONSOLE) && defined(CONFIG_USART4_RXDMA)
# define SERIAL_HAVE_CONSOLE_DMA 1
#elif defined(CONFIG_USART5_SERIAL_CONSOLE) && defined(CONFIG_USART5_RXDMA)
# define SERIAL_HAVE_CONSOLE_DMA 1
#elif defined(CONFIG_USART6_SERIAL_CONSOLE) && defined(CONFIG_USART6_RXDMA)
# define SERIAL_HAVE_CONSOLE_DMA 1
#elif defined(CONFIG_USART7_SERIAL_CONSOLE) && defined(CONFIG_USART7_RXDMA)
# define SERIAL_HAVE_CONSOLE_DMA 1
#elif defined(CONFIG_USART8_SERIAL_CONSOLE) && defined(CONFIG_USART8_RXDMA)
# define SERIAL_HAVE_CONSOLE_DMA 1
#endif
/* Is DMA used on all (enabled) USARTs */
#define SERIAL_HAVE_ONLY_DMA 1
#if defined(CONFIG_STM32F0_USART1_SERIALDRIVER) && !defined(CONFIG_USART1_RXDMA)
# undef SERIAL_HAVE_ONLY_DMA
#elif defined(CONFIG_STM32F0_USART2_SERIALDRIVER) && !defined(CONFIG_USART2_RXDMA)
# undef SERIAL_HAVE_ONLY_DMA
#elif defined(CONFIG_STM32F0_USART3_SERIALDRIVER) && !defined(CONFIG_USART3_RXDMA)
# undef SERIAL_HAVE_ONLY_DMA
#elif defined(CONFIG_STM32F0_USART4_SERIALDRIVER) && !defined(CONFIG_USART4_RXDMA)
# undef SERIAL_HAVE_ONLY_DMA
#elif defined(CONFIG_STM32F0_USART5_SERIALDRIVER) && !defined(CONFIG_USART5_RXDMA)
# undef SERIAL_HAVE_ONLY_DMA
#elif defined(CONFIG_STM32F0_USART6_SERIALDRIVER) && !defined(CONFIG_USART6_RXDMA)
# undef SERIAL_HAVE_ONLY_DMA
#elif defined(CONFIG_STM32F0_USART7_SERIALDRIVER) && !defined(CONFIG_USART7_RXDMA)
# undef SERIAL_HAVE_ONLY_DMA
#elif defined(CONFIG_STM32F0_USART8_SERIALDRIVER) && !defined(CONFIG_USART8_RXDMA)
# undef SERIAL_HAVE_ONLY_DMA
#endif
/* Is RS-485 used? */
#if defined(CONFIG_USART1_RS485) || defined(CONFIG_USART2_RS485) || \
defined(CONFIG_USART3_RS485) || defined(CONFIG_USART4_RS485) || \
defined(CONFIG_USART5_RS485) || defined(CONFIG_USART6_RS485) || \
defined(CONFIG_USART7_RS485) || defined(CONFIG_USART8_RS485)
# define HAVE_RS485 1
#endif
#ifdef HAVE_RS485
# define USART_CR1_USED_INTS (USART_CR1_RXNEIE | USART_CR1_TXEIE | USART_CR1_PEIE | USART_CR1_TCIE)
#else
# define USART_CR1_USED_INTS (USART_CR1_RXNEIE | USART_CR1_TXEIE | USART_CR1_PEIE)
#endif
/************************************************************************************
* Public Types
************************************************************************************/
/************************************************************************************
* Public Data
************************************************************************************/
#ifndef __ASSEMBLY__
#undef EXTERN
#if defined(__cplusplus)
#define EXTERN extern "C"
extern "C"
{
#else
#define EXTERN extern
#endif
/************************************************************************************
* Public Functions
************************************************************************************/
/************************************************************************************
* Name: stm32f0_serial_dma_poll
*
* Description:
* Must be called periodically if any STM32 USART is configured for DMA. The DMA
* callback is triggered for each fifo size/2 bytes, but this can result in some
* bytes being transferred but not collected if the incoming data is not a whole
* multiple of half the FIFO size.
*
* May be safely called from either interrupt or thread context.
*
************************************************************************************/
#ifdef SERIAL_HAVE_DMA
void stm32f0_serial_dma_poll(void);
#endif
#undef EXTERN
#if defined(__cplusplus)
}
#endif
#endif /* __ASSEMBLY__ */
#endif /* __ARCH_ARM_STC_STM32F0_STM32F0_UART_H */

View File

@ -1037,6 +1037,15 @@ config ARCH_BOARD_STM3240G_EVAL
microcontroller (ARM Cortex-M4 with FPU). This port uses a GNU Cortex-M4
toolchain (such as CodeSourcery).
config ARCH_BOARD_STM32F0_DISCOVERY
bool "STMicro STM32F0-Discovery board"
depends on ARCH_CHIP_STM32F051R8
select ARCH_HAVE_LEDS
select ARCH_HAVE_BUTTONS
select ARCH_HAVE_IRQBUTTONS
---help---
STMicro STM32F-Discovery board based on the STMicro ARCH_CHIP_STM32F051R8 MCU.
config ARCH_BOARD_STM32F3_DISCOVERY
bool "STMicro STM32F3-Discovery board"
depends on ARCH_CHIP_STM32F303VC
@ -1522,6 +1531,7 @@ config ARCH_BOARD
default "photon" if ARCH_BOARD_PHOTON
default "stm32butterfly2" if ARCH_BOARD_STM32_BUTTERFLY2
default "stm32_tiny" if ARCH_BOARD_STM32_TINY
default "stm32f0discovery" if ARCH_BOARD_STM32F0_DISCOVERY
default "stm32f103-minimum" if ARCH_BOARD_STM32F103_MINIMUM
default "stm3210e-eval" if ARCH_BOARD_STM3210E_EVAL
default "stm3220g-eval" if ARCH_BOARD_STM3220G_EVAL
@ -1881,6 +1891,9 @@ endif
if ARCH_BOARD_STM32_TINY
source "configs/stm32_tiny/Kconfig"
endif
if ARCH_BOARD_STM32F0_DISCOVERY
source "configs/stm32f0discovery/Kconfig"
endif
if ARCH_BOARD_STM32F103_MINIMUM
source "configs/stm32f103-minimum/Kconfig"
endif

View File

@ -660,6 +660,10 @@ configs/stm32butterfly2
Kamami stm32butterfly2 development board with optional ETH phy. See
https://kamami.pl/zestawy-uruchomieniowe-stm32/178507-stm32butterfly2.html
configs/stm32f0discovery
STMicro STM32F-Discovery board based on the STMicro ARCH_CHIP_STM32F051R8
MCU.
configs/stm32f103-minimum
Generic STM32F103C8T6 Minimum ARM Development Board.

View File

@ -0,0 +1,8 @@
#
# For a description of the syntax of this configuration file,
# see the file kconfig-language.txt in the NuttX tools repository.
#
if ARCH_BOARD_STM32F0_DISCOVERY
endif

View File

View File

@ -0,0 +1,274 @@
/************************************************************************************
* configs/stm32f0discovery/include/board.h
*
* Copyright (C) 2017 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
* Alan Carvalho de Assis <acassis@gmail.com>
*
* 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 NuttX 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 OWNER 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.
*
************************************************************************************/
#ifndef __CONFIG_STM32F0DISCOVERY_INCLUDE_BOARD_H
#define __CONFIG_STM32F0DISCOVERY_INCLUDE_BOARD_H
/************************************************************************************
* Included Files
************************************************************************************/
#include <nuttx/config.h>
#ifndef __ASSEMBLY__
# include <stdint.h>
#endif
/************************************************************************************
* Pre-processor Definitions
************************************************************************************/
/* Clocking *************************************************************************/
/* Four different clock sources can be used to drive the system clock (SYSCLK):
*
* - HSI high-speed internal oscillator clock
* Generated from an internal 16 MHz RC oscillator
* - HSE high-speed external oscillator clock
* Normally driven by an external crystal (X3). However, this crystal is not fitted
* on the STM32L-Discovery board.
* - PLL clock
* - MSI multispeed internal oscillator clock
* The MSI clock signal is generated from an internal RC oscillator. Seven frequency
* ranges are available: 65.536 kHz, 131.072 kHz, 262.144 kHz, 524.288 kHz, 1.048 MHz,
* 2.097 MHz (default value) and 4.194 MHz.
*
* The devices have the following two secondary clock sources
* - LSI low-speed internal RC clock
* Drives the watchdog and RTC. Approximately 37KHz
* - LSE low-speed external oscillator clock
* Driven by 32.768KHz crystal (X2) on the OSC32_IN and OSC32_OUT pins.
*/
#define STM32F0_BOARD_XTAL 8000000ul /* X3 on board (not fitted)*/
#define STM32F0_HSI_FREQUENCY 16000000ul /* Approximately 16MHz */
#define STM32F0_HSE_FREQUENCY STM32F0_BOARD_XTAL
#define STM32F0_MSI_FREQUENCY 2097000 /* Default is approximately 2.097Mhz */
#define STM32F0_LSI_FREQUENCY 37000 /* Approximately 37KHz */
#define STM32F0_LSE_FREQUENCY 32768 /* X2 on board */
/* This is the clock setup we configure for:
*
* SYSCLK = BOARD_OSCCLK_FREQUENCY = 12MHz -> Select Main oscillator for source
* PLL0CLK = (2 * 20 * SYSCLK) / 1 = 480MHz -> PLL0 multipler=20, pre-divider=1
* MCLK = 480MHz / 6 = 80MHz -> MCLK divider = 6
*/
#define STM32F0_MCLK 48000000 /* 48Mhz */
/* PLL Configuration
*
* - PLL source is HSI -> 16MHz input (nominal)
* - PLL multipler is 6 -> 96MHz PLL VCO clock output (for USB)
* - PLL output divider 3 -> 32MHz divided down PLL VCO clock output
*
* Resulting SYSCLK frequency is 16MHz x 6 / 3 = 32MHz
*
* USB/SDIO:
* If the USB or SDIO interface is used in the application, the PLL VCO
* clock (defined by STM32F0_CFGR_PLLMUL) must be programmed to output a 96
* MHz frequency. This is required to provide a 48 MHz clock to the USB or
* SDIO (SDIOCLK or USBCLK = PLLVCO/2).
* SYSCLK
* The system clock is derived from the PLL VCO divided by the output division factor.
* Limitations:
* 96 MHz as PLLVCO when the product is in range 1 (1.8V),
* 48 MHz as PLLVCO when the product is in range 2 (1.5V),
* 24 MHz when the product is in range 3 (1.2V).
* Output division to avoid exceeding 32 MHz as SYSCLK.
* The minimum input clock frequency for PLL is 2 MHz (when using HSE as PLL source).
*/
#define STM32F0_CFGR_PLLSRC 0 /* Source is 16MHz HSI */
#ifdef CONFIG_STM32F0_USB
# define STM32F0_CFGR_PLLMUL RCC_CFGR_PLLMUL_CLKx6 /* PLLMUL = 6 */
# define STM32F0_CFGR_PLLDIV RCC_CFGR_PLLDIV_3 /* PLLDIV = 3 */
# define STM32F0_PLL_FREQUENCY (6*STM32F0_HSI_FREQUENCY) /* PLL VCO Frequency is 96MHz */
#else
# define STM32F0_CFGR_PLLMUL RCC_CFGR_PLLMUL_CLKx4 /* PLLMUL = 4 */
# define STM32F0_CFGR_PLLDIV RCC_CFGR_PLLDIV_2 /* PLLDIV = 2 */
# define STM32F0_PLL_FREQUENCY (4*STM32F0_HSI_FREQUENCY) /* PLL VCO Frequency is 64MHz */
#endif
/* Use the PLL and set the SYSCLK source to be the divided down PLL VCO output
* frequency (STM32F0_PLL_FREQUENCY divided by the PLLDIV value).
*/
#define STM32F0_SYSCLK_SW RCC_CFGR_SW_PLL /* Use the PLL as the SYSCLK */
#define STM32F0_SYSCLK_SWS RCC_CFGR_SWS_PLL
#ifdef CONFIG_STM32F0_USB
# define STM32F0_SYSCLK_FREQUENCY (STM32F0_PLL_FREQUENCY/3) /* SYSCLK frequence is 96MHz/PLLDIV = 32MHz */
#else
# define STM32F0_SYSCLK_FREQUENCY (STM32F0_PLL_FREQUENCY/2) /* SYSCLK frequence is 64MHz/PLLDIV = 32MHz */
#endif
/* AHB clock (HCLK) is SYSCLK (32MHz) */
#define STM32F0_RCC_CFGR_HPRE RCC_CFGR_HPRE_SYSCLK
#define STM32F0_HCLK_FREQUENCY STM32F0_SYSCLK_FREQUENCY
#define STM32F0_BOARD_HCLK STM32F0_HCLK_FREQUENCY /* Same as above, to satisfy compiler */
/* APB2 clock (PCLK2) is HCLK (32MHz) */
#define STM32F0_RCC_CFGR_PPRE2 RCC_CFGR_PPRE2_HCLK
#define STM32F0_PCLK2_FREQUENCY STM32F0_HCLK_FREQUENCY
#define STM32F0_APB2_CLKIN (STM32F0_PCLK2_FREQUENCY)
/* APB2 timers 9, 10, and 11 will receive PCLK2. */
#define STM32F0_APB2_TIM9_CLKIN (STM32F0_PCLK2_FREQUENCY)
#define STM32F0_APB2_TIM10_CLKIN (STM32F0_PCLK2_FREQUENCY)
#define STM32F0_APB2_TIM11_CLKIN (STM32F0_PCLK2_FREQUENCY)
/* APB1 clock (PCLK1) is HCLK (32MHz) */
#define STM32F0_RCC_CFGR_PPRE1 RCC_CFGR_PPRE1_HCLK
#define STM32F0_PCLK1_FREQUENCY (STM32F0_HCLK_FREQUENCY)
/* APB1 timers 2-7 will receive PCLK1 */
#define STM32F0_APB1_TIM2_CLKIN (STM32F0_PCLK1_FREQUENCY)
#define STM32F0_APB1_TIM3_CLKIN (STM32F0_PCLK1_FREQUENCY)
#define STM32F0_APB1_TIM4_CLKIN (STM32F0_PCLK1_FREQUENCY)
#define STM32F0_APB1_TIM5_CLKIN (STM32F0_PCLK1_FREQUENCY)
#define STM32F0_APB1_TIM6_CLKIN (STM32F0_PCLK1_FREQUENCY)
#define STM32F0_APB1_TIM7_CLKIN (STM32F0_PCLK1_FREQUENCY)
/* LED definitions ******************************************************************/
/* The STM32L-Discovery board has four LEDs. Two of these are controlled by
* logic on the board and are not available for software control:
*
* LD1 COM: LD2 default status is red. LD2 turns to green to indicate that
* communications are in progress between the PC and the ST-LINK/V2.
* LD2 PWR: Red LED indicates that the board is powered.
*
* And two LEDs can be controlled by software:
*
* User LD3: Green LED is a user LED connected to the I/O PB7 of the STM32L152
* MCU.
* User LD4: Blue LED is a user LED connected to the I/O PB6 of the STM32L152
* MCU.
*
* If CONFIG_ARCH_LEDS is not defined, then the user can control the LEDs in any
* way. The following definitions are used to access individual LEDs.
*/
/* LED index values for use with board_userled() */
#define BOARD_LED1 0 /* User LD3 */
#define BOARD_LED2 1 /* User LD4 */
#define BOARD_NLEDS 2
/* LED bits for use with board_userled_all() */
#define BOARD_LED1_BIT (1 << BOARD_LED1)
#define BOARD_LED2_BIT (1 << BOARD_LED2)
/* If CONFIG_ARCH_LEDs is defined, then NuttX will control the 8 LEDs on board the
* STM32L-Discovery. The following definitions describe how NuttX controls the LEDs:
*
* SYMBOL Meaning LED state
* LED1 LED2
* ------------------- ----------------------- -------- --------
* LED_STARTED NuttX has been started OFF OFF
* LED_HEAPALLOCATE Heap has been allocated OFF OFF
* LED_IRQSENABLED Interrupts enabled OFF OFF
* LED_STACKCREATED Idle stack created ON OFF
* LED_INIRQ In an interrupt No change
* LED_SIGNAL In a signal handler No change
* LED_ASSERTION An assertion failed No change
* LED_PANIC The system has crashed OFF Blinking
* LED_IDLE STM32 is is sleep mode Not used
*/
#define LED_STARTED 0
#define LED_HEAPALLOCATE 0
#define LED_IRQSENABLED 0
#define LED_STACKCREATED 1
#define LED_INIRQ 2
#define LED_SIGNAL 2
#define LED_ASSERTION 2
#define LED_PANIC 3
/* Button definitions ***************************************************************/
/* The STM32L-Discovery supports two buttons; only one button is controllable by
* software:
*
* B1 USER: user and wake-up button connected to the I/O PA0 of the STM32L152RBT6.
* B2 RESET: pushbutton connected to NRST is used to RESET the STM32L152RBT6.
*/
#define BUTTON_USER 0
#define NUM_BUTTONS 1
#define BUTTON_USER_BIT (1 << BUTTON_USER)
/* Alternate Pin Functions **********************************************************/
/* The STM32L-Discovery has no on-board RS-232 driver. Further, there are no USART
* pins that do not conflict with the on board resources, in particular, the LCD:
* Most USART pins are available if the LCD is enabled; USART2 may be used if either
* the LCD or the on-board LEDs are disabled.
*
* PA9 USART1_TX LCD glass COM1 P2, pin 22
* PA10 USART1_RX LCD glass COM2 P2, pin 21
* PB6 USART1_TX LED Blue P2, pin 8
* PB7 USART1_RX LED Green P2, pin 7
*
* PA2 USART2_TX LCD SEG1 P1, pin 17
* PA3 USART2_RX LCD SEG2 P1, pin 18
*
* PB10 USART3_TX LCD SEG6 P1, pin 22
* PB11 USART3_RX LCD SEG7 P1, pin 23
* PC10 USART3_TX LCD SEG22 P2, pin 15
* PC11 USART3_RX LCD SEG23 P2, pin 14
*/
/* Select PA9 and PA10 if the LCD is not enabled */
//#define GPIO_USART1_RX GPIO_USART1_RX_1 /* PA10 */
//#define GPIO_USART1_TX GPIO_USART1_TX_1 /* PA9 */
/* This there are no other options for USART1 on this part */
#define GPIO_USART2_RX GPIO_USART2_RX_1 /* PA3 */
#define GPIO_USART2_TX GPIO_USART2_TX_1 /* PA2 */
/* Arbirtrarily select PB10 and PB11 */
#define GPIO_USART3_RX GPIO_USART3_RX_1 /* PB11 */
#define GPIO_USART3_TX GPIO_USART3_TX_1 /* PB10 */
#endif /* __CONFIG_STM32F0DISCOVERY_INCLUDE_BOARD_H */

View File

@ -0,0 +1,113 @@
############################################################################
# configs/stm32f0discovery/nsh/Make.defs
#
# Copyright (C) 2017 Gregory Nutt. All rights reserved.
# Author: Gregory Nutt <gnutt@nuttx.org>
# Alan Carvalho de Assis <acassis@gmail.com>
#
# 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 NuttX 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 OWNER 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.
#
############################################################################
include ${TOPDIR}/.config
include ${TOPDIR}/tools/Config.mk
include ${TOPDIR}/arch/arm/src/armv6-m/Toolchain.defs
LDSCRIPT = flash.ld
ifeq ($(WINTOOL),y)
# Windows-native toolchains
DIRLINK = $(TOPDIR)/tools/copydir.sh
DIRUNLINK = $(TOPDIR)/tools/unlink.sh
MKDEP = $(TOPDIR)/tools/mkwindeps.sh
ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}"
ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}"
ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)}"
else
# Linux/Cygwin-native toolchain
MKDEP = $(TOPDIR)/tools/mkdeps$(HOSTEXEEXT)
ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)
endif
CC = $(CROSSDEV)gcc
CXX = $(CROSSDEV)g++
CPP = $(CROSSDEV)gcc -E
LD = $(CROSSDEV)ld
AR = $(ARCROSSDEV)ar rcs
NM = $(ARCROSSDEV)nm
OBJCOPY = $(CROSSDEV)objcopy
OBJDUMP = $(CROSSDEV)objdump
ARCHCCVERSION = ${shell $(CC) -v 2>&1 | sed -n '/^gcc version/p' | sed -e 's/^gcc version \([0-9\.]\)/\1/g' -e 's/[-\ ].*//g' -e '1q'}
ARCHCCMAJOR = ${shell echo $(ARCHCCVERSION) | cut -d'.' -f1}
ifeq ($(CONFIG_DEBUG_SYMBOLS),y)
ARCHOPTIMIZATION = -g
endif
ifneq ($(CONFIG_DEBUG_NOOPT),y)
ARCHOPTIMIZATION += $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer
endif
ARCHCFLAGS = -fno-builtin
ARCHCXXFLAGS = -fno-builtin -fno-exceptions -fcheck-new -fno-rtti
ARCHWARNINGS = -Wall -Wstrict-prototypes -Wshadow -Wundef
ARCHWARNINGSXX = -Wall -Wshadow -Wundef
ARCHDEFINES =
ARCHPICFLAGS = -fpic -msingle-pic-base -mpic-register=r10
CFLAGS = $(ARCHCFLAGS) $(ARCHWARNINGS) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe
CPICFLAGS = $(ARCHPICFLAGS) $(CFLAGS)
CXXFLAGS = $(ARCHCXXFLAGS) $(ARCHWARNINGSXX) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHXXINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe
CXXPICFLAGS = $(ARCHPICFLAGS) $(CXXFLAGS)
CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES)
AFLAGS = $(CFLAGS) -D__ASSEMBLY__
NXFLATLDFLAGS1 = -r -d -warn-common
NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections
LDNXFLATFLAGS = -e main -s 2048
ASMEXT = .S
OBJEXT = .o
LIBEXT = .a
EXEEXT =
ifneq ($(CROSSDEV),arm-nuttx-elf-)
LDFLAGS += -nostartfiles -nodefaultlibs
endif
ifeq ($(CONFIG_DEBUG_SYMBOLS),y)
LDFLAGS += -g
endif
HOSTCC = gcc
HOSTINCLUDES = -I.
HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -Wundef -g -pipe
HOSTLDFLAGS =

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,76 @@
#!/bin/bash
# configs/stm32f0discovery/nsh/setenv.sh
#
# Copyright (C) 2017 Gregory Nutt. All rights reserved.
# Author: Gregory Nutt <gnutt@nuttx.org>
# Alan Carvalho de Assis <acassis@gmail.com>
#
# 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 NuttX 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 OWNER 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.
#
if [ "$_" = "$0" ] ; then
echo "You must source this script, not run it!" 1>&2
exit 1
fi
WD=`pwd`
if [ ! -x "setenv.sh" ]; then
echo "This script must be executed from the top-level NuttX build directory"
exit 1
fi
if [ -z "${PATH_ORIG}" ]; then
export PATH_ORIG="${PATH}"
fi
# This is the Cygwin path to the location where I installed the RIDE
# toolchain under windows. You will also have to edit this if you install
# the RIDE toolchain in any other location
#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
# This is the Cygwin path to the location where I installed the CodeSourcery
# toolchain under windows. You will also have to edit this if you install
# the CodeSourcery toolchain in any other location
export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
# These are the Cygwin paths to the locations where I installed the Atollic
# toolchain under windows. You will also have to edit this if you install
# the Atollic toolchain in any other location. /usr/bin is added before
# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
# at those locations as well.
#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
# This is the Cygwin path to the location where I build the buildroot
# toolchain.
#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
# Add the path to the toolchain to the PATH varialble
export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
echo "PATH : ${PATH}"

View File

@ -0,0 +1,120 @@
/****************************************************************************
* configs/stm32f0discovery/scripts/flash.ld
*
* Copyright (C) 2017 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
* Alan Carvalho de Assis <acassis@gmail.com>
*
* 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 NuttX 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 OWNER 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.
*
****************************************************************************/
/* The STM32F051R8T6 has 64KB of FLASH beginning at address 0x0800:0000 and
* 8Kb of SRAM at address 0x20000000.
*
* When booting from FLASH, FLASH memory is aliased to address 0x0000:0000
* where the code expects to begin execution by jumping to the entry point in
* the 0x0800:0000 address range.
*/
MEMORY
{
flash (rx) : ORIGIN = 0x08000000, LENGTH = 64K
sram (rwx) : ORIGIN = 0x20000000, LENGTH = 8K
}
OUTPUT_ARCH(arm)
EXTERN(_vectors)
ENTRY(_stext)
SECTIONS
{
.text : {
_stext = ABSOLUTE(.);
*(.vectors)
*(.text .text.*)
*(.fixup)
*(.gnu.warning)
*(.rodata .rodata.*)
*(.gnu.linkonce.t.*)
*(.glue_7)
*(.glue_7t)
*(.got)
*(.gcc_except_table)
*(.gnu.linkonce.r.*)
_etext = ABSOLUTE(.);
} > flash
.init_section : {
_sinit = ABSOLUTE(.);
*(.init_array .init_array.*)
_einit = ABSOLUTE(.);
} > flash
.ARM.extab : {
*(.ARM.extab*)
} > flash
__exidx_start = ABSOLUTE(.);
.ARM.exidx : {
*(.ARM.exidx*)
} > flash
__exidx_end = ABSOLUTE(.);
_eronly = ABSOLUTE(.);
.data : {
_sdata = ABSOLUTE(.);
*(.data .data.*)
*(.gnu.linkonce.d.*)
CONSTRUCTORS
_edata = ABSOLUTE(.);
} > sram AT > flash
.bss : {
_sbss = ABSOLUTE(.);
*(.bss .bss.*)
*(.gnu.linkonce.b.*)
*(COMMON)
_ebss = ABSOLUTE(.);
} > sram
/* Stabs debugging sections. */
.stab 0 : { *(.stab) }
.stabstr 0 : { *(.stabstr) }
.stab.excl 0 : { *(.stab.excl) }
.stab.exclstr 0 : { *(.stab.exclstr) }
.stab.index 0 : { *(.stab.index) }
.stab.indexstr 0 : { *(.stab.indexstr) }
.comment 0 : { *(.comment) }
.debug_abbrev 0 : { *(.debug_abbrev) }
.debug_info 0 : { *(.debug_info) }
.debug_line 0 : { *(.debug_line) }
.debug_pubnames 0 : { *(.debug_pubnames) }
.debug_aranges 0 : { *(.debug_aranges) }
}

View File

@ -0,0 +1,130 @@
/****************************************************************************
* configs/stm32f0discovery/scripts/gnu-elf.ld
*
* Copyright (C) 2017 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
* Alan Carvalho de Assis <acassis@gmail.com>
*
* 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 NuttX 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 OWNER 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.
*
****************************************************************************/
SECTIONS
{
.text 0x00000000 :
{
_stext = . ;
*(.text)
*(.text.*)
*(.gnu.warning)
*(.stub)
*(.glue_7)
*(.glue_7t)
*(.jcr)
/* C++ support: The .init and .fini sections contain specific logic
* to manage static constructors and destructors.
*/
*(.gnu.linkonce.t.*)
*(.init) /* Old ABI */
*(.fini) /* Old ABI */
_etext = . ;
}
.rodata :
{
_srodata = . ;
*(.rodata)
*(.rodata1)
*(.rodata.*)
*(.gnu.linkonce.r*)
_erodata = . ;
}
.data :
{
_sdata = . ;
*(.data)
*(.data1)
*(.data.*)
*(.gnu.linkonce.d*)
_edata = . ;
}
/* C++ support. For each global and static local C++ object,
* GCC creates a small subroutine to construct the object. Pointers
* to these routines (not the routines themselves) are stored as
* simple, linear arrays in the .ctors section of the object file.
* Similarly, pointers to global/static destructor routines are
* stored in .dtors.
*/
.ctors :
{
_sctors = . ;
*(.ctors) /* Old ABI: Unallocated */
*(.init_array) /* New ABI: Allocated */
_edtors = . ;
}
.dtors :
{
_sdtors = . ;
*(.dtors) /* Old ABI: Unallocated */
*(.fini_array) /* New ABI: Allocated */
_edtors = . ;
}
.bss :
{
_sbss = . ;
*(.bss)
*(.bss.*)
*(.sbss)
*(.sbss.*)
*(.gnu.linkonce.b*)
*(COMMON)
_ebss = . ;
}
/* Stabs debugging sections. */
.stab 0 : { *(.stab) }
.stabstr 0 : { *(.stabstr) }
.stab.excl 0 : { *(.stab.excl) }
.stab.exclstr 0 : { *(.stab.exclstr) }
.stab.index 0 : { *(.stab.index) }
.stab.indexstr 0 : { *(.stab.indexstr) }
.comment 0 : { *(.comment) }
.debug_abbrev 0 : { *(.debug_abbrev) }
.debug_info 0 : { *(.debug_info) }
.debug_line 0 : { *(.debug_line) }
.debug_pubnames 0 : { *(.debug_pubnames) }
.debug_aranges 0 : { *(.debug_aranges) }
}

View File

@ -0,0 +1,2 @@
/.depend
/Make.dep

View File

@ -0,0 +1,68 @@
############################################################################
# configs/stm32f0discovery/src/Makefile
#
# Copyright (C) 2017 Gregory Nutt. All rights reserved.
# Author: Gregory Nutt <gnutt@nuttx.org>
# Alan Carvalho de Assis <acassis@gmail.com>
#
# 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 NuttX 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 OWNER 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.
#
############################################################################
-include $(TOPDIR)/Make.defs
ASRCS =
CSRCS = stm32_boot.c stm32_bringup.c
ifeq ($(CONFIG_ARCH_LEDS),y)
CSRCS += stm32_autoleds.c
else
CSRCS += stm32_userleds.c
endif
ifeq ($(CONFIG_ARCH_BUTTONS),y)
CSRCS += stm32_buttons.c
endif
ifeq ($(CONFIG_STM32F0_SPI),y)
CSRCS += stm32_spi.c
endif
ifeq ($(CONFIG_PWM),y)
CSRCS += stm32_pwm.c
endif
ifeq ($(CONFIG_QENCODER),y)
CSRCS += stm32_qencoder.c
endif
ifeq ($(CONFIG_LIB_BOARDCTL),y)
CSRCS += stm32_appinit.c
endif
include $(TOPDIR)/configs/Board.mk

View File

@ -0,0 +1,87 @@
/****************************************************************************
* config/stm32f0discovery/src/stm32_appinit.c
*
* Copyright (C) 2017 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
* Alan Carvalho de Assis <acassis@gmail.com>
*
* 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 NuttX 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 OWNER 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.
*
****************************************************************************/
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <stdint.h>
#include <nuttx/board.h>
#include "stm32f0discovery.h"
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: board_app_initialize
*
* Description:
* Perform application specific initialization. This function is never
* called directly from application code, but only indirectly via the
* (non-standard) boardctl() interface using the command BOARDIOC_INIT.
*
* Input Parameters:
* arg - The boardctl() argument is passed to the board_app_initialize()
* implementation without modification. The argument has no
* meaning to NuttX; the meaning of the argument is a contract
* between the board-specific initalization logic and the the
* matching application logic. The value cold be such things as a
* mode enumeration value, a set of DIP switch switch settings, a
* pointer to configuration data read from a file or serial FLASH,
* or whatever you would like to do with it. Every implementation
* should accept zero/NULL as a default configuration.
*
* Returned Value:
* Zero (OK) is returned on success; a negated errno value is returned on
* any failure to indicate the nature of the failure.
*
****************************************************************************/
int board_app_initialize(uintptr_t arg)
{
/* Did we already initialize via board_initialize()? */
#ifndef CONFIG_BOARD_INITIALIZE
return stm32_bringup();
#else
return OK;
#endif
}

View File

@ -0,0 +1,137 @@
/****************************************************************************
* configs/stm32f0discovery/src/stm32_autoleds.c
*
* Copyright (C) 2017 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
* Alan Carvalho de Assis <acassis@gmail.com>
*
* 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 NuttX 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 OWNER 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.
*
****************************************************************************/
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <stdint.h>
#include <stdbool.h>
#include <debug.h>
#include <nuttx/board.h>
#include <arch/board/board.h>
#include "chip.h"
#include "stm32f0discovery.h"
#ifdef CONFIG_ARCH_LEDS
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/* If CONFIG_ARCH_LEDs is defined, then NuttX will control the 2 LEDs on
* board the STM32L-Discovery. The following definitions describe how NuttX
* controls the LEDs:
*
* SYMBOL Meaning LED state
* LED1 LED2
* ------------------- ----------------------- -------- --------
* LED_STARTED NuttX has been started OFF OFF
* LED_HEAPALLOCATE Heap has been allocated OFF OFF
* LED_IRQSENABLED Interrupts enabled OFF OFF
* LED_STACKCREATED Idle stack created ON OFF
* LED_INIRQ In an interrupt No change
* LED_SIGNAL In a signal handler No change
* LED_ASSERTION An assertion failed No change
* LED_PANIC The system has crashed OFF Blinking
* LED_IDLE STM32 is is sleep mode Not used
*/
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: board_autoled_initialize
****************************************************************************/
void board_autoled_initialize(void)
{
/* Configure LED1-2 GPIOs for output */
stm32f0_configgpio(GPIO_LED1);
stm32f0_configgpio(GPIO_LED2);
}
/****************************************************************************
* Name: board_autoled_on
****************************************************************************/
void board_autoled_on(int led)
{
bool led1on = false;
bool led2on = false;
switch (led)
{
case 0: /* LED_STARTED, LED_HEAPALLOCATE, LED_IRQSENABLED */
break;
case 1: /* LED_STACKCREATED */
led1on = true;
break;
default:
case 2: /* LED_INIRQ, LED_SIGNAL, LED_ASSERTION */
return;
case 3: /* LED_PANIC */
led2on = true;
break;
}
stm32f0_gpiowrite(GPIO_LED1, led1on);
stm32f0_gpiowrite(GPIO_LED2, led2on);
}
/****************************************************************************
* Name: board_autoled_off
****************************************************************************/
void board_autoled_off(int led)
{
if (led != 2)
{
stm32f0_gpiowrite(GPIO_LED1, false);
stm32f0_gpiowrite(GPIO_LED2, false);
}
}
#endif /* CONFIG_ARCH_LEDS */

View File

@ -0,0 +1,95 @@
/************************************************************************************
* configs/stm32f0discovery/src/stm32f0_boot.c
*
* Copyright (C) 2017 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
* Alan Carvalho de Assis <acassis@gmail.com>
*
* 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 NuttX 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 OWNER 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.
*
************************************************************************************/
/************************************************************************************
* Included Files
************************************************************************************/
#include <nuttx/config.h>
#include <debug.h>
#include <nuttx/board.h>
#include <arch/board/board.h>
#include "up_arch.h"
#include "stm32f0discovery.h"
/************************************************************************************
* Public Functions
************************************************************************************/
/************************************************************************************
* Name: stm32f0_boardinitialize
*
* Description:
* All STM32 architectures must provide the following entry point. This entry point
* is called early in the intitialization -- after all memory has been configured
* and mapped but before any devices have been initialized.
*
************************************************************************************/
void stm32f0_boardinitialize(void)
{
#ifdef CONFIG_ARCH_LEDS
/* Configure on-board LEDs if LED support has been selected. */
board_autoled_initialize();
#endif
}
/****************************************************************************
* Name: board_initialize
*
* Description:
* If CONFIG_BOARD_INITIALIZE is selected, then an additional
* initialization call will be performed in the boot-up sequence to a
* function called board_initialize(). board_initialize() will be
* called immediately after up_initialize() is called and just before the
* initial application is started. This additional initialization phase
* may be used, for example, to initialize board-specific device drivers.
*
****************************************************************************/
#ifdef CONFIG_BOARD_INITIALIZE
void board_initialize(void)
{
/* Perform board-specific initialization here if so configured */
(void)stm32_bringup();
}
#endif

View File

@ -0,0 +1,81 @@
/****************************************************************************
* config/stm32f0discovery/src/stm32_bringup.c
*
* Copyright (C) 2017 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* 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 NuttX 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 OWNER 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.
*
****************************************************************************/
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <sys/mount.h>
#include <sys/types.h>
#include "stm32f0discovery.h"
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: stm32_bringup
*
* Description:
* Perform architecture-specific initialization
*
* CONFIG_BOARD_INITIALIZE=y :
* Called from board_initialize().
*
* CONFIG_BOARD_INITIALIZE=n && CONFIG_LIB_BOARDCTL=y :
* Called from the NSH library
*
****************************************************************************/
int stm32_bringup(void)
{
int ret;
#ifdef CONFIG_FS_PROCFS
/* Mount the procfs file system */
ret = mount(NULL, "/proc", "procfs", 0, NULL);
if (ret < 0)
{
syslog(LOG_ERR, "ERROR: Failed to mount procfs at /proc: %d\n", ret);
}
#endif
UNUSED(ret);
return OK;
}

View File

@ -0,0 +1,162 @@
/****************************************************************************
* configs/stm32f0discovery/src/board_buttons.c
*
* Copyright (C) 2017 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
* Alan Carvalho de Assis <acassis@gmail.com>
*
* 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 NuttX 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 OWNER 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.
*
****************************************************************************/
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <stdint.h>
#include <errno.h>
#include <nuttx/arch.h>
#include <nuttx/board.h>
#include <arch/board/board.h>
#include "stm32f0discovery.h"
#ifdef CONFIG_ARCH_BUTTONS
/****************************************************************************
* Private Data
****************************************************************************/
/* Pin configuration for each STM32F3Discovery button. This array is indexed by
* the BUTTON_* definitions in board.h
*/
static const uint32_t g_buttons[NUM_BUTTONS] =
{
GPIO_BTN_USER
};
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: board_button_initialize
*
* Description:
* board_button_initialize() must be called to initialize button resources. After
* that, board_buttons() may be called to collect the current state of all
* buttons or board_button_irq() may be called to register button interrupt
* handlers.
*
****************************************************************************/
void board_button_initialize(void)
{
int i;
/* Configure the GPIO pins as inputs. NOTE that EXTI interrupts are
* configured for all pins.
*/
for (i = 0; i < NUM_BUTTONS; i++)
{
stm32_configgpio(g_buttons[i]);
}
}
/****************************************************************************
* Name: board_buttons
****************************************************************************/
uint8_t board_buttons(void)
{
uint8_t ret = 0;
int i;
/* Check that state of each key */
for (i = 0; i < NUM_BUTTONS; i++)
{
/* A LOW value means that the key is pressed.
*/
bool released = stm32_gpioread(g_buttons[i]);
/* Accumulate the set of depressed (not released) keys */
if (!released)
{
ret |= (1 << i);
}
}
return ret;
}
/************************************************************************************
* Button support.
*
* Description:
* board_button_initialize() must be called to initialize button resources. After
* that, board_buttons() may be called to collect the current state of all
* buttons or board_button_irq() may be called to register button interrupt
* handlers.
*
* After board_button_initialize() has been called, board_buttons() may be called to
* collect the state of all buttons. board_buttons() returns an 8-bit bit set
* with each bit associated with a button. See the BUTTON_*_BIT
* definitions in board.h for the meaning of each bit.
*
* board_button_irq() may be called to register an interrupt handler that will
* be called when a button is depressed or released. The ID value is a
* button enumeration value that uniquely identifies a button resource. See the
* BUTTON_* definitions in board.h for the meaning of enumeration
* value.
*
************************************************************************************/
#ifdef CONFIG_ARCH_IRQBUTTONS
int board_button_irq(int id, xcpt_t irqhandler, FAR void *arg)
{
int ret = -EINVAL;
/* The following should be atomic */
if (id >= MIN_IRQBUTTON && id <= MAX_IRQBUTTON)
{
ret = stm32_gpiosetevent(g_buttons[id], true, true, true, irqhandler, arg);
}
return ret;
}
#endif
#endif /* CONFIG_ARCH_BUTTONS */

View File

@ -0,0 +1,110 @@
/****************************************************************************
* configs/stm32f0discovery/src/stm32_userleds.c
*
* Copyright (C) 2017 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
* Alan Carvalho de Assis <acassis@gmail.com>
*
* 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 NuttX 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 OWNER 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.
*
****************************************************************************/
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <stdint.h>
#include <stdbool.h>
#include <debug.h>
#include <arch/board/board.h>
#include "chip.h"
#include "stm32.h"
#include "stm32f0discovery.h"
#ifndef CONFIG_ARCH_LEDS
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: board_userled_initialize
****************************************************************************/
void board_userled_initialize(void)
{
/* Configure LED1-2 GPIOs for output */
stm32_configgpio(GPIO_LED1);
stm32_configgpio(GPIO_LED2);
}
/****************************************************************************
* Name: board_userled
****************************************************************************/
void board_userled(int led, bool ledon)
{
uint32_t ledcfg;
if (led == BOARD_LED1)
{
ledcfg = GPIO_LED1;
}
else if (led == BOARD_LED2)
{
ledcfg = GPIO_LED2;
}
else
{
return;
}
stm32_gpiowrite(ledcfg, ledon);
}
/****************************************************************************
* Name: board_userled_all
****************************************************************************/
void board_userled_all(uint8_t ledset)
{
bool ledon;
ledon = ((ledset & BOARD_LED1_BIT) != 0);
stm32_gpiowrite(GPIO_LED1, ledon);
ledon = ((ledset & BOARD_LED2_BIT) != 0);
stm32_gpiowrite(GPIO_LED2, ledon);
}
#endif /* !CONFIG_ARCH_LEDS */

View File

@ -0,0 +1,135 @@
/****************************************************************************************************
* configs/stm32f0discovery/src/stm32f0discovery.h
*
* Copyright (C) 2017 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
* Alan Carvalho de Assis <acassis@gmail.com>
*
* 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 NuttX 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 OWNER 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.
*
****************************************************************************************************/
#ifndef __CONFIGS_STM32F0DISCOVERY_SRC_STM32F0DISCOVERY_H
#define __CONFIGS_STM32F0DISCOVERY_SRC_STM32F0DISCOVERY_H
/****************************************************************************************************
* Included Files
****************************************************************************************************/
#include <nuttx/config.h>
#include <nuttx/compiler.h>
#include <stdint.h>
#include "stm32f0_gpio.h"
/****************************************************************************************************
* Pre-processor Definitions
****************************************************************************************************/
/* Configuration ************************************************************************************/
/* How many SPI modules does this chip support? */
#if STM32F0_NSPI < 1
# undef CONFIG_STM32F0_SPI1
# undef CONFIG_STM32F0_SPI2
# undef CONFIG_STM32F0_SPI3
#elif STM32F0_NSPI < 2
# undef CONFIG_STM32F0_SPI2
# undef CONFIG_STM32F0_SPI3
#elif STM32F0_NSPI < 3
# undef CONFIG_STM32F0_SPI3
#endif
/* STM32F0Discovery GPIOs ***************************************************************************/
/* The STM32F0Discovery board has four LEDs. Two of these are controlled by logic on the board and
* are not available for software control:
*
* LD1 COM: LD2 default status is red. LD2 turns to green to indicate that communications are in
* progress between the PC and the ST-LINK/V2.
* LD2 PWR: Red LED indicates that the board is powered.
*
* And two LEDs can be controlled by software:
*
* User LD3: Green LED is a user LED connected to the I/O PB7 of the STM32L152 MCU.
* User LD4: Blue LED is a user LED connected to the I/O PB6 of the STM32L152 MCU.
*
* The other side of the LED connects to ground so high value will illuminate the LED.
*/
#define GPIO_LED1 (GPIO_OUTPUT | GPIO_PUSHPULL | GPIO_SPEED_10MHz | \
GPIO_OUTPUT_CLEAR | GPIO_PORTC | GPIO_PIN9)
#define GPIO_LED2 (GPIO_OUTPUT | GPIO_PUSHPULL | GPIO_SPEED_10MHz | \
GPIO_OUTPUT_CLEAR | GPIO_PORTC | GPIO_PIN8)
/* Button definitions *******************************************************************************/
/* The STM32F0Discovery supports two buttons; only one button is controllable by software:
*
* B1 USER: user and wake-up button connected to the I/O PA0 of the STM32F303VCT6.
* B2 RESET: pushbutton connected to NRST is used to RESET the STM32F303VCT6.
*
* NOTE that EXTI interrupts are configured
*/
#define MIN_IRQBUTTON BUTTON_USER
#define MAX_IRQBUTTON BUTTON_USER
#define NUM_IRQBUTTONS 1
#define GPIO_BTN_USER (GPIO_INPUT | GPIO_FLOAT | GPIO_EXTI | GPIO_PORTA | GPIO_PIN0)
/****************************************************************************************************
* Public Types
****************************************************************************************************/
/****************************************************************************************************
* Public data
****************************************************************************************************/
#ifndef __ASSEMBLY__
/****************************************************************************************************
* Public Functions
****************************************************************************************************/
/****************************************************************************
* Name: stm32_bringup
*
* Description:
* Perform architecture-specific initialization
*
* CONFIG_BOARD_INITIALIZE=y :
* Called from board_initialize().
*
* CONFIG_BOARD_INITIALIZE=n && CONFIG_LIB_BOARDCTL=y :
* Called from the NSH library
*
****************************************************************************/
int stm32_bringup(void);
#endif /* __ASSEMBLY__ */
#endif /* __CONFIGS_STM32F0DISCOVERY_SRC_STM32F0DISCOVERY_H */

View File

@ -204,7 +204,7 @@ int waitid(idtype_t idtype, id_t id, FAR siginfo_t *info, int options)
#ifdef CONFIG_SCHED_CHILD_STATUS
/* Does this task retain child status? */
retains = ((rtcb->group->tg_flags && GROUP_FLAG_NOCLDWAIT) == 0);
retains = ((rtcb->group->tg_flags & GROUP_FLAG_NOCLDWAIT) == 0);
if (rtcb->group->tg_children == NULL && retains)
{

View File

@ -346,7 +346,7 @@ pid_t waitpid(pid_t pid, int *stat_loc, int options)
#ifdef CONFIG_SCHED_CHILD_STATUS
/* Does this task retain child status? */
retains = ((rtcb->group->tg_flags && GROUP_FLAG_NOCLDWAIT) == 0);
retains = ((rtcb->group->tg_flags & GROUP_FLAG_NOCLDWAIT) == 0);
if (rtcb->group->tg_children == NULL && retains)
{

View File

@ -163,7 +163,7 @@ int task_reparent(pid_t ppid, pid_t chpid)
{
/* Has the new parent's task group supressed child exit status? */
if ((pgrp->tg_flags && GROUP_FLAG_NOCLDWAIT) == 0)
if ((pgrp->tg_flags & GROUP_FLAG_NOCLDWAIT) == 0)
{
/* No.. Add the child status entry to the new parent's task group */
@ -186,7 +186,7 @@ int task_reparent(pid_t ppid, pid_t chpid)
* suppressed child exit status.
*/
ret = ((ogrp->tg_flags && GROUP_FLAG_NOCLDWAIT) == 0) ? -ENOENT : OK;
ret = ((ogrp->tg_flags & GROUP_FLAG_NOCLDWAIT) == 0) ? -ENOENT : OK;
}
#else /* CONFIG_SCHED_CHILD_STATUS */
@ -276,7 +276,7 @@ int task_reparent(pid_t ppid, pid_t chpid)
{
/* Has the new parent's task group supressed child exit status? */
if ((ptcb->group->tg_flags && GROUP_FLAG_NOCLDWAIT) == 0)
if ((ptcb->group->tg_flags & GROUP_FLAG_NOCLDWAIT) == 0)
{
/* No.. Add the child status entry to the new parent's task group */
@ -299,7 +299,7 @@ int task_reparent(pid_t ppid, pid_t chpid)
* suppressed child exit status.
*/
ret = ((otcb->group->tg_flags && GROUP_FLAG_NOCLDWAIT) == 0) ? -ENOENT : OK;
ret = ((otcb->group->tg_flags & GROUP_FLAG_NOCLDWAIT) == 0) ? -ENOENT : OK;
}
#else /* CONFIG_SCHED_CHILD_STATUS */

View File

@ -237,7 +237,7 @@ static inline void task_saveparent(FAR struct tcb_s *tcb, uint8_t ttype)
* the SA_NOCLDWAIT flag with sigaction().
*/
if ((rtcb->group->tg_flags && GROUP_FLAG_NOCLDWAIT) == 0)
if ((rtcb->group->tg_flags & GROUP_FLAG_NOCLDWAIT) == 0)
{
FAR struct child_status_s *child;