forked from Archive/PX4-Autopilot
Add support for the STM3220G-EVAL board
git-svn-id: https://nuttx.svn.sourceforge.net/svnroot/nuttx/trunk@4472 7fd9a85b-ad96-42d3-883c-3090e2eb8679
This commit is contained in:
parent
0cba35270a
commit
288631c44f
|
@ -2545,4 +2545,9 @@
|
|||
* arch/mips/src/pic32mx/pic32mx_ethernet.c: Verifed the PIC32 Ethernet
|
||||
driver on the PIC32 Starter Kit. Status: It is occasionally functional
|
||||
but no stable enough for use.
|
||||
* arch/arm/include/stm32, arch/arm/src/stm32: Add general support for
|
||||
the STM32 F2 family. Contributed by Gary Teravskis,
|
||||
* configs/stm3220g-eval: Add support for the STMicro STM3220G-EVAL board.
|
||||
Contributed by Gary Teravskis,
|
||||
|
||||
|
||||
|
|
|
@ -0,0 +1,416 @@
|
|||
/************************************************************************************
|
||||
* arch/arm/src/stm32/chip/stm32f105vb_pinmap.h
|
||||
*
|
||||
* Copyright (C) 2009, 2011 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
*
|
||||
* 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_STM32_CHIP_STM32F105VB_PINMAP_H
|
||||
#define __ARCH_ARM_SRC_STM32_CHIP_STM32F105VB_PINMAP_H
|
||||
|
||||
/************************************************************************************
|
||||
* Included Files
|
||||
************************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
|
||||
/************************************************************************************
|
||||
* Pre-processor Definitions
|
||||
************************************************************************************/
|
||||
|
||||
/* Alternate Pin Functions: */
|
||||
|
||||
#define GPIO_ADC12_IN0 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN0)
|
||||
#define GPIO_ADC12_IN1 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN1)
|
||||
#define GPIO_ADC12_IN10 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN0)
|
||||
#define GPIO_ADC12_IN11 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN1)
|
||||
#define GPIO_ADC12_IN12 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN2)
|
||||
#define GPIO_ADC12_IN13 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN3)
|
||||
#define GPIO_ADC12_IN14 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN4)
|
||||
#define GPIO_ADC12_IN15 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN5)
|
||||
#define GPIO_ADC12_IN2 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN2)
|
||||
#define GPIO_ADC12_IN3 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN3)
|
||||
#define GPIO_ADC12_IN4 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN4)
|
||||
#define GPIO_ADC12_IN5 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN5)
|
||||
#define GPIO_ADC12_IN6 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN6)
|
||||
#define GPIO_ADC12_IN7 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN7)
|
||||
#define GPIO_ADC12_IN8 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN0)
|
||||
#define GPIO_ADC12_IN9 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN1)
|
||||
|
||||
#if defined(CONFIG_STM32_CAN1_FULL_REMAP)
|
||||
# define GPIO_CAN1_TX (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTD|GPIO_PIN0)
|
||||
# define GPIO_CAN1_RX (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTD|GPIO_PIN1)
|
||||
#elif defined(CONFIG_STM32_CAN1_PARTIAL_REMAP)
|
||||
# define GPIO_CAN1_TX (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN8)
|
||||
# define GPIO_CAN1_RX (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN9)
|
||||
#else
|
||||
# define GPIO_CAN1_TX (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN11)
|
||||
# define GPIO_CAN1_RX (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN12)
|
||||
#endif
|
||||
|
||||
#if defined(CONFIG_STM32_CAN2_REMAP)
|
||||
# define GPIO_CAN2_TX (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN5)
|
||||
# define GPIO_CAN2_RX (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN6)
|
||||
#else
|
||||
# define GPIO_CAN2_TX (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN12)
|
||||
# define GPIO_CAN2_RX (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN13)
|
||||
#endif
|
||||
|
||||
#if 0 /* Needs further investigation */
|
||||
#define GPIO_DAC_OUT1 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUTz|GPIO_PORTA|GPIO_PIN4)
|
||||
#define GPIO_DAC_OUT2 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN5)
|
||||
#endif
|
||||
|
||||
#if 0 /* Needs further investigation */
|
||||
#define GPIO_ETH_MDC (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTC|GPIO_PIN1)
|
||||
#define GPIO_ETH_MDIO (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN2)
|
||||
#define GPIO_ETH_MIICOL (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN3)
|
||||
#define GPIO_ETH_MIICRSWKUP (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN0)
|
||||
#define GPIO_ETH_MIIRXCLK (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN1)
|
||||
|
||||
#if defined(CONFIG_STM32_ETH_REMAP)
|
||||
# define GPIO_ETH_MIIRXD0 (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTD|GPIO_PIN9)
|
||||
# define GPIO_ETH_MIIRXD1 (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTD|GPIO_PIN10)
|
||||
# define GPIO_ETH_MIIRXD2 (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTD|GPIO_PIN11)
|
||||
# define GPIO_ETH_MIIRXD3 (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTD|GPIO_PIN12)
|
||||
# define GPIO_ETH_MIIRXDV (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTD|GPIO_PIN8)
|
||||
#else
|
||||
# define GPIO_ETH_MIIRXD0 (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTC|GPIO_PIN4)
|
||||
# define GPIO_ETH_MIIRXD1 (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTC|GPIO_PIN5)
|
||||
# define GPIO_ETH_MIIRXD2 (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN0)
|
||||
# define GPIO_ETH_MIIRXD3 (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN1)
|
||||
# define GPIO_ETH_MIIRXDV (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN7)
|
||||
#endif
|
||||
|
||||
#define GPIO_ETH_MIIRXER (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN10)
|
||||
#define GPIO_ETH_MIITXCLK (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTC|GPIO_PIN3)
|
||||
#define GPIO_ETH_MIITXD0 (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN12)
|
||||
#define GPIO_ETH_MIITXD1 (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN13)
|
||||
#define GPIO_ETH_MIITXD2 (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTC|GPIO_PIN2)
|
||||
#define GPIO_ETH_MIITXD3 (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN8)
|
||||
#define GPIO_ETH_MIITXEN (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN11)
|
||||
#define GPIO_ETH_PPSOUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN5)
|
||||
#define GPIO_ETH_RMIICRSDV (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN7)
|
||||
#define GPIO_ETH_RMIIREFCLK (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN1)
|
||||
#define GPIO_ETH_RMIIRXD0 (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTC|GPIO_PIN4)
|
||||
#define GPIO_ETH_RMIIRXD1 (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTC|GPIO_PIN5)
|
||||
#define GPIO_ETH_RMIITXD0 (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN12)
|
||||
#define GPIO_ETH_RMIITXD1 (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN13)
|
||||
#define GPIO_ETH_RMIITXEN (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN11)
|
||||
#endif
|
||||
|
||||
#if defined(CONFIG_STM32_I2C1_REMAP)
|
||||
# define GPIO_I2C1_SCL (GPIO_ALT|GPIO_CNF_AFOD|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN8)
|
||||
# define GPIO_I2C1_SDA (GPIO_ALT|GPIO_CNF_AFOD|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN9)
|
||||
#else
|
||||
# define GPIO_I2C1_SCL (GPIO_ALT|GPIO_CNF_AFOD|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN6)
|
||||
# define GPIO_I2C1_SDA (GPIO_ALT|GPIO_CNF_AFOD|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN7)
|
||||
#endif
|
||||
#define GPIO_I2C1_SMBA (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN5)
|
||||
|
||||
#define GPIO_I2C2_SCL (GPIO_ALT|GPIO_CNF_AFOD|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN10)
|
||||
#define GPIO_I2C2_SDA (GPIO_ALT|GPIO_CNF_AFOD|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN11)
|
||||
#define GPIO_I2C2_SMBA (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN12)
|
||||
#define GPIO_I2S2_CK (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN13)
|
||||
#define GPIO_I2S2_MCK (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTC|GPIO_PIN6)
|
||||
#define GPIO_I2S2_WS (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN12)
|
||||
|
||||
#define GPIO_I2S3_CK (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN3)
|
||||
#define GPIO_I2S3_MCK (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTC|GPIO_PIN7)
|
||||
#define GPIO_I2S3_SD (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN5)
|
||||
#define GPIO_I2S3_WS (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN15)
|
||||
|
||||
#if 0 /* Needs further investigation */
|
||||
#define GPIO_MCO (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN8)
|
||||
#endif
|
||||
|
||||
#if 0 /* Needs further investigation */
|
||||
#define GPIO_OTG_FSDM (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN11)
|
||||
#define GPIO_OTG_FSDP (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN12)
|
||||
#define GPIO_OTG_FSID (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN10)
|
||||
#define GPIO_OTG_FSSOF (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN8)
|
||||
#define GPIO_OTG_FSVBUS (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN9)
|
||||
#endif
|
||||
|
||||
#if defined(CONFIG_STM32_SPI1_REMAP)
|
||||
# define GPIO_SPI1_NSS (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN15)
|
||||
# define GPIO_SPI1_SCK (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN3)
|
||||
# define GPIO_SPI1_MISO (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN4)
|
||||
# define GPIO_SPI1_MOSI (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN5)
|
||||
#else
|
||||
# define GPIO_SPI1_NSS (GPIO_INPUT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN4)
|
||||
# define GPIO_SPI1_SCK (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN5)
|
||||
# define GPIO_SPI1_MISO (GPIO_INPUT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN6)
|
||||
# define GPIO_SPI1_MOSI (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN7)
|
||||
#endif
|
||||
|
||||
#define GPIO_SPI2_NSS (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN12)
|
||||
#define GPIO_SPI2_SCK (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN13)
|
||||
#define GPIO_SPI2_MISO (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN14)
|
||||
#define GPIO_SPI2_MOSI (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN15)
|
||||
|
||||
#if defined(CONFIG_STM32_SPI3_REMAP)
|
||||
# define GPIO_SPI3_NSS (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN4)
|
||||
# define GPIO_SPI3_SCK (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTC|GPIO_PIN10)
|
||||
# define GPIO_SPI3_MISO (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN11)
|
||||
# define GPIO_SPI3_MOSI (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTC|GPIO_PIN12)
|
||||
#else
|
||||
# define GPIO_SPI3_NSS (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN15)
|
||||
# define GPIO_SPI3_SCK (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN3)
|
||||
# define GPIO_SPI3_MISO (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN4)
|
||||
# define GPIO_SPI3_MOSI (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN5)
|
||||
#endif
|
||||
|
||||
#if 0 /* Needs further investigation */
|
||||
#define GPIO_TAMPER_RTC (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTC|GPIO_PIN13)
|
||||
#endif
|
||||
|
||||
#if defined(CONFIG_STM32_TIM1_FULL_REMAP)
|
||||
# define GPIO_TIM1_ETR (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTE|GPIO_PIN7)
|
||||
# define GPIO_TIM1_CH1IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTE|GPIO_PIN9)
|
||||
# define GPIO_TIM1_CH1OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTE|GPIO_PIN9)
|
||||
# define GPIO_TIM1_CH2IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTE|GPIO_PIN11)
|
||||
# define GPIO_TIM1_CH2OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTE|GPIO_PIN11)
|
||||
# define GPIO_TIM1_CH3IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTE|GPIO_PIN13)
|
||||
# define GPIO_TIM1_CH3OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTE|GPIO_PIN13)
|
||||
# define GPIO_TIM1_CH4IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTE|GPIO_PIN14)
|
||||
# define GPIO_TIM1_CH4OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTE|GPIO_PIN14)
|
||||
# define GPIO_TIM1_BKIN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTE|GPIO_PIN15)
|
||||
# define GPIO_TIM1_CH1N (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTE|GPIO_PIN8)
|
||||
# define GPIO_TIM1_CH2N (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTE|GPIO_PIN10)
|
||||
# define GPIO_TIM1_CH3N (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTE|GPIO_PIN12)
|
||||
#elif defined(CONFIG_STM32_TIM1_PARTIAL_REMAP)
|
||||
# define GPIO_TIM1_ETR (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN12)
|
||||
# define GPIO_TIM1_CH1IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN8)
|
||||
# define GPIO_TIM1_CH1OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN8)
|
||||
# define GPIO_TIM1_CH2IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN9)
|
||||
# define GPIO_TIM1_CH2OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN9)
|
||||
# define GPIO_TIM1_CH3IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN10)
|
||||
# define GPIO_TIM1_CH3OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN10)
|
||||
# define GPIO_TIM1_CH4IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN11)
|
||||
# define GPIO_TIM1_CH4OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN11)
|
||||
# define GPIO_TIM1_BKIN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN6)
|
||||
# define GPIO_TIM1_CH1N (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN7)
|
||||
# define GPIO_TIM1_CH2N (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN0)
|
||||
# define GPIO_TIM1_CH3N (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN1)
|
||||
#else
|
||||
# define GPIO_TIM1_ETR (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN12)
|
||||
# define GPIO_TIM1_CH1IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN8)
|
||||
# define GPIO_TIM1_CH1OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN8)
|
||||
# define GPIO_TIM1_CH2IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN9)
|
||||
# define GPIO_TIM1_CH2OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN9)
|
||||
# define GPIO_TIM1_CH3IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN10)
|
||||
# define GPIO_TIM1_CH3OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN10)
|
||||
# define GPIO_TIM1_CH4IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN11)
|
||||
# define GPIO_TIM1_CH4OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN11)
|
||||
# define GPIO_TIM1_BKIN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN12)
|
||||
# define GPIO_TIM1_CH1N (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN13)
|
||||
# define GPIO_TIM1_CH2N (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN14)
|
||||
# define GPIO_TIM1_CH3N (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN15)
|
||||
#endif
|
||||
|
||||
#if defined(CONFIG_STM32_TIM2_FULL_REMAP)
|
||||
# define GPIO_TIM2_ETR (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN15)
|
||||
# define GPIO_TIM2_CH1IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN15)
|
||||
# define GPIO_TIM2_CH1OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN15)
|
||||
# define GPIO_TIM2_CH2IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN3)
|
||||
# define GPIO_TIM2_CH2OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN3)
|
||||
# define GPIO_TIM2_CH3IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN10)
|
||||
# define GPIO_TIM2_CH3OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN10)
|
||||
# define GPIO_TIM2_CH4IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN11)
|
||||
# define GPIO_TIM2_CH4OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN11)
|
||||
#elif defined(CONFIG_STM32_TIM2_PARTIAL_REMAP_1)
|
||||
# define GPIO_TIM2_ETR (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN15)
|
||||
# define GPIO_TIM2_CH1IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN15)
|
||||
# define GPIO_TIM2_CH1OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN15)
|
||||
# define GPIO_TIM2_CH2IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN3)
|
||||
# define GPIO_TIM2_CH2OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN3)
|
||||
# define GPIO_TIM2_CH3IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN2)
|
||||
# define GPIO_TIM2_CH3OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN2)
|
||||
# define GPIO_TIM2_CH4IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN3)
|
||||
# define GPIO_TIM2_CH4OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN3)
|
||||
#elif defined(CONFIG_STM32_TIM2_PARTIAL_REMAP_2)
|
||||
# define GPIO_TIM2_ETR (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN0)
|
||||
# define GPIO_TIM2_CH1IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN0)
|
||||
# define GPIO_TIM2_CH1OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN0)
|
||||
# define GPIO_TIM2_CH2IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN1)
|
||||
# define GPIO_TIM2_CH2OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN1)
|
||||
# define GPIO_TIM2_CH3IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN10)
|
||||
# define GPIO_TIM2_CH3OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN10)
|
||||
# define GPIO_TIM2_CH4IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN11)
|
||||
# define GPIO_TIM2_CH4OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN11)
|
||||
#else
|
||||
# define GPIO_TIM2_ETR (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN0)
|
||||
# define GPIO_TIM2_CH1IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN0)
|
||||
# define GPIO_TIM2_CH1OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN0)
|
||||
# define GPIO_TIM2_CH2IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN1)
|
||||
# define GPIO_TIM2_CH2OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN1)
|
||||
# define GPIO_TIM2_CH3IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN2)
|
||||
# define GPIO_TIM2_CH3OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN2)
|
||||
# define GPIO_TIM2_CH4IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN3)
|
||||
# define GPIO_TIM2_CH4OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN3)
|
||||
#endif
|
||||
|
||||
#if defined(CONFIG_STM32_TIM3_FULL_REMAP)
|
||||
# define GPIO_TIM3_CH1IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN6)
|
||||
# define GPIO_TIM3_CH1OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTC|GPIO_PIN6)
|
||||
# define GPIO_TIM3_CH2IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN7)
|
||||
# define GPIO_TIM3_CH2OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTC|GPIO_PIN7)
|
||||
# define GPIO_TIM3_CH3IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN8)
|
||||
# define GPIO_TIM3_CH3OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTC|GPIO_PIN8)
|
||||
# define GPIO_TIM3_CH4IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN9)
|
||||
# define GPIO_TIM3_CH4OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTC|GPIO_PIN9)
|
||||
#elif defined(CONFIG_STM32_TIM3_PARTIAL_REMAP)
|
||||
# define GPIO_TIM3_CH1IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN4)
|
||||
# define GPIO_TIM3_CH1OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN4)
|
||||
# define GPIO_TIM3_CH2IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN5)
|
||||
# define GPIO_TIM3_CH2OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN5)
|
||||
# define GPIO_TIM3_CH3IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN0)
|
||||
# define GPIO_TIM3_CH3OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN0)
|
||||
# define GPIO_TIM3_CH4IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN1)
|
||||
# define GPIO_TIM3_CH4OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN1)
|
||||
#else
|
||||
# define GPIO_TIM3_CH1IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN6)
|
||||
# define GPIO_TIM3_CH1OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN6)
|
||||
# define GPIO_TIM3_CH2IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN7)
|
||||
# define GPIO_TIM3_CH2OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN7)
|
||||
# define GPIO_TIM3_CH3IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN0)
|
||||
# define GPIO_TIM3_CH3OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN0)
|
||||
# define GPIO_TIM3_CH4IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN1)
|
||||
# define GPIO_TIM3_CH4OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN1)
|
||||
#endif
|
||||
#define GPIO_TIM3_ETR (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTD|GPIO_PIN2)
|
||||
|
||||
#if defined(CONFIG_STM32_TIM4_REMAP)
|
||||
# define GPIO_TIM4_CH1IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTD|GPIO_PIN12)
|
||||
# define GPIO_TIM4_CH1OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTD|GPIO_PIN12)
|
||||
# define GPIO_TIM4_CH2IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTD|GPIO_PIN13)
|
||||
# define GPIO_TIM4_CH2OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTD|GPIO_PIN13)
|
||||
# define GPIO_TIM4_CH3IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTD|GPIO_PIN14)
|
||||
# define GPIO_TIM4_CH3OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTD|GPIO_PIN14)
|
||||
# define GPIO_TIM4_CH4IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTD|GPIO_PIN15)
|
||||
# define GPIO_TIM4_CH4OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTD|GPIO_PIN15)
|
||||
#else
|
||||
# define GPIO_TIM4_CH1IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN6)
|
||||
# define GPIO_TIM4_CH1OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN6)
|
||||
# define GPIO_TIM4_CH2IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN7)
|
||||
# define GPIO_TIM4_CH2OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN7)
|
||||
# define GPIO_TIM4_CH3IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN8)
|
||||
# define GPIO_TIM4_CH3OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN8)
|
||||
# define GPIO_TIM4_CH4IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN9)
|
||||
# define GPIO_TIM4_CH4OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN9)
|
||||
#endif
|
||||
#define GPIO_TIM4_ETR (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTE|GPIO_PIN0)
|
||||
|
||||
#define GPIO_TIM5_CH1IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN0)
|
||||
#define GPIO_TIM5_CH1OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN0)
|
||||
#define GPIO_TIM5_CH2IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN1)
|
||||
#define GPIO_TIM5_CH2OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN1)
|
||||
#define GPIO_TIM5_CH3IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN2)
|
||||
#define GPIO_TIM5_CH3OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN2)
|
||||
#define GPIO_TIM5_CH4IN (GGPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN3)
|
||||
#define GPIO_TIM5_CH4OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN3)
|
||||
|
||||
#if 0 /* Needs further investigation */
|
||||
#define GPIO_TRACECK (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTE|GPIO_PIN2)
|
||||
#define GPIO_TRACED0 (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTE|GPIO_PIN3)
|
||||
#define GPIO_TRACED1 (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTE|GPIO_PIN4)
|
||||
#define GPIO_TRACED2 (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTE|GPIO_PIN5)
|
||||
#define GPIO_TRACED3 (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTE|GPIO_PIN6)
|
||||
#if defined(CONFIG_STM32_TRACESWO_REMAP)
|
||||
# define GPIO_TRACESWO (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN3)
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#define GPIO_USART1_CTS (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN11)
|
||||
#define GPIO_USART1_RTS (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN12)
|
||||
#define GPIO_USART1_CK (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN8)
|
||||
#if defined(CONFIG_STM32_USART1_REMAP)
|
||||
# define GPIO_USART1_TX (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN9)
|
||||
# define GPIO_USART1_RX (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN10)
|
||||
#else
|
||||
# define GPIO_USART1_TX (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN9)
|
||||
# define GPIO_USART1_RX (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN10)
|
||||
#endif
|
||||
|
||||
#if defined(CONFIG_STM32_USART2_REMAP)
|
||||
# define GPIO_USART2_CTS (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTD|GPIO_PIN3)
|
||||
# define GPIO_USART2_RTS (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTD|GPIO_PIN4)
|
||||
# define GPIO_USART2_TX (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTD|GPIO_PIN5)
|
||||
# define GPIO_USART2_RX (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTD|GPIO_PIN6)
|
||||
# define GPIO_USART2_CK (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTD|GPIO_PIN7)
|
||||
#else
|
||||
# define GPIO_USART2_CTS (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN0)
|
||||
# define GPIO_USART2_RTS (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN1)
|
||||
# define GPIO_USART2_TX (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN2)
|
||||
# define GPIO_USART2_RX (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN3)
|
||||
# define GPIO_USART2_CK (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN4)
|
||||
#endif
|
||||
|
||||
#if defined(CONFIG_STM32_USART3_FULL_REMAP)
|
||||
# define GPIO_USART3_TX (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTD|GPIO_PIN8)
|
||||
# define GPIO_USART3_RX (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTD|GPIO_PIN9)
|
||||
# define GPIO_USART3_CK (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTD|GPIO_PIN10)
|
||||
# define GPIO_USART3_CTS (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTD|GPIO_PIN11)
|
||||
# define GPIO_USART3_RTS (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTD|GPIO_PIN12)
|
||||
#elif defined(CONFIG_STM32_USART3_PARTIAL_REMAP)
|
||||
# define GPIO_USART3_TX (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTC|GPIO_PIN10)
|
||||
# define GPIO_USART3_RX (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN11)
|
||||
# define GPIO_USART3_CK (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTC|GPIO_PIN12)
|
||||
# define GPIO_USART3_CTS (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN13)
|
||||
# define GPIO_USART3_RTS (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN14)
|
||||
#else
|
||||
# define GPIO_USART3_TX (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN10)
|
||||
# define GPIO_USART3_RX (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN11)
|
||||
# define GPIO_USART3_CK (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN12)
|
||||
# define GPIO_USART3_CTS (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN13)
|
||||
# define GPIO_USART3_RTS (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN14)
|
||||
#endif
|
||||
|
||||
#define GPIO_UART4_RX (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN11)
|
||||
#define GPIO_UART4_TX (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTC|GPIO_PIN10)
|
||||
|
||||
#define GPIO_UART5_RX (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTD|GPIO_PIN2)
|
||||
#define GPIO_UART5_TX (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTC|GPIO_PIN12)
|
||||
|
||||
#define GPIO_WKUP (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN0)
|
||||
|
||||
/* Some GPIOs are accessible only as remapped, alternate functions */
|
||||
|
||||
#if 0 /* Needs further investigation */
|
||||
#define GPIO_PA13 (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN13)
|
||||
#define GPIO_PA14 (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN14)
|
||||
#define GPIO_PA15 (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN15)
|
||||
#define GPIO_PB3 (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN3)
|
||||
#define GPIO_PB4 (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN4)
|
||||
#endif
|
||||
|
||||
#endif /* __ARCH_ARM_SRC_STM32_CHIP_STM32F105VB_PINMAP_H */
|
|
@ -0,0 +1,499 @@
|
|||
/************************************************************************************
|
||||
* arch/arm/src/stm32/chip/stm32f20xxx_dma.h
|
||||
*
|
||||
* Copyright (C) 2011 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.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
#ifndef __ARCH_ARM_SRC_STM32_CHIP_STM32F20XXX_DMA_H
|
||||
#define __ARCH_ARM_SRC_STM32_CHIP_STM32F20XXX_DMA_H
|
||||
|
||||
/************************************************************************************
|
||||
* Pre-processor Definitions
|
||||
************************************************************************************/
|
||||
|
||||
/* 2 DMA controllers */
|
||||
|
||||
#define DMA1 (0)
|
||||
#define DMA2 (1)
|
||||
|
||||
/* 8 DMA streams */
|
||||
|
||||
#define DMA_STREAM0 (0)
|
||||
#define DMA_STREAM1 (1)
|
||||
#define DMA_STREAM2 (2)
|
||||
#define DMA_STREAM3 (3)
|
||||
#define DMA_STREAM4 (4)
|
||||
#define DMA_STREAM5 (5)
|
||||
#define DMA_STREAM6 (6)
|
||||
#define DMA_STREAM7 (7)
|
||||
|
||||
/* 8 DMA channels */
|
||||
|
||||
#define DMA_CHAN0 (0)
|
||||
#define DMA_CHAN1 (1)
|
||||
#define DMA_CHAN2 (2)
|
||||
#define DMA_CHAN3 (3)
|
||||
#define DMA_CHAN4 (4)
|
||||
#define DMA_CHAN5 (5)
|
||||
#define DMA_CHAN6 (6)
|
||||
#define DMA_CHAN7 (7)
|
||||
|
||||
/* Register Offsets *****************************************************************/
|
||||
|
||||
#define STM32_DMA_LISR_OFFSET 0x0000 /* DMA low interrupt status register */
|
||||
#define STM32_DMA_HISR_OFFSET 0x0004 /* DMA high interrupt status register */
|
||||
#define STM32_DMA_LIFCR_OFFSET 0x0008 /* DMA low interrupt flag clear register */
|
||||
#define STM32_DMA_HIFCR_OFFSET 0x000c /* DMA high interrupt flag clear register */
|
||||
|
||||
#define STM32_DMA_OFFSET(n) (0x0010+0x0018*(n))
|
||||
#define STM32_DMA_SCR_OFFSET 0x0000 /* DMA stream n configuration register */
|
||||
#define STM32_DMA_SNDTR_OFFSET 0x0004 /* DMA stream n number of data register */
|
||||
#define STM32_DMA_SPAR_OFFSET 0x0008 /* DMA stream n peripheral address register */
|
||||
#define STM32_DMA_SM0AR_OFFSET 0x000c /* DMA stream n memory 0 address register */
|
||||
#define STM32_DMA_SM1AR_OFFSET 0x0010 /* DMA stream n memory 1 address register */
|
||||
#define STM32_DMA_SFCR_OFFSET 0x0014 /* DMA stream n FIFO control register */
|
||||
|
||||
#define STM32_DMA_S0CR_OFFSET 0x0010 /* DMA stream 0 configuration register */
|
||||
#define STM32_DMA_S1CR_OFFSET 0x0028 /* DMA stream 1 configuration register */
|
||||
#define STM32_DMA_S2CR_OFFSET 0x0040 /* DMA stream 2 configuration register */
|
||||
#define STM32_DMA_S3CR_OFFSET 0x0058 /* DMA stream 3 configuration register */
|
||||
#define STM32_DMA_S4CR_OFFSET 0x0070 /* DMA stream 4 configuration register */
|
||||
#define STM32_DMA_S5CR_OFFSET 0x0088 /* DMA stream 5 configuration register */
|
||||
#define STM32_DMA_S6CR_OFFSET 0x00a0 /* DMA stream 6 configuration register */
|
||||
#define STM32_DMA_S7CR_OFFSET 0x00b8 /* DMA stream 7 configuration register */
|
||||
|
||||
#define STM32_DMA_S0NDTR_OFFSET 0x0014 /* DMA stream 0 number of data register */
|
||||
#define STM32_DMA_S1NDTR_OFFSET 0x002c /* DMA stream 1 number of data register */
|
||||
#define STM32_DMA_S2NDTR_OFFSET 0x0044 /* DMA stream 2 number of data register */
|
||||
#define STM32_DMA_S3NDTR_OFFSET 0x005c /* DMA stream 3 number of data register */
|
||||
#define STM32_DMA_S4NDTR_OFFSET 0x0074 /* DMA stream 4 number of data register */
|
||||
#define STM32_DMA_S5NDTR_OFFSET 0x008c /* DMA stream 5 number of data register */
|
||||
#define STM32_DMA_S6NDTR_OFFSET 0x00a4 /* DMA stream 6 number of data register */
|
||||
#define STM32_DMA_S7NDTR_OFFSET 0x00bc /* DMA stream 7 number of data register */
|
||||
|
||||
#define STM32_DMA_S0PAR_OFFSET 0x0018 /* DMA stream 0 peripheral address register */
|
||||
#define STM32_DMA_S1PAR_OFFSET 0x0030 /* DMA stream 1 peripheral address register */
|
||||
#define STM32_DMA_S2PAR_OFFSET 0x0048 /* DMA stream 2 peripheral address register */
|
||||
#define STM32_DMA_S3PAR_OFFSET 0x0060 /* DMA stream 3 peripheral address register */
|
||||
#define STM32_DMA_S4PAR_OFFSET 0x0078 /* DMA stream 4 peripheral address register */
|
||||
#define STM32_DMA_S5PAR_OFFSET 0x0090 /* DMA stream 5 peripheral address register */
|
||||
#define STM32_DMA_S6PAR_OFFSET 0x00a8 /* DMA stream 6 peripheral address register */
|
||||
#define STM32_DMA_S7PAR_OFFSET 0x00c0 /* DMA stream 7 peripheral address register */
|
||||
|
||||
#define STM32_DMA_S0M0AR_OFFSET 0x001c /* DMA stream 0 memory 0 address register */
|
||||
#define STM32_DMA_S1M0AR_OFFSET 0x0034 /* DMA stream 1 memory 0 address register */
|
||||
#define STM32_DMA_S2M0AR_OFFSET 0x004c /* DMA stream 2 memory 0 address register */
|
||||
#define STM32_DMA_S3M0AR_OFFSET 0x0064 /* DMA stream 3 memory 0 address register */
|
||||
#define STM32_DMA_S4M0AR_OFFSET 0x007c /* DMA stream 4 memory 0 address register */
|
||||
#define STM32_DMA_S5M0AR_OFFSET 0x0094 /* DMA stream 5 memory 0 address register */
|
||||
#define STM32_DMA_S6M0AR_OFFSET 0x00ac /* DMA stream 6 memory 0 address register */
|
||||
#define STM32_DMA_S7M0AR_OFFSET 0x00c4 /* DMA stream 7 memory 0 address register */
|
||||
|
||||
#define STM32_DMA_S0M1AR_OFFSET 0x0020 /* DMA stream 0 memory 1 address register */
|
||||
#define STM32_DMA_S1M1AR_OFFSET 0x0038 /* DMA stream 1 memory 1 address register */
|
||||
#define STM32_DMA_S2M1AR_OFFSET 0x0050 /* DMA stream 2 memory 1 address register */
|
||||
#define STM32_DMA_S3M1AR_OFFSET 0x0068 /* DMA stream 3 memory 1 address register */
|
||||
#define STM32_DMA_S4M1AR_OFFSET 0x0080 /* DMA stream 4 memory 1 address register */
|
||||
#define STM32_DMA_S5M1AR_OFFSET 0x0098 /* DMA stream 5 memory 1 address register */
|
||||
#define STM32_DMA_S6M1AR_OFFSET 0x00b0 /* DMA stream 6 memory 1 address register */
|
||||
#define STM32_DMA_S7M1AR_OFFSET 0x00c8 /* DMA stream 7 memory 1 address register */
|
||||
|
||||
#define STM32_DMA_S0FCR_OFFSET 0x0024 /* DMA stream 0 FIFO control register */
|
||||
#define STM32_DMA_S1FCR_OFFSET 0x003c /* DMA stream 1 FIFO control register */
|
||||
#define STM32_DMA_S2FCR_OFFSET 0x0054 /* DMA stream 2 FIFO control register */
|
||||
#define STM32_DMA_S3FCR_OFFSET 0x006c /* DMA stream 3 FIFO control register */
|
||||
#define STM32_DMA_S4FCR_OFFSET 0x0084 /* DMA stream 4 FIFO control register */
|
||||
#define STM32_DMA_S5FCR_OFFSET 0x009c /* DMA stream 5 FIFO control register */
|
||||
#define STM32_DMA_S6FCR_OFFSET 0x00b4 /* DMA stream 6 FIFO control register */
|
||||
#define STM32_DMA_S7FCR_OFFSET 0x00cc /* DMA stream 7 FIFO control register */
|
||||
|
||||
/* Register Addresses ***************************************************************/
|
||||
|
||||
#define STM32_DMA1_LISRC (STM32_DMA1_BASE+STM32_DMA_LISR_OFFSET)
|
||||
#define STM32_DMA1_HISRC (STM32_DMA1_BASE+STM32_DMA_HISR_OFFSET)
|
||||
#define STM32_DMA1_LIFCR (STM32_DMA1_BASE+STM32_DMA_LIFCR_OFFSET)
|
||||
#define STM32_DMA1_HIFCR (STM32_DMA1_BASE+STM32_DMA_HIFCR_OFFSET)
|
||||
|
||||
#define STM32_DMA1_SCR(n) (STM32_DMA1_BASE+STM32_DMA_SCR_OFFSET+STM32_DMA_OFFSET(n))
|
||||
#define STM32_DMA1_S0CR (STM32_DMA1_BASE+STM32_DMA_S0CR_OFFSET)
|
||||
#define STM32_DMA1_S1CR (STM32_DMA1_BASE+STM32_DMA_S1CR_OFFSET)
|
||||
#define STM32_DMA1_S2CR (STM32_DMA1_BASE+STM32_DMA_S2CR_OFFSET)
|
||||
#define STM32_DMA1_S3CR (STM32_DMA1_BASE+STM32_DMA_S3CR_OFFSET)
|
||||
#define STM32_DMA1_S4CR (STM32_DMA1_BASE+STM32_DMA_S4CR_OFFSET)
|
||||
#define STM32_DMA1_S5CR (STM32_DMA1_BASE+STM32_DMA_S5CR_OFFSET)
|
||||
#define STM32_DMA1_S6CR (STM32_DMA1_BASE+STM32_DMA_S6CR_OFFSET)
|
||||
#define STM32_DMA1_S7CR (STM32_DMA1_BASE+STM32_DMA_S7CR_OFFSET)
|
||||
|
||||
#define STM32_DMA1_SNDTR(n) (STM32_DMA1_BASE+STM32_DMA_SNDTR_OFFSET+STM32_DMA_OFFSET(n))
|
||||
#define STM32_DMA1_S0NDTR (STM32_DMA1_BASE+STM32_DMA_S0NDTR_OFFSET)
|
||||
#define STM32_DMA1_S1NDTR (STM32_DMA1_BASE+STM32_DMA_S1NDTR_OFFSET)
|
||||
#define STM32_DMA1_S2NDTR (STM32_DMA1_BASE+STM32_DMA_S2NDTR_OFFSET)
|
||||
#define STM32_DMA1_S3NDTR (STM32_DMA1_BASE+STM32_DMA_S3NDTR_OFFSET)
|
||||
#define STM32_DMA1_S4NDTR (STM32_DMA1_BASE+STM32_DMA_S4NDTR_OFFSET)
|
||||
#define STM32_DMA1_S5NDTR (STM32_DMA1_BASE+STM32_DMA_S5NDTR_OFFSET)
|
||||
#define STM32_DMA1_S6NDTR (STM32_DMA1_BASE+STM32_DMA_S6NDTR_OFFSET)
|
||||
#define STM32_DMA1_S7NDTR (STM32_DMA1_BASE+STM32_DMA_S7NDTR_OFFSET)
|
||||
|
||||
#define STM32_DMA1_SPAR(n) (STM32_DMA1_BASE+STM32_DMA_SPAR_OFFSET+STM32_DMA_OFFSET(n))
|
||||
#define STM32_DMA1_S0PAR (STM32_DMA1_BASE+STM32_DMA_S0PAR_OFFSET)
|
||||
#define STM32_DMA1_S1PAR (STM32_DMA1_BASE+STM32_DMA_S1PAR_OFFSET)
|
||||
#define STM32_DMA1_S2PAR (STM32_DMA1_BASE+STM32_DMA_S2PAR_OFFSET)
|
||||
#define STM32_DMA1_S3PAR (STM32_DMA1_BASE+STM32_DMA_S3PAR_OFFSET)
|
||||
#define STM32_DMA1_S4PAR (STM32_DMA1_BASE+STM32_DMA_S4PAR_OFFSET)
|
||||
#define STM32_DMA1_S5PAR (STM32_DMA1_BASE+STM32_DMA_S5PAR_OFFSET)
|
||||
#define STM32_DMA1_S6PAR (STM32_DMA1_BASE+STM32_DMA_S6PAR_OFFSET)
|
||||
#define STM32_DMA1_S7PAR (STM32_DMA1_BASE+STM32_DMA_S7PAR_OFFSET)
|
||||
|
||||
#define STM32_DMA1_SM0AR(n) (STM32_DMA1_BASE+STM32_DMA_SM0AR_OFFSET+STM32_DMA_OFFSET(n))
|
||||
#define STM32_DMA1_S0M0AR (STM32_DMA1_BASE+STM32_DMA_S0M0AR_OFFSET)
|
||||
#define STM32_DMA1_S1M0AR (STM32_DMA1_BASE+STM32_DMA_S1M0AR_OFFSET)
|
||||
#define STM32_DMA1_S2M0AR (STM32_DMA1_BASE+STM32_DMA_S2M0AR_OFFSET)
|
||||
#define STM32_DMA1_S3M0AR (STM32_DMA1_BASE+STM32_DMA_S3M0AR_OFFSET)
|
||||
#define STM32_DMA1_S4M0AR (STM32_DMA1_BASE+STM32_DMA_S4M0AR_OFFSET)
|
||||
#define STM32_DMA1_S5M0AR (STM32_DMA1_BASE+STM32_DMA_S5M0AR_OFFSET)
|
||||
#define STM32_DMA1_S6M0AR (STM32_DMA1_BASE+STM32_DMA_S6M0AR_OFFSET)
|
||||
#define STM32_DMA1_S7M0AR (STM32_DMA1_BASE+STM32_DMA_S7M0AR_OFFSET)
|
||||
|
||||
#define STM32_DMA1_SM1AR(n) (STM32_DMA1_BASE+STM32_DMA_SM1AR_OFFSET+STM32_DMA_OFFSET(n))
|
||||
#define STM32_DMA1_S0M1AR (STM32_DMA1_BASE+STM32_DMA_S0M1AR_OFFSET)
|
||||
#define STM32_DMA1_S1M1AR (STM32_DMA1_BASE+STM32_DMA_S1M1AR_OFFSET)
|
||||
#define STM32_DMA1_S2M1AR (STM32_DMA1_BASE+STM32_DMA_S2M1AR_OFFSET)
|
||||
#define STM32_DMA1_S3M1AR (STM32_DMA1_BASE+STM32_DMA_S3M1AR_OFFSET)
|
||||
#define STM32_DMA1_S4M1AR (STM32_DMA1_BASE+STM32_DMA_S4M1AR_OFFSET)
|
||||
#define STM32_DMA1_S5M1AR (STM32_DMA1_BASE+STM32_DMA_S5M1AR_OFFSET)
|
||||
#define STM32_DMA1_S6M1AR (STM32_DMA1_BASE+STM32_DMA_S6M1AR_OFFSET)
|
||||
#define STM32_DMA1_S7M1AR (STM32_DMA1_BASE+STM32_DMA_S7M1AR_OFFSET)
|
||||
|
||||
#define STM32_DMA1_SFCR(n) (STM32_DMA1_BASE+STM32_DMA_SFCR_OFFSET+STM32_DMA_OFFSET(n))
|
||||
#define STM32_DMA1_S0FCR (STM32_DMA1_BASE+STM32_DMA_S0FCR_OFFSET)
|
||||
#define STM32_DMA1_S1FCR (STM32_DMA1_BASE+STM32_DMA_S1FCR_OFFSET)
|
||||
#define STM32_DMA1_S2FCR (STM32_DMA1_BASE+STM32_DMA_S2FCR_OFFSET)
|
||||
#define STM32_DMA1_S3FCR (STM32_DMA1_BASE+STM32_DMA_S3FCR_OFFSET)
|
||||
#define STM32_DMA1_S4FCR (STM32_DMA1_BASE+STM32_DMA_S4FCR_OFFSET)
|
||||
#define STM32_DMA1_S5FCR (STM32_DMA1_BASE+STM32_DMA_S5FCR_OFFSET)
|
||||
#define STM32_DMA1_S6FCR (STM32_DMA1_BASE+STM32_DMA_S6FCR_OFFSET)
|
||||
#define STM32_DMA1_S7FCR (STM32_DMA1_BASE+STM32_DMA_S7FCR_OFFSET)
|
||||
|
||||
#define STM32_DMA2_LISRC (STM32_DMA2_BASE+STM32_DMA_LISR_OFFSET)
|
||||
#define STM32_DMA2_HISRC (STM32_DMA2_BASE+STM32_DMA_HISR_OFFSET)
|
||||
#define STM32_DMA2_LIFCR (STM32_DMA2_BASE+STM32_DMA_LIFCR_OFFSET)
|
||||
#define STM32_DMA2_HIFCR (STM32_DMA2_BASE+STM32_DMA_HIFCR_OFFSET)
|
||||
|
||||
#define STM32_DMA2_SCR(n) (STM32_DMA2_BASE+STM32_DMA_SCR_OFFSET+STM32_DMA_OFFSET(n))
|
||||
#define STM32_DMA2_S0CR (STM32_DMA2_BASE+STM32_DMA_S0CR_OFFSET)
|
||||
#define STM32_DMA2_S1CR (STM32_DMA2_BASE+STM32_DMA_S1CR_OFFSET)
|
||||
#define STM32_DMA2_S2CR (STM32_DMA2_BASE+STM32_DMA_S2CR_OFFSET)
|
||||
#define STM32_DMA2_S3CR (STM32_DMA2_BASE+STM32_DMA_S3CR_OFFSET)
|
||||
#define STM32_DMA2_S4CR (STM32_DMA2_BASE+STM32_DMA_S4CR_OFFSET)
|
||||
#define STM32_DMA2_S5CR (STM32_DMA2_BASE+STM32_DMA_S5CR_OFFSET)
|
||||
#define STM32_DMA2_S6CR (STM32_DMA2_BASE+STM32_DMA_S6CR_OFFSET)
|
||||
#define STM32_DMA2_S7CR (STM32_DMA2_BASE+STM32_DMA_S7CR_OFFSET)
|
||||
|
||||
#define STM32_DMA2_SNDTR(n) (STM32_DMA2_BASE+STM32_DMA_SNDTR_OFFSET+STM32_DMA_OFFSET(n))
|
||||
#define STM32_DMA2_S0NDTR (STM32_DMA2_BASE+STM32_DMA_S0NDTR_OFFSET)
|
||||
#define STM32_DMA2_S1NDTR (STM32_DMA2_BASE+STM32_DMA_S1NDTR_OFFSET)
|
||||
#define STM32_DMA2_S2NDTR (STM32_DMA2_BASE+STM32_DMA_S2NDTR_OFFSET)
|
||||
#define STM32_DMA2_S3NDTR (STM32_DMA2_BASE+STM32_DMA_S3NDTR_OFFSET)
|
||||
#define STM32_DMA2_S4NDTR (STM32_DMA2_BASE+STM32_DMA_S4NDTR_OFFSET)
|
||||
#define STM32_DMA2_S5NDTR (STM32_DMA2_BASE+STM32_DMA_S5NDTR_OFFSET)
|
||||
#define STM32_DMA2_S6NDTR (STM32_DMA2_BASE+STM32_DMA_S6NDTR_OFFSET)
|
||||
#define STM32_DMA2_S7NDTR (STM32_DMA2_BASE+STM32_DMA_S7NDTR_OFFSET)
|
||||
|
||||
#define STM32_DMA2_SPAR(n) (STM32_DMA2_BASE+STM32_DMA_SPAR_OFFSET+STM32_DMA_OFFSET(n))
|
||||
#define STM32_DMA2_S0PAR (STM32_DMA2_BASE+STM32_DMA_S0PAR_OFFSET)
|
||||
#define STM32_DMA2_S1PAR (STM32_DMA2_BASE+STM32_DMA_S1PAR_OFFSET)
|
||||
#define STM32_DMA2_S2PAR (STM32_DMA2_BASE+STM32_DMA_S2PAR_OFFSET)
|
||||
#define STM32_DMA2_S3PAR (STM32_DMA2_BASE+STM32_DMA_S3PAR_OFFSET)
|
||||
#define STM32_DMA2_S4PAR (STM32_DMA2_BASE+STM32_DMA_S4PAR_OFFSET)
|
||||
#define STM32_DMA2_S5PAR (STM32_DMA2_BASE+STM32_DMA_S5PAR_OFFSET)
|
||||
#define STM32_DMA2_S6PAR (STM32_DMA2_BASE+STM32_DMA_S6PAR_OFFSET)
|
||||
#define STM32_DMA2_S7PAR (STM32_DMA2_BASE+STM32_DMA_S7PAR_OFFSET)
|
||||
|
||||
#define STM32_DMA2_SM0AR(n) (STM32_DMA2_BASE+STM32_DMA_SM0AR_OFFSET+STM32_DMA_OFFSET(n))
|
||||
#define STM32_DMA2_S0M0AR (STM32_DMA2_BASE+STM32_DMA_S0M0AR_OFFSET)
|
||||
#define STM32_DMA2_S1M0AR (STM32_DMA2_BASE+STM32_DMA_S1M0AR_OFFSET)
|
||||
#define STM32_DMA2_S2M0AR (STM32_DMA2_BASE+STM32_DMA_S2M0AR_OFFSET)
|
||||
#define STM32_DMA2_S3M0AR (STM32_DMA2_BASE+STM32_DMA_S3M0AR_OFFSET)
|
||||
#define STM32_DMA2_S4M0AR (STM32_DMA2_BASE+STM32_DMA_S4M0AR_OFFSET)
|
||||
#define STM32_DMA2_S5M0AR (STM32_DMA2_BASE+STM32_DMA_S5M0AR_OFFSET)
|
||||
#define STM32_DMA2_S6M0AR (STM32_DMA2_BASE+STM32_DMA_S6M0AR_OFFSET)
|
||||
#define STM32_DMA2_S7M0AR (STM32_DMA2_BASE+STM32_DMA_S7M0AR_OFFSET)
|
||||
|
||||
#define STM32_DMA2_SM1AR(n) (STM32_DMA2_BASE+STM32_DMA_SM1AR_OFFSET+STM32_DMA_OFFSET(n))
|
||||
#define STM32_DMA2_S0M1AR (STM32_DMA2_BASE+STM32_DMA_S0M1AR_OFFSET)
|
||||
#define STM32_DMA2_S1M1AR (STM32_DMA2_BASE+STM32_DMA_S1M1AR_OFFSET)
|
||||
#define STM32_DMA2_S2M1AR (STM32_DMA2_BASE+STM32_DMA_S2M1AR_OFFSET)
|
||||
#define STM32_DMA2_S3M1AR (STM32_DMA2_BASE+STM32_DMA_S3M1AR_OFFSET)
|
||||
#define STM32_DMA2_S4M1AR (STM32_DMA2_BASE+STM32_DMA_S4M1AR_OFFSET)
|
||||
#define STM32_DMA2_S5M1AR (STM32_DMA2_BASE+STM32_DMA_S5M1AR_OFFSET)
|
||||
#define STM32_DMA2_S6M1AR (STM32_DMA2_BASE+STM32_DMA_S6M1AR_OFFSET)
|
||||
#define STM32_DMA2_S7M1AR (STM32_DMA2_BASE+STM32_DMA_S7M1AR_OFFSET)
|
||||
|
||||
#define STM32_DMA2_SFCR(n) (STM32_DMA2_BASE+STM32_DMA_SFCR_OFFSET+STM32_DMA_OFFSET(n))
|
||||
#define STM32_DMA2_S0FCR (STM32_DMA2_BASE+STM32_DMA_S0FCR_OFFSET)
|
||||
#define STM32_DMA2_S1FCR (STM32_DMA2_BASE+STM32_DMA_S1FCR_OFFSET)
|
||||
#define STM32_DMA2_S2FCR (STM32_DMA2_BASE+STM32_DMA_S2FCR_OFFSET)
|
||||
#define STM32_DMA2_S3FCR (STM32_DMA2_BASE+STM32_DMA_S3FCR_OFFSET)
|
||||
#define STM32_DMA2_S4FCR (STM32_DMA2_BASE+STM32_DMA_S4FCR_OFFSET)
|
||||
#define STM32_DMA2_S5FCR (STM32_DMA2_BASE+STM32_DMA_S5FCR_OFFSET)
|
||||
#define STM32_DMA2_S6FCR (STM32_DMA2_BASE+STM32_DMA_S6FCR_OFFSET)
|
||||
#define STM32_DMA2_S7FCR (STM32_DMA2_BASE+STM32_DMA_S7FCR_OFFSET)
|
||||
|
||||
/* Register Bitfield Definitions ****************************************************/
|
||||
|
||||
#define DMA_STREAM_MASK 0x3f
|
||||
#define DMA_STREAM_FEIF_BIT (1 << 0) /* Bit 0: Stream FIFO error interrupt flag */
|
||||
#define DMA_STREAM_DMEIF_BIT (1 << 2) /* Bit 2: Stream direct mode error interrupt flag */
|
||||
#define DMA_STREAM_TEIF_BIT (1 << 3) /* Bit 3: Stream Transfer Error flag */
|
||||
#define DMA_STREAM_HTIF_BIT (1 << 4) /* Bit 4: Stream Half Transfer flag */
|
||||
#define DMA_STREAM_TCIF_BIT (1 << 5) /* Bit 5: Stream Transfer Complete flag */
|
||||
|
||||
/* DMA interrupt status register and interrupt flag clear register field defintions */
|
||||
|
||||
#define DMA_INT_STREAM0_SHIFT (0) /* Bits 0-5: DMA Stream 0 interrupt */
|
||||
#define DMA_INT_STREAM0_MASK (DMA_STREAM_MASK << DMA_INT_STREAM0_SHIFT)
|
||||
#define DMA_INT_STREAM1_SHIFT (6) /* Bits 6-11: DMA Stream 1 interrupt */
|
||||
#define DMA_INT_STREAM1_MASK (DMA_STREAM_MASK << DMA_INT_STREAM1_SHIFT)
|
||||
#define DMA_INT_STREAM2_SHIFT (16) /* Bits 16-21: DMA Stream 2 interrupt */
|
||||
#define DMA_INT_STREAM2_MASK (DMA_STREAM_MASK << DMA_INT_STREAM2_SHIFT)
|
||||
#define DMA_INT_STREAM3_SHIFT (22) /* Bits 22-27: DMA Stream 3 interrupt */
|
||||
#define DMA_INT_STREAM3_MASK (DMA_STREAM_MASK << DMA_INT_STREAM3_SHIFT)
|
||||
|
||||
#define DMA_INT_STREAM4_SHIFT (0) /* Bits 0-5: DMA Stream 4 interrupt */
|
||||
#define DMA_INT_STREAM4_MASK (DMA_STREAM_MASK << DMA_INT_STREAM4_SHIFT)
|
||||
#define DMA_INT_STREAM5_SHIFT (6) /* Bits 6-11: DMA Stream 5 interrupt */
|
||||
#define DMA_INT_STREAM5_MASK (DMA_STREAM_MASK << DMA_INT_STREAM5_SHIFT)
|
||||
#define DMA_INT_STREAM6_SHIFT (16) /* Bits 16-21: DMA Stream 6 interrupt */
|
||||
#define DMA_INT_STREAM6_MASK (DMA_STREAM_MASK << DMA_INT_STREAM6_SHIFT)
|
||||
#define DMA_INT_STREAM7_SHIFT (22) /* Bits 22-27: DMA Stream 7 interrupt */
|
||||
#define DMA_INT_STREAM7_MASK (DMA_STREAM_MASK << DMA_INT_STREAM7_SHIFT)
|
||||
|
||||
/* DMA stream configuration register */
|
||||
|
||||
#define DMA_SCR_EN (1 << 0) /* Bit 0: Stream enable */
|
||||
#define DMA_SCR_DMEIE (1 << 1) /* Bit 1: Direct mode error interrupt enable */
|
||||
#define DMA_SCR_TEIE (1 << 2) /* Bit 2: Transfer error interrupt enable */
|
||||
#define DMA_SCR_HTIE (1 << 3) /* Bit 3: Half Transfer interrupt enable */
|
||||
#define DMA_SCR_TCIE (1 << 4) /* Bit 4: Transfer complete interrupt enable */
|
||||
#define DMA_SCR_PFCTRL (1 << 5) /* Bit 5: Peripheral flow controller */
|
||||
#define DMA_SCR_DIR_SHIFT (6) /* Bits 6-7: Data transfer direction */
|
||||
#define DMA_SCR_DIR_MASK (3 << DMA_SCR_DIR_SHIFT)
|
||||
# define DMA_SCR_DIR_P2M (0 << DMA_SCR_DIR_SHIFT) /* 00: Peripheral-to-memory */
|
||||
# define DMA_SCR_DIR_M2P (1 << DMA_SCR_DIR_SHIFT) /* 01: Memory-to-peripheral */
|
||||
# define DMA_SCR_DIR_M2M (2 << DMA_SCR_DIR_SHIFT) /* 10: Memory-to-memory */
|
||||
#define DMA_SCR_CIRC (1 << 8) /* Bit 8: Circular mode */
|
||||
#define DMA_SCR_PINC (1 << 9) /* Bit 9: Peripheral increment mode */
|
||||
#define DMA_SCR_MINC (1 << 10) /* Bit 10: Memory increment mode */
|
||||
#define DMA_SCR_PSIZE_SHIFT (11) /* Bits 11-12: Peripheral size */
|
||||
#define DMA_SCR_PSIZE_MASK (3 << DMA_SCR_PSIZE_SHIFT)
|
||||
# define DMA_SCR_PSIZE_8BITS (0 << DMA_SCR_PSIZE_SHIFT) /* 00: 8-bits */
|
||||
# define DMA_SCR_PSIZE_16BITS (1 << DMA_SCR_PSIZE_SHIFT) /* 01: 16-bits */
|
||||
# define DMA_SCR_PSIZE_32BITS (2 << DMA_SCR_PSIZE_SHIFT) /* 10: 32-bits */
|
||||
#define DMA_SCR_MSIZE_SHIFT (13) /* Bits 13-14: Memory size */
|
||||
#define DMA_SCR_MSIZE_MASK (3 << DMA_SCR_MSIZE_SHIFT)
|
||||
# define DMA_SCR_MSIZE_8BITS (0 << DMA_SCR_MSIZE_SHIFT) /* 00: 8-bits */
|
||||
# define DMA_SCR_MSIZE_16BITS (1 << DMA_SCR_MSIZE_SHIFT) /* 01: 16-bits */
|
||||
# define DMA_SCR_MSIZE_32BITS (2 << DMA_SCR_MSIZE_SHIFT) /* 10: 32-bits */
|
||||
#define DMA_SCR_PINCOS (1 << 15) /* Bit 15: Peripheral increment offset size */
|
||||
#define DMA_SCR_PL_SHIFT (16) /* Bits 16-17: Stream Priority level */
|
||||
#define DMA_SCR_PL_MASK (3 << DMA_SCR_PL_SHIFT)
|
||||
# define DMA_SCR_PRILO (0 << DMA_SCR_PL_SHIFT) /* 00: Low */
|
||||
# define DMA_SCR_PRIMED (1 << DMA_SCR_PL_SHIFT) /* 01: Medium */
|
||||
# define DMA_SCR_PRIHI (2 << DMA_SCR_PL_SHIFT) /* 10: High */
|
||||
# define DMA_SCR_PRIVERYHI (3 << DMA_SCR_PL_SHIFT) /* 11: Very high */
|
||||
#define DMA_SCR_DBM (1 << 18) /* Bit 15: Double buffer mode */
|
||||
#define DMA_SCR_CT (1 << 19) /* Bit 19: Current target */
|
||||
#define DMA_SCR_PBURST_SHIFT (21) /* Bits 21-22: Peripheral burst transfer configuration */
|
||||
#define DMA_SCR_PBURST_MASK (3 << DMA_SCR_PBURST_SHIFT)
|
||||
# define DMA_SCR_PBURST_SINGLE (0 << DMA_SCR_PBURST_SHIFT) /* 00: Single transfer */
|
||||
# define DMA_SCR_PBURST_INCR4 (1 << DMA_SCR_PBURST_SHIFT) /* 01: Incremental burst of 4 beats */
|
||||
# define DMA_SCR_PBURST_INCR8 (2 << DMA_SCR_PBURST_SHIFT) /* 10: Incremental burst of 8 beats */
|
||||
# define DMA_SCR_PBURST_INCR16 (3 << DMA_SCR_PBURST_SHIFT) /* 11: Incremental burst of 16 beats */
|
||||
#define DMA_SCR_MBURST_SHIFT (23) /* Bits 23-24: Memory burst transfer configuration */
|
||||
#define DMA_SCR_MBURST_MASK (3 << DMA_SCR_MBURST_SHIFT)
|
||||
# define DMA_SCR_MBURST_SINGLE (0 << DMA_SCR_MBURST_SHIFT) /* 00: Single transfer */
|
||||
# define DMA_SCR_MBURST_INCR4 (1 << DMA_SCR_MBURST_SHIFT) /* 01: Incremental burst of 4 beats */
|
||||
# define DMA_SCR_MBURST_INCR8 (2 << DMA_SCR_MBURST_SHIFT) /* 10: Incremental burst of 8 beats */
|
||||
# define DMA_SCR_MBURST_INCR16 (3 << DMA_SCR_MBURST_SHIFT) /* 11: Incremental burst of 16 beats */
|
||||
#define DMA_SCR_CHSEL_SHIFT (25) /* Bits 25-27: Channel selection */
|
||||
#define DMA_SCR_CHSEL_MASK (7 << DMA_SCR_CHSEL_SHIFT)
|
||||
# define DMA_SCR_CHSEL(n) ((n) << DMA_SCR_CHSEL_SHIFT)
|
||||
|
||||
#define DMA_SCR_ALLINTS (DMA_SCR_DMEIE|DMA_SCR_TEIE|DMA_SCR_HTIE|DMA_SCR_TCIE)
|
||||
|
||||
/* DMA stream number of data register */
|
||||
|
||||
#define DMA_SNDTR_NDT_SHIFT (0) /* Bits 15-0: Number of data to Transfer */
|
||||
#define DMA_SNDTR_NDT_MASK (0xffff << DMA_SNDTR_NDT_SHIFT)
|
||||
|
||||
/* DMA Stream mapping. Each DMA stream has a mapping to several possible
|
||||
* sources/sinks of data. The requests from peripherals assigned to a stream
|
||||
* are simply OR'ed together before entering the DMA block. This means that only
|
||||
* one request on a given stream can be enabled at once.
|
||||
*
|
||||
* Alternative stream selections are provided with a numeric suffix like _1, _2, etc.
|
||||
* The DMA driver, however, will use the pin selection without the numeric suffix.
|
||||
* Additional definitions are required in the board.h file. For example, if
|
||||
* SPI3_RX connects via DMA STREAM0, then following should be application-specific
|
||||
* mapping should be used:
|
||||
*
|
||||
* #define DMAMAP_SPI3_RX DMAMAP_SPI3_RX_1
|
||||
*/
|
||||
|
||||
#define STM32_DMA_MAP(d,c,s) ((d) << 6 | (s) << 3 | (c))
|
||||
#define STM32_DMA_CONTROLLER(m) (((m) >> 6) & 1)
|
||||
#define STM32_DMA_STREAM(m) (((m) >> 3) & 7)
|
||||
#define STM32_DMA_CHAN(c) ((c) & 7)
|
||||
|
||||
#define DMAMAP_SPI3_RX_1 STM32_DMA_MAP(DMA1,DMA_STREAM0,DMA_CHAN0)
|
||||
#define DMAMAP_SPI3_RX_2 STM32_DMA_MAP(DMA1,DMA_STREAM2,DMA_CHAN0)
|
||||
#define DMAMAP_SPI2_RX STM32_DMA_MAP(DMA1,DMA_STREAM3,DMA_CHAN0)
|
||||
#define DMAMAP_SPI2_TX STM32_DMA_MAP(DMA1,DMA_STREAM4,DMA_CHAN0)
|
||||
#define DMAMAP_SPI3_TX_1 STM32_DMA_MAP(DMA1,DMA_STREAM5,DMA_CHAN0)
|
||||
#define DMAMAP_SPI3_TX_2 STM32_DMA_MAP(DMA1,DMA_STREAM7,DMA_CHAN0)
|
||||
|
||||
#define DMAMAP_I2C1_RX_1 STM32_DMA_MAP(DMA1,DMA_STREAM0,DMA_CHAN1)
|
||||
#define DMAMAP_TIM7_UP_1 STM32_DMA_MAP(DMA1,DMA_STREAM2,DMA_CHAN1)
|
||||
#define DMAMAP_TIM7_UP_2 STM32_DMA_MAP(DMA1,DMA_STREAM4,DMA_CHAN1)
|
||||
#define DMAMAP_I2C1_RX_2 STM32_DMA_MAP(DMA1,DMA_STREAM5,DMA_CHAN1)
|
||||
#define DMAMAP_I2C1_TX_1 STM32_DMA_MAP(DMA1,DMA_STREAM6,DMA_CHAN1)
|
||||
#define DMAMAP_I2C1_TX_2 STM32_DMA_MAP(DMA1,DMA_STREAM7,DMA_CHAN1)
|
||||
|
||||
#define DMAMAP_TIM4_CH1 STM32_DMA_MAP(DMA1,DMA_STREAM0,DMA_CHAN2)
|
||||
#define DMAMAP_I2S2_EXT_RX_1 STM32_DMA_MAP(DMA1,DMA_STREAM2,DMA_CHAN2)
|
||||
#define DMAMAP_TIM4_CH2 STM32_DMA_MAP(DMA1,DMA_STREAM3,DMA_CHAN2)
|
||||
#define DMAMAP_I2S2_EXT_TX STM32_DMA_MAP(DMA1,DMA_STREAM4,DMA_CHAN2)
|
||||
#define DMAMAP_I2S3_EXT_TX STM32_DMA_MAP(DMA1,DMA_STREAM5,DMA_CHAN2)
|
||||
#define DMAMAP_TIM4_UP STM32_DMA_MAP(DMA1,DMA_STREAM6,DMA_CHAN2)
|
||||
#define DMAMAP_TIM4_CH3 STM32_DMA_MAP(DMA1,DMA_STREAM7,DMA_CHAN2)
|
||||
|
||||
#define DMAMAP_I2S3_EXT_RX STM32_DMA_MAP(DMA1,DMA_STREAM0,DMA_CHAN3)
|
||||
#define DMAMAP_TIM2_UP_1 STM32_DMA_MAP(DMA1,DMA_STREAM1,DMA_CHAN3)
|
||||
#define DMAMAP_TIM2_CH3 STM32_DMA_MAP(DMA1,DMA_STREAM2,DMA_CHAN3)
|
||||
#define DMAMAP_I2C3_RX STM32_DMA_MAP(DMA1,DMA_STREAM2,DMA_CHAN3)
|
||||
#define DMAMAP_I2S2_EXT_RX_2 STM32_DMA_MAP(DMA1,DMA_STREAM3,DMA_CHAN3)
|
||||
#define DMAMAP_I2C3_TX STM32_DMA_MAP(DMA1,DMA_STREAM4,DMA_CHAN3)
|
||||
#define DMAMAP_TIM2_CH1 STM32_DMA_MAP(DMA1,DMA_STREAM5,DMA_CHAN3)
|
||||
#define DMAMAP_TIM2_CH2 STM32_DMA_MAP(DMA1,DMA_STREAM6,DMA_CHAN3)
|
||||
#define DMAMAP_TIM2_CH4_1 STM32_DMA_MAP(DMA1,DMA_STREAM6,DMA_CHAN3)
|
||||
#define DMAMAP_TIM2_UP_2 STM32_DMA_MAP(DMA1,DMA_STREAM7,DMA_CHAN3)
|
||||
#define DMAMAP_TIM2_CH4_2 STM32_DMA_MAP(DMA1,DMA_STREAM7,DMA_CHAN3)
|
||||
|
||||
#define DMAMAP_UART5_RX STM32_DMA_MAP(DMA1,DMA_STREAM0,DMA_CHAN4)
|
||||
#define DMAMAP_USART3_RX STM32_DMA_MAP(DMA1,DMA_STREAM1,DMA_CHAN4)
|
||||
#define DMAMAP_UART4_RX STM32_DMA_MAP(DMA1,DMA_STREAM2,DMA_CHAN4)
|
||||
#define DMAMAP_USART3_TX_1 STM32_DMA_MAP(DMA1,DMA_STREAM3,DMA_CHAN4)
|
||||
#define DMAMAP_UART4_TX STM32_DMA_MAP(DMA1,DMA_STREAM4,DMA_CHAN4)
|
||||
#define DMAMAP_USART2_RX STM32_DMA_MAP(DMA1,DMA_STREAM5,DMA_CHAN4)
|
||||
#define DMAMAP_USART2_TX STM32_DMA_MAP(DMA1,DMA_STREAM6,DMA_CHAN4)
|
||||
#define DMAMAP_UART5_TX STM32_DMA_MAP(DMA1,DMA_STREAM7,DMA_CHAN4)
|
||||
|
||||
#define DMAMAP_TIM3_CH4 STM32_DMA_MAP(DMA1,DMA_STREAM2,DMA_CHAN5)
|
||||
#define DMAMAP_TIM3_UP STM32_DMA_MAP(DMA1,DMA_STREAM2,DMA_CHAN5)
|
||||
#define DMAMAP_TIM3_CH1 STM32_DMA_MAP(DMA1,DMA_STREAM4,DMA_CHAN5)
|
||||
#define DMAMAP_TIM3_TRIG STM32_DMA_MAP(DMA1,DMA_STREAM4,DMA_CHAN5)
|
||||
#define DMAMAP_TIM3_CH2 STM32_DMA_MAP(DMA1,DMA_STREAM5,DMA_CHAN5)
|
||||
#define DMAMAP_TIM3_CH3 STM32_DMA_MAP(DMA1,DMA_STREAM7,DMA_CHAN5)
|
||||
|
||||
#define DMAMAP_TIM5_CH3 STM32_DMA_MAP(DMA1,DMA_STREAM0,DMA_CHAN6)
|
||||
#define DMAMAP_TIM5_UP_1 STM32_DMA_MAP(DMA1,DMA_STREAM0,DMA_CHAN6)
|
||||
#define DMAMAP_TIM5_CH4_1 STM32_DMA_MAP(DMA1,DMA_STREAM1,DMA_CHAN6)
|
||||
#define DMAMAP_TIM5_TRIG_1 STM32_DMA_MAP(DMA1,DMA_STREAM1,DMA_CHAN6)
|
||||
#define DMAMAP_TIM5_CH1 STM32_DMA_MAP(DMA1,DMA_STREAM2,DMA_CHAN6)
|
||||
#define DMAMAP_TIM5_CH4_2 STM32_DMA_MAP(DMA1,DMA_STREAM3,DMA_CHAN6)
|
||||
#define DMAMAP_TIM5_TRIG_2 STM32_DMA_MAP(DMA1,DMA_STREAM3,DMA_CHAN6)
|
||||
#define DMAMAP_TIM5_CH2 STM32_DMA_MAP(DMA1,DMA_STREAM4,DMA_CHAN6)
|
||||
#define DMAMAP_TIM5_UP_2 STM32_DMA_MAP(DMA1,DMA_STREAM6,DMA_CHAN6)
|
||||
|
||||
#define DMAMAP_TIM6_UP STM32_DMA_MAP(DMA1,DMA_STREAM1,DMA_CHAN7)
|
||||
#define DMAMAP_I2C2_RX_1 STM32_DMA_MAP(DMA1,DMA_STREAM2,DMA_CHAN7)
|
||||
#define DMAMAP_I2C2_RX_2 STM32_DMA_MAP(DMA1,DMA_STREAM3,DMA_CHAN7)
|
||||
#define DMAMAP_USART3_TX_2 STM32_DMA_MAP(DMA1,DMA_STREAM4,DMA_CHAN7)
|
||||
#define DMAMAP_DAC1 STM32_DMA_MAP(DMA1,DMA_STREAM5,DMA_CHAN7)
|
||||
#define DMAMAP_DAC2 STM32_DMA_MAP(DMA1,DMA_STREAM6,DMA_CHAN7)
|
||||
#define DMAMAP_I2C2_TX STM32_DMA_MAP(DMA1,DMA_STREAM7,DMA_CHAN7)
|
||||
|
||||
#define DMAMAP_ADC1_1 STM32_DMA_MAP(DMA2,DMA_STREAM0,DMA_CHAN0)
|
||||
#define DMAMAP_TIM8_CH1_1 STM32_DMA_MAP(DMA2,DMA_STREAM2,DMA_CHAN0)
|
||||
#define DMAMAP_TIM8_CH2_1 STM32_DMA_MAP(DMA2,DMA_STREAM2,DMA_CHAN0)
|
||||
#define DMAMAP_TIM8_CH3_1 STM32_DMA_MAP(DMA2,DMA_STREAM2,DMA_CHAN0)
|
||||
#define DMAMAP_ADC1_2 STM32_DMA_MAP(DMA2,DMA_STREAM4,DMA_CHAN0)
|
||||
#define DMAMAP_TIM1_CH1_1 STM32_DMA_MAP(DMA2,DMA_STREAM6,DMA_CHAN0)
|
||||
#define DMAMAP_TIM1_CH2_1 STM32_DMA_MAP(DMA2,DMA_STREAM6,DMA_CHAN0)
|
||||
#define DMAMAP_TIM1_CH3_1 STM32_DMA_MAP(DMA2,DMA_STREAM6,DMA_CHAN0)
|
||||
|
||||
#define DMAMAP_DCMI_1 STM32_DMA_MAP(DMA2,DMA_STREAM1,DMA_CHAN1)
|
||||
#define DMAMAP_ADC2_1 STM32_DMA_MAP(DMA2,DMA_STREAM2,DMA_CHAN1)
|
||||
#define DMAMAP_ADC2_2 STM32_DMA_MAP(DMA2,DMA_STREAM3,DMA_CHAN1)
|
||||
#define DMAMAP_DCMI_2 STM32_DMA_MAP(DMA2,DMA_STREAM7,DMA_CHAN1)
|
||||
|
||||
#define DMAMAP_ADC3_1 STM32_DMA_MAP(DMA2,DMA_STREAM0,DMA_CHAN2)
|
||||
#define DMAMAP_ADC3_2 STM32_DMA_MAP(DMA2,DMA_STREAM1,DMA_CHAN2)
|
||||
#define DMAMAP_CRYP_OUT STM32_DMA_MAP(DMA2,DMA_STREAM5,DMA_CHAN2)
|
||||
#define DMAMAP_CRYP_IN STM32_DMA_MAP(DMA2,DMA_STREAM6,DMA_CHAN2)
|
||||
#define DMAMAP_HASH_IN STM32_DMA_MAP(DMA2,DMA_STREAM7,DMA_CHAN2)
|
||||
|
||||
#define DMAMAP_SPI1_RX_1 STM32_DMA_MAP(DMA2,DMA_STREAM0,DMA_CHAN3)
|
||||
#define DMAMAP_SPI1_RX_2 STM32_DMA_MAP(DMA2,DMA_STREAM2,DMA_CHAN3)
|
||||
#define DMAMAP_SPI1_TX_1 STM32_DMA_MAP(DMA2,DMA_STREAM3,DMA_CHAN3)
|
||||
#define DMAMAP_SPI1_TX_2 STM32_DMA_MAP(DMA2,DMA_STREAM5,DMA_CHAN3)
|
||||
|
||||
#define DMAMAP_USART1_RX_1 STM32_DMA_MAP(DMA2,DMA_STREAM2,DMA_CHAN4)
|
||||
#define DMAMAP_SDIO_1 STM32_DMA_MAP(DMA2,DMA_STREAM3,DMA_CHAN4)
|
||||
#define DMAMAP_USART1_RX_2 STM32_DMA_MAP(DMA2,DMA_STREAM5,DMA_CHAN4)
|
||||
#define DMAMAP_SDIO_2 STM32_DMA_MAP(DMA2,DMA_STREAM6,DMA_CHAN4)
|
||||
#define DMAMAP_USART1_TX STM32_DMA_MAP(DMA2,DMA_STREAM7,DMA_CHAN4)
|
||||
|
||||
#define DMAMAP_USART6_RX_1 STM32_DMA_MAP(DMA2,DMA_STREAM1,DMA_CHAN5)
|
||||
#define DMAMAP_USART6_RX_2 STM32_DMA_MAP(DMA2,DMA_STREAM2,DMA_CHAN5)
|
||||
#define DMAMAP_USART6_TX_1 STM32_DMA_MAP(DMA2,DMA_STREAM6,DMA_CHAN5)
|
||||
#define DMAMAP_USART6_TX_2 STM32_DMA_MAP(DMA2,DMA_STREAM7,DMA_CHAN5)
|
||||
|
||||
#define DMAMAP_TIM1_TRIG_1 STM32_DMA_MAP(DMA2,DMA_STREAM0,DMA_CHAN6)
|
||||
#define DMAMAP_TIM1_CH1_2 STM32_DMA_MAP(DMA2,DMA_STREAM1,DMA_CHAN6)
|
||||
#define DMAMAP_TIM1_CH2_2 STM32_DMA_MAP(DMA2,DMA_STREAM2,DMA_CHAN6)
|
||||
#define DMAMAP_TIM1_CH1 STM32_DMA_MAP(DMA2,DMA_STREAM3,DMA_CHAN6)
|
||||
#define DMAMAP_TIM1_CH4 STM32_DMA_MAP(DMA2,DMA_STREAM4,DMA_CHAN6)
|
||||
#define DMAMAP_TIM1_TRIG_2 STM32_DMA_MAP(DMA2,DMA_STREAM4,DMA_CHAN6)
|
||||
#define DMAMAP_TIM1_COM STM32_DMA_MAP(DMA2,DMA_STREAM4,DMA_CHAN6)
|
||||
#define DMAMAP_TIM1_UP STM32_DMA_MAP(DMA2,DMA_STREAM5,DMA_CHAN6)
|
||||
#define DMAMAP_TIM1_CH3_2 STM32_DMA_MAP(DMA2,DMA_STREAM6,DMA_CHAN6)
|
||||
|
||||
#define DMAMAP_TIM8_UP STM32_DMA_MAP(DMA2,DMA_STREAM1,DMA_CHAN7)
|
||||
#define DMAMAP_TIM8_CH1_2 STM32_DMA_MAP(DMA2,DMA_STREAM2,DMA_CHAN7)
|
||||
#define DMAMAP_TIM8_CH2_2 STM32_DMA_MAP(DMA2,DMA_STREAM3,DMA_CHAN7)
|
||||
#define DMAMAP_TIM8_CH3_2 STM32_DMA_MAP(DMA2,DMA_STREAM5,DMA_CHAN7)
|
||||
#define DMAMAP_TIM8_CH4 STM32_DMA_MAP(DMA2,DMA_STREAM7,DMA_CHAN7)
|
||||
#define DMAMAP_TIM8_TRIG STM32_DMA_MAP(DMA2,DMA_STREAM7,DMA_CHAN7)
|
||||
#define DMAMAP_TIM8_COM STM32_DMA_MAP(DMA2,DMA_STREAM7,DMA_CHAN7)
|
||||
|
||||
#endif /* __ARCH_ARM_SRC_STM32_CHIP_STM32F20XXX_DMA_H */
|
|
@ -0,0 +1,370 @@
|
|||
/************************************************************************************
|
||||
* arch/arm/src/stm32/chip/stm32f20xxx_gpio.h
|
||||
*
|
||||
* Copyright (C) 2009, 2011 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
*
|
||||
* 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_STM32_CHIP_STM32F20XXX_GPIO_H
|
||||
#define __ARCH_ARM_SRC_STM32_CHIP_STM32F20XXX_GPIO_H
|
||||
|
||||
/************************************************************************************
|
||||
* Pre-processor Definitions
|
||||
************************************************************************************/
|
||||
|
||||
#define STM32_NGPIO_PORTS ((STM32_NGPIO + 15) >> 4)
|
||||
|
||||
/* Register Offsets *****************************************************************/
|
||||
|
||||
#define STM32_GPIO_MODER_OFFSET 0x0000 /* GPIO port mode register */
|
||||
#define STM32_GPIO_OTYPER_OFFSET 0x0004 /* GPIO port output type register */
|
||||
#define STM32_GPIO_OSPEED_OFFSET 0x0008 /* GPIO port output speed register */
|
||||
#define STM32_GPIO_PUPDR_OFFSET 0x000c /* GPIO port pull-up/pull-down register */
|
||||
#define STM32_GPIO_IDR_OFFSET 0x0010 /* GPIO port input data register */
|
||||
#define STM32_GPIO_ODR_OFFSET 0x0014 /* GPIO port output data register */
|
||||
#define STM32_GPIO_BSRR_OFFSET 0x0018 /* GPIO port bit set/reset register */
|
||||
#define STM32_GPIO_LCKR_OFFSET 0x001c /* GPIO port configuration lock register */
|
||||
#define STM32_GPIO_AFRL_OFFSET 0x0020 /* GPIO alternate function low register */
|
||||
#define STM32_GPIO_ARFH_OFFSET 0x0024 /* GPIO alternate function high register */
|
||||
|
||||
/* Register Addresses ***************************************************************/
|
||||
|
||||
#if STM32_NGPIO_PORTS > 0
|
||||
# define STM32_GPIOA_MODER (STM32_GPIOA_BASE+STM32_GPIO_MODER_OFFSET)
|
||||
# define STM32_GPIOA_OTYPER (STM32_GPIOA_BASE+STM32_GPIO_OTYPER_OFFSET)
|
||||
# define STM32_GPIOA_OSPEED (STM32_GPIOA_BASE+STM32_GPIO_OSPEED_OFFSET)
|
||||
# define STM32_GPIOA_PUPDR (STM32_GPIOA_BASE+STM32_GPIO_PUPDR_OFFSET)
|
||||
# define STM32_GPIOA_IDR (STM32_GPIOA_BASE+STM32_GPIO_IDR_OFFSET)
|
||||
# define STM32_GPIOA_ODR (STM32_GPIOA_BASE+STM32_GPIO_ODR_OFFSET)
|
||||
# define STM32_GPIOA_BSRR (STM32_GPIOA_BASE+STM32_GPIO_BSRR_OFFSET)
|
||||
# define STM32_GPIOA_LCKR (STM32_GPIOA_BASE+STM32_GPIO_LCKR_OFFSET)
|
||||
# define STM32_GPIOA_AFRL (STM32_GPIOA_BASE+STM32_GPIO_AFRL_OFFSET)
|
||||
# define STM32_GPIOA_ARFH (STM32_GPIOA_BASE+STM32_GPIO_ARFH_OFFSET)
|
||||
#endif
|
||||
|
||||
#if STM32_NGPIO_PORTS > 1
|
||||
# define STM32_GPIOB_MODER (STM32_GPIOB_BASE+STM32_GPIO_MODER_OFFSET)
|
||||
# define STM32_GPIOB_OTYPER (STM32_GPIOB_BASE+STM32_GPIO_OTYPER_OFFSET)
|
||||
# define STM32_GPIOB_OSPEED (STM32_GPIOB_BASE+STM32_GPIO_OSPEED_OFFSET)
|
||||
# define STM32_GPIOB_PUPDR (STM32_GPIOB_BASE+STM32_GPIO_PUPDR_OFFSET)
|
||||
# define STM32_GPIOB_IDR (STM32_GPIOB_BASE+STM32_GPIO_IDR_OFFSET)
|
||||
# define STM32_GPIOB_ODR (STM32_GPIOB_BASE+STM32_GPIO_ODR_OFFSET)
|
||||
# define STM32_GPIOB_BSRR (STM32_GPIOB_BASE+STM32_GPIO_BSRR_OFFSET)
|
||||
# define STM32_GPIOB_LCKR (STM32_GPIOB_BASE+STM32_GPIO_LCKR_OFFSET)
|
||||
# define STM32_GPIOB_AFRL (STM32_GPIOB_BASE+STM32_GPIO_AFRL_OFFSET)
|
||||
# define STM32_GPIOB_ARFH (STM32_GPIOB_BASE+STM32_GPIO_ARFH_OFFSET)
|
||||
#endif
|
||||
|
||||
#if STM32_NGPIO_PORTS > 2
|
||||
# define STM32_GPIOC_MODER (STM32_GPIOC_BASE+STM32_GPIO_MODER_OFFSET)
|
||||
# define STM32_GPIOC_OTYPER (STM32_GPIOC_BASE+STM32_GPIO_OTYPER_OFFSET)
|
||||
# define STM32_GPIOC_OSPEED (STM32_GPIOC_BASE+STM32_GPIO_OSPEED_OFFSET)
|
||||
# define STM32_GPIOC_PUPDR (STM32_GPIOC_BASE+STM32_GPIO_PUPDR_OFFSET)
|
||||
# define STM32_GPIOC_IDR (STM32_GPIOC_BASE+STM32_GPIO_IDR_OFFSET)
|
||||
# define STM32_GPIOC_ODR (STM32_GPIOC_BASE+STM32_GPIO_ODR_OFFSET)
|
||||
# define STM32_GPIOC_BSRR (STM32_GPIOC_BASE+STM32_GPIO_BSRR_OFFSET)
|
||||
# define STM32_GPIOC_LCKR (STM32_GPIOC_BASE+STM32_GPIO_LCKR_OFFSET)
|
||||
# define STM32_GPIOC_AFRL (STM32_GPIOC_BASE+STM32_GPIO_AFRL_OFFSET)
|
||||
# define STM32_GPIOC_ARFH (STM32_GPIOC_BASE+STM32_GPIO_ARFH_OFFSET)
|
||||
#endif
|
||||
|
||||
#if STM32_NGPIO_PORTS > 3
|
||||
# define STM32_GPIOD_MODER (STM32_GPIOD_BASE+STM32_GPIO_MODER_OFFSET)
|
||||
# define STM32_GPIOD_OTYPER (STM32_GPIOD_BASE+STM32_GPIO_OTYPER_OFFSET)
|
||||
# define STM32_GPIOD_OSPEED (STM32_GPIOD_BASE+STM32_GPIO_OSPEED_OFFSET)
|
||||
# define STM32_GPIOD_PUPDR (STM32_GPIOD_BASE+STM32_GPIO_PUPDR_OFFSET)
|
||||
# define STM32_GPIOD_IDR (STM32_GPIOD_BASE+STM32_GPIO_IDR_OFFSET)
|
||||
# define STM32_GPIOD_ODR (STM32_GPIOD_BASE+STM32_GPIO_ODR_OFFSET)
|
||||
# define STM32_GPIOD_BSRR (STM32_GPIOD_BASE+STM32_GPIO_BSRR_OFFSET)
|
||||
# define STM32_GPIOD_LCKR (STM32_GPIOD_BASE+STM32_GPIO_LCKR_OFFSET)
|
||||
# define STM32_GPIOD_AFRL (STM32_GPIOD_BASE+STM32_GPIO_AFRL_OFFSET)
|
||||
# define STM32_GPIOD_ARFH (STM32_GPIOD_BASE+STM32_GPIO_ARFH_OFFSET)
|
||||
#endif
|
||||
|
||||
#if STM32_NGPIO_PORTS > 4
|
||||
# define STM32_GPIOE_MODER (STM32_GPIOE_BASE+STM32_GPIO_MODER_OFFSET)
|
||||
# define STM32_GPIOE_OTYPER (STM32_GPIOE_BASE+STM32_GPIO_OTYPER_OFFSET)
|
||||
# define STM32_GPIOE_OSPEED (STM32_GPIOE_BASE+STM32_GPIO_OSPEED_OFFSET)
|
||||
# define STM32_GPIOE_PUPDR (STM32_GPIOE_BASE+STM32_GPIO_PUPDR_OFFSET)
|
||||
# define STM32_GPIOE_IDR (STM32_GPIOE_BASE+STM32_GPIO_IDR_OFFSET)
|
||||
# define STM32_GPIOE_ODR (STM32_GPIOE_BASE+STM32_GPIO_ODR_OFFSET)
|
||||
# define STM32_GPIOE_BSRR (STM32_GPIOE_BASE+STM32_GPIO_BSRR_OFFSET)
|
||||
# define STM32_GPIOE_LCKR (STM32_GPIOE_BASE+STM32_GPIO_LCKR_OFFSET)
|
||||
# define STM32_GPIOE_AFRL (STM32_GPIOE_BASE+STM32_GPIO_AFRL_OFFSET)
|
||||
# define STM32_GPIOE_ARFH (STM32_GPIOE_BASE+STM32_GPIO_ARFH_OFFSET)
|
||||
#endif
|
||||
|
||||
#if STM32_NGPIO_PORTS > 5
|
||||
# define STM32_GPIOF_MODER (STM32_GPIOF_BASE+STM32_GPIO_MODER_OFFSET)
|
||||
# define STM32_GPIOF_OTYPER (STM32_GPIOF_BASE+STM32_GPIO_OTYPER_OFFSET)
|
||||
# define STM32_GPIOF_OSPEED (STM32_GPIOF_BASE+STM32_GPIO_OSPEED_OFFSET)
|
||||
# define STM32_GPIOF_PUPDR (STM32_GPIOF_BASE+STM32_GPIO_PUPDR_OFFSET)
|
||||
# define STM32_GPIOF_IDR (STM32_GPIOF_BASE+STM32_GPIO_IDR_OFFSET)
|
||||
# define STM32_GPIOF_ODR (STM32_GPIOF_BASE+STM32_GPIO_ODR_OFFSET)
|
||||
# define STM32_GPIOF_BSRR (STM32_GPIOF_BASE+STM32_GPIO_BSRR_OFFSET)
|
||||
# define STM32_GPIOF_LCKR (STM32_GPIOF_BASE+STM32_GPIO_LCKR_OFFSET)
|
||||
# define STM32_GPIOF_AFRL (STM32_GPIOF_BASE+STM32_GPIO_AFRL_OFFSET)
|
||||
# define STM32_GPIOF_ARFH (STM32_GPIOF_BASE+STM32_GPIO_ARFH_OFFSET)
|
||||
#endif
|
||||
|
||||
#if STM32_NGPIO_PORTS > 6
|
||||
# define STM32_GPIOG_MODER (STM32_GPIOG_BASE+STM32_GPIO_MODER_OFFSET)
|
||||
# define STM32_GPIOG_OTYPER (STM32_GPIOG_BASE+STM32_GPIO_OTYPER_OFFSET)
|
||||
# define STM32_GPIOG_OSPEED (STM32_GPIOG_BASE+STM32_GPIO_OSPEED_OFFSET)
|
||||
# define STM32_GPIOG_PUPDR (STM32_GPIOG_BASE+STM32_GPIO_PUPDR_OFFSET)
|
||||
# define STM32_GPIOG_IDR (STM32_GPIOG_BASE+STM32_GPIO_IDR_OFFSET)
|
||||
# define STM32_GPIOG_ODR (STM32_GPIOG_BASE+STM32_GPIO_ODR_OFFSET)
|
||||
# define STM32_GPIOG_BSRR (STM32_GPIOG_BASE+STM32_GPIO_BSRR_OFFSET)
|
||||
# define STM32_GPIOG_LCKR (STM32_GPIOG_BASE+STM32_GPIO_LCKR_OFFSET)
|
||||
# define STM32_GPIOG_AFRL (STM32_GPIOG_BASE+STM32_GPIO_AFRL_OFFSET)
|
||||
# define STM32_GPIOG_ARFH (STM32_GPIOG_BASE+STM32_GPIO_ARFH_OFFSET)
|
||||
#endif
|
||||
|
||||
#if STM32_NGPIO_PORTS > 7
|
||||
# define STM32_GPIOH_MODER (STM32_GPIOH_BASE+STM32_GPIO_MODER_OFFSET)
|
||||
# define STM32_GPIOH_OTYPER (STM32_GPIOH_BASE+STM32_GPIO_OTYPER_OFFSET)
|
||||
# define STM32_GPIOH_OSPEED (STM32_GPIOH_BASE+STM32_GPIO_OSPEED_OFFSET)
|
||||
# define STM32_GPIOH_PUPDR (STM32_GPIOH_BASE+STM32_GPIO_PUPDR_OFFSET)
|
||||
# define STM32_GPIOH_IDR (STM32_GPIOH_BASE+STM32_GPIO_IDR_OFFSET)
|
||||
# define STM32_GPIOH_ODR (STM32_GPIOH_BASE+STM32_GPIO_ODR_OFFSET)
|
||||
# define STM32_GPIOH_BSRR (STM32_GPIOH_BASE+STM32_GPIO_BSRR_OFFSET)
|
||||
# define STM32_GPIOH_LCKR (STM32_GPIOH_BASE+STM32_GPIO_LCKR_OFFSET)
|
||||
# define STM32_GPIOH_AFRL (STM32_GPIOH_BASE+STM32_GPIO_AFRL_OFFSET)
|
||||
# define STM32_GPIOH_ARFH (STM32_GPIOH_BASE+STM32_GPIO_ARFH_OFFSET)
|
||||
#endif
|
||||
|
||||
#if STM32_NGPIO_PORTS > 8
|
||||
# define STM32_GPIOI_MODER (STM32_GPIOI_BASE+STM32_GPIO_MODER_OFFSET)
|
||||
# define STM32_GPIOI_OTYPER (STM32_GPIOI_BASE+STM32_GPIO_OTYPER_OFFSET)
|
||||
# define STM32_GPIOI_OSPEED (STM32_GPIOI_BASE+STM32_GPIO_OSPEED_OFFSET)
|
||||
# define STM32_GPIOI_PUPDR (STM32_GPIOI_BASE+STM32_GPIO_PUPDR_OFFSET)
|
||||
# define STM32_GPIOI_IDR (STM32_GPIOI_BASE+STM32_GPIO_IDR_OFFSET)
|
||||
# define STM32_GPIOI_ODR (STM32_GPIOI_BASE+STM32_GPIO_ODR_OFFSET)
|
||||
# define STM32_GPIOI_BSRR (STM32_GPIOI_BASE+STM32_GPIO_BSRR_OFFSET)
|
||||
# define STM32_GPIOI_LCKR (STM32_GPIOI_BASE+STM32_GPIO_LCKR_OFFSET)
|
||||
# define STM32_GPIOI_AFRL (STM32_GPIOI_BASE+STM32_GPIO_AFRL_OFFSET)
|
||||
# define STM32_GPIOI_ARFH (STM32_GPIOI_BASE+STM32_GPIO_ARFH_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) /* 2 MHz Low speed */
|
||||
#define GPIO_OSPEED_25MHz (1) /* 25 MHz Medium speed */
|
||||
#define GPIO_OSPEED_50MHz (2) /* 50 MHz Fast speed */
|
||||
#define GPIO_OSPEED_100MHz (3) /* 100 MHz High speed on 30 pF (80 MHz Output max speed on 15 pF) */
|
||||
|
||||
#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)
|
||||
|
||||
#endif /* __ARCH_ARM_SRC_STM32_CHIP_STM32F20XXX_GPIO_H */
|
||||
|
|
@ -0,0 +1,197 @@
|
|||
/************************************************************************************
|
||||
* arch/arm/src/stm32/chip/stm32f20xxx_memorymap.h
|
||||
*
|
||||
* Copyright (C) 2011 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.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
#ifndef __ARCH_ARM_SRC_STM32_CHIP_STM32F20XXX_MEMORYMAP_H
|
||||
#define __ARCH_ARM_SRC_STM32_CHIP_STM32F20XXX_MEMORYMAP_H
|
||||
|
||||
/************************************************************************************
|
||||
* Pre-processor Definitions
|
||||
************************************************************************************/
|
||||
|
||||
/* STM32F20XXX Address Blocks *******************************************************/
|
||||
|
||||
#define STM32_CODE_BASE 0x00000000 /* 0x00000000-0x1fffffff: 512Mb code block */
|
||||
#define STM32_SRAM_BASE 0x20000000 /* 0x20000000-0x3fffffff: 512Mb sram block */
|
||||
#define STM32_PERIPH_BASE 0x40000000 /* 0x40000000-0x5fffffff: 512Mb peripheral block */
|
||||
#define STM32_FSMC_BASE12 0x60000000 /* 0x60000000-0x7fffffff: 512Mb FSMC bank1&2 block */
|
||||
#define STM32_FSMC_BASE34 0x80000000 /* 0x80000000-0x8fffffff: 512Mb FSMC bank3&4 block */
|
||||
#define STM32_FSMC_BASE 0xa0000000 /* 0xa0000000-0xbfffffff: 512Mb FSMC register block */
|
||||
/* 0xc0000000-0xdfffffff: 512Mb (not used) */
|
||||
#define STM32_CORTEX_BASE 0xe0000000 /* 0xe0000000-0xffffffff: 512Mb Cortex-M4 block */
|
||||
|
||||
/* Code Base Addresses **************************************************************/
|
||||
|
||||
#define STM32_BOOT_BASE 0x00000000 /* 0x00000000-0x000fffff: Aliased boot memory */
|
||||
/* 0x00100000-0x07ffffff: Reserved */
|
||||
#define STM32_FLASH_BASE 0x08000000 /* 0x08000000-0x080fffff: FLASH memory */
|
||||
/* 0x08100000-0x0fffffff: Reserved */
|
||||
#define STM32_TCMRAM_BASE 0x10000000 /* 0x10000000-0x1000ffff: 64Kb TCM data RAM */
|
||||
/* 0x10010000-0x1ffeffff: Reserved */
|
||||
#define STM32_SYSMEM_BASE 0x1fff0000 /* 0x1fff0000-0x1fff7a0f: System memory */
|
||||
/* 0x1fff7a10-0x1fff7fff: Reserved */
|
||||
#define STM32_OPTION_BASE 0x1fffc000 /* 0x1fffc000-0x1fffc007: Option bytes */
|
||||
/* 0x1fffc008-0x1fffffff: Reserved */
|
||||
|
||||
/* SRAM Base Addresses **************************************************************/
|
||||
|
||||
/* 0x20000000-0x2001bfff: 112Kb aliased by bit-banding */
|
||||
/* 0x2001c000-0x2001ffff: 16Kb aliased by bit-banding */
|
||||
#define STM32_SRAMBB_BASE 0x22000000 /* 0x22000000- : SRAM bit-band region */
|
||||
|
||||
/* Peripheral Base Addresses ********************************************************/
|
||||
|
||||
#define STM32_APB1_BASE 0x40000000 /* 0x40000000-0x400023ff: APB1 */
|
||||
/* 0x40002400-0x400027ff: Reserved */
|
||||
/* 0x40002800-0x400077ff: APB1 */
|
||||
/* 0x40007800-0x4000ffff: Reserved */
|
||||
#define STM32_APB2_BASE 0x40010000 /* 0x40010000-0x400023ff: APB2 */
|
||||
/* 0x40013400-0x400137ff: Reserved */
|
||||
/* 0x40013800-0x40013bff: SYSCFG */
|
||||
#define STM32_EXTI_BASE 0x40013c00 /* 0x40013c00-0x40013fff: EXTI */
|
||||
/* 0x40014000-0x40014bff: APB2 */
|
||||
/* 0x40014c00-0x4001ffff: Reserved */
|
||||
#define STM32_AHB1_BASE 0x40020000 /* 0x40020000-0x400223ff: APB1 */
|
||||
/* 0x40022400-0x40022fff: Reserved */
|
||||
/* 0x40023000-0x400233ff: CRC */
|
||||
/* 0x40023400-0x400237ff: Reserved */
|
||||
/* 0x40023800-0x40023bff: Reset and Clock control RCC */
|
||||
/* 0x40023c00-0x400293ff: AHB1 (?) */
|
||||
/* 0x40029400-0x4fffffff: Reserved (?) */
|
||||
#define STM32_AHB2_BASE 0x50000000 /* 0x50000000-0x5003ffff: AHB2 */
|
||||
/* 0x50040000-0x5004ffff: Reserved */
|
||||
/* 0x50050000-0x500503ff: AHB2 */
|
||||
/* 0x50050400-0x500607ff: Reserved */
|
||||
/* 0x50060800-0x50060bff: AHB2 */
|
||||
/* 0x50060c00-0x5fffffff: Reserved */
|
||||
|
||||
/* FSMC Base Addresses **************************************************************/
|
||||
|
||||
#define STM32_AHB3_BASE 0x60000000 /* 0x60000000-0xa0000fff: AHB3 */
|
||||
|
||||
/* APB1 Base Addresses **************************************************************/
|
||||
|
||||
#define STM32_TIM2_BASE 0x40000000 /* 0x40000000-0x400003ff: TIM2 timer */
|
||||
#define STM32_TIM3_BASE 0x40000400 /* 0x40000400-0x400007ff: TIM3 timer */
|
||||
#define STM32_TIM4_BASE 0x40000800 /* 0x40000800-0x40000bff: TIM4 timer */
|
||||
#define STM32_TIM5_BASE 0x40000c00 /* 0x40000c00-0x40000fff: TIM5 timer */
|
||||
#define STM32_TIM6_BASE 0x40001000 /* 0x40001000-0x400013ff: TIM6 timer */
|
||||
#define STM32_TIM7_BASE 0x40001400 /* 0x40001400-0x400017ff: TIM7 timer */
|
||||
#define STM32_TIM12_BASE 0x40001800 /* 0x40001800-0x40001bff: TIM12 timer */
|
||||
#define STM32_TIM13_BASE 0x40001c00 /* 0x40001c00-0x40001fff: TIM13 timer */
|
||||
#define STM32_TIM14_BASE 0x40002000 /* 0x40002000-0x400023ff: TIM14 timer */
|
||||
#define STM32_RTC_BASE 0x40002800 /* 0x40002800-0x40002bff: RTC & BKP registers */
|
||||
#define STM32_BKP_BASE 0x40002850
|
||||
#define STM32_WWDG_BASE 0x40002c00 /* 0x40002c00-0x40002fff: Window watchdog (WWDG) */
|
||||
#define STM32_IWDG_BASE 0x40003000 /* 0x40003000-0x400033ff: Independent watchdog (IWDG) */
|
||||
#define STM32_I2S2EXT_BASE 0x40003400 /* 0x40003400-0x400037ff: I2S2ext */
|
||||
#define STM32_SPI2_BASE 0x40003800 /* 0x40003800-0x40003bff: SPI2/I2S2 */
|
||||
#define STM32_I2S2_BASE 0x40003800
|
||||
#define STM32_SPI3_BASE 0x40003c00 /* 0x40003c00-0x40003fff: SPI3/I2S3 */
|
||||
#define STM32_I2S3_BASE 0x40003c00
|
||||
#define STM32_I2S3EXT_BASE 0x40004000 /* 0x40003400-0x400043ff: I2S3ext */
|
||||
#define STM32_USART2_BASE 0x40004400 /* 0x40004400-0x400047ff: USART2 */
|
||||
#define STM32_USART3_BASE 0x40004800 /* 0x40004800-0x40004bff: USART3 */
|
||||
#define STM32_UART4_BASE 0x40004c00 /* 0x40004c00-0x40004fff: UART4 */
|
||||
#define STM32_UART5_BASE 0x40005000 /* 0x40005000-0x400053ff: UART5 */
|
||||
#define STM32_I2C1_BASE 0x40005400 /* 0x40005400-0x400057ff: I2C1 */
|
||||
#define STM32_I2C2_BASE 0x40005800 /* 0x40005800-0x40005Bff: I2C2 */
|
||||
#define STM32_I2C3_BASE 0x40005c00 /* 0x40005c00-0x40005fff: I2C3 */
|
||||
#define STM32_CAN1_BASE 0x40006400 /* 0x40006400-0x400067ff: bxCAN1 */
|
||||
#define STM32_CAN2_BASE 0x40006800 /* 0x40006800-0x40006bff: bxCAN2 */
|
||||
#define STM32_PWR_BASE 0x40007000 /* 0x40007000-0x400073ff: Power control PWR */
|
||||
#define STM32_DAC_BASE 0x40007400 /* 0x40007400-0x400077ff: DAC */
|
||||
|
||||
/* APB2 Base Addresses **************************************************************/
|
||||
|
||||
#define STM32_TIM1_BASE 0x40010000 /* 0x40010000-0x400103ff: TIM1 timer */
|
||||
#define STM32_TIM8_BASE 0x40010400 /* 0x40010400-0x400107ff: TIM8 timer */
|
||||
#define STM32_USART1_BASE 0x40011000 /* 0x40011000-0x400113ff: USART1 */
|
||||
#define STM32_USART6_BASE 0x40011400 /* 0x40011400-0x400117ff: USART6 */
|
||||
#define STM32_ADC_BASE 0x40012000 /* 0x40012000-0x400123ff: ADC1-3 */
|
||||
# define STM32_ADC1_BASE 0x40012000 /* ADC1 */
|
||||
# define STM32_ADC2_BASE 0x40012100 /* ADC2 */
|
||||
# define STM32_ADC3_BASE 0x40012200 /* ADC3 */
|
||||
# define STM32_ADCCMN_BASE 0x40012300 /* Common */
|
||||
#define STM32_SDIO_BASE 0x40012c00 /* 0x40012c00-0x40012fff: SDIO */
|
||||
#define STM32_SPI1_BASE 0x40013000 /* 0x40013000-0x400133ff: SPI1 */
|
||||
#define STM32_SYSCFG_BASE 0x40013800 /* 0x40013800-0x40013bff: SYSCFG */
|
||||
#define STM32_EXTI_BASE 0x40013c00 /* 0x40013c00-0x40013fff: EXTI */
|
||||
#define STM32_TIM9_BASE 0x40014000 /* 0x40014000-0x400143ff: TIM9 timer */
|
||||
#define STM32_TIM10_BASE 0x40014400 /* 0x40014400-0x400147ff: TIM10 timer */
|
||||
#define STM32_TIM11_BASE 0x40014800 /* 0x40014800-0x40014bff: TIM11 timer */
|
||||
|
||||
/* AHB1 Base Addresses **************************************************************/
|
||||
|
||||
#define STM32_GPIOA_BASE 0x40020000 /* 0x40020000-0x400203ff: GPIO Port A */
|
||||
#define STM32_GPIOB_BASE 0x40020400 /* 0x40020400-0x400207ff: GPIO Port B */
|
||||
#define STM32_GPIOC_BASE 0x40020800 /* 0x40020800-0x40020bff: GPIO Port C */
|
||||
#define STM32_GPIOD_BASE 0X40020C00 /* 0x40020c00-0x40020fff: GPIO Port D */
|
||||
#define STM32_GPIOE_BASE 0x40021000 /* 0x40021000-0x400213ff: GPIO Port E */
|
||||
#define STM32_GPIOF_BASE 0x40021400 /* 0x40021400-0x400217ff: GPIO Port F */
|
||||
#define STM32_GPIOG_BASE 0x40021800 /* 0x40021800-0x40021bff: GPIO Port G */
|
||||
#define STM32_GPIOH_BASE 0x40021C00 /* 0x40021C00-0x40021fff: GPIO Port H */
|
||||
#define STM32_GPIOI_BASE 0x40022000 /* 0x40022000-0x400223ff: GPIO Port I */
|
||||
#define STM32_CRC_BASE 0x40023000 /* 0x40023000-0x400233ff: CRC */
|
||||
#define STM32_RCC_BASE 0x40023800 /* 0x40023800-0x40023bff: Reset and Clock control RCC */
|
||||
#define STM32_FLASHIF_BASE 0x40023c00 /* 0x40023c00-0x40023fff: Flash memory interface */
|
||||
#define STM32_BKPSRAM_BASE 0x40024000 /* 0x40024000-0x40024fff: Backup SRAM (BKPSRAM) */
|
||||
#define STM32_DMA1_BASE 0x40026000 /* 0x40026000-0x400263ff: DMA1 */
|
||||
#define STM32_DMA2_BASE 0x40026400 /* 0x40026400-0x400267ff: DMA2 */
|
||||
#define STM32_ETHERNET_BASE 0x40028000 /* 0x40028000-0x400283ff: Ethernet MAC */
|
||||
/* 0x40028400-0x400287ff: Ethernet MAC */
|
||||
/* 0x40028800-0x40028bff: Ethernet MAC */
|
||||
/* 0x40028c00-0x40028fff: Ethernet MAC */
|
||||
/* 0x40029000-0x400293ff: Ethernet MAC */
|
||||
#define STM32_OTGHS_BASE 0x40040000 /* 0x40040000-0x4007ffff: USB OTG HS */
|
||||
#define STM32_PERIPHBB_BASE 0x42000000 /* Peripheral bit-band region */
|
||||
|
||||
/* AHB2 Base Addresses **************************************************************/
|
||||
|
||||
#define STM32_OTGFS_BASE 0x50000000 /* 0x50000000-0x5003ffff: USB OTG FS */
|
||||
#define STM32_DCMI_BASE 0x50050000 /* 0x50050000-0x500503ff: DCMI */
|
||||
#define STM32_CRYP_BASE 0x50060000 /* 0x50060000-0x500603ff: CRYP */
|
||||
#define STM32_HASH_BASE 0x50060400 /* 0x50060400-0x500607ff: HASH */
|
||||
#define STM32_RNG_BASE 0x50060800 /* 0x50060800-0x50060bff: RNG */
|
||||
|
||||
/* Cortex-M4 Base Addresses *********************************************************/
|
||||
/* Other registers -- see armv7-m/nvic.h for standard Cortex-M3 registers in this
|
||||
* address range
|
||||
*/
|
||||
|
||||
#define STM32_SCS_BASE 0xe000e000
|
||||
#define STM32_DEBUGMCU_BASE 0xe0042000
|
||||
|
||||
#endif /* __ARCH_ARM_SRC_STM32_CHIP_STM32F20XXX_MEMORYMAP_H */
|
||||
|
|
@ -0,0 +1,628 @@
|
|||
/************************************************************************************
|
||||
* arch/arm/src/stm32/chip/stm32f20xxx_pinmap.h
|
||||
*
|
||||
* Copyright (C) 2011 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
*
|
||||
* 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_STM32_CHIP_STM32F20XXX_PINMAP_H
|
||||
#define __ARCH_ARM_SRC_STM32_CHIP_STM32F20XXX_PINMAP_H
|
||||
|
||||
/************************************************************************************
|
||||
* Included Files
|
||||
************************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
|
||||
#include "stm32_gpio.h"
|
||||
|
||||
/************************************************************************************
|
||||
* Pre-processor Definitions
|
||||
************************************************************************************/
|
||||
|
||||
/* Alternate Pin Functions. All members of the STM32F20xxx family share the same
|
||||
* pin multiplexing (although they may differ in the pins physically available).
|
||||
*
|
||||
* Alternative pin 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. For example, if
|
||||
* CAN1_RX connects vis PA11 on some board, then the following definitions should
|
||||
* appear inthe board.h header file for that board:
|
||||
*
|
||||
* #define GPIO_CAN1_RX GPIO_CAN1_RX_1
|
||||
*
|
||||
* The driver will then automatically configre PA11 as the CAN1 RX pin.
|
||||
*/
|
||||
|
||||
/* WARNING!!! WARNING!!! WARNING!!! WARNING!!! WARNING!!! WARNING!!! WARNING!!!
|
||||
* Additional effort is required to select specific GPIO options such as frequency,
|
||||
* open-drain/push-pull, and pull-up/down! Just the basics are defined for most
|
||||
* pins in this file.
|
||||
*/
|
||||
|
||||
/* ADC */
|
||||
|
||||
#define GPIO_ADC1_IN0 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN0)
|
||||
#define GPIO_ADC1_IN1 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN1)
|
||||
#define GPIO_ADC1_IN2 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN2)
|
||||
#define GPIO_ADC1_IN3 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN3)
|
||||
#define GPIO_ADC1_IN4 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN4)
|
||||
#define GPIO_ADC1_IN5 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN5)
|
||||
#define GPIO_ADC1_IN6 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN6)
|
||||
#define GPIO_ADC1_IN7 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN7)
|
||||
#define GPIO_ADC1_IN8 (GPIO_ANALOG|GPIO_PORTB|GPIO_PIN0)
|
||||
#define GPIO_ADC1_IN9 (GPIO_ANALOG|GPIO_PORTB|GPIO_PIN1)
|
||||
#define GPIO_ADC1_IN10 (GPIO_ANALOG|GPIO_PORTC|GPIO_PIN0)
|
||||
#define GPIO_ADC1_IN11 (GPIO_ANALOG|GPIO_PORTC|GPIO_PIN1)
|
||||
#define GPIO_ADC1_IN12 (GPIO_ANALOG|GPIO_PORTC|GPIO_PIN2)
|
||||
#define GPIO_ADC1_IN13 (GPIO_ANALOG|GPIO_PORTC|GPIO_PIN3)
|
||||
#define GPIO_ADC1_IN14 (GPIO_ANALOG|GPIO_PORTC|GPIO_PIN4)
|
||||
#define GPIO_ADC1_IN15 (GPIO_ANALOG|GPIO_PORTC|GPIO_PIN5)
|
||||
|
||||
#define GPIO_ADC2_IN0 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN0)
|
||||
#define GPIO_ADC2_IN1 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN1)
|
||||
#define GPIO_ADC2_IN2 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN2)
|
||||
#define GPIO_ADC2_IN3 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN3)
|
||||
#define GPIO_ADC2_IN4 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN4)
|
||||
#define GPIO_ADC2_IN5 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN5)
|
||||
#define GPIO_ADC2_IN6 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN6)
|
||||
#define GPIO_ADC2_IN7 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN7)
|
||||
#define GPIO_ADC2_IN8 (GPIO_ANALOG|GPIO_PORTB|GPIO_PIN0)
|
||||
#define GPIO_ADC2_IN9 (GPIO_ANALOG|GPIO_PORTB|GPIO_PIN1)
|
||||
#define GPIO_ADC2_IN10 (GPIO_ANALOG|GPIO_PORTC|GPIO_PIN0)
|
||||
#define GPIO_ADC2_IN11 (GPIO_ANALOG|GPIO_PORTC|GPIO_PIN1)
|
||||
#define GPIO_ADC2_IN12 (GPIO_ANALOG|GPIO_PORTC|GPIO_PIN2)
|
||||
#define GPIO_ADC2_IN13 (GPIO_ANALOG|GPIO_PORTC|GPIO_PIN3)
|
||||
#define GPIO_ADC2_IN14 (GPIO_ANALOG|GPIO_PORTC|GPIO_PIN4)
|
||||
#define GPIO_ADC2_IN15 (GPIO_ANALOG|GPIO_PORTC|GPIO_PIN5)
|
||||
|
||||
#define GPIO_ADC3_IN0 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN0)
|
||||
#define GPIO_ADC3_IN1 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN1)
|
||||
#define GPIO_ADC3_IN2 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN2)
|
||||
#define GPIO_ADC3_IN3 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN3)
|
||||
#define GPIO_ADC3_IN4 (GPIO_ANALOG|GPIO_PORTF|GPIO_PIN6)
|
||||
#define GPIO_ADC3_IN5 (GPIO_ANALOG|GPIO_PORTF|GPIO_PIN7)
|
||||
#define GPIO_ADC3_IN6 (GPIO_ANALOG|GPIO_PORTF|GPIO_PIN8)
|
||||
#define GPIO_ADC3_IN7 (GPIO_ANALOG|GPIO_PORTF|GPIO_PIN9)
|
||||
#define GPIO_ADC3_IN9 (GPIO_ANALOG|GPIO_PORTF|GPIO_PIN3)
|
||||
#define GPIO_ADC3_IN10 (GPIO_ANALOG|GPIO_PORTC|GPIO_PIN0)
|
||||
#define GPIO_ADC3_IN11 (GPIO_ANALOG|GPIO_PORTC|GPIO_PIN1)
|
||||
#define GPIO_ADC3_IN12 (GPIO_ANALOG|GPIO_PORTC|GPIO_PIN2)
|
||||
#define GPIO_ADC3_IN13 (GPIO_ANALOG|GPIO_PORTC|GPIO_PIN3)
|
||||
#define GPIO_ADC3_IN14 (GPIO_ANALOG|GPIO_PORTF|GPIO_PIN4)
|
||||
#define GPIO_ADC3_IN15 (GPIO_ANALOG|GPIO_PORTF|GPIO_PIN5)
|
||||
|
||||
/* CAN */
|
||||
|
||||
#define GPIO_CAN1_RX_1 (GPIO_ALT|GPIO_AF9|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN11)
|
||||
#define GPIO_CAN1_RX_2 (GPIO_ALT|GPIO_AF9|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN8)
|
||||
#define GPIO_CAN1_RX_3 (GPIO_ALT|GPIO_AF9|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTD|GPIO_PIN0)
|
||||
#define GPIO_CAN1_RX_4 (GPIO_ALT|GPIO_AF9|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTI|GPIO_PIN9)
|
||||
#define GPIO_CAN1_TX_1 (GPIO_ALT|GPIO_AF9|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN12)
|
||||
#define GPIO_CAN1_TX_2 (GPIO_ALT|GPIO_AF9|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN9)
|
||||
#define GPIO_CAN1_TX_3 (GPIO_ALT|GPIO_AF9|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTD|GPIO_PIN1)
|
||||
#define GPIO_CAN1_TX_4 (GPIO_ALT|GPIO_AF9|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTH|GPIO_PIN13)
|
||||
|
||||
#define GPIO_CAN2_RX_1 (GPIO_ALT|GPIO_AF9|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN12)
|
||||
#define GPIO_CAN2_RX_2 (GPIO_ALT|GPIO_AF9|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN5)
|
||||
#define GPIO_CAN2_TX_1 (GPIO_ALT|GPIO_AF9|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN13)
|
||||
#define GPIO_CAN2_TX_2 (GPIO_ALT|GPIO_AF9|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN6)
|
||||
|
||||
/* DAC -" Once the DAC channelx is enabled, the corresponding GPIO pin
|
||||
* (PA4 or PA5) is automatically connected to the analog converter output
|
||||
* (DAC_OUTx). In order to avoid parasitic consumption, the PA4 or PA5 pin
|
||||
* should first be configured to analog (AIN)".
|
||||
*/
|
||||
|
||||
#define GPIO_DAC1_OUT (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN4)
|
||||
#define GPIO_DAC2_OUT (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN5)
|
||||
|
||||
/* Digital Camera Interface (DCMI) */
|
||||
|
||||
#define GPIO_DCMI_D0_1 (GPIO_ALT|GPIO_AF13|GPIO_PORTA|GPIO_PIN9)
|
||||
#define GPIO_DCMI_D0_2 (GPIO_ALT|GPIO_AF13|GPIO_PORTC|GPIO_PIN6)
|
||||
#define GPIO_DCMI_D0_3 (GPIO_ALT|GPIO_AF13|GPIO_PORTH|GPIO_PIN9)
|
||||
#define GPIO_DCMI_D1_1 (GPIO_ALT|GPIO_AF13|GPIO_PORTA|GPIO_PIN10)
|
||||
#define GPIO_DCMI_D1_2 (GPIO_ALT|GPIO_AF13|GPIO_PORTC|GPIO_PIN7)
|
||||
#define GPIO_DCMI_D1_3 (GPIO_ALT|GPIO_AF13|GPIO_PORTH|GPIO_PIN10)
|
||||
#define GPIO_DCMI_D2_1 (GPIO_ALT|GPIO_AF13|GPIO_PORTC|GPIO_PIN8)
|
||||
#define GPIO_DCMI_D2_2 (GPIO_ALT|GPIO_AF13|GPIO_PORTE|GPIO_PIN0)
|
||||
#define GPIO_DCMI_D2_3 (GPIO_ALT|GPIO_AF13|GPIO_PORTH|GPIO_PIN11)
|
||||
#define GPIO_DCMI_D3_1 (GPIO_ALT|GPIO_AF13|GPIO_PORTC|GPIO_PIN9)
|
||||
#define GPIO_DCMI_D3_2 (GPIO_ALT|GPIO_AF13|GPIO_PORTE|GPIO_PIN1)
|
||||
#define GPIO_DCMI_D3_3 (GPIO_ALT|GPIO_AF13|GPIO_PORTH|GPIO_PIN12)
|
||||
#define GPIO_DCMI_D4_1 (GPIO_ALT|GPIO_AF13|GPIO_PORTC|GPIO_PIN11)
|
||||
#define GPIO_DCMI_D4_2 (GPIO_ALT|GPIO_AF13|GPIO_PORTE|GPIO_PIN4)
|
||||
#define GPIO_DCMI_D4_3 (GPIO_ALT|GPIO_AF13|GPIO_PORTH|GPIO_PIN14)
|
||||
#define GPIO_DCMI_D5_1 (GPIO_ALT|GPIO_AF13|GPIO_PORTB|GPIO_PIN6)
|
||||
#define GPIO_DCMI_D5_2 (GPIO_ALT|GPIO_AF13|GPIO_PORTI|GPIO_PIN4)
|
||||
#define GPIO_DCMI_D6_1 (GPIO_ALT|GPIO_AF13|GPIO_PORTB|GPIO_PIN8)
|
||||
#define GPIO_DCMI_D6_2 (GPIO_ALT|GPIO_AF13|GPIO_PORTE|GPIO_PIN5)
|
||||
#define GPIO_DCMI_D6_3 (GPIO_ALT|GPIO_AF13|GPIO_PORTI|GPIO_PIN6)
|
||||
#define GPIO_DCMI_D7_1 (GPIO_ALT|GPIO_AF13|GPIO_PORTB|GPIO_PIN9)
|
||||
#define GPIO_DCMI_D7_2 (GPIO_ALT|GPIO_AF13|GPIO_PORTE|GPIO_PIN6)
|
||||
#define GPIO_DCMI_D7_3 (GPIO_ALT|GPIO_AF13|GPIO_PORTI|GPIO_PIN7)
|
||||
#define GPIO_DCMI_D8_1 (GPIO_ALT|GPIO_AF13|GPIO_PORTC|GPIO_PIN10)
|
||||
#define GPIO_DCMI_D8_2 (GPIO_ALT|GPIO_AF13|GPIO_PORTI|GPIO_PIN1)
|
||||
#define GPIO_DCMI_D9_1 (GPIO_ALT|GPIO_AF13|GPIO_PORTC|GPIO_PIN12)
|
||||
#define GPIO_DCMI_D9_2 (GPIO_ALT|GPIO_AF13|GPIO_PORTI|GPIO_PIN2)
|
||||
#define GPIO_DCMI_D10_1 (GPIO_ALT|GPIO_AF13|GPIO_PORTB|GPIO_PIN5)
|
||||
#define GPIO_DCMI_D10_2 (GPIO_ALT|GPIO_AF13|GPIO_PORTI|GPIO_PIN3)
|
||||
#define GPIO_DCMI_D11_1 (GPIO_ALT|GPIO_AF13|GPIO_PORTD|GPIO_PIN2)
|
||||
#define GPIO_DCMI_D11_2 (GPIO_ALT|GPIO_AF13|GPIO_PORTH|GPIO_PIN15)
|
||||
#define GPIO_DCMI_D12 (GPIO_ALT|GPIO_AF13|GPIO_PORTF|GPIO_PIN11)
|
||||
#define GPIO_DCMI_D13_1 (GPIO_ALT|GPIO_AF13|GPIO_PORTG|GPIO_PIN15)
|
||||
#define GPIO_DCMI_D13_2 (GPIO_ALT|GPIO_AF13|GPIO_PORTI|GPIO_PIN0)
|
||||
#define GPIO_DCMI_HSYNC_1 (GPIO_ALT|GPIO_AF13|GPIO_PORTA|GPIO_PIN4)
|
||||
#define GPIO_DCMI_HSYNC_2 (GPIO_ALT|GPIO_AF13|GPIO_PORTH|GPIO_PIN8)
|
||||
#define GPIO_DCMI_PIXCK (GPIO_ALT|GPIO_AF13|GPIO_PORTA|GPIO_PIN6)
|
||||
#define GPIO_DCMI_VSYNC_1 (GPIO_ALT|GPIO_AF13|GPIO_PORTB|GPIO_PIN7)
|
||||
#define GPIO_DCMI_VSYNC_2 (GPIO_ALT|GPIO_AF13|GPIO_PORTI|GPIO_PIN5)
|
||||
|
||||
/* Clocks outputs */
|
||||
|
||||
#define GPIO_MCO1 (GPIO_ALT|GPIO_AF0|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN8)
|
||||
#define GPIO_MCO2 (GPIO_ALT|GPIO_AF0|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN9)
|
||||
|
||||
/* Ethernet MAC */
|
||||
|
||||
#define GPIO_ETH_MDC (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN1)
|
||||
#define GPIO_ETH_MDIO (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN2)
|
||||
#define GPIO_ETH_MII_COL_1 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN3)
|
||||
#define GPIO_ETH_MII_COL_2 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTH|GPIO_PIN3)
|
||||
#define GPIO_ETH_MII_CRS_1 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN0)
|
||||
#define GPIO_ETH_MII_CRS_2 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTH|GPIO_PIN2)
|
||||
#define GPIO_ETH_MII_RXD0 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN4)
|
||||
#define GPIO_ETH_MII_RXD1 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN5)
|
||||
#define GPIO_ETH_MII_RXD2_1 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN0)
|
||||
#define GPIO_ETH_MII_RXD2_2 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTH|GPIO_PIN6)
|
||||
#define GPIO_ETH_MII_RXD3_1 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN1)
|
||||
#define GPIO_ETH_MII_RXD3_2 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTH|GPIO_PIN7)
|
||||
#define GPIO_ETH_MII_RX_CLK (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN1)
|
||||
#define GPIO_ETH_MII_RX_DV (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN7)
|
||||
#define GPIO_ETH_MII_RX_ER_1 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN10)
|
||||
#define GPIO_ETH_MII_RX_ER_2 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTI|GPIO_PIN10)
|
||||
#define GPIO_ETH_MII_TXD0_1 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN12)
|
||||
#define GPIO_ETH_MII_TXD0_2 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTG|GPIO_PIN13)
|
||||
#define GPIO_ETH_MII_TXD1_1 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN13)
|
||||
#define GPIO_ETH_MII_TXD1_2 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTG|GPIO_PIN14)
|
||||
#define GPIO_ETH_MII_TXD2 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN2)
|
||||
#define GPIO_ETH_MII_TXD3_1 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN8)
|
||||
#define GPIO_ETH_MII_TXD3_2 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTE|GPIO_PIN2)
|
||||
#define GPIO_ETH_MII_TX_CLK (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN3)
|
||||
#define GPIO_ETH_MII_TX_EN_1 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN11)
|
||||
#define GPIO_ETH_MII_TX_EN_2 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTG|GPIO_PIN11)
|
||||
#define GPIO_ETH_PPS_OUT_1 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN5)
|
||||
#define GPIO_ETH_PPS_OUT_2 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTG|GPIO_PIN8)
|
||||
#define GPIO_ETH_RMII_CRS_DV (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULLGPIO_PORTA|GPIO_PIN7)
|
||||
#define GPIO_ETH_RMII_REF_CLK (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN1)
|
||||
#define GPIO_ETH_RMII_RXD0 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN4)
|
||||
#define GPIO_ETH_RMII_RXD1 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN5)
|
||||
#define GPIO_ETH_RMII_TXD0_1 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN12)
|
||||
#define GPIO_ETH_RMII_TXD0_2 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTG|GPIO_PIN13)
|
||||
#define GPIO_ETH_RMII_TXD1_1 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN13)
|
||||
#define GPIO_ETH_RMII_TXD1_2 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTG|GPIO_PIN14)
|
||||
#define GPIO_ETH_RMII_TX_CLK (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN3)
|
||||
#define GPIO_ETH_RMII_TX_EN_1 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN11)
|
||||
#define GPIO_ETH_RMII_TX_EN_2 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTG|GPIO_PIN11)
|
||||
|
||||
/* Flexible Static Memory Controller (FSMC) */
|
||||
|
||||
#define GPIO_FSMC_A0 (GPIO_ALT|GPIO_AF12|GPIO_PORTF|GPIO_PIN0)
|
||||
#define GPIO_FSMC_A1 (GPIO_ALT|GPIO_AF12|GPIO_PORTF|GPIO_PIN1)
|
||||
#define GPIO_FSMC_A2 (GPIO_ALT|GPIO_AF12|GPIO_PORTF|GPIO_PIN2)
|
||||
#define GPIO_FSMC_A3 (GPIO_ALT|GPIO_AF12|GPIO_PORTF|GPIO_PIN3)
|
||||
#define GPIO_FSMC_A4 (GPIO_ALT|GPIO_AF12|GPIO_PORTF|GPIO_PIN4)
|
||||
#define GPIO_FSMC_A5 (GPIO_ALT|GPIO_AF12|GPIO_PORTF|GPIO_PIN5)
|
||||
#define GPIO_FSMC_A6 (GPIO_ALT|GPIO_AF12|GPIO_PORTF|GPIO_PIN12)
|
||||
#define GPIO_FSMC_A7 (GPIO_ALT|GPIO_AF12|GPIO_PORTF|GPIO_PIN13)
|
||||
#define GPIO_FSMC_A8 (GPIO_ALT|GPIO_AF12|GPIO_PORTF|GPIO_PIN14)
|
||||
#define GPIO_FSMC_A9 (GPIO_ALT|GPIO_AF12|GPIO_PORTF|GPIO_PIN15)
|
||||
#define GPIO_FSMC_A10 (GPIO_ALT|GPIO_AF12|GPIO_PORTG|GPIO_PIN0)
|
||||
#define GPIO_FSMC_A11 (GPIO_ALT|GPIO_AF12|GPIO_PORTG|GPIO_PIN1)
|
||||
#define GPIO_FSMC_A12 (GPIO_ALT|GPIO_AF12|GPIO_PORTG|GPIO_PIN2)
|
||||
#define GPIO_FSMC_A13 (GPIO_ALT|GPIO_AF12|GPIO_PORTG|GPIO_PIN3)
|
||||
#define GPIO_FSMC_A14 (GPIO_ALT|GPIO_AF12|GPIO_PORTG|GPIO_PIN4)
|
||||
#define GPIO_FSMC_A15 (GPIO_ALT|GPIO_AF12|GPIO_PORTG|GPIO_PIN5)
|
||||
#define GPIO_FSMC_A16 (GPIO_ALT|GPIO_AF12|GPIO_PORTD|GPIO_PIN11)
|
||||
#define GPIO_FSMC_A17 (GPIO_ALT|GPIO_AF12|GPIO_PORTD|GPIO_PIN12)
|
||||
#define GPIO_FSMC_A18 (GPIO_ALT|GPIO_AF12|GPIO_PORTD|GPIO_PIN13)
|
||||
#define GPIO_FSMC_A19 (GPIO_ALT|GPIO_AF12|GPIO_PORTE|GPIO_PIN3)
|
||||
#define GPIO_FSMC_A20 (GPIO_ALT|GPIO_AF12|GPIO_PORTE|GPIO_PIN4)
|
||||
#define GPIO_FSMC_A21 (GPIO_ALT|GPIO_AF12|GPIO_PORTE|GPIO_PIN5)
|
||||
#define GPIO_FSMC_A22 (GPIO_ALT|GPIO_AF12|GPIO_PORTE|GPIO_PIN6)
|
||||
#define GPIO_FSMC_A23 (GPIO_ALT|GPIO_AF12|GPIO_PORTE|GPIO_PIN2)
|
||||
#define GPIO_FSMC_A24 (GPIO_ALT|GPIO_AF12|GPIO_PORTG|GPIO_PIN13)
|
||||
#define GPIO_FSMC_A25 (GPIO_ALT|GPIO_AF12|GPIO_PORTG|GPIO_PIN14)
|
||||
#define GPIO_FSMC_BLN1 (GPIO_ALT|GPIO_AF12|GPIO_PORTE|GPIO_PIN1)
|
||||
#define GPIO_FSMC_CD (GPIO_ALT|GPIO_AF12|GPIO_PORTF|GPIO_PIN9)
|
||||
#define GPIO_FSMC_CLK (GPIO_ALT|GPIO_AF12|GPIO_PORTD|GPIO_PIN3)
|
||||
#define GPIO_FSMC_D0 (GPIO_ALT|GPIO_AF12|GPIO_PORTD|GPIO_PIN14)
|
||||
#define GPIO_FSMC_D1 (GPIO_ALT|GPIO_AF12|GPIO_PORTD|GPIO_PIN15)
|
||||
#define GPIO_FSMC_D2 (GPIO_ALT|GPIO_AF12|GPIO_PORTD|GPIO_PIN0)
|
||||
#define GPIO_FSMC_D3 (GPIO_ALT|GPIO_AF12|GPIO_PORTD|GPIO_PIN1)
|
||||
#define GPIO_FSMC_D4 (GPIO_ALT|GPIO_AF12|GPIO_PORTE|GPIO_PIN7)
|
||||
#define GPIO_FSMC_D5 (GPIO_ALT|GPIO_AF12|GPIO_PORTE|GPIO_PIN8)
|
||||
#define GPIO_FSMC_D6 (GPIO_ALT|GPIO_AF12|GPIO_PORTE|GPIO_PIN9)
|
||||
#define GPIO_FSMC_D7 (GPIO_ALT|GPIO_AF12|GPIO_PORTE|GPIO_PIN10)
|
||||
#define GPIO_FSMC_D8 (GPIO_ALT|GPIO_AF12|GPIO_PORTE|GPIO_PIN11)
|
||||
#define GPIO_FSMC_D9 (GPIO_ALT|GPIO_AF12|GPIO_PORTE|GPIO_PIN12)
|
||||
#define GPIO_FSMC_D10 (GPIO_ALT|GPIO_AF12|GPIO_PORTE|GPIO_PIN13)
|
||||
#define GPIO_FSMC_D11 (GPIO_ALT|GPIO_AF12|GPIO_PORTE|GPIO_PIN14)
|
||||
#define GPIO_FSMC_D12 (GPIO_ALT|GPIO_AF12|GPIO_PORTE|GPIO_PIN15)
|
||||
#define GPIO_FSMC_D13 (GPIO_ALT|GPIO_AF12|GPIO_PORTD|GPIO_PIN8)
|
||||
#define GPIO_FSMC_D14 (GPIO_ALT|GPIO_AF12|GPIO_PORTD|GPIO_PIN9)
|
||||
#define GPIO_FSMC_D15 (GPIO_ALT|GPIO_AF12|GPIO_PORTD|GPIO_PIN10)
|
||||
#define GPIO_FSMC_INT2 (GPIO_ALT|GPIO_AF12|GPIO_PORTG|GPIO_PIN6)
|
||||
#define GPIO_FSMC_INT3 (GPIO_ALT|GPIO_AF12|GPIO_PORTG|GPIO_PIN7)
|
||||
#define GPIO_FSMC_INTR (GPIO_ALT|GPIO_AF12|GPIO_PORTF|GPIO_PIN10)
|
||||
#define GPIO_FSMC_NBL0 (GPIO_ALT|GPIO_AF12|GPIO_PORTE|GPIO_PIN0)
|
||||
#define GPIO_FSMC_NCE2 (GPIO_ALT|GPIO_AF12|GPIO_PORTD|GPIO_PIN7)
|
||||
#define GPIO_FSMC_NCE3 (GPIO_ALT|GPIO_AF12|GPIO_PORTG|GPIO_PIN9)
|
||||
#define GPIO_FSMC_NCE4_1 (GPIO_ALT|GPIO_AF12|GPIO_PORTG|GPIO_PIN10)
|
||||
#define GPIO_FSMC_NCE4_2 (GPIO_ALT|GPIO_AF12|GPIO_PORTG|GPIO_PIN11)
|
||||
#define GPIO_FSMC_NE1 (GPIO_ALT|GPIO_AF12|GPIO_PORTD|GPIO_PIN7)
|
||||
#define GPIO_FSMC_NE2 (GPIO_ALT|GPIO_AF12|GPIO_PORTG|GPIO_PIN9)
|
||||
#define GPIO_FSMC_NE3 (GPIO_ALT|GPIO_AF12|GPIO_PORTG|GPIO_PIN10)
|
||||
#define GPIO_FSMC_NE4 (GPIO_ALT|GPIO_AF12|GPIO_PORTG|GPIO_PIN12)
|
||||
#define GPIO_FSMC_NIORD (GPIO_ALT|GPIO_AF12|GPIO_PORTF|GPIO_PIN6)
|
||||
#define GPIO_FSMC_NIOWR (GPIO_ALT|GPIO_AF12|GPIO_PORTF|GPIO_PIN8)
|
||||
#define GPIO_FSMC_NL (GPIO_ALT|GPIO_AF12|GPIO_PORTB|GPIO_PIN7)
|
||||
#define GPIO_FSMC_NOE (GPIO_ALT|GPIO_AF12|GPIO_PORTD|GPIO_PIN4)
|
||||
#define GPIO_FSMC_NREG (GPIO_ALT|GPIO_AF12|GPIO_PORTF|GPIO_PIN7)
|
||||
#define GPIO_FSMC_NWAIT (GPIO_ALT|GPIO_AF12|GPIO_PORTD|GPIO_PIN6)
|
||||
#define GPIO_FSMC_NWE (GPIO_ALT|GPIO_AF12|GPIO_PORTD|GPIO_PIN5)
|
||||
|
||||
/* I2C */
|
||||
|
||||
#define GPIO_I2C1_SCL_1 (GPIO_ALT|GPIO_AF4|GPIO_SPEED_50MHz|GPIO_OPENDRAIN|GPIO_PORTB|GPIO_PIN6)
|
||||
#define GPIO_I2C1_SCL_2 (GPIO_ALT|GPIO_AF4|GPIO_SPEED_50MHz|GPIO_OPENDRAIN|GPIO_PORTB|GPIO_PIN8)
|
||||
#define GPIO_I2C1_SDA_1 (GPIO_ALT|GPIO_AF4|GPIO_SPEED_50MHz|GPIO_OPENDRAIN|GPIO_PORTB|GPIO_PIN7)
|
||||
#define GPIO_I2C1_SDA_2 (GPIO_ALT|GPIO_AF4|GPIO_SPEED_50MHz|GPIO_OPENDRAIN|GPIO_PORTB|GPIO_PIN9)
|
||||
#define GPIO_I2C1_SMBA (GPIO_ALT|GPIO_AF4|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN5)
|
||||
|
||||
#define GPIO_I2C2_SCL_1 (GPIO_ALT|GPIO_AF4|GPIO_SPEED_50MHz|GPIO_OPENDRAIN|GPIO_PORTB|GPIO_PIN10)
|
||||
#define GPIO_I2C2_SCL_2 (GPIO_ALT|GPIO_AF4|GPIO_SPEED_50MHz|GPIO_OPENDRAIN|GPIO_PORTF|GPIO_PIN1)
|
||||
#define GPIO_I2C2_SCL_3 (GPIO_ALT|GPIO_AF4|GPIO_SPEED_50MHz|GPIO_OPENDRAIN|GPIO_PORTH|GPIO_PIN4)
|
||||
#define GPIO_I2C2_SDA_1 (GPIO_ALT|GPIO_AF4|GPIO_SPEED_50MHz|GPIO_OPENDRAIN|GPIO_PORTB|GPIO_PIN11)
|
||||
#define GPIO_I2C2_SDA_2 (GPIO_ALT|GPIO_AF4|GPIO_SPEED_50MHz|GPIO_OPENDRAIN|GPIO_PORTF|GPIO_PIN0)
|
||||
#define GPIO_I2C2_SDA_3 (GPIO_ALT|GPIO_AF4|GPIO_SPEED_50MHz|GPIO_OPENDRAIN|GPIO_PORTH|GPIO_PIN5)
|
||||
#define GPIO_I2C2_SMBA_1 (GPIO_ALT|GPIO_AF4|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN12)
|
||||
#define GPIO_I2C2_SMBA_2 (GPIO_ALT|GPIO_AF4|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTF|GPIO_PIN2)
|
||||
#define GPIO_I2C2_SMBA_3 (GPIO_ALT|GPIO_AF4|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTH|GPIO_PIN6)
|
||||
|
||||
#define GPIO_I2C3_SCL_1 (GPIO_ALT|GPIO_AF4|GPIO_SPEED_50MHz|GPIO_OPENDRAIN|GPIO_PORTA|GPIO_PIN8)
|
||||
#define GPIO_I2C3_SCL_2 (GPIO_ALT|GPIO_AF4|GPIO_SPEED_50MHz|GPIO_OPENDRAIN|GPIO_PORTH|GPIO_PIN7)
|
||||
#define GPIO_I2C3_SDA_1 (GPIO_ALT|GPIO_AF4|GPIO_SPEED_50MHz|GPIO_OPENDRAIN|GPIO_PORTC|GPIO_PIN9)
|
||||
#define GPIO_I2C3_SDA_2 (GPIO_ALT|GPIO_AF4|GPIO_SPEED_50MHz|GPIO_OPENDRAIN|GPIO_PORTH|GPIO_PIN8)
|
||||
#define GPIO_I2C3_SMBA_1 (GPIO_ALT|GPIO_AF4|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN9)
|
||||
#define GPIO_I2C3_SMBA_2 (GPIO_ALT|GPIO_AF4|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTH|GPIO_PIN9)
|
||||
|
||||
/* I2S */
|
||||
|
||||
#define GPIO_I2S2_CK_1 (GPIO_ALT|GPIO_AF5|GPIO_PORTB|GPIO_PIN10)
|
||||
#define GPIO_I2S2_CK_2 (GPIO_ALT|GPIO_AF5|GPIO_PORTB|GPIO_PIN13)
|
||||
#define GPIO_I2S2_CK_3 (GPIO_ALT|GPIO_AF5|GPIO_PORTI|GPIO_PIN1)
|
||||
#define GPIO_I2S2_MCK (GPIO_ALT|GPIO_AF5|GPIO_PORTC|GPIO_PIN6)
|
||||
#define GPIO_I2S2_SD_1 (GPIO_ALT|GPIO_AF5|GPIO_PORTC|GPIO_PIN15)
|
||||
#define GPIO_I2S2_SD_2 (GPIO_ALT|GPIO_AF5|GPIO_PORTC|GPIO_PIN3)
|
||||
#define GPIO_I2S2_SD_3 (GPIO_ALT|GPIO_AF5|GPIO_PORTI|GPIO_PIN3)
|
||||
#define GPIO_I2S2_WS_1 (GPIO_ALT|GPIO_AF5|GPIO_PORTB|GPIO_PIN12)
|
||||
#define GPIO_I2S2_WS_2 (GPIO_ALT|GPIO_AF5|GPIO_PORTB|GPIO_PIN6)
|
||||
#define GPIO_I2S2_WS_3 (GPIO_ALT|GPIO_AF5|GPIO_PORTB|GPIO_PIN9)
|
||||
#define GPIO_I2S2_WS_4 (GPIO_ALT|GPIO_AF5|GPIO_PORTI|GPIO_PIN0)
|
||||
|
||||
#define GPIO_I2S2EXT_SD_1 (GPIO_ALT|GPIO_AF6|GPIO_PORTB|GPIO_PIN14)
|
||||
#define GPIO_I2S2EXT_SD_2 (GPIO_ALT|GPIO_AF6|GPIO_PORTC|GPIO_PIN2)
|
||||
#define GPIO_I2S2EXT_SD_3 (GPIO_ALT|GPIO_AF6|GPIO_PORTI|GPIO_PIN2)
|
||||
|
||||
#define GPIO_I2S3_CK_1 (GPIO_ALT|GPIO_AF6|GPIO_PORTB|GPIO_PIN3)
|
||||
#define GPIO_I2S3_CK_2 (GPIO_ALT|GPIO_AF6|GPIO_PORTC|GPIO_PIN10)
|
||||
#define GPIO_I2S3_MCK (GPIO_ALT|GPIO_AF6|GPIO_PORTC|GPIO_PIN7)
|
||||
#define GPIO_I2S3_SD_1 (GPIO_ALT|GPIO_AF6|GPIO_PORTB|GPIO_PIN5)
|
||||
#define GPIO_I2S3_SD_2 (GPIO_ALT|GPIO_AF6|GPIO_PORTC|GPIO_PIN12)
|
||||
#define GPIO_I2S3_WS_1 (GPIO_ALT|GPIO_AF6|GPIO_PORTA|GPIO_PIN4)
|
||||
#define GPIO_I2S3_WS_2 (GPIO_ALT|GPIO_AF6|GPIO_PORTA|GPIO_PIN15)
|
||||
|
||||
#define GPIO_I2S3EXT_SD_1 (GPIO_ALT|GPIO_AF6|GPIO_PORTC|GPIO_PIN11)
|
||||
#define GPIO_I2S3EXT_SD_2 (GPIO_ALT|GPIO_AF7|GPIO_PORTB|GPIO_PIN4)
|
||||
|
||||
#define GPIO_I2S_CKIN (GPIO_ALT|GPIO_AF5|GPIO_PORTC|GPIO_PIN9)
|
||||
|
||||
/* JTAG */
|
||||
|
||||
#define GPIO_JTCK_SWCLK (GPIO_ALT|GPIO_AF0|GPIO_PORTA|GPIO_PIN14)
|
||||
#define GPIO_JTDI (GPIO_ALT|GPIO_AF0|GPIO_PORTA|GPIO_PIN15)
|
||||
#define GPIO_JTDO (GPIO_ALT|GPIO_AF0|GPIO_PORTB|GPIO_PIN3)
|
||||
#define GPIO_JTMS_SWDIO (GPIO_ALT|GPIO_AF0|GPIO_PORTA|GPIO_PIN13)
|
||||
#define GPIO_JTRST (GPIO_ALT|GPIO_AF0|GPIO_PORTB|GPIO_PIN4)
|
||||
|
||||
/* OTG FS/HS */
|
||||
|
||||
#define GPIO_OTGFS_DM (GPIO_ALT|GPIO_AF10|GPIO_PORTA|GPIO_PIN11)
|
||||
#define GPIO_OTGFS_DP (GPIO_ALT|GPIO_AF10|GPIO_PORTA|GPIO_PIN12)
|
||||
#define GPIO_OTGFS_ID (GPIO_ALT|GPIO_AF10|GPIO_PORTA|GPIO_PIN10)
|
||||
#define GPIO_OTGFS_SCL (GPIO_ALT|GPIO_AF10|GPIO_PORTB|GPIO_PIN8)
|
||||
#define GPIO_OTGFS_SDA (GPIO_ALT|GPIO_AF10|GPIO_PORTB|GPIO_PIN9)
|
||||
#define GPIO_OTGFS_SOF (GPIO_ALT|GPIO_AF10|GPIO_PORTA|GPIO_PIN8)
|
||||
|
||||
#define GPIO_OTGHS_DM (GPIO_ALT|GPIO_AF12|GPIO_PORTB|GPIO_PIN14)
|
||||
#define GPIO_OTGHS_DP (GPIO_ALT|GPIO_AF12|GPIO_PORTC|GPIO_PIN15)
|
||||
#define GPIO_OTGHS_ID (GPIO_ALT|GPIO_AF12|GPIO_PORTB|GPIO_PIN12)
|
||||
#define GPIO_OTGHS_INTN_1 (GPIO_ALT|GPIO_AF12|GPIO_PORTB|GPIO_PIN1)
|
||||
#define GPIO_OTGFS_INTN_2 (GPIO_ALT|GPIO_AF10|GPIO_PORTB|GPIO_PIN6)
|
||||
#define GPIO_OTGHS_SCL (GPIO_ALT|GPIO_AF12|GPIO_PORTB|GPIO_PIN10)
|
||||
#define GPIO_OTGHS_SDA (GPIO_ALT|GPIO_AF12|GPIO_PORTB|GPIO_PIN11)
|
||||
#define GPIO_OTGHS_SOF (GPIO_ALT|GPIO_AF12|GPIO_PORTA|GPIO_PIN4)
|
||||
#define GPIO_OTGHS_ULPI_CK (GPIO_ALT|GPIO_AF10|GPIO_PORTA|GPIO_PIN5)
|
||||
#define GPIO_OTGHS_ULPI_D0 (GPIO_ALT|GPIO_AF10|GPIO_PORTA|GPIO_PIN3)
|
||||
#define GPIO_OTGHS_ULPI_D1 (GPIO_ALT|GPIO_AF10|GPIO_PORTB|GPIO_PIN0)
|
||||
#define GPIO_OTGHS_ULPI_D2 (GPIO_ALT|GPIO_AF10|GPIO_PORTB|GPIO_PIN1)
|
||||
#define GPIO_OTGHS_ULPI_D3 (GPIO_ALT|GPIO_AF10|GPIO_PORTB|GPIO_PIN10)
|
||||
#define GPIO_OTGHS_ULPI_D4 (GPIO_ALT|GPIO_AF10|GPIO_PORTB|GPIO_PIN11)
|
||||
#define GPIO_OTGHS_ULPI_D5 (GPIO_ALT|GPIO_AF10|GPIO_PORTB|GPIO_PIN12)
|
||||
#define GPIO_OTGHS_ULPI_D6 (GPIO_ALT|GPIO_AF10|GPIO_PORTB|GPIO_PIN13)
|
||||
#define GPIO_OTGHS_ULPI_D7 (GPIO_ALT|GPIO_AF10|GPIO_PORTB|GPIO_PIN5)
|
||||
#define GPIO_OTGHS_ULPI_DIR_1 (GPIO_ALT|GPIO_AF10|GPIO_PORTC|GPIO_PIN2)
|
||||
#define GPIO_OTGHS_ULPI_DIR_2 (GPIO_ALT|GPIO_AF10|GPIO_PORTI|GPIO_PIN11)
|
||||
#define GPIO_OTGHS_ULPI_NXT_1 (GPIO_ALT|GPIO_AF10|GPIO_PORTC|GPIO_PIN3)
|
||||
#define GPIO_OTGHS_ULPI_NXT_2 (GPIO_ALT|GPIO_AF10|GPIO_PORTH|GPIO_PIN4)
|
||||
#define GPIO_OTGHS_ULPI_STP (GPIO_ALT|GPIO_AF10|GPIO_PORTC|GPIO_PIN0)
|
||||
|
||||
/* RTC */
|
||||
|
||||
#define GPIO_RTC_50HZ (GPIO_ALT|GPIO_AF0|GPIO_PORTC|GPIO_PIN15)
|
||||
|
||||
/* SDIO */
|
||||
|
||||
#define GPIO_SDIO_CK (GPIO_ALT|GPIO_AF12|GPIO_PORTC|GPIO_PIN12)
|
||||
#define GPIO_SDIO_CMD (GPIO_ALT|GPIO_AF12|GPIO_PORTD|GPIO_PIN2)
|
||||
#define GPIO_SDIO_D0 (GPIO_ALT|GPIO_AF12|GPIO_PORTC|GPIO_PIN8)
|
||||
#define GPIO_SDIO_D1 (GPIO_ALT|GPIO_AF12|GPIO_PORTC|GPIO_PIN9)
|
||||
#define GPIO_SDIO_D2 (GPIO_ALT|GPIO_AF12|GPIO_PORTC|GPIO_PIN10)
|
||||
#define GPIO_SDIO_D3 (GPIO_ALT|GPIO_AF12|GPIO_PORTC|GPIO_PIN11)
|
||||
#define GPIO_SDIO_D4 (GPIO_ALT|GPIO_AF12|GPIO_PORTB|GPIO_PIN8)
|
||||
#define GPIO_SDIO_D5 (GPIO_ALT|GPIO_AF12|GPIO_PORTB|GPIO_PIN9)
|
||||
#define GPIO_SDIO_D6 (GPIO_ALT|GPIO_AF12|GPIO_PORTC|GPIO_PIN6)
|
||||
#define GPIO_SDIO_D7 (GPIO_ALT|GPIO_AF12|GPIO_PORTC|GPIO_PIN7)
|
||||
|
||||
/* SPI */
|
||||
|
||||
#define GPIO_SPI1_MISO_1 (GPIO_ALT|GPIO_AF5|GPIO_PORTA|GPIO_PIN6)
|
||||
#define GPIO_SPI1_MISO_2 (GPIO_ALT|GPIO_AF5|GPIO_PORTB|GPIO_PIN4)
|
||||
#define GPIO_SPI1_MOSI_1 (GPIO_ALT|GPIO_AF5|GPIO_PORTA|GPIO_PIN7)
|
||||
#define GPIO_SPI1_MOSI_2 (GPIO_ALT|GPIO_AF5|GPIO_PORTB|GPIO_PIN5)
|
||||
#define GPIO_SPI1_NSS_1 (GPIO_ALT|GPIO_AF5|GPIO_PORTA|GPIO_PIN15)
|
||||
#define GPIO_SPI1_NSS_2 (GPIO_ALT|GPIO_AF5|GPIO_PORTA|GPIO_PIN4)
|
||||
#define GPIO_SPI1_SCK_1 (GPIO_ALT|GPIO_AF5|GPIO_PORTA|GPIO_PIN5)
|
||||
#define GPIO_SPI1_SCK_2 (GPIO_ALT|GPIO_AF5|GPIO_PORTB|GPIO_PIN3)
|
||||
|
||||
#define GPIO_SPI2_MISO_1 (GPIO_ALT|GPIO_AF5|GPIO_PORTB|GPIO_PIN14)
|
||||
#define GPIO_SPI2_MISO_2 (GPIO_ALT|GPIO_AF5|GPIO_PORTC|GPIO_PIN2)
|
||||
#define GPIO_SPI2_MISO_3 (GPIO_ALT|GPIO_AF5|GPIO_PORTI|GPIO_PIN2)
|
||||
#define GPIO_SPI2_MOSI_1 (GPIO_ALT|GPIO_AF5|GPIO_PORTC|GPIO_PIN15)
|
||||
#define GPIO_SPI2_MOSI_2 (GPIO_ALT|GPIO_AF5|GPIO_PORTC|GPIO_PIN3)
|
||||
#define GPIO_SPI2_MOSI_3 (GPIO_ALT|GPIO_AF5|GPIO_PORTI|GPIO_PIN3)
|
||||
#define GPIO_SPI2_NSS_1 (GPIO_ALT|GPIO_AF5|GPIO_PORTB|GPIO_PIN12)
|
||||
#define GPIO_SPI2_NSS_2 (GPIO_ALT|GPIO_AF5|GPIO_PORTB|GPIO_PIN9)
|
||||
#define GPIO_SPI2_NSS_3 (GPIO_ALT|GPIO_AF5|GPIO_PORTI|GPIO_PIN0)
|
||||
#define GPIO_SPI2_SCK_1 (GPIO_ALT|GPIO_AF5|GPIO_PORTB|GPIO_PIN10)
|
||||
#define GPIO_SPI2_SCK_2 (GPIO_ALT|GPIO_AF5|GPIO_PORTB|GPIO_PIN13)
|
||||
#define GPIO_SPI2_SCK_3 (GPIO_ALT|GPIO_AF5|GPIO_PORTI|GPIO_PIN1)
|
||||
|
||||
#define GPIO_SPI3_MISO_1 (GPIO_ALT|GPIO_AF6|GPIO_PORTB|GPIO_PIN4)
|
||||
#define GPIO_SPI3_MISO_2 (GPIO_ALT|GPIO_AF6|GPIO_PORTC|GPIO_PIN11)
|
||||
#define GPIO_SPI3_MOSI_1 (GPIO_ALT|GPIO_AF6|GPIO_PORTB|GPIO_PIN5)
|
||||
#define GPIO_SPI3_MOSI_2 (GPIO_ALT|GPIO_AF6|GPIO_PORTC|GPIO_PIN12)
|
||||
#define GPIO_SPI3_NSS_1 (GPIO_ALT|GPIO_AF6|GPIO_PORTA|GPIO_PIN15)
|
||||
#define GPIO_SPI3_NSS_2 (GPIO_ALT|GPIO_AF6|GPIO_PORTA|GPIO_PIN4)
|
||||
#define GPIO_SPI3_SCK_1 (GPIO_ALT|GPIO_AF6|GPIO_PORTB|GPIO_PIN3)
|
||||
#define GPIO_SPI3_SCK_2 (GPIO_ALT|GPIO_AF6|GPIO_PORTC|GPIO_PIN10)
|
||||
|
||||
/* Timers */
|
||||
|
||||
#define GPIO_TIM1_BKIN_1 (GPIO_ALT|GPIO_AF1|GPIO_PORTA|GPIO_PIN6)
|
||||
#define GPIO_TIM1_BKIN_2 (GPIO_ALT|GPIO_AF1|GPIO_PORTB|GPIO_PIN12)
|
||||
#define GPIO_TIM1_BKIN_3 (GPIO_ALT|GPIO_AF1|GPIO_PORTE|GPIO_PIN15)
|
||||
#define GPIO_TIM1_CH1N_1 (GPIO_ALT|GPIO_AF1|GPIO_PORTA|GPIO_PIN7)
|
||||
#define GPIO_TIM1_CH1N_2 (GPIO_ALT|GPIO_AF1|GPIO_PORTB|GPIO_PIN13)
|
||||
#define GPIO_TIM1_CH1N_3 (GPIO_ALT|GPIO_AF1|GPIO_PORTE|GPIO_PIN8)
|
||||
#define GPIO_TIM1_CH1OUT_1 (GPIO_ALT|GPIO_AF1|GPIO_PORTA|GPIO_PIN8)
|
||||
#define GPIO_TIM1_CH1OUT_2 (GPIO_ALT|GPIO_AF1|GPIO_PORTE|GPIO_PIN9)
|
||||
#define GPIO_TIM1_CH2N_1 (GPIO_ALT|GPIO_AF1|GPIO_PORTB|GPIO_PIN0)
|
||||
#define GPIO_TIM1_CH2N_2 (GPIO_ALT|GPIO_AF1|GPIO_PORTB|GPIO_PIN14)
|
||||
#define GPIO_TIM1_CH2N_3 (GPIO_ALT|GPIO_AF1|GPIO_PORTE|GPIO_PIN10)
|
||||
#define GPIO_TIM1_CH2OUT_1 (GPIO_ALT|GPIO_AF1|GPIO_PORTA|GPIO_PIN9)
|
||||
#define GPIO_TIM1_CH2OUT_2 (GPIO_ALT|GPIO_AF1|GPIO_PORTE|GPIO_PIN11)
|
||||
#define GPIO_TIM1_CH3N_1 (GPIO_ALT|GPIO_AF1|GPIO_PORTB|GPIO_PIN1)
|
||||
#define GPIO_TIM1_CH3N_2 (GPIO_ALT|GPIO_AF1|GPIO_PORTC|GPIO_PIN15)
|
||||
#define GPIO_TIM1_CH3N_3 (GPIO_ALT|GPIO_AF1|GPIO_PORTE|GPIO_PIN12)
|
||||
#define GPIO_TIM1_CH3OUT_1 (GPIO_ALT|GPIO_AF1|GPIO_PORTA|GPIO_PIN10)
|
||||
#define GPIO_TIM1_CH3OUT_2 (GPIO_ALT|GPIO_AF1|GPIO_PORTE|GPIO_PIN13)
|
||||
#define GPIO_TIM1_CH4OUT_1 (GPIO_ALT|GPIO_AF1|GPIO_PORTA|GPIO_PIN11)
|
||||
#define GPIO_TIM1_CH4OUT_2 (GPIO_ALT|GPIO_AF1|GPIO_PORTE|GPIO_PIN14)
|
||||
#define GPIO_TIM1_ETR_1 (GPIO_ALT|GPIO_AF1|GPIO_PORTA|GPIO_PIN12)
|
||||
#define GPIO_TIM1_ETR_2 (GPIO_ALT|GPIO_AF1|GPIO_PORTE|GPIO_PIN7)
|
||||
|
||||
#define GPIO_TIM2_CH1OUT_1 (GPIO_ALT|GPIO_AF1|GPIO_PORTA|GPIO_PIN0)
|
||||
#define GPIO_TIM2_CH1OUT_2 (GPIO_ALT|GPIO_AF1|GPIO_PORTA|GPIO_PIN15)
|
||||
#define GPIO_TIM2_CH1OUT_3 (GPIO_ALT|GPIO_AF1|GPIO_PORTA|GPIO_PIN5)
|
||||
#define GPIO_TIM2_CH2OUT_1 (GPIO_ALT|GPIO_AF1|GPIO_PORTA|GPIO_PIN1)
|
||||
#define GPIO_TIM2_CH2OUT_2 (GPIO_ALT|GPIO_AF1|GPIO_PORTB|GPIO_PIN3)
|
||||
#define GPIO_TIM2_CH3OUT_1 (GPIO_ALT|GPIO_AF1|GPIO_PORTA|GPIO_PIN2)
|
||||
#define GPIO_TIM2_CH3OUT_2 (GPIO_ALT|GPIO_AF1|GPIO_PORTB|GPIO_PIN10)
|
||||
#define GPIO_TIM2_CH4OUT_1 (GPIO_ALT|GPIO_AF1|GPIO_PORTA|GPIO_PIN3)
|
||||
#define GPIO_TIM2_CH4OUT_2 (GPIO_ALT|GPIO_AF1|GPIO_PORTB|GPIO_PIN11)
|
||||
#define GPIO_TIM2_ETR_1 (GPIO_ALT|GPIO_AF1|GPIO_PORTA|GPIO_PIN0)
|
||||
#define GPIO_TIM2_ETR_2 (GPIO_ALT|GPIO_AF1|GPIO_PORTA|GPIO_PIN15)
|
||||
#define GPIO_TIM2_ETR_3 (GPIO_ALT|GPIO_AF1|GPIO_PORTA|GPIO_PIN5)
|
||||
|
||||
#define GPIO_TIM3_CH1OUT_1 (GPIO_ALT|GPIO_AF2|GPIO_PORTA|GPIO_PIN6)
|
||||
#define GPIO_TIM3_CH1OUT_2 (GPIO_ALT|GPIO_AF2|GPIO_PORTB|GPIO_PIN4)
|
||||
#define GPIO_TIM3_CH1OUT_3 (GPIO_ALT|GPIO_AF2|GPIO_PORTC|GPIO_PIN6)
|
||||
#define GPIO_TIM3_CH2OUT_1 (GPIO_ALT|GPIO_AF2|GPIO_PORTA|GPIO_PIN7)
|
||||
#define GPIO_TIM3_CH2OUT_2 (GPIO_ALT|GPIO_AF2|GPIO_PORTB|GPIO_PIN5)
|
||||
#define GPIO_TIM3_CH2OUT_3 (GPIO_ALT|GPIO_AF2|GPIO_PORTC|GPIO_PIN7)
|
||||
#define GPIO_TIM3_CH3OUT_1 (GPIO_ALT|GPIO_AF2|GPIO_PORTB|GPIO_PIN0)
|
||||
#define GPIO_TIM3_CH3OUT_2 (GPIO_ALT|GPIO_AF2|GPIO_PORTC|GPIO_PIN8)
|
||||
#define GPIO_TIM3_CH4OUT_1 (GPIO_ALT|GPIO_AF2|GPIO_PORTB|GPIO_PIN1)
|
||||
#define GPIO_TIM3_CH4OUT_3 (GPIO_ALT|GPIO_AF2|GPIO_PORTC|GPIO_PIN9)
|
||||
#define GPIO_TIM3_ETR (GPIO_ALT|GPIO_AF2|GPIO_PORTD|GPIO_PIN2)
|
||||
|
||||
#define GPIO_TIM4_CH1OUT_1 (GPIO_ALT|GPIO_AF2|GPIO_PORTB|GPIO_PIN6)
|
||||
#define GPIO_TIM4_CH1OUT_2 (GPIO_ALT|GPIO_AF2|GPIO_PORTD|GPIO_PIN12)
|
||||
#define GPIO_TIM4_CH2OUT_1 (GPIO_ALT|GPIO_AF2|GPIO_PORTB|GPIO_PIN7)
|
||||
#define GPIO_TIM4_CH2OUT_2 (GPIO_ALT|GPIO_AF2|GPIO_PORTD|GPIO_PIN13)
|
||||
#define GPIO_TIM4_CH3OUT_1 (GPIO_ALT|GPIO_AF2|GPIO_PORTB|GPIO_PIN8)
|
||||
#define GPIO_TIM4_CH3OUT_2 (GPIO_ALT|GPIO_AF2|GPIO_PORTD|GPIO_PIN14)
|
||||
#define GPIO_TIM4_CH4OUT_1 (GPIO_ALT|GPIO_AF2|GPIO_PORTB|GPIO_PIN9)
|
||||
#define GPIO_TIM4_CH4OUT_3 (GPIO_ALT|GPIO_AF2|GPIO_PORTD|GPIO_PIN15)
|
||||
#define GPIO_TIM4_ETR (GPIO_ALT|GPIO_AF2|GPIO_PORTE|GPIO_PIN0)
|
||||
|
||||
#define GPIO_TIM5_CH1OUT_1 (GPIO_ALT|GPIO_AF2|GPIO_PORTA|GPIO_PIN0)
|
||||
#define GPIO_TIM5_CH1OUT_2 (GPIO_ALT|GPIO_AF2|GPIO_PORTH|GPIO_PIN10)
|
||||
#define GPIO_TIM5_CH2OUT_1 (GPIO_ALT|GPIO_AF2|GPIO_PORTA|GPIO_PIN1)
|
||||
#define GPIO_TIM5_CH2OUT_2 (GPIO_ALT|GPIO_AF2|GPIO_PORTH|GPIO_PIN11)
|
||||
#define GPIO_TIM5_CH3OUT_1 (GPIO_ALT|GPIO_AF2|GPIO_PORTA|GPIO_PIN2)
|
||||
#define GPIO_TIM5_CH3OUT_2 (GPIO_ALT|GPIO_AF2|GPIO_PORTH|GPIO_PIN12)
|
||||
#define GPIO_TIM5_CH4OUT_1 (GPIO_ALT|GPIO_AF2|GPIO_PORTA|GPIO_PIN3)
|
||||
#define GPIO_TIM5_CH4OUT_2 (GPIO_ALT|GPIO_AF2|GPIO_PORTI|GPIO_PIN0)
|
||||
#define GPIO_TIM5_ETR (GPIO_ALT|GPIO_AF2|GPIO_PORTH|GPIO_PIN10)
|
||||
|
||||
#define GPIO_TIM8_BKIN_1 (GPIO_ALT|GPIO_AF3|GPIO_PORTA|GPIO_PIN6)
|
||||
#define GPIO_TIM8_BKIN_2 (GPIO_ALT|GPIO_AF3|GPIO_PORTI|GPIO_PIN4)
|
||||
#define GPIO_TIM8_CH1N_1 (GPIO_ALT|GPIO_AF3|GPIO_PORTA|GPIO_PIN5)
|
||||
#define GPIO_TIM8_CH1N_2 (GPIO_ALT|GPIO_AF3|GPIO_PORTA|GPIO_PIN7)
|
||||
#define GPIO_TIM8_CH1N_3 (GPIO_ALT|GPIO_AF3|GPIO_PORTH|GPIO_PIN13)
|
||||
#define GPIO_TIM8_CH1OUT_1 (GPIO_ALT|GPIO_AF3|GPIO_PORTC|GPIO_PIN6)
|
||||
#define GPIO_TIM8_CH1OUT_2 (GPIO_ALT|GPIO_AF3|GPIO_PORTI|GPIO_PIN5)
|
||||
#define GPIO_TIM8_CH2OUT_1 (GPIO_ALT|GPIO_AF3|GPIO_PORTC|GPIO_PIN7)
|
||||
#define GPIO_TIM8_CH2OUT_2 (GPIO_ALT|GPIO_AF3|GPIO_PORTI|GPIO_PIN6)
|
||||
#define GPIO_TIM8_CH2N_1 (GPIO_ALT|GPIO_AF3|GPIO_PORTB|GPIO_PIN0)
|
||||
#define GPIO_TIM8_CH2N_2 (GPIO_ALT|GPIO_AF3|GPIO_PORTB|GPIO_PIN14)
|
||||
#define GPIO_TIM8_CH2N_3 (GPIO_ALT|GPIO_AF3|GPIO_PORTH|GPIO_PIN14)
|
||||
#define GPIO_TIM8_CH3N_1 (GPIO_ALT|GPIO_AF3|GPIO_PORTB|GPIO_PIN1)
|
||||
#define GPIO_TIM8_CH3N_2 (GPIO_ALT|GPIO_AF3|GPIO_PORTC|GPIO_PIN15)
|
||||
#define GPIO_TIM8_CH3N_3 (GPIO_ALT|GPIO_AF3|GPIO_PORTH|GPIO_PIN15)
|
||||
#define GPIO_TIM8_CH3OUT_1 (GPIO_ALT|GPIO_AF3|GPIO_PORTC|GPIO_PIN8)
|
||||
#define GPIO_TIM8_CH3OUT_2 (GPIO_ALT|GPIO_AF3|GPIO_PORTI|GPIO_PIN7)
|
||||
#define GPIO_TIM8_CH4OUT_1 (GPIO_ALT|GPIO_AF3|GPIO_PORTC|GPIO_PIN9)
|
||||
#define GPIO_TIM8_CH4OUT_2 (GPIO_ALT|GPIO_AF3|GPIO_PORTI|GPIO_PIN2)
|
||||
#define GPIO_TIM8_ETR_1 (GPIO_ALT|GPIO_AF3|GPIO_PORTA|GPIO_PIN0)
|
||||
#define GPIO_TIM8_ETR_2 (GPIO_ALT|GPIO_AF3|GPIO_PORTI|GPIO_PIN3)
|
||||
|
||||
#define GPIO_TIM9_CH1OUT_1 (GPIO_ALT|GPIO_AF3|GPIO_PORTA|GPIO_PIN2)
|
||||
#define GPIO_TIM9_CH1OUT_2 (GPIO_ALT|GPIO_AF3|GPIO_PORTE|GPIO_PIN5)
|
||||
#define GPIO_TIM9_CH2OUT_1 (GPIO_ALT|GPIO_AF3|GPIO_PORTA|GPIO_PIN3)
|
||||
#define GPIO_TIM9_CH2OUT_2 (GPIO_ALT|GPIO_AF3|GPIO_PORTE|GPIO_PIN6)
|
||||
|
||||
#define GPIO_TIM10_CH1OUT_1 (GPIO_ALT|GPIO_AF3|GPIO_PORTB|GPIO_PIN8)
|
||||
#define GPIO_TIM10_CH1OUT_2 (GPIO_ALT|GPIO_AF3|GPIO_PORTF|GPIO_PIN6)
|
||||
|
||||
#define GPIO_TIM11_CH1OUT_1 (GPIO_ALT|GPIO_AF3|GPIO_PORTB|GPIO_PIN9)
|
||||
#define GPIO_TIM11_CH1OUT_2 (GPIO_ALT|GPIO_AF3|GPIO_PORTF|GPIO_PIN7)
|
||||
|
||||
#define GPIO_TIM12_CH1OUT_1 (GPIO_ALT|GPIO_AF8|GPIO_PORTH|GPIO_PIN6)
|
||||
#define GPIO_TIM12_CH1OUT_2 (GPIO_ALT|GPIO_AF9|GPIO_PORTB|GPIO_PIN14)
|
||||
#define GPIO_TIM12_CH2OUT_1 (GPIO_ALT|GPIO_AF9|GPIO_PORTC|GPIO_PIN15)
|
||||
#define GPIO_TIM12_CH2OUT_2 (GPIO_ALT|GPIO_AF9|GPIO_PORTH|GPIO_PIN9)
|
||||
|
||||
#define GPIO_TIM13_CH1OUT_1 (GPIO_ALT|GPIO_AF9|GPIO_PORTA|GPIO_PIN6)
|
||||
#define GPIO_TIM13_CH1OUT_2 (GPIO_ALT|GPIO_AF9|GPIO_PORTF|GPIO_PIN8)
|
||||
|
||||
#define GPIO_TIM14_CH1OUT_1 (GPIO_ALT|GPIO_AF9|GPIO_PORTA|GPIO_PIN7)
|
||||
#define GPIO_TIM14_CH1OUT_2 (GPIO_ALT|GPIO_AF9|GPIO_PORTF|GPIO_PIN9)
|
||||
|
||||
/* Trace */
|
||||
|
||||
#define GPIO_TRACECLK (GPIO_ALT|GPIO_AF0|GPIO_PORTE|GPIO_PIN2)
|
||||
#define GPIO_TRACED0 (GPIO_ALT|GPIO_AF0|GPIO_PORTE|GPIO_PIN3)
|
||||
#define GPIO_TRACED1 (GPIO_ALT|GPIO_AF0|GPIO_PORTE|GPIO_PIN4)
|
||||
#define GPIO_TRACED2 (GPIO_ALT|GPIO_AF0|GPIO_PORTE|GPIO_PIN5)
|
||||
#define GPIO_TRACED3 (GPIO_ALT|GPIO_AF0|GPIO_PORTE|GPIO_PIN6)
|
||||
#define GPIO_TRACESWO (GPIO_ALT|GPIO_AF0|GPIO_PORTB|GPIO_PIN3)
|
||||
|
||||
/* UARTs/USARTs */
|
||||
|
||||
#define GPIO_USART1_CK (GPIO_ALT|GPIO_AF7|GPIO_PORTA|GPIO_PIN8)
|
||||
#define GPIO_USART1_CTS (GPIO_ALT|GPIO_AF7|GPIO_PORTA|GPIO_PIN11)
|
||||
#define GPIO_USART1_RTS (GPIO_ALT|GPIO_AF7|GPIO_PORTA|GPIO_PIN12)
|
||||
#define GPIO_USART1_RX_1 (GPIO_ALT|GPIO_AF7|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN10)
|
||||
#define GPIO_USART1_RX_2 (GPIO_ALT|GPIO_AF7|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN7)
|
||||
#define GPIO_USART1_TX_1 (GPIO_ALT|GPIO_AF7|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN9)
|
||||
#define GPIO_USART1_TX_2 (GPIO_ALT|GPIO_AF7|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN6)
|
||||
|
||||
#define GPIO_USART2_CK_1 (GPIO_ALT|GPIO_AF7|GPIO_PORTA|GPIO_PIN4)
|
||||
#define GPIO_USART2_CK_2 (GPIO_ALT|GPIO_AF7|GPIO_PORTD|GPIO_PIN7)
|
||||
#define GPIO_USART2_CTS_1 (GPIO_ALT|GPIO_AF7|GPIO_PORTA|GPIO_PIN0)
|
||||
#define GPIO_USART2_CTS_2 (GPIO_ALT|GPIO_AF7|GPIO_PORTD|GPIO_PIN3)
|
||||
#define GPIO_USART2_RTS_1 (GPIO_ALT|GPIO_AF7|GPIO_PORTA|GPIO_PIN1)
|
||||
#define GPIO_USART2_RTS_2 (GPIO_ALT|GPIO_AF7|GPIO_PORTD|GPIO_PIN4)
|
||||
#define GPIO_USART2_RX_1 (GPIO_ALT|GPIO_AF7|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN3)
|
||||
#define GPIO_USART2_RX_2 (GPIO_ALT|GPIO_AF7|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTD|GPIO_PIN6)
|
||||
#define GPIO_USART2_TX_1 (GPIO_ALT|GPIO_AF7|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN2)
|
||||
#define GPIO_USART2_TX_2 (GPIO_ALT|GPIO_AF7|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTD|GPIO_PIN5)
|
||||
|
||||
#define GPIO_USART3_CK_1 (GPIO_ALT|GPIO_AF7|GPIO_PORTB|GPIO_PIN12)
|
||||
#define GPIO_USART3_CK_2 (GPIO_ALT|GPIO_AF7|GPIO_PORTC|GPIO_PIN12)
|
||||
#define GPIO_USART3_CK_3 (GPIO_ALT|GPIO_AF7|GPIO_PORTD|GPIO_PIN10)
|
||||
#define GPIO_USART3_CTS_1 (GPIO_ALT|GPIO_AF7|GPIO_PORTB|GPIO_PIN13)
|
||||
#define GPIO_USART3_CTS_2 (GPIO_ALT|GPIO_AF7|GPIO_PORTD|GPIO_PIN11)
|
||||
#define GPIO_USART3_RTS_1 (GPIO_ALT|GPIO_AF7|GPIO_PORTB|GPIO_PIN14)
|
||||
#define GPIO_USART3_RTS_2 (GPIO_ALT|GPIO_AF7|GPIO_PORTD|GPIO_PIN12)
|
||||
#define GPIO_USART3_RX_1 (GPIO_ALT|GPIO_AF7|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN11)
|
||||
#define GPIO_USART3_RX_2 (GPIO_ALT|GPIO_AF7|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN11)
|
||||
#define GPIO_USART3_RX_3 (GPIO_ALT|GPIO_AF7|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTD|GPIO_PIN9)
|
||||
#define GPIO_USART3_TX_1 (GPIO_ALT|GPIO_AF7|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN10)
|
||||
#define GPIO_USART3_TX_2 (GPIO_ALT|GPIO_AF7|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN10)
|
||||
#define GPIO_USART3_TX_3 (GPIO_ALT|GPIO_AF7|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTD|GPIO_PIN8)
|
||||
|
||||
#define GPIO_UART4_RX_1 (GPIO_ALT|GPIO_AF8|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN1)
|
||||
#define GPIO_UART4_RX_2 (GPIO_ALT|GPIO_AF8|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN11)
|
||||
#define GPIO_UART4_TX_1 (GPIO_ALT|GPIO_AF8|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN0)
|
||||
#define GPIO_UART4_TX_2 (GPIO_ALT|GPIO_AF8|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN10)
|
||||
|
||||
#define GPIO_UART5_RX (GPIO_ALT|GPIO_AF8|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTD|GPIO_PIN2)
|
||||
#define GPIO_UART5_TX (GPIO_ALT|GPIO_AF8|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN12)
|
||||
|
||||
#define GPIO_USART6_CK_1 (GPIO_ALT|GPIO_AF8|GPIO_PORTC|GPIO_PIN8)
|
||||
#define GPIO_USART6_CK_2 (GPIO_ALT|GPIO_AF8|GPIO_PORTG|GPIO_PIN7)
|
||||
#define GPIO_USART6_CTS_1 (GPIO_ALT|GPIO_AF8|GPIO_PORTG|GPIO_PIN13)
|
||||
#define GPIO_USART6_CTS_2 (GPIO_ALT|GPIO_AF8|GPIO_PORTG|GPIO_PIN15)
|
||||
#define GPIO_USART6_RTS_1 (GPIO_ALT|GPIO_AF8|GPIO_PORTG|GPIO_PIN12)
|
||||
#define GPIO_USART6_RTS_2 (GPIO_ALT|GPIO_AF8|GPIO_PORTG|GPIO_PIN8)
|
||||
#define GPIO_USART6_RX_1 (GPIO_ALT|GPIO_AF8|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN7)
|
||||
#define GPIO_USART6_RX_2 (GPIO_ALT|GPIO_AF8|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTG|GPIO_PIN9)
|
||||
#define GPIO_USART6_TX_1 (GPIO_ALT|GPIO_AF8|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN6)
|
||||
#define GPIO_USART6_TX_2 (GPIO_ALT|GPIO_AF8|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTG|GPIO_PIN14)
|
||||
|
||||
#endif /* __ARCH_ARM_SRC_STM32_CHIP_STM32F20XXX_PINMAP_H */
|
||||
|
|
@ -0,0 +1,506 @@
|
|||
/****************************************************************************************************
|
||||
* arch/arm/src/stm32/chip/stm32f20xxx_rcc.h
|
||||
*
|
||||
* Copyright (C) 2009, 2011 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.
|
||||
*
|
||||
****************************************************************************************************/
|
||||
|
||||
#ifndef __ARCH_ARM_SRC_STM32_CHIP_STM32F20XXX_RCC_H
|
||||
#define __ARCH_ARM_SRC_STM32_CHIP_STM32F20XXX_RCC_H
|
||||
|
||||
/****************************************************************************************************
|
||||
* Pre-processor Definitions
|
||||
****************************************************************************************************/
|
||||
|
||||
/* Register Offsets *********************************************************************************/
|
||||
|
||||
#define STM32_RCC_CR_OFFSET 0x0000 /* Clock control register */
|
||||
#define STM32_RCC_PLLCFG_OFFSET 0x0004 /* PLL configuration register */
|
||||
#define STM32_RCC_CFGR_OFFSET 0x0008 /* Clock configuration register */
|
||||
#define STM32_RCC_CIR_OFFSET 0x000c /* Clock interrupt register */
|
||||
#define STM32_RCC_AHB1RSTR_OFFSET 0x0010 /* AHB1 peripheral reset register */
|
||||
#define STM32_RCC_AHB2RSTR_OFFSET 0x0014 /* AHB2 peripheral reset register */
|
||||
#define STM32_RCC_AHB3RSTR_OFFSET 0x0018 /* AHB3 peripheral reset register */
|
||||
#define STM32_RCC_APB1RSTR_OFFSET 0x0020 /* APB1 Peripheral reset register */
|
||||
#define STM32_RCC_APB2RSTR_OFFSET 0x0024 /* APB2 Peripheral reset register */
|
||||
#define STM32_RCC_AHB1ENR_OFFSET 0x0030 /* AHB1 Peripheral Clock enable register */
|
||||
#define STM32_RCC_AHB2ENR_OFFSET 0x0034 /* AHB2 Peripheral Clock enable register */
|
||||
#define STM32_RCC_AHB3ENR_OFFSET 0x0038 /* AHB3 Peripheral Clock enable register */
|
||||
#define STM32_RCC_APB1ENR_OFFSET 0x0040 /* APB1 Peripheral Clock enable register */
|
||||
#define STM32_RCC_APB2ENR_OFFSET 0x0044 /* APB2 Peripheral Clock enable register */
|
||||
#define STM32_RCC_AHB1LPENR_OFFSET 0x0050 /* RCC AHB1 low power modeperipheral clock enable register */
|
||||
#define STM32_RCC_AH2BLPENR_OFFSET 0x0054 /* RCC AHB2 low power modeperipheral clock enable register */
|
||||
#define STM32_RCC_AH3BLPENR_OFFSET 0x0058 /* RCC AHB3 low power modeperipheral clock enable register */
|
||||
#define STM32_RCC_APB1LPENR_OFFSET 0x0060 /* RCC APB1 low power modeperipheral clock enable register */
|
||||
#define STM32_RCC_APB2LPENR_OFFSET 0x0060 /* RCC APB2 low power modeperipheral clock enable register */
|
||||
#define STM32_RCC_BDCR_OFFSET 0x0070 /* Backup domain control register */
|
||||
#define STM32_RCC_CSR_OFFSET 0x0074 /* Control/status register */
|
||||
#define STM32_RCC_SSCGR_OFFSET 0x0080 /* Spread spectrum clock generation register */
|
||||
#define STM32_RCC_PLLI2SCFGR_OFFSET 0x0084 /* PLLI2S configuration register */
|
||||
|
||||
/* Register Addresses *******************************************************************************/
|
||||
|
||||
#define STM32_RCC_CR (STM32_RCC_BASE+STM32_RCC_CR_OFFSET)
|
||||
#define STM32_RCC_PLLCFG (STM32_RCC_BASE+STM32_RCC_PLLCFG_OFFSET)
|
||||
#define STM32_RCC_CFGR (STM32_RCC_BASE+STM32_RCC_CFGR_OFFSET)
|
||||
#define STM32_RCC_CIR (STM32_RCC_BASE+STM32_RCC_CIR_OFFSET)
|
||||
#define STM32_RCC_AHB1RSTR (STM32_RCC_BASE+STM32_RCC_AHB1RSTR_OFFSET)
|
||||
#define STM32_RCC_AHB2RSTR (STM32_RCC_BASE+STM32_RCC_AHB2RSTR_OFFSET)
|
||||
#define STM32_RCC_AHB3RSTR (STM32_RCC_BASE+STM32_RCC_AHB3RSTR_OFFSET)
|
||||
#define STM32_RCC_APB1RSTR (STM32_RCC_BASE+STM32_RCC_APB1RSTR_OFFSET)
|
||||
#define STM32_RCC_APB2RSTR (STM32_RCC_BASE+STM32_RCC_APB2RSTR_OFFSET)
|
||||
#define STM32_RCC_AHB1ENR (STM32_RCC_BASE+STM32_RCC_AHB1ENR_OFFSET)
|
||||
#define STM32_RCC_AHB2ENR (STM32_RCC_BASE+STM32_RCC_AHB2ENR_OFFSET)
|
||||
#define STM32_RCC_AHB3ENR (STM32_RCC_BASE+STM32_RCC_AHB3ENR_OFFSET)
|
||||
#define STM32_RCC_APB1ENR (STM32_RCC_BASE+STM32_RCC_APB1ENR_OFFSET)
|
||||
#define STM32_RCC_APB2ENR (STM32_RCC_BASE+STM32_RCC_APB2ENR_OFFSET)
|
||||
#define STM32_RCC_AHB1LPENR (STM32_RCC_BASE+STM32_RCC_AHB1LPENR_OFFSET)
|
||||
#define STM32_RCC_AH2BLPENR (STM32_RCC_BASE+STM32_RCC_AH2BLPENR)
|
||||
#define STM32_RCC_AH3BLPENR (STM32_RCC_BASE+STM32_RCC_AH3BLPENR_OFFSET)
|
||||
#define STM32_RCC_APB1LPENR (STM32_RCC_BASE+STM32_RCC_APB1LPENR_OFFSET)
|
||||
#define STM32_RCC_APB2LPENR (STM32_RCC_BASE+STM32_RCC_APB2LPENR_OFFSET)
|
||||
#define STM32_RCC_BDCR (STM32_RCC_BASE+STM32_RCC_BDCR_OFFSET)
|
||||
#define STM32_RCC_CSR (STM32_RCC_BASE+STM32_RCC_CSR_OFFSET)
|
||||
#define STM32_RCC_SSCGR (STM32_RCC_BASE+STM32_RCC_SSCGR_OFFSET)
|
||||
#define STM32_RCC_PLLI2SCFGR (STM32_RCC_BASE+STM32_RCC_PLLI2SCFGR_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 */
|
||||
#define RCC_CR_PLLI2SON (1 << 26) /* Bit 26: PLLI2S enable */
|
||||
#define RCC_CR_PLLI2SRDY (1 << 27) /* Bit 27: PLLI2S clock ready flag */
|
||||
|
||||
/* PLL configuration register */
|
||||
|
||||
#define RCC_PLLCFG_PLLM_SHIFT (0) /* Bits 0-5: Main PLL (PLL) and audio PLL (PLLI2S)
|
||||
* input clock divider */
|
||||
#define RCC_PLLCFG_PLLM_MASK (0x3f << RCC_PLLCFG_PLLM_SHIFT)
|
||||
# define RCC_PLLCFG_PLLM(n) ((n) << RCC_PLLCFG_PLLM_SHIFT) /* n = 2..63 */
|
||||
#define RCC_PLLCFG_PLLN_SHIFT (6) /* Bits 6-14: Main PLL (PLL) VCO multiplier */
|
||||
#define RCC_PLLCFG_PLLN_MASK (0x1ff << RCC_PLLCFG_PLLN_SHIFT)
|
||||
# define RCC_PLLCFG_PLLN(n) ((n) << RCC_PLLCFG_PLLN_SHIFT) /* n = 2..432 */
|
||||
#define RCC_PLLCFG_PLLP_SHIFT (16) /* Bits 16-17: Main PLL (PLL) main system clock divider */
|
||||
#define RCC_PLLCFG_PLLP_MASK (3 << RCC_PLLCFG_PLLP_SHIFT)
|
||||
# define RCC_PLLCFG_PLLP(n) ((((n)>>1)-1)<< RCC_PLLCFG_PLLP_SHIFT) /* n=2,4,6,8 */
|
||||
# define RCC_PLLCFG_PLLP_2 (0 << RCC_PLLCFG_PLLP_SHIFT) /* 00: PLLP = 2 */
|
||||
# define RCC_PLLCFG_PLLP_4 (1 << RCC_PLLCFG_PLLP_SHIFT) /* 01: PLLP = 4 */
|
||||
# define RCC_PLLCFG_PLLP_6 (2 << RCC_PLLCFG_PLLP_SHIFT) /* 10: PLLP = 6 */
|
||||
# define RCC_PLLCFG_PLLP_8 (3 << RCC_PLLCFG_PLLP_SHIFT) /* 11: PLLP = 8 */
|
||||
#define RCC_PLLCFG_PLLSRC (1 << 22) /* Bit 22: Main PLL(PLL) and audio PLL (PLLI2S)
|
||||
* entry clock source */
|
||||
# define RCC_PLLCFG_PLLSRC_HSI (0)
|
||||
# define RCC_PLLCFG_PLLSRC_HSE RCC_PLLCFG_PLLSRC
|
||||
#define RCC_PLLCFG_PLLQ_SHIFT (24) /* Bits 24-27: Main PLL (PLL) divider
|
||||
* (USB OTG FS, SDIO and RNG clocks) */
|
||||
#define RCC_PLLCFG_PLLQ_MASK (15 << RCC_PLLCFG_PLLQ_SHIFT)
|
||||
# define RCC_PLLCFG_PLLQ(n) ((n) << RCC_PLLCFG_PLLQ_SHIFT) /* n=2..15 */
|
||||
|
||||
#define RCC_PLLCFG_RESET (0x24003010) /* PLLCFG reset value */
|
||||
|
||||
/* Clock configuration register */
|
||||
|
||||
#define RCC_CFGR_SW_SHIFT (0) /* Bits 0-1: 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_SWS_SHIFT (2) /* Bits 2-3: 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_HPRE_SHIFT (4) /* Bits 4-7: 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 (10) /* Bits 10-12: 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 */
|
||||
#define RCC_CFGR_PPRE2_SHIFT (13) /* Bits 13-15: APB High speed prescaler (APB2) */
|
||||
#define RCC_CFGR_PPRE2_MASK (7 << RCC_CFGR_PPRE2_SHIFT)
|
||||
# define RCC_CFGR_PPRE2_HCLK (0 << RCC_CFGR_PPRE2_SHIFT) /* 0xx: HCLK not divided */
|
||||
# define RCC_CFGR_PPRE2_HCLKd2 (4 << RCC_CFGR_PPRE2_SHIFT) /* 100: HCLK divided by 2 */
|
||||
# define RCC_CFGR_PPRE2_HCLKd4 (5 << RCC_CFGR_PPRE2_SHIFT) /* 101: HCLK divided by 4 */
|
||||
# define RCC_CFGR_PPRE2_HCLKd8 (6 << RCC_CFGR_PPRE2_SHIFT) /* 110: HCLK divided by 8 */
|
||||
# define RCC_CFGR_PPRE2_HCLKd16 (7 << RCC_CFGR_PPRE2_SHIFT) /* 111: HCLK divided by 16 */
|
||||
#define RCC_CFGR_RTCPRE_SHIFT (16) /* Bits 16-20: APB High speed prescaler (APB2) */
|
||||
#define RCC_CFGR_RTCPRE_MASK (31 << RCC_CFGR_RTCPRE)
|
||||
# define RCC_CFGR_RTCPRE(n) ((n) << RCC_CFGR_RTCPRE) /* HSE/n, n=1..31 */
|
||||
#define RCC_CFGR_MCO1_SHIFT (21) /* Bits 21-22: Microcontroller Clock Output */
|
||||
#define RCC_CFGR_MCO1_MASK (3 << RCC_CFGR_MCO1_SHIFT)
|
||||
# define RCC_CFGR_MCO1_HSI (0 << RCC_CFGR_MCO1_SHIFT) /* 00: HSI clock selected */
|
||||
# define RCC_CFGR_MCO1_LSE (1 << RCC_CFGR_MCO1_SHIFT) /* 01: LSE oscillator selected */
|
||||
# define RCC_CFGR_MCO1_HSE (2 << RCC_CFGR_MCO1_SHIFT) /* 10: HSE oscillator clock selected */
|
||||
# define RCC_CFGR_MCO1_PLL (3 << RCC_CFGR_MCO1_SHIFT) /* 11: PLL clock selected */
|
||||
#define TCC_CFGR_I2SSRC (1 << 23) /* Bit 23: I2S clock selection */
|
||||
#define RCC_CFGR_MCO1PRE_SHIFT (24) /* Bits 24-26: MCO1 prescaler */
|
||||
#define RCC_CFGR_MCO1PRE_MASK (7 << RCC_CFGR_MCO1PRE_SHIFT)
|
||||
# define RCC_CFGR_MCO1PRE_NONE (0 << RCC_CFGR_MCO1PRE_SHIFT) /* 0xx: no division */
|
||||
# define RCC_CFGR_MCO1PRE_DIV2 (4 << RCC_CFGR_MCO1PRE_SHIFT) /* 100: division by 2 */
|
||||
# define RCC_CFGR_MCO1PRE_DIV3 (5 << RCC_CFGR_MCO1PRE_SHIFT) /* 101: division by 3 */
|
||||
# define RCC_CFGR_MCO1PRE_DIV4 (6 << RCC_CFGR_MCO1PRE_SHIFT) /* 110: division by 4 */
|
||||
# define RCC_CFGR_MCO1PRE_DIV5 (7 << RCC_CFGR_MCO1PRE_SHIFT) /* 111: division by 5 */
|
||||
#define RCC_CFGR_MCO2PRE_SHIFT (27) /* Bits 27-29: MCO2 prescaler */
|
||||
#define RCC_CFGR_MCO2PRE_MASK (7 << RCC_CFGR_MCO2PRE_SHIFT)
|
||||
# define RCC_CFGR_MCO2PRE_NONE (0 << RCC_CFGR_MCO2PRE_SHIFT) /* 0xx: no division */
|
||||
# define RCC_CFGR_MCO2PRE_DIV2 (4 << RCC_CFGR_MCO2PRE_SHIFT) /* 100: division by 2 */
|
||||
# define RCC_CFGR_MCO2PRE_DIV3 (5 << RCC_CFGR_MCO2PRE_SHIFT) /* 101: division by 3 */
|
||||
# define RCC_CFGR_MCO2PRE_DIV4 (6 << RCC_CFGR_MCO2PRE_SHIFT) /* 110: division by 4 */
|
||||
# define RCC_CFGR_MCO2PRE_DIV5 (7 << RCC_CFGR_MCO2PRE_SHIFT) /* 111: division by 5 */
|
||||
#define RCC_CFGR_MCO2_SHIFT (30) /* Bits 30-31: Microcontroller clock output 2 */
|
||||
#define RCC_CFGR_MCO2_MASK (3 << RCC_CFGR_MCO2_SHIFT)
|
||||
# define RCC_CFGR_MCO2_SYSCLK (0 << RCC_CFGR_MCO2_SHIFT) /* 00: System clock (SYSCLK) selected */
|
||||
# define RCC_CFGR_MCO2_PLLI2S (1 << RCC_CFGR_MCO2_SHIFT) /* 01: PLLI2S clock selected */
|
||||
# define RCC_CFGR_MCO2_HSE (2 << RCC_CFGR_MCO2_SHIFT) /* 10: HSE oscillator clock selected */
|
||||
# define RCC_CFGR_MCO2_PLL (3 << RCC_CFGR_MCO2_SHIFT) /* 11: PLL clock selected */
|
||||
|
||||
/* 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_PLLI2SRDYF (1 << 5) /* Bit 5: PLLI2S 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_PLLI2SRDYIE (1 << 13) /* Bit 13: PLLI2S 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_PLLI2SRDYC (1 << 21) /* Bit 21: PLLI2S Ready Interrupt clear */
|
||||
#define RCC_CIR_CSSC (1 << 23) /* Bit 23: Clock Security System Interrupt Clear */
|
||||
|
||||
/* AHB1 peripheral reset register */
|
||||
|
||||
#define RCC_AHB1RSTR_GPIOARST (1 << 0) /* Bit 0: IO port A reset */
|
||||
#define RCC_AHB1RSTR_GPIOBRST (1 << 1) /* Bit 1: IO port B reset */
|
||||
#define RCC_AHB1RSTR_GPIOCRST (1 << 2) /* Bit 2: IO port C reset */
|
||||
#define RCC_AHB1RSTR_GPIODRST (1 << 3) /* Bit 3: IO port D reset */
|
||||
#define RCC_AHB1RSTR_GPIOERST (1 << 4) /* Bit 4: IO port E reset */
|
||||
#define RCC_AHB1RSTR_GPIOFRST (1 << 5) /* Bit 5: IO port F reset */
|
||||
#define RCC_AHB1RSTR_GPIOGRST (1 << 6) /* Bit 6: IO port G reset */
|
||||
#define RCC_AHB1RSTR_GPIOHRST (1 << 7) /* Bit 7: IO port H reset */
|
||||
#define RCC_AHB1RSTR_CRCRST (1 << 12) /* Bit 12 IO port I reset */
|
||||
#define RCC_AHB1RSTR_DMA1RST (1 << 21) /* Bit 21: DMA2 reset */
|
||||
#define RCC_AHB1RSTR_DMA2RST (1 << 22) /* Bit 22: DMA2 reset */
|
||||
#define RCC_AHB1RSTR_ETHMACRST (1 << 25) /* Bit 25: Ethernet MAC reset */
|
||||
#define RCC_AHB1RSTR_OTGHSRST (1 << 29) /* Bit 29: USB OTG HS module reset */
|
||||
|
||||
/* AHB2 peripheral reset register */
|
||||
|
||||
#define RCC_AHB2RSTR_DCMIRST (1 << 0) /* Bit 0: Camera interface reset */
|
||||
#define RCC_AHB2RSTR_CRYPRST (1 << 4) /* Bit 4: Cryptographic module reset */
|
||||
#define RCC_AHB2RSTR_HASHRST (1 << 5) /* Bit 5: Hash module reset */
|
||||
#define RCC_AHB2RSTR_RNGRST (1 << 6) /* Bit 6: Random number generator module reset */
|
||||
#define RCC_AHB2RSTR_OTGFSRST (1 << 7) /* Bit 7: USB OTG FS module reset */
|
||||
|
||||
/* AHB3 peripheral reset register */
|
||||
|
||||
#define RCC_AHB3RSTR_FSMCRST (1 << 0) /* Bit 0: Flexible static memory controller module reset */
|
||||
|
||||
/* APB1 Peripheral reset register */
|
||||
|
||||
#define RCC_APB1RSTR_TIM2RST (1 << 0) /* Bit 0: TIM2 reset */
|
||||
#define RCC_APB1RSTR_TIM3RST (1 << 1) /* Bit 1: TIM3 reset */
|
||||
#define RCC_APB1RSTR_TIM4RST (1 << 2) /* Bit 2: TIM4 reset */
|
||||
#define RCC_APB1RSTR_TIM5RST (1 << 3) /* Bit 3: TIM5 reset */
|
||||
#define RCC_APB1RSTR_TIM6RST (1 << 4) /* Bit 4: TIM6 reset */
|
||||
#define RCC_APB1RSTR_TIM7RST (1 << 5) /* Bit 5: TIM7 reset */
|
||||
#define RCC_APB1RSTR_TIM12RST (1 << 6) /* Bit 6: TIM12 reset */
|
||||
#define RCC_APB1RSTR_TIM13RST (1 << 7) /* Bit 7: TIM13 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_SPI3RST (1 << 15) /* Bit 15: SPI 3 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: USART 4 reset */
|
||||
#define RCC_APB1RSTR_UART5RST (1 << 20) /* Bit 20: USART 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_I2C3RST (1 << 23) /* Bit 23: I2C3 reset */
|
||||
#define RCC_APB1RSTR_CAN1RST (1 << 25) /* Bit 25: CAN1 reset */
|
||||
#define RCC_APB1RSTR_CAN2RST (1 << 26) /* Bit 26: CAN2 reset */
|
||||
#define RCC_APB1RSTR_PWRRST (1 << 28) /* Bit 28: Power interface reset */
|
||||
#define RCC_APB1RSTR_DACRST (1 << 29) /* Bit 29: DAC reset */
|
||||
|
||||
/* APB2 Peripheral reset register */
|
||||
|
||||
#define RCC_APB2RSTR_TIM1RST (1 << 0) /* Bit 0: TIM1 reset */
|
||||
#define RCC_APB2RSTR_TIM8RST (1 << 1) /* Bit 1: TIM8 reset */
|
||||
#define RCC_APB2RSTR_USART1RST (1 << 4) /* Bit 4: USART1 reset */
|
||||
#define RCC_APB2RSTR_USART6RST (1 << 5) /* Bit 5: USART6 reset */
|
||||
#define RCC_APB2RSTR_ADCRST (1 << 8) /* Bit 8: ADC interface reset (common to all ADCs) */
|
||||
#define RCC_APB2RSTR_SDIORST (1 << 11) /* Bit 11: SDIO reset */
|
||||
#define RCC_APB2RSTR_SPI1RST (1 << 12) /* Bit 12: SPI 1 reset */
|
||||
#define RCC_APB2RSTR_SYSCFGRST (1 << 14) /* Bit 14: System configuration controller reset */
|
||||
#define RCC_APB2RSTR_TIM9RST (1 << 16) /* Bit 16: TIM9 reset */
|
||||
#define RCC_APB2RSTR_TIM10RST (1 << 17) /* Bit 17: TIM10 reset */
|
||||
#define RCC_APB2RSTR_TIM11RST (1 << 18) /* Bit 18: TIM11 reset */
|
||||
|
||||
/* AHB1 Peripheral Clock enable register */
|
||||
|
||||
#define RCC_AHB1ENR_GPIOEN(n) (1 << (n))
|
||||
#define RCC_AHB1ENR_GPIOAEN (1 << 0) /* Bit 0: IO port A clock enable */
|
||||
#define RCC_AHB1ENR_GPIOBEN (1 << 1) /* Bit 1: IO port B clock enable */
|
||||
#define RCC_AHB1ENR_GPIOCEN (1 << 2) /* Bit 2: IO port C clock enable */
|
||||
#define RCC_AHB1ENR_GPIODEN (1 << 3) /* Bit 3: IO port D clock enable */
|
||||
#define RCC_AHB1ENR_GPIOEEN (1 << 4) /* Bit 4: IO port E clock enable */
|
||||
#define RCC_AHB1ENR_GPIOFEN (1 << 5) /* Bit 5: IO port F clock enable */
|
||||
#define RCC_AHB1ENR_GPIOGEN (1 << 6) /* Bit 6: IO port G clock enable */
|
||||
#define RCC_AHB1ENR_GPIOHEN (1 << 7) /* Bit 7: IO port H clock enable */
|
||||
#define RCC_AHB1ENR_GPIOIEN (1 << 8) /* Bit 8: IO port I clock enable */
|
||||
#define RCC_AHB1ENR_CRCEN (1 << 12) /* Bit 12: CRC clock enable */
|
||||
#define RCC_AHB1ENR_BKPSRAMEN (1 << 18) /* Bit 18: Backup SRAM interface clock enable */
|
||||
#define RCC_AHB1ENR_CCMDATARAMEN (1 << 20) /* Bit 20: CCM data RAM clock enable */
|
||||
#define RCC_AHB1ENR_DMA1EN (1 << 21) /* Bit 21: DMA1 clock enable */
|
||||
#define RCC_AHB1ENR_DMA2EN (1 << 22) /* Bit 22: DMA2 clock enable */
|
||||
#define RCC_AHB1ENR_ETHMACEN (1 << 25) /* Bit 25: Ethernet MAC clock enable */
|
||||
#define RCC_AHB1ENR_ETHMACTXEN (1 << 26) /* Bit 26: Ethernet Transmission clock enable */
|
||||
#define RCC_AHB1ENR_ETHMACRXEN (1 << 27) /* Bit 27: Ethernet Reception clock enable */
|
||||
#define RCC_AHB1ENR_ETHMACPTPEN (1 << 28) /* Bit 28: Ethernet PTP clock enable */
|
||||
#define RCC_AHB1ENR_OTGHSEN (1 << 29) /* Bit 29: USB OTG HS clock enable */
|
||||
#define RCC_AHB1ENR_OTGHSULPIEN (1 << 30) /* Bit 30: USB OTG HSULPI clock enable */
|
||||
|
||||
/* AHB2 Peripheral Clock enable register */
|
||||
|
||||
#define RCC_AHB2ENR_DCMIEN (1 << 0) /* Bit 0: Camera interface enable */
|
||||
#define RCC_AHB2ENR_CRYPEN (1 << 4) /* Bit 4: Cryptographic modules clock enable */
|
||||
#define RCC_AHB2ENR_HASHEN (1 << 5) /* Bit 5: Hash modules clock enable */
|
||||
#define RCC_AHB2ENR_RNGEN (1 << 6) /* Bit 6: Random number generator clock enable */
|
||||
#define RCC_AHB2ENR_OTGFSEN (1 << 7) /* Bit 7: USB OTG FS clock enable */
|
||||
|
||||
/* AHB3 Peripheral Clock enable register */
|
||||
|
||||
#define RCC_AHB3ENR_FSMCEN (1 << 0) /* Bit 0: Flexible static memory controller module clock enable */
|
||||
|
||||
/* APB1 Peripheral Clock enable register */
|
||||
|
||||
#define RCC_APB1ENR_TIM2EN (1 << 0) /* Bit 0: TIM2 clock enable */
|
||||
#define RCC_APB1ENR_TIM3EN (1 << 1) /* Bit 1: TIM3 clock enable */
|
||||
#define RCC_APB1ENR_TIM4EN (1 << 2) /* Bit 2: TIM4 clock enable */
|
||||
#define RCC_APB1ENR_TIM5EN (1 << 3) /* Bit 3: TIM5 clock enable */
|
||||
#define RCC_APB1ENR_TIM6EN (1 << 4) /* Bit 4: TIM6 clock enable */
|
||||
#define RCC_APB1ENR_TIM7EN (1 << 5) /* Bit 5: TIM7 clock enable */
|
||||
#define RCC_APB1ENR_TIM12EN (1 << 6) /* Bit 6: TIM12 clock enable */
|
||||
#define RCC_APB1ENR_TIM13EN (1 << 7) /* Bit 7: TIM13 clock enable */
|
||||
#define RCC_APB1ENR_TIM14EN (1 << 8) /* Bit 8: TIM14 clock enable */
|
||||
#define RCC_APB1ENR_WWDGEN (1 << 11) /* Bit 11: Window watchdog clock enable */
|
||||
#define RCC_APB1ENR_SPI2EN (1 << 14) /* Bit 14: SPI2 clock enable */
|
||||
#define RCC_APB1ENR_SPI3EN (1 << 15) /* Bit 15: SPI3 clock enable */
|
||||
#define RCC_APB1ENR_USART2EN (1 << 17) /* Bit 17: USART 2 clock enable */
|
||||
#define RCC_APB1ENR_USART3EN (1 << 18) /* Bit 18: USART3 clock enable */
|
||||
#define RCC_APB1ENR_UART4EN (1 << 19) /* Bit 19: UART4 clock enable */
|
||||
#define RCC_APB1ENR_UART5EN (1 << 20) /* Bit 20: UART5 clock enable */
|
||||
#define RCC_APB1ENR_I2C1EN (1 << 21) /* Bit 21: I2C1 clock enable */
|
||||
#define RCC_APB1ENR_I2C2EN (1 << 22) /* Bit 22: I2C2 clock enable */
|
||||
#define RCC_APB1ENR_I2C3EN (1 << 23) /* Bit 23: I2C3 clock enable */
|
||||
#define RCC_APB1ENR_CAN1EN (1 << 25) /* Bit 25: CAN 1 clock enable */
|
||||
#define RCC_APB1ENR_CAN2EN (1 << 26) /* Bit 26: CAN 2 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 */
|
||||
|
||||
/* APB2 Peripheral Clock enable register */
|
||||
|
||||
#define RCC_APB2ENR_TIM1EN (1 << 0) /* Bit 0: TIM1 clock enable */
|
||||
#define RCC_APB2ENR_TIM8EN (1 << 1) /* Bit 1: TIM8 clock enable */
|
||||
#define RCC_APB2ENR_USART1EN (1 << 4) /* Bit 4: USART1 clock enable */
|
||||
#define RCC_APB2ENR_USART6EN (1 << 5) /* Bit 5: USART6 clock enable */
|
||||
#define RCC_APB2ENR_ADC1EN (1 << 8) /* Bit 8: ADC1 clock enable */
|
||||
#define RCC_APB2ENR_ADC2EN (1 << 9) /* Bit 9: ADC2 clock enable */
|
||||
#define RCC_APB2ENR_ADC3EN (1 << 10) /* Bit 10: ADC3 clock enable */
|
||||
#define RCC_APB2ENR_SDIOEN (1 << 11) /* Bit 11: SDIO clock enable */
|
||||
#define RCC_APB2ENR_SPI1EN (1 << 12) /* Bit 12: SPI1 clock enable */
|
||||
#define RCC_APB2ENR_SYSCFGEN (1 << 14) /* Bit 14: System configuration controller clock enable */
|
||||
#define RCC_APB2ENR_TIM9EN (1 << 16) /* Bit 16: TIM9 clock enable */
|
||||
#define RCC_APB2ENR_TIM10EN (1 << 17) /* Bit 17: TIM10 clock enable */
|
||||
#define RCC_APB2ENR_TIM11EN (1 << 18) /* Bit 18: TIM11 clock enable */
|
||||
|
||||
/* RCC AHB1 low power modeperipheral clock enable register */
|
||||
|
||||
#define RCC_AHB1LPENR_GPIOLPEN(n) (1 << (n))
|
||||
#define RCC_AHB1LPENR_GPIOALPEN (1 << 0) /* Bit 0: IO port A clock enable during Sleep mode */
|
||||
#define RCC_AHB1LPENR_GPIOBLPEN (1 << 1) /* Bit 1: IO port B clock enable during Sleep mode */
|
||||
#define RCC_AHB1LPENR_GPIOCLPEN (1 << 2) /* Bit 2: IO port C clock enable during Sleep mode */
|
||||
#define RCC_AHB1LPENR_GPIODLPEN (1 << 3) /* Bit 3: IO port D clock enable during Sleep mode */
|
||||
#define RCC_AHB1LPENR_GPIOELPEN (1 << 4) /* Bit 4: IO port E clock enable during Sleep mode */
|
||||
#define RCC_AHB1LPENR_GPIOFLPEN (1 << 5) /* Bit 5: IO port F clock enable during Sleep mode */
|
||||
#define RCC_AHB1LPENR_GPIOGLPEN (1 << 6) /* Bit 6: IO port G clock enable during Sleep mode */
|
||||
#define RCC_AHB1LPENR_GPIOHLPEN (1 << 7) /* Bit 7: IO port H clock enable during Sleep mode */
|
||||
#define RCC_AHB1LPENR_GPIOILPEN (1 << 8) /* Bit 8: IO port I clock enable during Sleep mode */
|
||||
#define RCC_AHB1LPENR_CRCLPEN (1 << 12) /* Bit 12: CRC clock enable during Sleep mode */
|
||||
#define RCC_AHB1LPENR_FLITFLPEN (1 << 15) /* Bit 15: Flash interface clock enable during Sleep mode */
|
||||
#define RCC_AHB1LPENR_SRAM1LPEN (1 << 16) /* Bit 16: SRAM 1 interface clock enable during Sleep mode */
|
||||
#define RCC_AHB1LPENR_SRAM2LPEN (1 << 17) /* Bit 17: SRAM 2 interface clock enable during Sleep mode */
|
||||
#define RCC_AHB1LPENR_BKPSRAMLPEN (1 << 18) /* Bit 18: Backup SRAM interface clock enable during Sleep mode */
|
||||
#define RCC_AHB1LPENR_CCMDATARAMLPEN (1 << 20) /* Bit 20: CCM data RAM clock enable during Sleep mode */
|
||||
#define RCC_AHB1LPENR_DMA1LPEN (1 << 21) /* Bit 21: DMA1 clock enable during Sleep mode */
|
||||
#define RCC_AHB1LPENR_DMA2LPEN (1 << 22) /* Bit 22: DMA2 clock enable during Sleep mode */
|
||||
#define RCC_AHB1LPENR_ETHMACLPEN (1 << 25) /* Bit 25: Ethernet MAC clock enable during Sleep mode */
|
||||
#define RCC_AHB1LPENR_ETHMACTXLPEN (1 << 26) /* Bit 26: Ethernet Transmission clock enable during Sleep mode */
|
||||
#define RCC_AHB1LPENR_ETHMACRXLPEN (1 << 27) /* Bit 27: Ethernet Reception clock enable during Sleep mode */
|
||||
#define RCC_AHB1LPENR_ETHMACPTPLPEN (1 << 28) /* Bit 28: Ethernet PTP clock enable during Sleep mode */
|
||||
#define RCC_AHB1LPENR_OTGHSLPEN (1 << 29) /* Bit 29: USB OTG HS clock enable during Sleep mode */
|
||||
#define RCC_AHB1LPENR_OTGHSULPILPEN (1 << 30) /* Bit 30: USB OTG HSULPI clock enable during Sleep mode */
|
||||
|
||||
/* RCC AHB2 low power modeperipheral clock enable register */
|
||||
|
||||
#define RCC_AHB2LPENR_DCMILPEN (1 << 0) /* Bit 0: Camera interface enable during Sleep mode */
|
||||
#define RCC_AHB2LPENR_CRYPLPEN (1 << 4) /* Bit 4: Cryptographic modules clock enable during Sleep mode */
|
||||
#define RCC_AHB2LPENR_HASHLPEN (1 << 5) /* Bit 5: Hash modules clock enable during Sleep mode */
|
||||
#define RCC_AHB2LPENR_RNGLPEN (1 << 6) /* Bit 6: Random number generator clock enable during Sleep mode */
|
||||
#define RCC_AHB2LPENR_OTGFLPSEN (1 << 7) /* Bit 7: USB OTG FS clock enable during Sleep mode */
|
||||
|
||||
/* RCC AHB3 low power modeperipheral clock enable register */
|
||||
|
||||
#define RCC_AHB3LPENR_FSMLPEN (1 << 0) /* Bit 0: Flexible static memory controller module clock
|
||||
* enable during Sleep mode */
|
||||
|
||||
/* RCC APB1 low power modeperipheral clock enable register */
|
||||
|
||||
#define RCC_APB1LPENR_TIM2LPEN (1 << 0) /* Bit 0: TIM2 clock enable during Sleep mode */
|
||||
#define RCC_APB1LPENR_TIM3LPEN (1 << 1) /* Bit 1: TIM3 clock enable during Sleep mode */
|
||||
#define RCC_APB1LPENR_TIM4LPEN (1 << 2) /* Bit 2: TIM4 clock enable during Sleep mode */
|
||||
#define RCC_APB1LPENR_TIM5LPEN (1 << 3) /* Bit 3: TIM5 clock enable during Sleep mode */
|
||||
#define RCC_APB1LPENR_TIM6LPEN (1 << 4) /* Bit 4: TIM6 clock enable during Sleep mode */
|
||||
#define RCC_APB1LPENR_TIM7LPEN (1 << 5) /* Bit 5: TIM7 clock enable during Sleep mode */
|
||||
#define RCC_APB1LPENR_TIM12LPEN (1 << 6) /* Bit 6: TIM12 clock enable during Sleep mode */
|
||||
#define RCC_APB1LPENR_TIM13LPEN (1 << 7) /* Bit 7: TIM13 clock enable during Sleep mode */
|
||||
#define RCC_APB1LPENR_TIM14LPEN (1 << 8) /* Bit 8: TIM14 clock enable during Sleep mode */
|
||||
#define RCC_APB1LPENR_WWDGLPEN (1 << 11) /* Bit 11: Window watchdog clock enable during Sleep mode */
|
||||
#define RCC_APB1LPENR_SPI2LPEN (1 << 14) /* Bit 14: SPI2 clock enable during Sleep mode */
|
||||
#define RCC_APB1LPENR_SPI3LPEN (1 << 15) /* Bit 15: SPI3 clock enable during Sleep mode */
|
||||
#define RCC_APB1LPENR_USART2LPEN (1 << 17) /* Bit 17: USART 2 clock enable during Sleep mode */
|
||||
#define RCC_APB1LPENR_USART3LPEN (1 << 18) /* Bit 18: USART3 clock enable during Sleep mode */
|
||||
#define RCC_APB1LPENR_UART4LPEN (1 << 19) /* Bit 19: UART4 clock enable during Sleep mode */
|
||||
#define RCC_APB1LPENR_UART5LPEN (1 << 20) /* Bit 20: UART5 clock enable during Sleep mode */
|
||||
#define RCC_APB1LPENR_I2C1LPEN (1 << 21) /* Bit 21: I2C1 clock enable during Sleep mode */
|
||||
#define RCC_APB1LPENR_I2C2LPEN (1 << 22) /* Bit 22: I2C2 clock enable during Sleep mode */
|
||||
#define RCC_APB1LPENR_I2C3LPEN (1 << 23) /* Bit 23: I2C3 clock enable during Sleep mode */
|
||||
#define RCC_APB1LPENR_CAN1LPEN (1 << 25) /* Bit 25: CAN 1 clock enable during Sleep mode */
|
||||
#define RCC_APB1LPENR_CAN2LPEN (1 << 26) /* Bit 26: CAN 2 clock enable during Sleep mode */
|
||||
#define RCC_APB1LPENR_PWRLPEN (1 << 28) /* Bit 28: Power interface clock enable during Sleep mode */
|
||||
#define RCC_APB1LPENR_DACLPEN (1 << 29) /* Bit 29: DAC interface clock enable during Sleep mode */
|
||||
|
||||
/* RCC APB2 low power modeperipheral clock enable register */
|
||||
|
||||
#define RCC_APB2LPENR_TIM1LPEN (1 << 0) /* Bit 0: TIM1 clock enable during Sleep mode */
|
||||
#define RCC_APB2LPENR_TIM8LPEN (1 << 1) /* Bit 1: TIM8 clock enable during Sleep mode */
|
||||
#define RCC_APB2LPENR_USART1LPEN (1 << 4) /* Bit 4: USART1 clock enable during Sleep mode */
|
||||
#define RCC_APB2LPENR_USART6LPEN (1 << 5) /* Bit 5: USART6 clock enable during Sleep mode */
|
||||
#define RCC_APB2LPENR_ADC1LPEN (1 << 8) /* Bit 8: ADC1 clock enable during Sleep mode */
|
||||
#define RCC_APB2LPENR_ADC2LPEN (1 << 9) /* Bit 9: ADC2 clock enable during Sleep mode */
|
||||
#define RCC_APB2LPENR_ADC3LPEN (1 << 10) /* Bit 10: ADC3 clock enable during Sleep mode */
|
||||
#define RCC_APB2LPENR_SDIOLPEN (1 << 11) /* Bit 11: SDIO clock enable during Sleep mode */
|
||||
#define RCC_APB2LPENR_SPI1LPEN (1 << 12) /* Bit 12: SPI1 clock enable during Sleep mode */
|
||||
#define RCC_APB2LPENR_SYSCFGLPEN (1 << 14) /* Bit 14: System configuration controller clock enable during Sleep mode */
|
||||
#define RCC_APB2LPENR_TIM9LPEN (1 << 16) /* Bit 16: TIM9 clock enable during Sleep mode */
|
||||
#define RCC_APB2LPENR_TIM10LPEN (1 << 17) /* Bit 17: TIM10 clock enable during Sleep mode */
|
||||
#define RCC_APB2LPENR_TIM11LPEN (1 << 18) /* Bit 18: TIM11 clock enable during Sleep mode */
|
||||
|
||||
/* Backup 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_RMVF (1 << 24) /* Bit 24: Remove reset flag */
|
||||
#define RCC_CSR_BORRSTF (1 << 25) /* Bit 25: BOR 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 */
|
||||
|
||||
/* Spread spectrum clock generation register */
|
||||
|
||||
#define RCC_SSCGR_MODPER_SHIFT (0) /* Bit 0-12: Modulation period */
|
||||
#define RCC_SSCGR_MODPER_MASK (0x1fff << RCC_SSCGR_MODPER_SHIFT)
|
||||
# define RCC_SSCGR_MODPER(n) ((n) << RCC_SSCGR_MODPER_SHIFT)
|
||||
#define RCC_SSCGR_INCSTEP_SHIFT (13) /* Bit 13-27: Incrementation step */
|
||||
#define RCC_SSCGR_INCSTEP_MASK (0x7fff << RCC_SSCGR_INCSTEP_SHIFT)
|
||||
# define RCC_SSCGR_INCSTEP(n) ((n) << RCC_SSCGR_INCSTEP_SHIFT)
|
||||
#define RCC_SSCGR_SPREADSEL (1 << 30) /* Bit 30: Spread Select */
|
||||
#define RCC_SSCGR_SSCGEN (1 << 31) /* Bit 31: Spread spectrum modulation enable */
|
||||
|
||||
/* PLLI2S configuration register */
|
||||
|
||||
#define RCC_PLLI2SCFGR_PLLI2SN_SHIFT (6) /* Bits 6-14: PLLI2S multiplication factor for VCO */
|
||||
#define RCC_PLLI2SCFGR_PLLI2SN_MASK (0x1ff << RCC_PLLI2SCFGR_PLLI2SN_SHIFT)
|
||||
#define RCC_PLLI2SCFGR_PLLI2SR_SHIFT (28) /* Bits 28-30: PLLI2S division factor for I2S clocks */
|
||||
#define RCC_PLLI2SCFGR_PLLI2SR_MASK (7 << RCC_PLLI2SCFGR_PLLI2SR_SHIFT)
|
||||
|
||||
#endif /* __ARCH_ARM_SRC_STM32_CHIP_STM32F20XXX_RCC_H */
|
||||
|
|
@ -0,0 +1,338 @@
|
|||
/************************************************************************************
|
||||
* arch/arm/src/stm32/chip/stm32f20xxx_rtc.h
|
||||
*
|
||||
* Copyright (C) 2011 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
*
|
||||
* 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_STM32_CHIP_STM32F20XXX_RTC_H
|
||||
#define __ARCH_ARM_SRC_STM32_CHIP_STM32F20XXX_RTC_H
|
||||
|
||||
/************************************************************************************
|
||||
* Pre-processor Definitions
|
||||
************************************************************************************/
|
||||
|
||||
/* Register Offsets *****************************************************************/
|
||||
|
||||
#define STM32_RTC_TR_OFFSET 0x0000 /* RTC time register */
|
||||
#define STM32_RTC_DR_OFFSET 0x0004 /* RTC date register */
|
||||
#define STM32_RTC_CR_OFFSET 0x0008 /* RTC control register */
|
||||
#define STM32_RTC_ISR_OFFSET 0x000c /* RTC initialization and status register */
|
||||
#define STM32_RTC_PRER_OFFSET 0x0010 /* RTC prescaler register */
|
||||
#define STM32_RTC_WUTR_OFFSET 0x0014 /* RTC wakeup timer register */
|
||||
#define STM32_RTC_CALIBR_OFFSET 0x0018 /* RTC calibration register */
|
||||
#define STM32_RTC_ALRMAR_OFFSET 0x001c /* RTC alarm A register */
|
||||
#define STM32_RTC_ALRMBR_OFFSET 0x0020 /* RTC alarm B register */
|
||||
#define STM32_RTC_WPR_OFFSET 0x0024 /* RTC write protection register */
|
||||
#define STM32_RTC_SSR_OFFSET 0x0028 /* RTC sub second register */
|
||||
#define STM32_RTC_SHIFTR_OFFSET 0x002c /* RTC shift control register */
|
||||
#define STM32_RTC_TSTR_OFFSET 0x0030 /* RTC time stamp time register */
|
||||
#define STM32_RTC_TSDR_OFFSET 0x0030 /* RTC time stamp date register */
|
||||
#define STM32_RTC_TSSSR_OFFSET 0x0038 /* RTC timestamp sub second register */
|
||||
#define STM32_RTC_CALR_OFFSET 0x003c /* RTC calibration register */
|
||||
#define STM32_RTC_TAFCR_OFFSET 0x0040 /* RTC tamper and alternate function configuration register */
|
||||
#define STM32_RTC_ALRMASSR_OFFSET 0x0044 /* RTC alarm A sub second register */
|
||||
#define STM32_RTC_ALRMBSSR_OFFSET 0x0048 /* RTC alarm B sub second register */
|
||||
|
||||
#define STM32_RTC_BKR_OFFSET(n) (0x0050+((n)<<2))
|
||||
#define STM32_RTC_BK0R_OFFSET 0x0050 /* RTC backup register 0 */
|
||||
#define STM32_RTC_BK1R_OFFSET 0x0054 /* RTC backup register 1 */
|
||||
#define STM32_RTC_BK2R_OFFSET 0x0058 /* RTC backup register 2 */
|
||||
#define STM32_RTC_BK3R_OFFSET 0x005c /* RTC backup register 3 */
|
||||
#define STM32_RTC_BK4R_OFFSET 0x0060 /* RTC backup register 4 */
|
||||
#define STM32_RTC_BK5R_OFFSET 0x0064 /* RTC backup register 5 */
|
||||
#define STM32_RTC_BK6R_OFFSET 0x0068 /* RTC backup register 6 */
|
||||
#define STM32_RTC_BK7R_OFFSET 0x006c /* RTC backup register 7 */
|
||||
#define STM32_RTC_BK8R_OFFSET 0x0070 /* RTC backup register 8 */
|
||||
#define STM32_RTC_BK9R_OFFSET 0x0074 /* RTC backup register 9 */
|
||||
#define STM32_RTC_BK10R_OFFSET 0x0078 /* RTC backup register 10 */
|
||||
#define STM32_RTC_BK11R_OFFSET 0x007c /* RTC backup register 11 */
|
||||
#define STM32_RTC_BK12R_OFFSET 0x0080 /* RTC backup register 12 */
|
||||
#define STM32_RTC_BK13R_OFFSET 0x0084 /* RTC backup register 13 */
|
||||
#define STM32_RTC_BK14R_OFFSET 0x0088 /* RTC backup register 14 */
|
||||
#define STM32_RTC_BK15R_OFFSET 0x008c /* RTC backup register 15 */
|
||||
#define STM32_RTC_BK16R_OFFSET 0x0090 /* RTC backup register 16 */
|
||||
#define STM32_RTC_BK17R_OFFSET 0x0094 /* RTC backup register 17 */
|
||||
#define STM32_RTC_BK18R_OFFSET 0x0098 /* RTC backup register 18 */
|
||||
#define STM32_RTC_BK19R_OFFSET 0x009c /* RTC backup register 19 */
|
||||
|
||||
/* Register Addresses ***************************************************************/
|
||||
|
||||
#define STM32_RTC_TR (STM32_RTC_BASE+STM32_RTC_TR_OFFSET)
|
||||
#define STM32_RTC_DR (STM32_RTC_BASE+STM32_RTC_DR_OFFSET)
|
||||
#define STM32_RTC_CR (STM32_RTC_BASE+STM32_RTC_CR_OFFSET)
|
||||
#define STM32_RTC_ISR (STM32_RTC_BASE+STM32_RTC_ISR_OFFSET)
|
||||
#define STM32_RTC_PRER (STM32_RTC_BASE+STM32_RTC_PRER_OFFSET)
|
||||
#define STM32_RTC_WUTR (STM32_RTC_BASE+STM32_RTC_WUTR_OFFSET)
|
||||
#define STM32_RTC_CALIBR (STM32_RTC_BASE+STM32_RTC_CALIBR_OFFSET)
|
||||
#define STM32_RTC_ALRMAR (STM32_RTC_BASE+STM32_RTC_ALRMAR_OFFSET)
|
||||
#define STM32_RTC_ALRMBR (STM32_RTC_BASE+STM32_RTC_ALRMBR_OFFSET)
|
||||
#define STM32_RTC_WPR (STM32_RTC_BASE+STM32_RTC_WPR_OFFSET)
|
||||
#define STM32_RTC_SSR (STM32_RTC_BASE+STM32_RTC_SSR_OFFSET)
|
||||
#define STM32_RTC_SHIFTR (STM32_RTC_BASE+STM32_RTC_SHIFTR_OFFSET)
|
||||
#define STM32_RTC_TSTR (STM32_RTC_BASE+STM32_RTC_TSTR_OFFSET)
|
||||
#define STM32_RTC_TSDR (STM32_RTC_BASE+STM32_RTC_TSDR_OFFSET)
|
||||
#define STM32_RTC_TSSSR (STM32_RTC_BASE+STM32_RTC_TSSSR_OFFSET)
|
||||
#define STM32_RTC_CALR (STM32_RTC_BASE+STM32_RTC_CALR_OFFSET)
|
||||
#define STM32_RTC_TAFCR (STM32_RTC_BASE+STM32_RTC_TAFCR_OFFSET)
|
||||
#define STM32_RTC_ALRMASSR (STM32_RTC_BASE+STM32_RTC_ALRMASSR_OFFSET)
|
||||
#define STM32_RTC_ALRMBSSR (STM32_RTC_BASE+STM32_RTC_ALRMBSSR_OFFSET)
|
||||
|
||||
#define STM32_RTC_BKR(n) (STM32_RTC_BASE+STM32_RTC_BKR_OFFSET(n))
|
||||
#define STM32_RTC_BK0R (STM32_RTC_BASE+STM32_RTC_BK0R_OFFSET)
|
||||
#define STM32_RTC_BK1R (STM32_RTC_BASE+STM32_RTC_BK1R_OFFSET)
|
||||
#define STM32_RTC_BK2R (STM32_RTC_BASE+STM32_RTC_BK2R_OFFSET)
|
||||
#define STM32_RTC_BK3R (STM32_RTC_BASE+STM32_RTC_BK3R_OFFSET)
|
||||
#define STM32_RTC_BK4R (STM32_RTC_BASE+STM32_RTC_BK4R_OFFSET)
|
||||
#define STM32_RTC_BK5R (STM32_RTC_BASE+STM32_RTC_BK5R_OFFSET)
|
||||
#define STM32_RTC_BK6R (STM32_RTC_BASE+STM32_RTC_BK6R_OFFSET)
|
||||
#define STM32_RTC_BK7R (STM32_RTC_BASE+STM32_RTC_BK7R_OFFSET)
|
||||
#define STM32_RTC_BK8R (STM32_RTC_BASE+STM32_RTC_BK8R_OFFSET)
|
||||
#define STM32_RTC_BK9R (STM32_RTC_BASE+STM32_RTC_BK9R_OFFSET)
|
||||
#define STM32_RTC_BK10R (STM32_RTC_BASE+STM32_RTC_BK10R_OFFSET)
|
||||
#define STM32_RTC_BK11R (STM32_RTC_BASE+STM32_RTC_BK11R_OFFSET)
|
||||
#define STM32_RTC_BK12R (STM32_RTC_BASE+STM32_RTC_BK12R_OFFSET)
|
||||
#define STM32_RTC_BK13R (STM32_RTC_BASE+STM32_RTC_BK13R_OFFSET)
|
||||
#define STM32_RTC_BK14R (STM32_RTC_BASE+STM32_RTC_BK14R_OFFSET)
|
||||
#define STM32_RTC_BK15R (STM32_RTC_BASE+STM32_RTC_BK15R_OFFSET)
|
||||
#define STM32_RTC_BK16R (STM32_RTC_BASE+STM32_RTC_BK16R_OFFSET)
|
||||
#define STM32_RTC_BK17R (STM32_RTC_BASE+STM32_RTC_BK17R_OFFSET)
|
||||
#define STM32_RTC_BK18R (STM32_RTC_BASE+STM32_RTC_BK18R_OFFSET)
|
||||
#define STM32_RTC_BK19R (STM32_RTC_BASE+STM32_RTC_BK19R_OFFSET)
|
||||
|
||||
/* 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_DCE (1 << 7) /* Bit 7: Coarse digital calibration enable */
|
||||
#define RTC_CR_ALRAE (1 << 8) /* Bit 8: Alarm A enable */
|
||||
#define RTC_CR_ALRBE (1 << 9) /* Bit 9: Alarm B 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_ALRBIE (1 << 13) /* Bit 13: Alarm B 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_ALRBWF (1 << 1) /* Bit 1: Alarm B 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_ALRBF (1 << 9) /* Bit 9: Alarm B 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_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 calibration register */
|
||||
|
||||
#define RTC_CALIBR_DCS (1 << 7) /* Bit 7 Digital calibration sign */
|
||||
#define RTC_CALIBR_DC_SHIFT (0) /* Bits 4:0 0-4: Digital calibration */
|
||||
#define RTC_CALIBR_DC_MASK (31 << RTC_CALIBR_DC_SHIFT)
|
||||
# define RTC_CALIBR_DC(n) (((n) >> 2) << RTC_CALIBR_DC_SHIFT) /* n= 0, 4, 8, ... 126 */
|
||||
|
||||
/* RTC alarm A/B registers */
|
||||
|
||||
#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 (0x7ffff << 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_
|
||||
|
||||
/* RTC tamper and alternate function configuration register */
|
||||
|
||||
#define RTC_TAFCR_CALM_SHIFT (0) /* Bits 0-8: Calibration minus */
|
||||
#define RTC_TAFCR_CALM_MASK (0x1ff << RTC_TAFCR_CALM_SHIFT)
|
||||
#define RTC_TAFCR_CALW16 (1 << 13) /* Bit 13: Use a 16-second calibration cycle period */
|
||||
#define RTC_TAFCR_CALW8 (1 << 14) /* Bit 14: Use an 8-second calibration cycle period */
|
||||
#define RTC_TAFCR_CALP (1 << 15) /* Bit 15: Increase frequency of RTC by 488.5 ppm */
|
||||
|
||||
/* RTC alarm A/B sub second register */
|
||||
|
||||
#define RTC_ALRMSSR_SS_SHIFT (0) /* Bits 0-15: Sub second value */
|
||||
#define RTC_ALRMSSR_SS_MASK (0xffff << RTC_ALRMSSR_SS_SHIFT)
|
||||
#define RTC_ALRMSSR_MASKSS_SHIFT (0) /* Bits 24-27: Mask the most-significant bits starting at this bit */
|
||||
#define RTC_ALRMSSR_MASKSS_MASK (0xffff << RTC_ALRMSSR_SS_SHIFT)
|
||||
|
||||
#endif /* __ARCH_ARM_SRC_STM32_CHIP_STM32F20XXX_RTC_H */
|
|
@ -0,0 +1,142 @@
|
|||
/************************************************************************************
|
||||
* arch/arm/src/stm32/chip/stm32f20xxx_vectors.h
|
||||
*
|
||||
* Copyright (C) 2012 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.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
/************************************************************************************
|
||||
* Pre-processor definitions
|
||||
************************************************************************************/
|
||||
|
||||
/* This file is included by stm32_vectors.S. It provides the macro VECTOR that
|
||||
* supplies ach STM32F20xxx vector in terms of a (lower-case) ISR label and an
|
||||
* (upper-case) IRQ number as defined in arch/arm/include/stm32/stm32f20xxx_irq.h.
|
||||
* stm32_vectors.S will defined the VECTOR in different ways in order to generate
|
||||
* the interrupt vectors and handlers in their final form.
|
||||
*/
|
||||
|
||||
/* If the common ARMv7-M vector handling is used, then all it needs is the following
|
||||
* definition that provides the number of supported vectors.
|
||||
*/
|
||||
|
||||
#ifdef CONFIG_ARMV7M_CMNVECTOR
|
||||
|
||||
/* Reserve 82 interrupt table entries for I/O interrupts. */
|
||||
|
||||
# define ARMV7M_PERIPHERAL_INTERRUPTS 82
|
||||
|
||||
#else
|
||||
|
||||
VECTOR(stm32_wwdg, STM32_IRQ_WWDG) /* Vector 16+0: Window Watchdog interrupt */
|
||||
VECTOR(stm32_pvd, STM32_IRQ_PVD) /* Vector 16+1: PVD through EXTI Line detection interrupt */
|
||||
VECTOR(stm32_tamper, STM32_IRQ_TAMPER) /* Vector 16+2: Tamper and time stamp interrupts */
|
||||
VECTOR(stm32_rtc_wkup, STM32_IRQ_RTC_WKUP) /* Vector 16+3: RTC global interrupt */
|
||||
VECTOR(stm32_flash, STM32_IRQ_FLASH) /* Vector 16+4: Flash global interrupt */
|
||||
VECTOR(stm32_rcc, STM32_IRQ_RCC) /* Vector 16+5: RCC global interrupt */
|
||||
VECTOR(stm32_exti0, STM32_IRQ_EXTI0) /* Vector 16+6: EXTI Line 0 interrupt */
|
||||
VECTOR(stm32_exti1, STM32_IRQ_EXTI1) /* Vector 16+7: EXTI Line 1 interrupt */
|
||||
VECTOR(stm32_exti2, STM32_IRQ_EXTI2) /* Vector 16+8: EXTI Line 2 interrupt */
|
||||
VECTOR(stm32_exti3, STM32_IRQ_EXTI3) /* Vector 16+9: EXTI Line 3 interrupt */
|
||||
VECTOR(stm32_exti4, STM32_IRQ_EXTI4) /* Vector 16+10: EXTI Line 4 interrupt */
|
||||
VECTOR(stm32_dma1s0, STM32_IRQ_DMA1S0) /* Vector 16+11: DMA1 Stream 0 global interrupt */
|
||||
VECTOR(stm32_dma1s1, STM32_IRQ_DMA1S1) /* Vector 16+12: DMA1 Stream 1 global interrupt */
|
||||
VECTOR(stm32_dma1s2, STM32_IRQ_DMA1S2) /* Vector 16+13: DMA1 Stream 2 global interrupt */
|
||||
VECTOR(stm32_dma1s3, STM32_IRQ_DMA1S3) /* Vector 16+14: DMA1 Stream 3 global interrupt */
|
||||
VECTOR(stm32_dma1s4, STM32_IRQ_DMA1S4) /* Vector 16+15: DMA1 Stream 4 global interrupt */
|
||||
VECTOR(stm32_dma1s5, STM32_IRQ_DMA1S5) /* Vector 16+16: DMA1 Stream 5 global interrupt */
|
||||
VECTOR(stm32_dma1s6, STM32_IRQ_DMA1S6) /* Vector 16+17: DMA1 Stream 6 global interrupt */
|
||||
VECTOR(stm32_adc, STM32_IRQ_ADC) /* Vector 16+18: ADC1, ADC2, and ADC3 global interrupt */
|
||||
VECTOR(stm32_can1tx, STM32_IRQ_CAN1TX) /* Vector 16+19: CAN1 TX interrupts */
|
||||
VECTOR(stm32_can1rx0, STM32_IRQ_CAN1RX0) /* Vector 16+20: CAN1 RX0 interrupts */
|
||||
VECTOR(stm32_can1rx1, STM32_IRQ_CAN1RX1) /* Vector 16+21: CAN1 RX1 interrupt */
|
||||
VECTOR(stm32_can1sce, STM32_IRQ_CAN1SCE) /* Vector 16+22: CAN1 SCE interrupt */
|
||||
VECTOR(stm32_exti95, STM32_IRQ_EXTI95) /* Vector 16+23: EXTI Line[9:5] interrupts */
|
||||
VECTOR(stm32_tim1brk, STM32_IRQ_TIM1BRK) /* Vector 16+24: TIM1 Break interrupt/TIM9 global interrupt */
|
||||
VECTOR(stm32_tim1up, STM32_IRQ_TIM1UP) /* Vector 16+25: TIM1 Update interrupt/TIM10 global interrupt */
|
||||
VECTOR(stm32_tim1trgcom, STM32_IRQ_TIM1TRGCOM) /* Vector 16+26: TIM1 Trigger and Commutation interrupts/TIM11 global interrupt */
|
||||
VECTOR(stm32_tim1cc, STM32_IRQ_TIM1CC) /* Vector 16+27: TIM1 Capture Compare interrupt */
|
||||
VECTOR(stm32_tim2, STM32_IRQ_TIM2) /* Vector 16+28: TIM2 global interrupt */
|
||||
VECTOR(stm32_tim3, STM32_IRQ_TIM3) /* Vector 16+29: TIM3 global interrupt */
|
||||
VECTOR(stm32_tim4, STM32_IRQ_TIM4) /* Vector 16+30: TIM4 global interrupt */
|
||||
VECTOR(stm32_i2c1ev, STM32_IRQ_I2C1EV) /* Vector 16+31: I2C1 event interrupt */
|
||||
VECTOR(stm32_i2c1er, STM32_IRQ_I2C1ER) /* Vector 16+32: I2C1 error interrupt */
|
||||
VECTOR(stm32_i2c2ev, STM32_IRQ_I2C2EV) /* Vector 16+33: I2C2 event interrupt */
|
||||
VECTOR(stm32_i2c2er, STM32_IRQ_I2C2ER) /* Vector 16+34: I2C2 error interrupt */
|
||||
VECTOR(stm32_spi1, STM32_IRQ_SPI1) /* Vector 16+35: SPI1 global interrupt */
|
||||
VECTOR(stm32_spi2, STM32_IRQ_SPI2) /* Vector 16+36: SPI2 global interrupt */
|
||||
VECTOR(stm32_usart1, STM32_IRQ_USART1) /* Vector 16+37: USART1 global interrupt */
|
||||
VECTOR(stm32_usart2, STM32_IRQ_USART2) /* Vector 16+38: USART2 global interrupt */
|
||||
VECTOR(stm32_usart3, STM32_IRQ_USART3) /* Vector 16+39: USART3 global interrupt */
|
||||
VECTOR(stm32_exti1510, STM32_IRQ_EXTI1510) /* Vector 16+40: EXTI Line[15:10] interrupts */
|
||||
VECTOR(stm32_rtcalrm, STM32_IRQ_RTCALRM) /* Vector 16+41: RTC alarm through EXTI line interrupt */
|
||||
VECTOR(stm32_otgfswkup, STM32_IRQ_OTGFSWKUP) /* Vector 16+42: USB On-The-Go FS Wakeup through EXTI line interrupt */
|
||||
VECTOR(stm32_tim8brk, STM32_IRQ_TIM8BRK) /* Vector 16+43: TIM8 Break interrupt/TIM12 global interrupt */
|
||||
VECTOR(stm32_tim8up, STM32_IRQ_TIM8UP) /* Vector 16+44: TIM8 Update interrup/TIM13 global interrupt */
|
||||
VECTOR(stm32_tim8trgcom, STM32_IRQ_TIM8TRGCOM) /* Vector 16+45: TIM8 Trigger and Commutation interrupts/TIM14 global interrupt */
|
||||
VECTOR(stm32_tim8cc, STM32_IRQ_TIM8CC) /* Vector 16+46: TIM8 Capture Compare interrupt */
|
||||
VECTOR(stm32_dma1s7, STM32_IRQ_DMA1S7) /* Vector 16+47: DMA1 Stream 7 global interrupt */
|
||||
VECTOR(stm32_fsmc, STM32_IRQ_FSMC) /* Vector 16+48: FSMC global interrupt */
|
||||
VECTOR(stm32_sdio, STM32_IRQ_SDIO) /* Vector 16+49: SDIO global interrupt */
|
||||
VECTOR(stm32_tim5, STM32_IRQ_TIM5) /* Vector 16+50: TIM5 global interrupt */
|
||||
VECTOR(stm32_spi3, STM32_IRQ_SPI3) /* Vector 16+51: SPI3 global interrupt */
|
||||
VECTOR(stm32_uart4, STM32_IRQ_UART4) /* Vector 16+52: UART4 global interrupt */
|
||||
VECTOR(stm32_uart5, STM32_IRQ_UART5) /* Vector 16+53: UART5 global interrupt */
|
||||
VECTOR(stm32_tim6, STM32_IRQ_TIM6) /* Vector 16+54: TIM6 global interrupt/DAC1 and DAC2 underrun error interrupts */
|
||||
VECTOR(stm32_tim7, STM32_IRQ_TIM7) /* Vector 16+55: TIM7 global interrupt */
|
||||
VECTOR(stm32_dma2s0, STM32_IRQ_DMA2S0) /* Vector 16+56: DMA2 Stream 0 global interrupt */
|
||||
VECTOR(stm32_dma2s1, STM32_IRQ_DMA2S1) /* Vector 16+57: DMA2 Stream 1 global interrupt */
|
||||
VECTOR(stm32_dma2s2, STM32_IRQ_DMA2S2) /* Vector 16+58: DMA2 Stream 2 global interrupt */
|
||||
VECTOR(stm32_dma2s3, STM32_IRQ_DMA2S3) /* Vector 16+59: DMA2 Stream 3 global interrupt */
|
||||
VECTOR(stm32_dma2s4, STM32_IRQ_DMA2S4) /* Vector 16+60: DMA2 Stream 4 global interrupt */
|
||||
VECTOR(stm32_eth, STM32_IRQ_ETH) /* Vector 16+61: Ethernet global interrupt */
|
||||
VECTOR(stm32_ethwkup, STM32_IRQ_ETHWKUP) /* Vector 16+62: Ethernet Wakeup through EXTI line interrupt */
|
||||
VECTOR(stm32_can2tx, STM32_IRQ_CAN2TX) /* Vector 16+63: CAN2 TX interrupts */
|
||||
VECTOR(stm32_can2rx0, STM32_IRQ_CAN2RX0) /* Vector 16+64: CAN2 RX0 interrupts */
|
||||
VECTOR(stm32_can2rx1, STM32_IRQ_CAN2RX1) /* Vector 16+65: CAN2 RX1 interrupt */
|
||||
VECTOR(stm32_can2sce, STM32_IRQ_CAN2SCE) /* Vector 16+66: CAN2 SCE interrupt */
|
||||
VECTOR(stm32_otgfs, STM32_IRQ_OTGFS) /* Vector 16+67: USB On The Go FS global interrupt */
|
||||
VECTOR(stm32_dma2s5, STM32_IRQ_DMA2S5) /* Vector 16+68: DMA2 Stream 5 global interrupt */
|
||||
VECTOR(stm32_dma2s6, STM32_IRQ_DMA2S6) /* Vector 16+69: DMA2 Stream 6 global interrupt */
|
||||
VECTOR(stm32_dma2s7, STM32_IRQ_DMA2S7) /* Vector 16+70: DMA2 Stream 7 global interrupt */
|
||||
VECTOR(stm32_usart6, STM32_IRQ_USART6) /* Vector 16+71: USART6 global interrupt */
|
||||
VECTOR(stm32_i2c3ev, STM32_IRQ_I2C3EV) /* Vector 16+72: I2C3 event interrupt */
|
||||
VECTOR(stm32_i2c3er, STM32_IRQ_I2C3ER) /* Vector 16+73: I2C3 error interrupt */
|
||||
VECTOR(stm32_otghsep1out, STM32_IRQ_OTGHSEP1OUT) /* Vector 16+74: USB On The Go HS End Point 1 Out global interrupt */
|
||||
VECTOR(stm32_otghsep1in, STM32_IRQ_OTGHSEP1IN) /* Vector 16+75: USB On The Go HS End Point 1 In global interrupt */
|
||||
VECTOR(stm32_otghswkup, STM32_IRQ_OTGHSWKUP) /* Vector 16+76: USB On The Go HS Wakeup through EXTI interrupt */
|
||||
VECTOR(stm32_otghs, STM32_IRQ_OTGHS ) /* Vector 16+77: USB On The Go HS global interrupt */
|
||||
VECTOR(stm32_dcmi, STM32_IRQ_DCMI) /* Vector 16+78: DCMI global interrupt */
|
||||
VECTOR(stm32_cryp, STM32_IRQ_CRYP) /* Vector 16+79: CRYP crypto global interrupt */
|
||||
VECTOR(stm32_hash, STM32_IRQ_HASH) /* Vector 16+80: Hash and Rng global interrupt */
|
||||
VECTOR(stm32_fpu, STM32_IRQ_FPU) /* Vector 16+81: FPU global interrupt */
|
||||
|
||||
#endif /* CONFIG_ARMV7M_CMNVECTOR */
|
|
@ -0,0 +1,661 @@
|
|||
/****************************************************************************
|
||||
* arch/arm/src/stm32/stm32f20xxx_dma.c
|
||||
*
|
||||
* Copyright (C) 2011 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 <stdint.h>
|
||||
#include <stdbool.h>
|
||||
#include <semaphore.h>
|
||||
#include <debug.h>
|
||||
#include <errno.h>
|
||||
|
||||
#include <nuttx/irq.h>
|
||||
#include <nuttx/arch.h>
|
||||
#include <arch/irq.h>
|
||||
|
||||
#include "up_arch.h"
|
||||
#include "up_internal.h"
|
||||
#include "os_internal.h"
|
||||
#include "chip.h"
|
||||
#include "stm32_dma.h"
|
||||
#include "stm32_internal.h"
|
||||
|
||||
/* This file supports only the STM32 F2 family
|
||||
*/
|
||||
|
||||
#if defined(CONFIG_STM32_STM32F20XX)
|
||||
|
||||
/****************************************************************************
|
||||
* Pre-processor Definitions
|
||||
****************************************************************************/
|
||||
|
||||
#define DMA1_NSTREAMS 8
|
||||
#if STM32_NDMA > 1
|
||||
# define DMA2_NSTREAMS 8
|
||||
# define DMA_NSTREAMS (DMA1_NSTREAMS+DMA2_NSTREAMS)
|
||||
#else
|
||||
# define DMA_NSTREAMS DMA1_NSTREAMS
|
||||
#endif
|
||||
|
||||
#ifndef CONFIG_DMA_PRI
|
||||
# define CONFIG_DMA_PRI NVIC_SYSH_PRIORITY_DEFAULT
|
||||
#endif
|
||||
|
||||
/* Convert the DMA stream base address to the DMA register block address */
|
||||
|
||||
#define DMA_BASE(ch) (ch & 0xfffffc00)
|
||||
|
||||
/****************************************************************************
|
||||
* Private Types
|
||||
****************************************************************************/
|
||||
|
||||
/* This structure descibes one DMA channel */
|
||||
|
||||
struct stm32_dma_s
|
||||
{
|
||||
uint8_t stream; /* DMA stream number (0-7) */
|
||||
uint8_t irq; /* DMA stream IRQ number */
|
||||
uint8_t shift; /* ISR/IFCR bit shift value */
|
||||
uint8_t pad; /* Unused */
|
||||
sem_t sem; /* Used to wait for DMA channel to become available */
|
||||
uint32_t base; /* DMA register channel base address */
|
||||
dma_callback_t callback; /* Callback invoked when the DMA completes */
|
||||
void *arg; /* Argument passed to callback function */
|
||||
};
|
||||
|
||||
/****************************************************************************
|
||||
* Private Data
|
||||
****************************************************************************/
|
||||
|
||||
/* This array describes the state of each DMA */
|
||||
|
||||
static struct stm32_dma_s g_dma[DMA_NSTREAMS] =
|
||||
{
|
||||
{
|
||||
.stream = 0,
|
||||
.irq = STM32_IRQ_DMA1S0,
|
||||
.shift = DMA_INT_STREAM0_SHIFT,
|
||||
.base = STM32_DMA1_BASE + STM32_DMA_OFFSET(0),
|
||||
},
|
||||
{
|
||||
.stream = 1,
|
||||
.irq = STM32_IRQ_DMA1S1,
|
||||
.shift = DMA_INT_STREAM1_SHIFT,
|
||||
.base = STM32_DMA1_BASE + STM32_DMA_OFFSET(1),
|
||||
},
|
||||
{
|
||||
.stream = 2,
|
||||
.irq = STM32_IRQ_DMA1S2,
|
||||
.shift = DMA_INT_STREAM2_SHIFT,
|
||||
.base = STM32_DMA1_BASE + STM32_DMA_OFFSET(2),
|
||||
},
|
||||
{
|
||||
.stream = 3,
|
||||
.irq = STM32_IRQ_DMA1S3,
|
||||
.shift = DMA_INT_STREAM3_SHIFT,
|
||||
.base = STM32_DMA1_BASE + STM32_DMA_OFFSET(4),
|
||||
},
|
||||
{
|
||||
.stream = 4,
|
||||
.irq = STM32_IRQ_DMA1S4,
|
||||
.shift = DMA_INT_STREAM4_SHIFT,
|
||||
.base = STM32_DMA1_BASE + STM32_DMA_OFFSET(4),
|
||||
},
|
||||
{
|
||||
.stream = 5,
|
||||
.irq = STM32_IRQ_DMA1S5,
|
||||
.shift = DMA_INT_STREAM5_SHIFT,
|
||||
.base = STM32_DMA1_BASE + STM32_DMA_OFFSET(5),
|
||||
},
|
||||
{
|
||||
.stream = 6,
|
||||
.irq = STM32_IRQ_DMA1S6,
|
||||
.shift = DMA_INT_STREAM6_SHIFT,
|
||||
.base = STM32_DMA1_BASE + STM32_DMA_OFFSET(6),
|
||||
},
|
||||
{
|
||||
.stream = 7,
|
||||
.irq = STM32_IRQ_DMA1S7,
|
||||
.shift = DMA_INT_STREAM7_SHIFT,
|
||||
.base = STM32_DMA1_BASE + STM32_DMA_OFFSET(7),
|
||||
},
|
||||
#if STM32_NDMA > 1
|
||||
{
|
||||
.stream = 0,
|
||||
.irq = STM32_IRQ_DMA2S0,
|
||||
.shift = DMA_INT_STREAM0_SHIFT,
|
||||
.base = STM32_DMA2_BASE + STM32_DMA_OFFSET(0),
|
||||
},
|
||||
{
|
||||
.stream = 1,
|
||||
.irq = STM32_IRQ_DMA2S1,
|
||||
.shift = DMA_INT_STREAM1_SHIFT,
|
||||
.base = STM32_DMA2_BASE + STM32_DMA_OFFSET(1),
|
||||
},
|
||||
{
|
||||
.stream = 2,
|
||||
.irq = STM32_IRQ_DMA2S2,
|
||||
.shift = DMA_INT_STREAM2_SHIFT,
|
||||
.base = STM32_DMA2_BASE + STM32_DMA_OFFSET(2),
|
||||
},
|
||||
{
|
||||
.stream = 3,
|
||||
.irq = STM32_IRQ_DMA2S3,
|
||||
.shift = DMA_INT_STREAM3_SHIFT,
|
||||
.base = STM32_DMA2_BASE + STM32_DMA_OFFSET(3),
|
||||
},
|
||||
{
|
||||
.stream = 4,
|
||||
.irq = STM32_IRQ_DMA2S4,
|
||||
.base = STM32_DMA2_BASE + STM32_DMA_OFFSET(4),
|
||||
},
|
||||
{
|
||||
.stream = 5,
|
||||
.irq = STM32_IRQ_DMA2S5,
|
||||
.shift = DMA_INT_STREAM5_SHIFT,
|
||||
.base = STM32_DMA2_BASE + STM32_DMA_OFFSET(5),
|
||||
},
|
||||
{
|
||||
.stream = 6,
|
||||
.irq = STM32_IRQ_DMA2S6,
|
||||
.shift = DMA_INT_STREAM6_SHIFT,
|
||||
.base = STM32_DMA2_BASE + STM32_DMA_OFFSET(6),
|
||||
},
|
||||
{
|
||||
.stream = 7,
|
||||
.irq = STM32_IRQ_DMA2S7,
|
||||
.shift = DMA_INT_STREAM7_SHIFT,
|
||||
.base = STM32_DMA2_BASE + STM32_DMA_OFFSET(7),
|
||||
},
|
||||
#endif
|
||||
};
|
||||
|
||||
/****************************************************************************
|
||||
* Private Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* DMA register access functions
|
||||
****************************************************************************/
|
||||
|
||||
/* Get non-channel register from DMA1 or DMA2 */
|
||||
|
||||
static inline uint32_t dmabase_getreg(struct stm32_dma_s *dmast, uint32_t offset)
|
||||
{
|
||||
return getreg32(DMA_BASE(dmast->base) + offset);
|
||||
}
|
||||
|
||||
/* Write to non-channel register in DMA1 or DMA2 */
|
||||
|
||||
static inline void dmabase_putreg(struct stm32_dma_s *dmast, uint32_t offset, uint32_t value)
|
||||
{
|
||||
putreg32(value, DMA_BASE(dmast->base) + offset);
|
||||
}
|
||||
|
||||
/* Get channel register from DMA1 or DMA2 */
|
||||
|
||||
static inline uint32_t dmast_getreg(struct stm32_dma_s *dmast, uint32_t offset)
|
||||
{
|
||||
return getreg32(dmast->base + offset);
|
||||
}
|
||||
|
||||
/* Write to channel register in DMA1 or DMA2 */
|
||||
|
||||
static inline void dmast_putreg(struct stm32_dma_s *dmast, uint32_t offset, uint32_t value)
|
||||
{
|
||||
putreg32(value, dmast->base + offset);
|
||||
}
|
||||
|
||||
/************************************************************************************
|
||||
* Name: stm32_dmatake() and stm32_dmagive()
|
||||
*
|
||||
* Description:
|
||||
* Used to get exclusive access to a DMA channel.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
static void stm32_dmatake(FAR struct stm32_dma_s *dmast)
|
||||
{
|
||||
/* Take the semaphore (perhaps waiting) */
|
||||
|
||||
while (sem_wait(&dmast->sem) != 0)
|
||||
{
|
||||
/* The only case that an error should occur here is if the wait was awakened
|
||||
* by a signal.
|
||||
*/
|
||||
|
||||
ASSERT(errno == EINTR);
|
||||
}
|
||||
}
|
||||
|
||||
static inline void stm32_dmagive(FAR struct stm32_dma_s *dmast)
|
||||
{
|
||||
(void)sem_post(&dmast->sem);
|
||||
}
|
||||
|
||||
/************************************************************************************
|
||||
* Name: stm32_dmastreamdisable
|
||||
*
|
||||
* Description:
|
||||
* Disable the DMA stream
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
static void stm32_dmastreamdisable(struct stm32_dma_s *dmast)
|
||||
{
|
||||
uint32_t regoffset;
|
||||
uint32_t regval;
|
||||
|
||||
/* Disable all interrupts at the DMA controller */
|
||||
|
||||
regval = dmast_getreg(dmast, STM32_DMA_SCR_OFFSET);
|
||||
regval &= ~DMA_SCR_ALLINTS;
|
||||
|
||||
/* Disable the DMA stream */
|
||||
|
||||
regval &= ~DMA_SCR_EN;
|
||||
dmast_putreg(dmast, STM32_DMA_SCR_OFFSET, regval);
|
||||
|
||||
/* Clear pending stream interrupts by setting bits in the upper or lower IFCR
|
||||
* register
|
||||
*/
|
||||
|
||||
if (dmast->stream < 4)
|
||||
{
|
||||
regoffset = STM32_DMA_LIFCR_OFFSET;
|
||||
}
|
||||
else
|
||||
{
|
||||
regoffset = STM32_DMA_HIFCR_OFFSET;
|
||||
}
|
||||
|
||||
dmabase_putreg(dmast, regoffset, (DMA_STREAM_MASK << dmast->shift));
|
||||
}
|
||||
|
||||
/************************************************************************************
|
||||
* Name: stm32_dmainterrupt
|
||||
*
|
||||
* Description:
|
||||
* DMA interrupt handler
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
static int stm32_dmainterrupt(int irq, void *context)
|
||||
{
|
||||
struct stm32_dma_s *dmast;
|
||||
uint32_t isr;
|
||||
uint32_t regoffset = 0;
|
||||
int stndx = 0;
|
||||
|
||||
/* Get the stream structure from the interrupt number */
|
||||
|
||||
if (irq >= STM32_IRQ_DMA1S0 && irq <= STM32_IRQ_DMA1S7)
|
||||
{
|
||||
stndx = irq - STM32_IRQ_DMA1S0;
|
||||
regoffset = STM32_DMA_LISR_OFFSET;
|
||||
}
|
||||
else
|
||||
#if STM32_NDMA > 1
|
||||
if (irq >= STM32_IRQ_DMA2S0 && irq <= STM32_IRQ_DMA2S7)
|
||||
{
|
||||
stndx = irq - STM32_IRQ_DMA2S0 + DMA1_NSTREAMS;
|
||||
regoffset = STM32_DMA_HISR_OFFSET;
|
||||
}
|
||||
else
|
||||
#endif
|
||||
{
|
||||
PANIC(OSERR_INTERNAL);
|
||||
}
|
||||
dmast = &g_dma[stndx];
|
||||
|
||||
/* Get the interrupt status for this stream */
|
||||
|
||||
isr = (dmabase_getreg(dmast, regoffset) >> dmast->shift) & DMA_STREAM_MASK;
|
||||
|
||||
/* Disable the DMA stream */
|
||||
|
||||
stm32_dmastreamdisable(dmast);
|
||||
|
||||
/* Invoke the callback */
|
||||
|
||||
if (dmast->callback)
|
||||
{
|
||||
dmast->callback(dmast, isr, dmast->arg);
|
||||
}
|
||||
return OK;
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Public Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Name: stm32_dmainitialize
|
||||
*
|
||||
* Description:
|
||||
* Initialize the DMA subsystem
|
||||
*
|
||||
* Returned Value:
|
||||
* None
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
void weak_function up_dmainitialize(void)
|
||||
{
|
||||
struct stm32_dma_s *dmast;
|
||||
int stndx;
|
||||
|
||||
/* Initialize each DMA stream */
|
||||
|
||||
for (stndx = 0; stndx < DMA_NSTREAMS; stndx++)
|
||||
{
|
||||
dmast = &g_dma[stndx];
|
||||
sem_init(&dmast->sem, 0, 1);
|
||||
|
||||
/* Attach DMA interrupt vectors */
|
||||
|
||||
(void)irq_attach(dmast->irq, stm32_dmainterrupt);
|
||||
|
||||
/* Disable the DMA stream */
|
||||
|
||||
stm32_dmastreamdisable(dmast);
|
||||
|
||||
/* Enable the IRQ at the NVIC (still disabled at the DMA controller) */
|
||||
|
||||
up_enable_irq(dmast->irq);
|
||||
|
||||
/* Set the interrrupt priority */
|
||||
|
||||
up_prioritize_irq(dmast->irq, CONFIG_DMA_PRI);
|
||||
}
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: stm32_dmachannel
|
||||
*
|
||||
* Description:
|
||||
* Allocate a DMA channel. This function gives the caller mutually
|
||||
* exclusive access to the DMA channel specified by the 'stndx' argument.
|
||||
* DMA channels are shared on the STM32: Devices sharing the same DMA
|
||||
* channel cannot do DMA concurrently! See the DMACHAN_* definitions in
|
||||
* stm32_dma.h.
|
||||
*
|
||||
* If the DMA channel is not available, then stm32_dmachannel() will wait
|
||||
* until the holder of the channel relinquishes the channel by calling
|
||||
* stm32_dmafree(). WARNING: If you have two devices sharing a DMA
|
||||
* channel and the code never releases the channel, the stm32_dmachannel
|
||||
* call for the other will hang forever in this function! Don't let your
|
||||
* design do that!
|
||||
*
|
||||
* Hmm.. I suppose this interface could be extended to make a non-blocking
|
||||
* version. Feel free to do that if that is what you need.
|
||||
*
|
||||
* Returned Value:
|
||||
* Provided that 'stndx' is valid, this function ALWAYS returns a non-NULL,
|
||||
* void* DMA channel handle. (If 'stndx' is invalid, the function will
|
||||
* assert if debug is enabled or do something ignorant otherwise).
|
||||
*
|
||||
* Assumptions:
|
||||
* - The caller does not hold he DMA channel.
|
||||
* - The caller can wait for the DMA channel to be freed if it is no
|
||||
* available.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
DMA_HANDLE stm32_dmachannel(int stndx)
|
||||
{
|
||||
struct stm32_dma_s *dmast = &g_dma[stndx];
|
||||
|
||||
DEBUGASSERT(stndx < DMA_NSTREAMS);
|
||||
|
||||
/* Get exclusive access to the DMA channel -- OR wait until the channel
|
||||
* is available if it is currently being used by another driver
|
||||
*/
|
||||
|
||||
stm32_dmatake(dmast);
|
||||
|
||||
/* The caller now has exclusive use of the DMA channel */
|
||||
|
||||
return (DMA_HANDLE)dmast;
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: stm32_dmafree
|
||||
*
|
||||
* Description:
|
||||
* Release a DMA channel. If another thread is waiting for this DMA channel
|
||||
* in a call to stm32_dmachannel, then this function will re-assign the
|
||||
* DMA channel to that thread and wake it up. NOTE: The 'handle' used
|
||||
* in this argument must NEVER be used again until stm32_dmachannel() is
|
||||
* called again to re-gain access to the channel.
|
||||
*
|
||||
* Returned Value:
|
||||
* None
|
||||
*
|
||||
* Assumptions:
|
||||
* - The caller holds the DMA channel.
|
||||
* - There is no DMA in progress
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
void stm32_dmafree(DMA_HANDLE handle)
|
||||
{
|
||||
struct stm32_dma_s *dmast = (struct stm32_dma_s *)handle;
|
||||
|
||||
DEBUGASSERT(handle != NULL);
|
||||
|
||||
/* Release the channel */
|
||||
|
||||
stm32_dmagive(dmast);
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: stm32_dmasetup
|
||||
*
|
||||
* Description:
|
||||
* Configure DMA before using
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
void stm32_dmasetup(DMA_HANDLE handle, uint32_t paddr, uint32_t maddr, size_t ntransfers, uint32_t scr)
|
||||
{
|
||||
struct stm32_dma_s *dmast = (struct stm32_dma_s *)handle;
|
||||
uint32_t regval;
|
||||
|
||||
/* Set the peripheral register address in the DMA_SPARx register. The data
|
||||
* will be moved from/to this address to/from the memory after the
|
||||
* peripheral event.
|
||||
*/
|
||||
|
||||
dmast_putreg(dmast, STM32_DMA_SPAR_OFFSET, paddr);
|
||||
|
||||
/* Set the memory address in the DMA_SM0ARx register. The data will be
|
||||
* written to or read from this memory after the peripheral event.
|
||||
* Note that only single-buffer mode is currently supported so SM1ARx
|
||||
* is not used.
|
||||
*/
|
||||
|
||||
dmast_putreg(dmast, STM32_DMA_SM0AR_OFFSET, maddr);
|
||||
|
||||
/* Configure the total number of data items to be transferred in the DMA_SNDTRx
|
||||
* register. After each peripheral event, this value will be decremented.
|
||||
*/
|
||||
|
||||
dmast_putreg(dmast, STM32_DMA_SNDTR_OFFSET, ntransfers);
|
||||
|
||||
/* Configure the stream priority using the PL[1:0] bits in the DMA_SCRx
|
||||
* register. Configure data transfer direction, circular mode, peripheral & memory
|
||||
* incremented mode, peripheral & memory data size, and interrupt after
|
||||
* half and/or full transfer in the DMA_CCRx register.
|
||||
*/
|
||||
|
||||
regval = dmast_getreg(dmast, STM32_DMA_SCR_OFFSET);
|
||||
regval &= ~(DMA_SCR_DIR_MASK|DMA_SCR_PINC|DMA_SCR_MINC|DMA_SCR_PSIZE_MASK|
|
||||
DMA_SCR_MSIZE_MASK|DMA_SCR_PINCOS|DMA_SCR_PL_MASK|DMA_SCR_PBURST_MASK|
|
||||
DMA_SCR_MBURST_MASK);
|
||||
scr &= (DMA_SCR_DIR_MASK|DMA_SCR_PINC|DMA_SCR_MINC|DMA_SCR_PSIZE_MASK|
|
||||
DMA_SCR_MSIZE_MASK|DMA_SCR_PINCOS|DMA_SCR_PL_MASK|DMA_SCR_PBURST_MASK|
|
||||
DMA_SCR_MBURST_MASK);
|
||||
regval |= scr;
|
||||
dmast_putreg(dmast, STM32_DMA_SCR_OFFSET, regval);
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: stm32_dmastart
|
||||
*
|
||||
* Description:
|
||||
* Start the DMA transfer
|
||||
*
|
||||
* Assumptions:
|
||||
* - DMA handle allocated by stm32_dmachannel()
|
||||
* - No DMA in progress
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
void stm32_dmastart(DMA_HANDLE handle, dma_callback_t callback, void *arg, bool half)
|
||||
{
|
||||
struct stm32_dma_s *dmast = (struct stm32_dma_s *)handle;
|
||||
uint32_t scr;
|
||||
|
||||
DEBUGASSERT(handle != NULL);
|
||||
|
||||
/* Save the callback info. This will be invoked whent the DMA commpletes */
|
||||
|
||||
dmast->callback = callback;
|
||||
dmast->arg = arg;
|
||||
|
||||
/* Activate the stream by setting the ENABLE bit in the DMA_SCRx register.
|
||||
* As soon as the stream is enabled, it can serve any DMA request from the
|
||||
* peripheral connected on the stream.
|
||||
*/
|
||||
|
||||
scr = dmast_getreg(dmast, STM32_DMA_SCR_OFFSET);
|
||||
scr |= DMA_SCR_EN;
|
||||
|
||||
/* Once half of the bytes are transferred, the half-transfer flag (HTIF) is
|
||||
* set and an interrupt is generated if the Half-Transfer Interrupt Enable
|
||||
* bit (HTIE) is set. At the end of the transfer, the Transfer Complete Flag
|
||||
* (TCIF) is set and an interrupt is generated if the Transfer Complete
|
||||
* Interrupt Enable bit (TCIE) is set.
|
||||
*/
|
||||
|
||||
scr |= (half ? (DMA_SCR_HTIE|DMA_SCR_TEIE) : (DMA_SCR_TCIE|DMA_SCR_TEIE));
|
||||
dmast_putreg(dmast, STM32_DMA_SCR_OFFSET, scr);
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: stm32_dmastop
|
||||
*
|
||||
* Description:
|
||||
* Cancel the DMA. After stm32_dmastop() is called, the DMA channel is
|
||||
* reset and stm32_dmasetup() must be called before stm32_dmastart() can be
|
||||
* called again
|
||||
*
|
||||
* Assumptions:
|
||||
* - DMA handle allocated by stm32_dmachannel()
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
void stm32_dmastop(DMA_HANDLE handle)
|
||||
{
|
||||
struct stm32_dma_s *dmast = (struct stm32_dma_s *)handle;
|
||||
stm32_dmastreamdisable(dmast);
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: stm32_dmasample
|
||||
*
|
||||
* Description:
|
||||
* Sample DMA register contents
|
||||
*
|
||||
* Assumptions:
|
||||
* - DMA handle allocated by stm32_dmachannel()
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#ifdef CONFIG_DEBUG_DMA
|
||||
void stm32_dmasample(DMA_HANDLE handle, struct stm32_dmaregs_s *regs)
|
||||
{
|
||||
struct stm32_dma_s *dmast = (struct stm32_dma_s *)handle;
|
||||
irqstate_t flags;
|
||||
|
||||
flags = irqsave();
|
||||
regs->lisr = dmabase_getreg(dmast, STM32_DMA_LISR_OFFSET);
|
||||
regs->hisr = dmabase_getreg(dmast, STM32_DMA_LISR_OFFSET);
|
||||
regs->scr = dmast_getreg(dmast, STM32_DMA_HISR_OFFSET);
|
||||
regs->sndtr = dmast_getreg(dmast, STM32_DMA_SNDTR_OFFSET);
|
||||
regs->spar = dmast_getreg(dmast, STM32_DMA_SPAR_OFFSET);
|
||||
regs->sm0ar = dmast_getreg(dmast, STM32_DMA_SM0AR_OFFSET);
|
||||
regs->sm1ar = dmast_getreg(dmast, STM32_DMA_SM1AR_OFFSET);
|
||||
regs->sfcr = dmast_getreg(dmast, STM32_DMA_SFCR_OFFSET);
|
||||
irqrestore(flags);
|
||||
}
|
||||
#endif
|
||||
|
||||
/****************************************************************************
|
||||
* Name: stm32_dmadump
|
||||
*
|
||||
* Description:
|
||||
* Dump previously sampled DMA register contents
|
||||
*
|
||||
* Assumptions:
|
||||
* - DMA handle allocated by stm32_dmachannel()
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#ifdef CONFIG_DEBUG_DMA
|
||||
void stm32_dmadump(DMA_HANDLE handle, const struct stm32_dmaregs_s *regs,
|
||||
const char *msg)
|
||||
{
|
||||
struct stm32_dma_s *dmast = (struct stm32_dma_s *)handle;
|
||||
uint32_t dmabase = DMA_BASE(dmast->base);
|
||||
|
||||
dmadbg("DMA Registers: %s\n", msg);
|
||||
dmadbg(" LISR[%08x]: %08x\n", dmabase + STM32_DMA_LISR_OFFSET, regs->lisr);
|
||||
dmadbg(" HISR[%08x]: %08x\n", dmabase + STM32_DMA_HISR_OFFSET, regs->hisr);
|
||||
dmadbg(" SCR[%08x]: %08x\n", dmast->base + STM32_DMA_SCR_OFFSET, regs->scr);
|
||||
dmadbg(" SNDTR[%08x]: %08x\n", dmast->base + STM32_DMA_SNDTR_OFFSET, regs->sndtr);
|
||||
dmadbg(" SPAR[%08x]: %08x\n", dmast->base + STM32_DMA_SPAR_OFFSET, regs->spar);
|
||||
dmadbg(" SM0AR[%08x]: %08x\n", dmast->base + STM32_DMA_SM0AR_OFFSET, regs->sm0ar);
|
||||
dmadbg(" SM1AR[%08x]: %08x\n", dmast->base + STM32_DMA_SM1AR_OFFSET, regs->sm1ar);
|
||||
dmadbg(" SFCRF[%08x]: %08x\n", dmast->base + STM32_DMA_SFCR_OFFSET, regs->sfcr);
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif /* CONFIG_STM32_STM32F20XX */
|
|
@ -0,0 +1,668 @@
|
|||
/****************************************************************************
|
||||
* arch/arm/src/stm32/stm32f20xxx_rcc.c
|
||||
*
|
||||
* Copyright (C) 2011 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
*
|
||||
* 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 "stm32_pwr.h"
|
||||
|
||||
/****************************************************************************
|
||||
* Definitions
|
||||
****************************************************************************/
|
||||
|
||||
/* Allow up to 100 milliseconds for the high speed clock to become ready.
|
||||
* that is a very long delay, but if the clock does not become ready we are
|
||||
* hosed anyway. Normally this is very fast, but I have seen at least one
|
||||
* board that required this long, long timeout for the HSE to be ready.
|
||||
*/
|
||||
|
||||
#define HSERDY_TIMEOUT (100 * CONFIG_BOARD_LOOPSPERMSEC)
|
||||
|
||||
/****************************************************************************
|
||||
* Private Data
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Private Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Name: rcc_reset
|
||||
*
|
||||
* Description:
|
||||
* Reset the RCC clock configuration to the default reset state
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
static inline void rcc_reset(void)
|
||||
{
|
||||
uint32_t regval;
|
||||
|
||||
/* Enable the Internal High Speed clock (HSI) */
|
||||
|
||||
regval = getreg32(STM32_RCC_CR);
|
||||
regval |= RCC_CR_HSION;
|
||||
putreg32(regval, STM32_RCC_CR);
|
||||
|
||||
/* Reset CFGR register */
|
||||
|
||||
putreg32(0x00000000, STM32_RCC_CFGR);
|
||||
|
||||
/* Reset HSEON, CSSON and PLLON bits */
|
||||
|
||||
regval = getreg32(STM32_RCC_CR);
|
||||
regval &= ~(RCC_CR_HSEON|RCC_CR_CSSON|RCC_CR_PLLON);
|
||||
putreg32(regval, STM32_RCC_CR);
|
||||
|
||||
/* Reset PLLCFGR register to reset default */
|
||||
|
||||
putreg32(RCC_PLLCFG_RESET, STM32_RCC_PLLCFG);
|
||||
|
||||
/* Reset HSEBYP bit */
|
||||
|
||||
regval = getreg32(STM32_RCC_CR);
|
||||
regval &= ~RCC_CR_HSEBYP;
|
||||
putreg32(regval, STM32_RCC_CR);
|
||||
|
||||
/* Disable all interrupts */
|
||||
|
||||
putreg32(0x00000000, STM32_RCC_CIR);
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: rcc_enableahb1
|
||||
*
|
||||
* Description:
|
||||
* Enable selected AHB1 peripherals
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
static inline void rcc_enableahb1(void)
|
||||
{
|
||||
uint32_t regval;
|
||||
|
||||
/* Set the appropriate bits in the AHB1ENR register to enabled the
|
||||
* selected AHB1 peripherals.
|
||||
*/
|
||||
|
||||
regval = getreg32(STM32_RCC_AHB1ENR);
|
||||
|
||||
/* Enable GPIOA, GPIOB, .... GPIOI*/
|
||||
|
||||
#if STM32_NGPIO > 0
|
||||
regval |= (RCC_AHB1ENR_GPIOAEN
|
||||
#if STM32_NGPIO > 16
|
||||
|RCC_AHB1ENR_GPIOBEN
|
||||
#endif
|
||||
#if STM32_NGPIO > 32
|
||||
|RCC_AHB1ENR_GPIOCEN
|
||||
#endif
|
||||
#if STM32_NGPIO > 48
|
||||
|RCC_AHB1ENR_GPIODEN
|
||||
#endif
|
||||
#if STM32_NGPIO > 64
|
||||
|RCC_AHB1ENR_GPIOEEN
|
||||
#endif
|
||||
#if STM32_NGPIO > 80
|
||||
|RCC_AHB1ENR_GPIOFEN
|
||||
#endif
|
||||
#if STM32_NGPIO > 96
|
||||
|RCC_AHB1ENR_GPIOGEN
|
||||
#endif
|
||||
#if STM32_NGPIO > 112
|
||||
|RCC_AHB1ENR_GPIOHEN
|
||||
#endif
|
||||
#if STM32_NGPIO > 128
|
||||
|RCC_AHB1ENR_GPIOIEN
|
||||
#endif
|
||||
);
|
||||
#endif
|
||||
|
||||
#if CONFIG_STM32_CRC
|
||||
/* CRC clock enable */
|
||||
|
||||
regval |= RCC_AHB1ENR_CRCEN;
|
||||
#endif
|
||||
|
||||
#if CONFIG_STM32_BKPSRAM
|
||||
/* Backup SRAM clock enable */
|
||||
|
||||
regval |= RCC_AHB1ENR_BKPSRAMEN;
|
||||
#endif
|
||||
|
||||
#if CONFIG_STM32_CCMDATARAM
|
||||
/* CCM data RAM clock enable */
|
||||
|
||||
regval |= RCC_AHB1ENR_CCMDATARAMEN;
|
||||
#endif
|
||||
|
||||
#if CONFIG_STM32_DMA1
|
||||
/* DMA 1 clock enable */
|
||||
|
||||
regval |= RCC_AHB1ENR_DMA1EN;
|
||||
#endif
|
||||
|
||||
#if CONFIG_STM32_DMA2
|
||||
/* DMA 2 clock enable */
|
||||
|
||||
regval |= RCC_AHB1ENR_DMA2EN;
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_STM32_ETHMAC
|
||||
/* Ethernet MAC clocking */
|
||||
|
||||
regval |= (RCC_AHB1ENR_ETHMACEN|RCC_AHB1ENR_ETHMACTXEN|RCC_AHB1ENR_ETHMACRXEN);
|
||||
|
||||
#ifdef CONFIG_STM32_ETH_PTP
|
||||
/* Precision Time Protocol (PTP) */
|
||||
|
||||
regval |= RCC_AHB1ENR_ETHMACPTPEN;
|
||||
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_STM32_OTGHS
|
||||
/* USB OTG HS */
|
||||
|
||||
regval |= (RCC_AHB1ENR_OTGHSEN|RCC_AHB1ENR_OTGHSULPIEN);
|
||||
#endif
|
||||
|
||||
putreg32(regval, STM32_RCC_AHB1ENR); /* Enable peripherals */
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: rcc_enableahb2
|
||||
*
|
||||
* Description:
|
||||
* Enable selected AHB2 peripherals
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
static inline void rcc_enableahb2(void)
|
||||
{
|
||||
uint32_t regval;
|
||||
|
||||
/* Set the appropriate bits in the AHB2ENR register to enabled the
|
||||
* selected AHB2 peripherals.
|
||||
*/
|
||||
|
||||
regval = getreg32(STM32_RCC_AHB2ENR);
|
||||
|
||||
#if CONFIG_STM32_DCMI
|
||||
/* Camera interface enable */
|
||||
|
||||
regval |= RCC_AHB2ENR_DCMIEN;
|
||||
#endif
|
||||
|
||||
#if CONFIG_STM32_CRYP
|
||||
/* Cryptographic modules clock enable */
|
||||
|
||||
regval |= RCC_AHB2ENR_CRYPEN;
|
||||
#endif
|
||||
|
||||
#if CONFIG_STM32_HASH
|
||||
/* Hash modules clock enable */
|
||||
|
||||
regval |= RCC_AHB2ENR_HASHEN;
|
||||
#endif
|
||||
|
||||
#if CONFIG_STM32_RNG
|
||||
/* Random number generator clock enable */
|
||||
|
||||
regval |= RCC_AHB2ENR_RNGEN;
|
||||
#endif
|
||||
|
||||
#if CONFIG_STM32_OTGFS
|
||||
/* USB OTG FS clock enable */
|
||||
|
||||
regval |= RCC_AHB2ENR_OTGFSEN;
|
||||
#endif
|
||||
|
||||
putreg32(regval, STM32_RCC_AHB2ENR); /* Enable peripherals */
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: rcc_enableahb3
|
||||
*
|
||||
* Description:
|
||||
* Enable selected AHB3 peripherals
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
static inline void rcc_enableahb3(void)
|
||||
{
|
||||
#if CONFIG_STM32_FSMC
|
||||
uint32_t regval;
|
||||
|
||||
/* Set the appropriate bits in the AHB3ENR register to enabled the
|
||||
* selected AHB3 peripherals.
|
||||
*/
|
||||
|
||||
regval = getreg32(STM32_RCC_AHB3ENR);
|
||||
|
||||
/* Flexible static memory controller module clock enable */
|
||||
|
||||
regval |= RCC_AHB3ENR_FSMCEN;
|
||||
|
||||
putreg32(regval, STM32_RCC_AHB3ENR); /* Enable peripherals */
|
||||
#endif
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: rcc_enableapb1
|
||||
*
|
||||
* Description:
|
||||
* Enable selected APB1 peripherals
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
static inline void rcc_enableapb1(void)
|
||||
{
|
||||
uint32_t regval;
|
||||
|
||||
/* Set the appropriate bits in the APB1ENR register to enabled the
|
||||
* selected APB1 peripherals.
|
||||
*/
|
||||
|
||||
regval = getreg32(STM32_RCC_APB1ENR);
|
||||
|
||||
#if CONFIG_STM32_TIM2
|
||||
/* TIM2 clock enable */
|
||||
|
||||
regval |= RCC_APB1ENR_TIM2EN;
|
||||
#endif
|
||||
|
||||
#if CONFIG_STM32_TIM3
|
||||
/* TIM3 clock enable */
|
||||
|
||||
regval |= RCC_APB1ENR_TIM3EN;
|
||||
#endif
|
||||
|
||||
#if CONFIG_STM32_TIM4
|
||||
/* TIM4 clock enable */
|
||||
|
||||
regval |= RCC_APB1ENR_TIM4EN;
|
||||
#endif
|
||||
|
||||
#if CONFIG_STM32_TIM5
|
||||
/* TIM5 clock enable */
|
||||
|
||||
regval |= RCC_APB1ENR_TIM5EN;
|
||||
#endif
|
||||
|
||||
#if CONFIG_STM32_TIM6
|
||||
/* TIM6 clock enable */
|
||||
|
||||
regval |= RCC_APB1ENR_TIM6EN;
|
||||
#endif
|
||||
|
||||
#if CONFIG_STM32_TIM7
|
||||
/* TIM7 clock enable */
|
||||
|
||||
regval |= RCC_APB1ENR_TIM7EN;
|
||||
#endif
|
||||
|
||||
#if CONFIG_STM32_TIM12
|
||||
/* TIM12 clock enable */
|
||||
|
||||
regval |= RCC_APB1ENR_TIM12EN;
|
||||
#endif
|
||||
|
||||
#if CONFIG_STM32_TIM13
|
||||
/* TIM13 clock enable */
|
||||
|
||||
regval |= RCC_APB1ENR_TIM13EN;
|
||||
#endif
|
||||
|
||||
#if CONFIG_STM32_TIM14
|
||||
/* TIM14 clock enable */
|
||||
|
||||
regval |= RCC_APB1ENR_TIM14EN;
|
||||
#endif
|
||||
|
||||
#if CONFIG_STM32_WWDG
|
||||
/* Window watchdog clock enable */
|
||||
|
||||
regval |= RCC_APB1ENR_WWDGEN;
|
||||
#endif
|
||||
|
||||
#if CONFIG_STM32_SPI2
|
||||
/* SPI2 clock enable */
|
||||
|
||||
regval |= RCC_APB1ENR_SPI2EN;
|
||||
#endif
|
||||
|
||||
#if CONFIG_STM32_SPI3
|
||||
/* SPI3 clock enable */
|
||||
|
||||
regval |= RCC_APB1ENR_SPI3EN;
|
||||
#endif
|
||||
|
||||
#if CONFIG_STM32_USART2
|
||||
/* USART 2 clock enable */
|
||||
|
||||
regval |= RCC_APB1ENR_USART2EN;
|
||||
#endif
|
||||
|
||||
#if CONFIG_STM32_USART3
|
||||
/* USART3 clock enable */
|
||||
|
||||
regval |= RCC_APB1ENR_USART3EN;
|
||||
#endif
|
||||
|
||||
#if CONFIG_STM32_UART4
|
||||
/* UART4 clock enable */
|
||||
|
||||
regval |= RCC_APB1ENR_UART4EN;
|
||||
#endif
|
||||
|
||||
#if CONFIG_STM32_UART5
|
||||
/* UART5 clock enable */
|
||||
|
||||
regval |= RCC_APB1ENR_UART5EN;
|
||||
#endif
|
||||
|
||||
#if CONFIG_STM32_I2C1
|
||||
/* I2C1 clock enable */
|
||||
|
||||
regval |= RCC_APB1ENR_I2C1EN;
|
||||
#endif
|
||||
|
||||
#if CONFIG_STM32_I2C2
|
||||
/* I2C2 clock enable */
|
||||
|
||||
regval |= RCC_APB1ENR_I2C2EN;
|
||||
#endif
|
||||
|
||||
#if CONFIG_STM32_I2C3
|
||||
/* I2C3 clock enable */
|
||||
|
||||
regval |= RCC_APB1ENR_I2C3EN;
|
||||
#endif
|
||||
|
||||
#if CONFIG_STM32_CAN1
|
||||
/* CAN 1 clock enable */
|
||||
|
||||
regval |= RCC_APB1ENR_CAN1EN;
|
||||
#endif
|
||||
|
||||
#if CONFIG_STM32_CAN2
|
||||
/* CAN 2 clock enable */
|
||||
|
||||
regval |= RCC_APB1ENR_CAN2EN;
|
||||
#endif
|
||||
|
||||
/* Power interface clock enable. The PWR block is always enabled so that
|
||||
* we can set the internal voltage regulator for maximum performance.
|
||||
*/
|
||||
|
||||
regval |= RCC_APB1ENR_PWREN;
|
||||
|
||||
#if defined (CONFIG_STM32_DAC1) || defined(CONFIG_STM32_DAC2)
|
||||
/* DAC interface clock enable */
|
||||
|
||||
regval |= RCC_APB1ENR_DACEN;
|
||||
#endif
|
||||
|
||||
putreg32(regval, STM32_RCC_APB1ENR); /* Enable peripherals */
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: rcc_enableapb2
|
||||
*
|
||||
* Description:
|
||||
* Enable selected APB2 peripherals
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
static inline void rcc_enableapb2(void)
|
||||
{
|
||||
uint32_t regval;
|
||||
|
||||
/* Set the appropriate bits in the APB2ENR register to enabled the
|
||||
* selected APB2 peripherals.
|
||||
*/
|
||||
|
||||
regval = getreg32(STM32_RCC_APB2ENR);
|
||||
|
||||
#if CONFIG_STM32_TIM1
|
||||
/* TIM1 clock enable */
|
||||
|
||||
regval |= RCC_APB2ENR_TIM1EN;
|
||||
#endif
|
||||
|
||||
#if CONFIG_STM32_TIM8
|
||||
/* TIM8 clock enable */
|
||||
|
||||
regval |= RCC_APB2ENR_TIM8EN;
|
||||
#endif
|
||||
|
||||
#if CONFIG_STM32_USART1
|
||||
/* USART1 clock enable */
|
||||
|
||||
regval |= RCC_APB2ENR_USART1EN;
|
||||
#endif
|
||||
|
||||
#if CONFIG_STM32_USART6
|
||||
/* USART6 clock enable */
|
||||
|
||||
regval |= RCC_APB2ENR_USART6EN;
|
||||
#endif
|
||||
|
||||
#if CONFIG_STM32_ADC1
|
||||
/* ADC1 clock enable */
|
||||
|
||||
regval |= RCC_APB2ENR_ADC1EN;
|
||||
#endif
|
||||
|
||||
#if CONFIG_STM32_ADC2
|
||||
/* ADC2 clock enable */
|
||||
|
||||
regval |= RCC_APB2ENR_ADC2EN;
|
||||
#endif
|
||||
|
||||
#if CONFIG_STM32_ADC3
|
||||
/* ADC3 clock enable */
|
||||
|
||||
regval |= RCC_APB2ENR_ADC3EN;
|
||||
#endif
|
||||
|
||||
#if CONFIG_STM32_SDIO
|
||||
/* SDIO clock enable */
|
||||
|
||||
regval |= RCC_APB2ENR_SDIOEN;
|
||||
#endif
|
||||
|
||||
#if CONFIG_STM32_SPI1
|
||||
/* SPI1 clock enable */
|
||||
|
||||
regval |= RCC_APB2ENR_SPI1EN;
|
||||
#endif
|
||||
|
||||
#if CONFIG_STM32_SYSCFG
|
||||
/* System configuration controller clock enable */
|
||||
|
||||
regval |= RCC_APB2ENR_SYSCFGEN;
|
||||
#endif
|
||||
|
||||
#if CONFIG_STM32_TIM9
|
||||
/* TIM9 clock enable */
|
||||
|
||||
regval |= RCC_APB2ENR_TIM9EN;
|
||||
#endif
|
||||
|
||||
#if CONFIG_STM32_TIM10
|
||||
/* TIM10 clock enable */
|
||||
|
||||
regval |= RCC_APB2ENR_TIM10EN;
|
||||
#endif
|
||||
|
||||
#if CONFIG_STM32_TIM11
|
||||
/* TIM11 clock enable */
|
||||
|
||||
regval |= RCC_APB2ENR_TIM11EN;
|
||||
#endif
|
||||
|
||||
putreg32(regval, STM32_RCC_APB2ENR); /* Enable peripherals */
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: stm32_stdclockconfig
|
||||
*
|
||||
* Description:
|
||||
* Called to change to new clock based on settings in board.h
|
||||
*
|
||||
* NOTE: This logic would need to be extended if you need to select low-
|
||||
* power clocking modes!
|
||||
****************************************************************************/
|
||||
|
||||
#ifndef CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG
|
||||
static inline void stm32_stdclockconfig(void)
|
||||
{
|
||||
uint32_t regval;
|
||||
volatile int32_t timeout;
|
||||
|
||||
/* Enable External High-Speed Clock (HSE) */
|
||||
|
||||
regval = getreg32(STM32_RCC_CR);
|
||||
regval |= RCC_CR_HSEON; /* Enable HSE */
|
||||
putreg32(regval, STM32_RCC_CR);
|
||||
|
||||
/* Wait until the HSE is ready (or until a timeout elapsed) */
|
||||
|
||||
for (timeout = HSERDY_TIMEOUT; timeout > 0; timeout--)
|
||||
{
|
||||
/* Check if the HSERDY flag is the set in the CR */
|
||||
|
||||
if ((getreg32(STM32_RCC_CR) & RCC_CR_HSERDY) != 0)
|
||||
{
|
||||
/* If so, then break-out with timeout > 0 */
|
||||
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
/* Check for a timeout. If this timeout occurs, then we are hosed. We
|
||||
* have no real back-up plan, although the following logic makes it look
|
||||
* as though we do.
|
||||
*/
|
||||
|
||||
if (timeout > 0)
|
||||
{
|
||||
/* Select regulator voltage output Scale 1 mode to support system
|
||||
* frequencies up to 168 MHz.
|
||||
*/
|
||||
|
||||
regval = getreg32(STM32_RCC_APB1ENR);
|
||||
regval |= RCC_APB1ENR_PWREN;
|
||||
putreg32(regval, STM32_RCC_APB1ENR);
|
||||
|
||||
regval = getreg32(STM32_PWR_CR);
|
||||
regval |= PWR_CR_VOS;
|
||||
putreg32(regval, STM32_PWR_CR);
|
||||
|
||||
/* Set the HCLK source/divider */
|
||||
|
||||
regval = getreg32(STM32_RCC_CFGR);
|
||||
regval &= ~RCC_CFGR_HPRE_MASK;
|
||||
regval |= STM32_RCC_CFGR_HPRE;
|
||||
putreg32(regval, STM32_RCC_CFGR);
|
||||
|
||||
/* Set the PCLK2 divider */
|
||||
|
||||
regval = getreg32(STM32_RCC_CFGR);
|
||||
regval &= ~RCC_CFGR_PPRE2_MASK;
|
||||
regval |= STM32_RCC_CFGR_PPRE2;
|
||||
putreg32(regval, STM32_RCC_CFGR);
|
||||
|
||||
/* Set the PCLK1 divider */
|
||||
|
||||
regval = getreg32(STM32_RCC_CFGR);
|
||||
regval &= ~RCC_CFGR_PPRE1_MASK;
|
||||
regval |= STM32_RCC_CFGR_PPRE1;
|
||||
putreg32(regval, STM32_RCC_CFGR);
|
||||
|
||||
/* Set the PLL dividers and multiplers to configure the main PLL */
|
||||
|
||||
regval = (STM32_PLLCFG_PLLM | STM32_PLLCFG_PLLN |STM32_PLLCFG_PLLP |
|
||||
RCC_PLLCFG_PLLSRC_HSE | STM32_PLLCFG_PPQ);
|
||||
putreg32(regval, STM32_RCC_PLLCFG);
|
||||
|
||||
/* Enable the main PLL */
|
||||
|
||||
regval = getreg32(STM32_RCC_CR);
|
||||
regval |= RCC_CR_PLLON;
|
||||
putreg32(regval, STM32_RCC_CR);
|
||||
|
||||
/* Wait until the PLL is ready */
|
||||
|
||||
while ((getreg32(STM32_RCC_CR) & RCC_CR_PLLRDY) == 0);
|
||||
|
||||
/* Enable FLASH prefetch, instruction cache, data cache, and 5 wait states */
|
||||
|
||||
regval = (FLASH_ACR_LATENCY_5 | FLASH_ACR_ICEN | FLASH_ACR_DCEN);
|
||||
putreg32(regval, STM32_FLASH_ACR);
|
||||
|
||||
/* Select the main PLL as system clock source */
|
||||
|
||||
regval = getreg32(STM32_RCC_CFGR);
|
||||
regval &= ~RCC_CFGR_SW_MASK;
|
||||
regval |= RCC_CFGR_SW_PLL;
|
||||
putreg32(regval, STM32_RCC_CFGR);
|
||||
|
||||
/* Wait until the PLL source is used as the system clock source */
|
||||
|
||||
while ((getreg32(STM32_RCC_CFGR) & RCC_CFGR_SWS_MASK) != RCC_CFGR_SWS_PLL);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
/****************************************************************************
|
||||
* Name: rcc_enableperiphals
|
||||
****************************************************************************/
|
||||
|
||||
static inline void rcc_enableperipherals(void)
|
||||
{
|
||||
rcc_enableahb1();
|
||||
rcc_enableahb2();
|
||||
rcc_enableahb3();
|
||||
rcc_enableapb1();
|
||||
rcc_enableapb2();
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Public Functions
|
||||
****************************************************************************/
|
|
@ -0,0 +1,842 @@
|
|||
/************************************************************************************
|
||||
* arch/arm/src/stm32/stm32f20xxx_rtc.c
|
||||
*
|
||||
* Copyright (C) 2011 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 <nuttx/arch.h>
|
||||
#include <nuttx/irq.h>
|
||||
#include <nuttx/rtc.h>
|
||||
|
||||
#include <time.h>
|
||||
#include <errno.h>
|
||||
#include <debug.h>
|
||||
|
||||
#include <arch/board/board.h>
|
||||
|
||||
#include "up_arch.h"
|
||||
|
||||
#include "stm32_rtc.h"
|
||||
|
||||
#ifdef CONFIG_RTC
|
||||
|
||||
/************************************************************************************
|
||||
* Pre-processor Definitions
|
||||
************************************************************************************/
|
||||
/* Configuration ********************************************************************/
|
||||
/* This RTC implementation supports only date/time RTC hardware */
|
||||
|
||||
#ifndef CONFIG_RTC_DATETIME
|
||||
# error "CONFIG_RTC_DATETIME must be set to use this driver"
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_RTC_HIRES
|
||||
# error "CONFIG_RTC_HIRES must NOT be set with this driver"
|
||||
#endif
|
||||
|
||||
#ifndef CONFIG_STM32_PWR
|
||||
# error "CONFIG_STM32_PWR must selected to use this driver"
|
||||
#endif
|
||||
|
||||
#ifndef CONFIG_DEBUG
|
||||
# undef CONFIG_DEBUG_RTC
|
||||
#endif
|
||||
|
||||
/* Constants ************************************************************************/
|
||||
|
||||
#define SYNCHRO_TIMEOUT (0x00020000)
|
||||
#define INITMODE_TIMEOUT (0x00010000)
|
||||
#define RTC_MAGIC (0xfacefeed)
|
||||
#define RTC_PREDIV_S (0xff)
|
||||
#define RTC_PREDIV_A (0x7f)
|
||||
|
||||
/* Debug ****************************************************************************/
|
||||
|
||||
#ifdef CONFIG_DEBUG_RTC
|
||||
# define rtcdbg dbg
|
||||
# define rtcvdbg vdbg
|
||||
# define rtclldbg lldbg
|
||||
# define rtcllvdbg llvdbg
|
||||
#else
|
||||
# define rtcdbg(x...)
|
||||
# define rtcvdbg(x...)
|
||||
# define rtclldbg(x...)
|
||||
# define rtcllvdbg(x...)
|
||||
#endif
|
||||
|
||||
/************************************************************************************
|
||||
* Private Types
|
||||
************************************************************************************/
|
||||
|
||||
/************************************************************************************
|
||||
* Private Data
|
||||
************************************************************************************/
|
||||
|
||||
/* Callback to use when the alarm expires */
|
||||
|
||||
#ifdef CONFIG_RTC_ALARM
|
||||
static alarmcb_t g_alarmcb;
|
||||
#endif
|
||||
|
||||
/************************************************************************************
|
||||
* Public Data
|
||||
************************************************************************************/
|
||||
|
||||
/* g_rtc_enabled is set true after the RTC has successfully initialized */
|
||||
|
||||
volatile bool g_rtc_enabled = false;
|
||||
|
||||
/************************************************************************************
|
||||
* Private Functions
|
||||
************************************************************************************/
|
||||
/************************************************************************************
|
||||
* Name: rtc_dumpregs
|
||||
*
|
||||
* Description:
|
||||
* Disable RTC write protection
|
||||
*
|
||||
* Input Parameters:
|
||||
* None
|
||||
*
|
||||
* Returned Value:
|
||||
* None
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
#ifdef CONFIG_DEBUG_RTC
|
||||
static void rtc_dumpregs(FAR const char *msg)
|
||||
{
|
||||
rtclldbg("%s:\n", msg);
|
||||
rtclldbg(" TR: %08x\n", getreg32(STM32_RTC_TR));
|
||||
rtclldbg(" DR: %08x\n", getreg32(STM32_RTC_DR));
|
||||
rtclldbg(" CR: %08x\n", getreg32(STM32_RTC_CR));
|
||||
rtclldbg(" ISR: %08x\n", getreg32(STM32_RTC_ISR));
|
||||
rtclldbg(" PRER: %08x\n", getreg32(STM32_RTC_PRER));
|
||||
rtclldbg(" WUTR: %08x\n", getreg32(STM32_RTC_WUTR));
|
||||
rtclldbg(" CALIBR: %08x\n", getreg32(STM32_RTC_CALIBR));
|
||||
rtclldbg(" ALRMAR: %08x\n", getreg32(STM32_RTC_ALRMAR));
|
||||
rtclldbg(" ALRMBR: %08x\n", getreg32(STM32_RTC_ALRMBR));
|
||||
rtclldbg(" SHIFTR: %08x\n", getreg32(STM32_RTC_SHIFTR));
|
||||
rtclldbg(" TSTR: %08x\n", getreg32(STM32_RTC_TSTR));
|
||||
rtclldbg(" TSDR: %08x\n", getreg32(STM32_RTC_TSDR));
|
||||
rtclldbg(" TSSSR: %08x\n", getreg32(STM32_RTC_TSSSR));
|
||||
rtclldbg(" CALR: %08x\n", getreg32(STM32_RTC_CALR));
|
||||
rtclldbg(" TAFCR: %08x\n", getreg32(STM32_RTC_TAFCR));
|
||||
rtclldbg("ALRMASSR: %08x\n", getreg32(STM32_RTC_ALRMASSR));
|
||||
rtclldbg("ALRMBSSR: %08x\n", getreg32(STM32_RTC_ALRMBSSR));
|
||||
rtclldbg(" BK0: %08x\n", getreg32(STM32_RTC_BK0R));
|
||||
}
|
||||
#else
|
||||
# define rtc_dumpregs(msg)
|
||||
#endif
|
||||
|
||||
/************************************************************************************
|
||||
* Name: rtc_dumptime
|
||||
*
|
||||
* Description:
|
||||
* Disable RTC write protection
|
||||
*
|
||||
* Input Parameters:
|
||||
* None
|
||||
*
|
||||
* Returned Value:
|
||||
* None
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
#ifdef CONFIG_DEBUG_RTC
|
||||
static void rtc_dumptime(FAR struct tm *tp, FAR const char *msg)
|
||||
{
|
||||
rtclldbg("%s:\n", msg);
|
||||
rtclldbg(" tm_sec: %08x\n", tp->tm_sec);
|
||||
rtclldbg(" tm_min: %08x\n", tp->tm_min);
|
||||
rtclldbg(" tm_hour: %08x\n", tp->tm_hour);
|
||||
rtclldbg(" tm_mday: %08x\n", tp->tm_mday);
|
||||
rtclldbg(" tm_mon: %08x\n", tp->tm_mon);
|
||||
rtclldbg(" tm_year: %08x\n", tp->tm_year);
|
||||
}
|
||||
#else
|
||||
# define rtc_dumptime(tp, msg)
|
||||
#endif
|
||||
|
||||
/************************************************************************************
|
||||
* Name: rtc_wprunlock
|
||||
*
|
||||
* Description:
|
||||
* Disable RTC write protection
|
||||
*
|
||||
* Input Parameters:
|
||||
* None
|
||||
*
|
||||
* Returned Value:
|
||||
* None
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
static void rtc_wprunlock(void)
|
||||
{
|
||||
/* The following steps are required to unlock the write protection on all the
|
||||
* RTC registers (except for RTC_ISR[13:8], RTC_TAFCR, and RTC_BKPxR).
|
||||
*
|
||||
* 1. Write 0xCA into the RTC_WPR register.
|
||||
* 2. Write 0x53 into the RTC_WPR register.
|
||||
*
|
||||
* Writing a wrong key reactivates the write protection.
|
||||
*/
|
||||
|
||||
putreg32(0xca, STM32_RTC_WPR);
|
||||
putreg32(0x53, STM32_RTC_WPR);
|
||||
}
|
||||
|
||||
/************************************************************************************
|
||||
* Name: rtc_wprunlock
|
||||
*
|
||||
* Description:
|
||||
* Enable RTC write protection
|
||||
*
|
||||
* Input Parameters:
|
||||
* None
|
||||
*
|
||||
* Returned Value:
|
||||
* None
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
static inline void rtc_wprlock(void)
|
||||
{
|
||||
/* Writing any wrong key reactivates the write protection. */
|
||||
|
||||
putreg32(0xff, STM32_RTC_WPR);
|
||||
}
|
||||
|
||||
/************************************************************************************
|
||||
* Name: rtc_synchwait
|
||||
*
|
||||
* Description:
|
||||
* Waits until the RTC Time and Date registers (RTC_TR and RTC_DR) are
|
||||
* synchronized with RTC APB clock.
|
||||
*
|
||||
* Input Parameters:
|
||||
* None
|
||||
*
|
||||
* Returned Value:
|
||||
* Zero (OK) on success; a negated errno on failure
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
static int rtc_synchwait(void)
|
||||
{
|
||||
volatile uint32_t timeout;
|
||||
uint32_t regval;
|
||||
int ret;
|
||||
|
||||
/* Disable the write protection for RTC registers */
|
||||
|
||||
rtc_wprunlock();
|
||||
|
||||
/* Clear Registers synchronization flag (RSF) */
|
||||
|
||||
regval = getreg32(STM32_RTC_ISR);
|
||||
regval &= ~RTC_ISR_RSF;
|
||||
putreg32(regval, STM32_RTC_ISR);
|
||||
|
||||
/* Now wait the registers to become synchronised */
|
||||
|
||||
ret = -ETIMEDOUT;
|
||||
for (timeout = 0; timeout < SYNCHRO_TIMEOUT; timeout++)
|
||||
{
|
||||
regval = getreg32(STM32_RTC_ISR);
|
||||
if ((regval & RTC_ISR_RSF) != 0)
|
||||
{
|
||||
/* Synchronized */
|
||||
|
||||
ret = OK;
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
/* Re-enable the write protection for RTC registers */
|
||||
|
||||
rtc_wprlock();
|
||||
return ret;
|
||||
}
|
||||
|
||||
/************************************************************************************
|
||||
* Name: rtc_enterinit
|
||||
*
|
||||
* Description:
|
||||
* Enter RTC initialization mode.
|
||||
*
|
||||
* Input Parameters:
|
||||
* None
|
||||
*
|
||||
* Returned Value:
|
||||
* Zero (OK) on success; a negated errno on failure
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
static int rtc_enterinit(void)
|
||||
{
|
||||
volatile uint32_t timeout;
|
||||
uint32_t regval;
|
||||
int ret;
|
||||
|
||||
/* Check if the Initialization mode is already set */
|
||||
|
||||
regval = getreg32(STM32_RTC_ISR);
|
||||
|
||||
ret = OK;
|
||||
if ((regval & RTC_ISR_INITF) == 0)
|
||||
{
|
||||
/* Set the Initialization mode */
|
||||
|
||||
putreg32(RTC_ISR_INIT, STM32_RTC_ISR);
|
||||
|
||||
/* Wait until the RTC is in the INIT state (or a timeout occurs) */
|
||||
|
||||
ret = -ETIMEDOUT;
|
||||
for (timeout = 0; timeout < INITMODE_TIMEOUT; timeout++)
|
||||
{
|
||||
regval = getreg32(STM32_RTC_ISR);
|
||||
if ((regval & RTC_ISR_INITF) != 0)
|
||||
{
|
||||
ret = OK;
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
/************************************************************************************
|
||||
* Name: rtc_exitinit
|
||||
*
|
||||
* Description:
|
||||
* Exit RTC initialization mode.
|
||||
*
|
||||
* Input Parameters:
|
||||
* None
|
||||
*
|
||||
* Returned Value:
|
||||
* Zero (OK) on success; a negated errno on failure
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
static void rtc_exitinit(void)
|
||||
{
|
||||
uint32_t regval;
|
||||
|
||||
regval = getreg32(STM32_RTC_ISR);
|
||||
regval &= ~(RTC_ISR_INIT);
|
||||
putreg32(regval, STM32_RTC_ISR);
|
||||
}
|
||||
|
||||
/************************************************************************************
|
||||
* Name: rtc_bin2bcd
|
||||
*
|
||||
* Description:
|
||||
* Converts a 2 digit binary to BCD format
|
||||
*
|
||||
* Input Parameters:
|
||||
* value - The byte to be converted.
|
||||
*
|
||||
* Returned Value:
|
||||
* The value in BCD representation
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
static uint32_t rtc_bin2bcd(int value)
|
||||
{
|
||||
uint32_t msbcd = 0;
|
||||
|
||||
while (value >= 10)
|
||||
{
|
||||
msbcd++;
|
||||
value -= 10;
|
||||
}
|
||||
|
||||
return (msbcd << 4) | value;
|
||||
}
|
||||
|
||||
/************************************************************************************
|
||||
* Name: rtc_bin2bcd
|
||||
*
|
||||
* Description:
|
||||
* Convert from 2 digit BCD to binary.
|
||||
*
|
||||
* Input Parameters:
|
||||
* value - The BCD value to be converted.
|
||||
*
|
||||
* Returned Value:
|
||||
* The value in binary representation
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
static int rtc_bcd2bin(uint32_t value)
|
||||
{
|
||||
uint32_t tens = (value >> 4) * 10;
|
||||
return (int)(tens + (value & 0x0f));
|
||||
}
|
||||
|
||||
/************************************************************************************
|
||||
* Name: rtc_setup
|
||||
*
|
||||
* Description:
|
||||
* Performs first time configuration of the RTC. A special value written into
|
||||
* back-up register 0 will prevent this function from being called on sub-sequent
|
||||
* resets or power up.
|
||||
*
|
||||
* Input Parameters:
|
||||
* None
|
||||
*
|
||||
* Returned Value:
|
||||
* Zero (OK) on success; a negated errno on failure
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
static int rtc_setup(void)
|
||||
{
|
||||
uint32_t regval;
|
||||
int ret;
|
||||
|
||||
/* Enable the External Low-Speed (LSE) Oscillator setup the LSE as the RTC clock\
|
||||
* source, and enable the RTC.
|
||||
*/
|
||||
|
||||
stm32_rcc_enablelse();
|
||||
|
||||
/* Wait for the RTC Time and Date registers to be synchronized with RTC APB
|
||||
* clock.
|
||||
*/
|
||||
|
||||
ret = rtc_synchwait();
|
||||
if (ret == OK)
|
||||
{
|
||||
/* Disable the write protection for RTC registers */
|
||||
|
||||
rtc_wprunlock();
|
||||
|
||||
/* Set Initialization mode */
|
||||
|
||||
ret = rtc_enterinit();
|
||||
if (ret == OK)
|
||||
{
|
||||
/* Set the 24 hour format by clearing the FMT bit in the RTC
|
||||
* control register
|
||||
*/
|
||||
|
||||
regval = getreg32(STM32_RTC_CR);
|
||||
regval &= ~RTC_CR_FMT;
|
||||
putreg32(regval, STM32_RTC_CR);
|
||||
|
||||
/* Configure RTC pre-scaler to the required, default values for
|
||||
* use with the 32.768 KHz LSE clock:
|
||||
*/
|
||||
|
||||
putreg32(((uint32_t)0xff << RTC_PRER_PREDIV_S_SHIFT) |
|
||||
((uint32_t)0x7f << RTC_PRER_PREDIV_A_SHIFT),
|
||||
STM32_RTC_PRER);
|
||||
|
||||
/* Exit RTC initialization mode */
|
||||
|
||||
rtc_exitinit();
|
||||
}
|
||||
|
||||
/* Re-enable the write protection for RTC registers */
|
||||
|
||||
rtc_wprlock();
|
||||
}
|
||||
return ret;
|
||||
}
|
||||
|
||||
/************************************************************************************
|
||||
* Name: rtc_resume
|
||||
*
|
||||
* Description:
|
||||
* Called when the RTC was already initialized on a previous power cycle. This
|
||||
* just brings the RTC back into full operation.
|
||||
*
|
||||
* Input Parameters:
|
||||
* None
|
||||
*
|
||||
* Returned Value:
|
||||
* Zero (OK) on success; a negated errno on failure
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
static int rtc_resume(void)
|
||||
{
|
||||
#ifdef CONFIG_RTC_ALARM
|
||||
uint32_t regval;
|
||||
#endif
|
||||
int ret;
|
||||
|
||||
/* Wait for the RTC Time and Date registers to be syncrhonized with RTC APB
|
||||
* clock.
|
||||
*/
|
||||
|
||||
ret = rtc_synchwait();
|
||||
|
||||
/* Clear the RTC alarm flags */
|
||||
|
||||
#ifdef CONFIG_RTC_ALARM
|
||||
regval = getreg32(STM32_RTC_ISR);
|
||||
regval &= ~(RTC_ISR_ALRAF|RTC_ISR_ALRBF);
|
||||
putreg32(regval, STM32_RTC_ISR);
|
||||
|
||||
/* Clear the EXTI Line 17 Pending bit (Connected internally to RTC Alarm) */
|
||||
|
||||
putreg32((1 << 17), STM32_EXTI_PR);
|
||||
#endif
|
||||
return ret;
|
||||
}
|
||||
|
||||
/************************************************************************************
|
||||
* Name: rtc_interrupt
|
||||
*
|
||||
* Description:
|
||||
* RTC interrupt service routine
|
||||
*
|
||||
* Input Parameters:
|
||||
* irq - The IRQ number that generated the interrupt
|
||||
* context - Architecture specific register save information.
|
||||
*
|
||||
* Returned Value:
|
||||
* Zero (OK) on success; A negated errno value on failure.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
#if CONFIG_RTC_ALARM
|
||||
static int rtc_interrupt(int irq, void *context)
|
||||
{
|
||||
#warning "Missing logic"
|
||||
return OK;
|
||||
}
|
||||
#endif
|
||||
|
||||
/************************************************************************************
|
||||
* Public Functions
|
||||
************************************************************************************/
|
||||
|
||||
/************************************************************************************
|
||||
* Name: up_rtcinitialize
|
||||
*
|
||||
* Description:
|
||||
* Initialize the hardware RTC per the selected configuration. This function is
|
||||
* called once during the OS initialization sequence
|
||||
*
|
||||
* Input Parameters:
|
||||
* None
|
||||
*
|
||||
* Returned Value:
|
||||
* Zero (OK) on success; a negated errno on failure
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
int up_rtcinitialize(void)
|
||||
{
|
||||
uint32_t regval;
|
||||
int ret;
|
||||
|
||||
rtc_dumpregs("On reset");
|
||||
|
||||
/* Clocking for the PWR block must be provided. However, this is done
|
||||
* unconditionally in stm32f40xxx_rcc.c on power up. This done unconditionally
|
||||
* because the PWR block is also needed to set the internal voltage regulator for
|
||||
* maximum performance.
|
||||
*/
|
||||
|
||||
/* Enable access to the backup domain (RTC registers, RTC backup data registers
|
||||
* and backup SRAM).
|
||||
*/
|
||||
|
||||
stm32_pwr_enablebkp();
|
||||
|
||||
/* Check if the one-time initialization of the RTC has already been performed.
|
||||
* We can determine this by checking if the magic number has been writing to
|
||||
* to back-up date register DR0.
|
||||
*/
|
||||
|
||||
regval = getreg32(STM32_RTC_BK0R);
|
||||
if (regval != RTC_MAGIC)
|
||||
{
|
||||
/* Perform the one-time setup of the LSE clocking to the RTC */
|
||||
|
||||
ret = rtc_setup();
|
||||
|
||||
/* Remember that the RTC is initialized */
|
||||
|
||||
putreg32(RTC_MAGIC, STM32_RTC_BK0R);
|
||||
}
|
||||
else
|
||||
{
|
||||
/* RTC already set-up, just resume normal operation */
|
||||
|
||||
ret = rtc_resume();
|
||||
}
|
||||
|
||||
/* Configure RTC interrupt to catch alarm interrupts. All RTC interrupts are
|
||||
* connected to the EXTI controller. To enable the RTC Alarm interrupt, the
|
||||
* following sequence is required:
|
||||
*
|
||||
* 1. Configure and enable the EXTI Line 17 in interrupt mode and select the
|
||||
* rising edge sensitivity.
|
||||
* 2. Configure and enable the RTC_Alarm IRQ channel in the NVIC.
|
||||
* 3. Configure the RTC to generate RTC alarms (Alarm A or Alarm B).
|
||||
*/
|
||||
|
||||
#ifdef CONFIG_RTC_ALARM
|
||||
# warning "Missing EXTI setup logic"
|
||||
|
||||
/* Then attach the ALARM interrupt handler */
|
||||
|
||||
irq_attach(STM32_IRQ_RTC, rtc_interrupt);
|
||||
up_enable_irq(STM32_IRQ_RTC);
|
||||
#endif
|
||||
|
||||
g_rtc_enabled = true;
|
||||
rtc_dumpregs("After Initialzation");
|
||||
return OK;
|
||||
}
|
||||
|
||||
/************************************************************************************
|
||||
* Name: up_rtc_getdatetime
|
||||
*
|
||||
* Description:
|
||||
* Get the current date and time from the date/time RTC. This interface
|
||||
* is only supported by the date/time RTC hardware implementation.
|
||||
* It is used to replace the system timer. It is only used by the RTOS during
|
||||
* intialization to set up the system time when CONFIG_RTC and CONFIG_RTC_DATETIME
|
||||
* are selected (and CONFIG_RTC_HIRES is not).
|
||||
*
|
||||
* NOTE: Some date/time RTC hardware is capability of sub-second accuracy. That
|
||||
* sub-second accuracy is lost in this interface. However, since the system time
|
||||
* is reinitialized on each power-up/reset, there will be no timing inaccuracy in
|
||||
* the long run.
|
||||
*
|
||||
* Input Parameters:
|
||||
* tp - The location to return the high resolution time value.
|
||||
*
|
||||
* Returned Value:
|
||||
* Zero (OK) on success; a negated errno on failure
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
int up_rtc_getdatetime(FAR struct tm *tp)
|
||||
{
|
||||
uint32_t dr;
|
||||
uint32_t tr;
|
||||
uint32_t tmp;
|
||||
|
||||
/* Sample the data time registers. There is a race condition here... If we sample
|
||||
* the time just before midnight on December 31, the date could be wrong because
|
||||
* the day rolled over while were sampling.
|
||||
*/
|
||||
|
||||
do
|
||||
{
|
||||
dr = getreg32(STM32_RTC_DR);
|
||||
tr = getreg32(STM32_RTC_TR);
|
||||
tmp = getreg32(STM32_RTC_DR);
|
||||
}
|
||||
while (tmp != dr);
|
||||
|
||||
rtc_dumpregs("Reading Time");
|
||||
|
||||
/* Convert the RTC time to fields in struct tm format. All of the STM32
|
||||
* All of the ranges of values correspond between struct tm and the time
|
||||
* register.
|
||||
*/
|
||||
|
||||
tmp = (tr & (RTC_TR_SU_MASK|RTC_TR_ST_MASK)) >> RTC_TR_SU_SHIFT;
|
||||
tp->tm_sec = rtc_bcd2bin(tmp);
|
||||
|
||||
tmp = (tr & (RTC_TR_MNU_MASK|RTC_TR_MNT_MASK)) >> RTC_TR_MNU_SHIFT;
|
||||
tp->tm_min = rtc_bcd2bin(tmp);
|
||||
|
||||
tmp = (tr & (RTC_TR_HU_MASK|RTC_TR_HT_MASK)) >> RTC_TR_HU_SHIFT;
|
||||
tp->tm_hour = rtc_bcd2bin(tmp);
|
||||
|
||||
/* Now convert the RTC date to fields in struct tm format:
|
||||
* Days: 1-31 match in both cases.
|
||||
* Month: STM32 is 1-12, struct tm is 0-11.
|
||||
* Years: STM32 is 00-99, struct tm is years since 1900.
|
||||
*
|
||||
* Issue: I am not sure what the STM32 years mean. Are these the
|
||||
* years 2000-2099? I'll assume so.
|
||||
*/
|
||||
|
||||
tmp = (dr & (RTC_DR_DU_MASK|RTC_DR_DT_MASK)) >> RTC_DR_DU_SHIFT;
|
||||
tp->tm_mday = rtc_bcd2bin(tmp);
|
||||
|
||||
tmp = (dr & (RTC_DR_MU_MASK|RTC_DR_MT)) >> RTC_DR_MU_SHIFT;
|
||||
tp->tm_mon = rtc_bcd2bin(tmp) - 1;
|
||||
|
||||
tmp = (dr & (RTC_DR_YU_MASK|RTC_DR_YT_MASK)) >> RTC_DR_YU_SHIFT;
|
||||
tp->tm_year = rtc_bcd2bin(tmp) + 100;
|
||||
|
||||
rtc_dumptime(tp, "Returning");
|
||||
return OK;
|
||||
}
|
||||
|
||||
/************************************************************************************
|
||||
* Name: up_rtc_settime
|
||||
*
|
||||
* Description:
|
||||
* Set the RTC to the provided time. All RTC implementations must be able to
|
||||
* set their time based on a standard timespec.
|
||||
*
|
||||
* Input Parameters:
|
||||
* tp - the time to use
|
||||
*
|
||||
* Returned Value:
|
||||
* Zero (OK) on success; a negated errno on failure
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
int up_rtc_settime(FAR const struct timespec *tp)
|
||||
{
|
||||
FAR struct tm newtime;
|
||||
uint32_t tr;
|
||||
uint32_t dr;
|
||||
int ret;
|
||||
|
||||
/* Break out the time values (not that the time is set only to units of seconds) */
|
||||
|
||||
(void)gmtime_r(&tp->tv_sec, &newtime);
|
||||
rtc_dumptime(&newtime, "Setting time");
|
||||
|
||||
/* Then write the broken out values to the RTC */
|
||||
|
||||
/* Convert the struct tm format to RTC time register fields. All of the STM32
|
||||
* All of the ranges of values correspond between struct tm and the time
|
||||
* register.
|
||||
*/
|
||||
|
||||
tr = (rtc_bin2bcd(newtime.tm_sec) << RTC_TR_SU_SHIFT) |
|
||||
(rtc_bin2bcd(newtime.tm_min) << RTC_TR_MNU_SHIFT) |
|
||||
(rtc_bin2bcd(newtime.tm_hour) << RTC_TR_HU_SHIFT);
|
||||
tr &= ~RTC_TR_RESERVED_BITS;
|
||||
|
||||
/* Now convert the fields in struct tm format to the RTC date register fields:
|
||||
* Days: 1-31 match in both cases.
|
||||
* Month: STM32 is 1-12, struct tm is 0-11.
|
||||
* Years: STM32 is 00-99, struct tm is years since 1900.
|
||||
*
|
||||
* Issue: I am not sure what the STM32 years mean. Are these the
|
||||
* years 2000-2099? I'll assume so.
|
||||
*/
|
||||
|
||||
dr = (rtc_bin2bcd(newtime.tm_mday) << RTC_DR_DU_SHIFT) |
|
||||
((rtc_bin2bcd(newtime.tm_mon + 1)) << RTC_DR_MU_SHIFT) |
|
||||
((rtc_bin2bcd(newtime.tm_year - 100)) << RTC_DR_YU_SHIFT);
|
||||
dr &= ~RTC_DR_RESERVED_BITS;
|
||||
|
||||
/* Disable the write protection for RTC registers */
|
||||
|
||||
rtc_wprunlock();
|
||||
|
||||
/* Set Initialization mode */
|
||||
|
||||
ret = rtc_enterinit();
|
||||
if (ret == OK)
|
||||
{
|
||||
/* Set the RTC TR and DR registers */
|
||||
|
||||
putreg32(tr, STM32_RTC_TR);
|
||||
putreg32(dr, STM32_RTC_DR);
|
||||
|
||||
/* Exit Initialization mode and wait for the RTC Time and Date
|
||||
* registers to be synchronized with RTC APB clock.
|
||||
*/
|
||||
|
||||
rtc_exitinit();
|
||||
ret = rtc_synchwait();
|
||||
}
|
||||
|
||||
/* Re-enable the write protection for RTC registers */
|
||||
|
||||
rtc_wprlock();
|
||||
rtc_dumpregs("New time setting");
|
||||
return ret;
|
||||
}
|
||||
|
||||
/************************************************************************************
|
||||
* Name: up_rtc_setalarm
|
||||
*
|
||||
* Description:
|
||||
* Set up an alarm. Up to two alarms can be supported (ALARM A and ALARM B).
|
||||
*
|
||||
* Input Parameters:
|
||||
* tp - the time to set the alarm
|
||||
* callback - the function to call when the alarm expires.
|
||||
*
|
||||
* Returned Value:
|
||||
* Zero (OK) on success; a negated errno on failure
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
#ifdef CONFIG_RTC_ALARM
|
||||
int up_rtc_setalarm(FAR const struct timespec *tp, alarmcb_t callback);
|
||||
{
|
||||
irqstate_t flags;
|
||||
int ret = -EBUSY;
|
||||
|
||||
/* Is there already something waiting on the ALARM? */
|
||||
|
||||
if (g_alarmcb == NULL)
|
||||
{
|
||||
/* No.. Save the callback function pointer */
|
||||
|
||||
g_alarmcb = callback;
|
||||
|
||||
/* Break out the time values */
|
||||
#warning "Missing logic"
|
||||
|
||||
/* The set the alarm */
|
||||
#warning "Missing logic"
|
||||
|
||||
ret = OK;
|
||||
}
|
||||
return ret;
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif /* CONFIG_RTC */
|
||||
|
|
@ -0,0 +1,738 @@
|
|||
README
|
||||
======
|
||||
|
||||
This README discusses issues unique to NuttX configurations for the
|
||||
STMicro STM32140G-EVAL development board.
|
||||
|
||||
Contents
|
||||
========
|
||||
|
||||
- Development Environment
|
||||
- GNU Toolchain Options
|
||||
- IDEs
|
||||
- NuttX buildroot Toolchain
|
||||
- STM3220G-EVAL-specific Configuration Options
|
||||
- LEDs
|
||||
- Ethernet
|
||||
- PWM
|
||||
- CAN
|
||||
- Configurations
|
||||
|
||||
Development Environment
|
||||
=======================
|
||||
|
||||
Either Linux or Cygwin on Windows can be used for the development environment.
|
||||
The source has been built only using the GNU toolchain (see below). Other
|
||||
toolchains will likely cause problems. Testing was performed using the Cygwin
|
||||
environment because the Raisonance R-Link emulatator and some RIDE7 development tools
|
||||
were used and those tools works only under Windows.
|
||||
|
||||
GNU Toolchain Options
|
||||
=====================
|
||||
|
||||
The NuttX make system has been modified to support the following different
|
||||
toolchain options.
|
||||
|
||||
1. The CodeSourcery GNU toolchain,
|
||||
2. The devkitARM GNU toolchain,
|
||||
3. Raisonance GNU toolchain, or
|
||||
4. The NuttX buildroot Toolchain (see below).
|
||||
|
||||
All testing has been conducted using the CodeSourcery toolchain for Windows. To use
|
||||
the devkitARM, Raisonance GNU, or NuttX buildroot toolchain, you simply need to
|
||||
add one of the following configuration options to your .config (or defconfig)
|
||||
file:
|
||||
|
||||
CONFIG_STM32_CODESOURCERYW=y : CodeSourcery under Windows
|
||||
CONFIG_STM32_CODESOURCERYL=y : CodeSourcery under Linux
|
||||
CONFIG_STM32_DEVKITARM=y : devkitARM under Windows
|
||||
CONFIG_STM32_RAISONANCE=y : Raisonance RIDE7 under Windows
|
||||
CONFIG_STM32_BUILDROOT=y : NuttX buildroot under Linux or Cygwin (default)
|
||||
|
||||
If you change the default toolchain, then you may also have to modify the PATH in
|
||||
the setenv.h file if your make cannot find the tools.
|
||||
|
||||
NOTE: the CodeSourcery (for Windows), devkitARM, and Raisonance toolchains are
|
||||
Windows native toolchains. The CodeSourcey (for Linux) and NuttX buildroot
|
||||
toolchains are Cygwin and/or Linux native toolchains. There are several limitations
|
||||
to using a Windows based toolchain in a Cygwin environment. The three biggest are:
|
||||
|
||||
1. The Windows toolchain cannot follow Cygwin paths. Path conversions are
|
||||
performed automatically in the Cygwin makefiles using the 'cygpath' utility
|
||||
but you might easily find some new path problems. If so, check out 'cygpath -w'
|
||||
|
||||
2. Windows toolchains cannot follow Cygwin symbolic links. Many symbolic links
|
||||
are used in Nuttx (e.g., include/arch). The make system works around these
|
||||
problems for the Windows tools by copying directories instead of linking them.
|
||||
But this can also cause some confusion for you: For example, you may edit
|
||||
a file in a "linked" directory and find that your changes had no effect.
|
||||
That is because you are building the copy of the file in the "fake" symbolic
|
||||
directory. If you use a Windows toolchain, you should get in the habit of
|
||||
making like this:
|
||||
|
||||
make clean_context all
|
||||
|
||||
An alias in your .bashrc file might make that less painful.
|
||||
|
||||
3. Dependencies are not made when using Windows versions of the GCC. This is
|
||||
because the dependencies are generated using Windows pathes which do not
|
||||
work with the Cygwin make.
|
||||
|
||||
Support has been added for making dependencies with the windows-native toolchains.
|
||||
That support can be enabled by modifying your Make.defs file as follows:
|
||||
|
||||
- MKDEP = $(TOPDIR)/tools/mknulldeps.sh
|
||||
+ MKDEP = $(TOPDIR)/tools/mkdeps.sh --winpaths "$(TOPDIR)"
|
||||
|
||||
If you have problems with the dependency build (for example, if you are not
|
||||
building on C:), then you may need to modify tools/mkdeps.sh
|
||||
|
||||
NOTE 1: The CodeSourcery toolchain (2009q1) does not work with default optimization
|
||||
level of -Os (See Make.defs). It will work with -O0, -O1, or -O2, but not with
|
||||
-Os.
|
||||
|
||||
NOTE 2: The devkitARM toolchain includes a version of MSYS make. Make sure that
|
||||
the paths to Cygwin's /bin and /usr/bin directories appear BEFORE the devkitARM
|
||||
path or will get the wrong version of make.
|
||||
|
||||
IDEs
|
||||
====
|
||||
|
||||
NuttX is built using command-line make. It can be used with an IDE, but some
|
||||
effort will be required to create the project.
|
||||
|
||||
Makefile Build
|
||||
--------------
|
||||
Under Eclipse, it is pretty easy to set up an "empty makefile project" and
|
||||
simply use the NuttX makefile to build the system. That is almost for free
|
||||
under Linux. Under Windows, you will need to set up the "Cygwin GCC" empty
|
||||
makefile project in order to work with Windows (Google for "Eclipse Cygwin" -
|
||||
there is a lot of help on the internet).
|
||||
|
||||
Native Build
|
||||
------------
|
||||
Here are a few tips before you start that effort:
|
||||
|
||||
1) Select the toolchain that you will be using in your .config file
|
||||
2) Start the NuttX build at least one time from the Cygwin command line
|
||||
before trying to create your project. This is necessary to create
|
||||
certain auto-generated files and directories that will be needed.
|
||||
3) Set up include pathes: You will need include/, arch/arm/src/stm32,
|
||||
arch/arm/src/common, arch/arm/src/armv7-m, and sched/.
|
||||
4) All assembly files need to have the definition option -D __ASSEMBLY__
|
||||
on the command line.
|
||||
|
||||
Startup files will probably cause you some headaches. The NuttX startup file
|
||||
is arch/arm/src/stm32/stm32_vectors.S. With RIDE, I have to build NuttX
|
||||
one time from the Cygwin command line in order to obtain the pre-built
|
||||
startup object needed by RIDE.
|
||||
|
||||
NuttX buildroot Toolchain
|
||||
=========================
|
||||
|
||||
A GNU GCC-based toolchain is assumed. The files */setenv.sh should
|
||||
be modified to point to the correct path to the Cortex-M3 GCC toolchain (if
|
||||
different from the default in your PATH variable).
|
||||
|
||||
If you have no Cortex-M3 toolchain, one can be downloaded from the NuttX
|
||||
SourceForge download site (https://sourceforge.net/project/showfiles.php?group_id=189573).
|
||||
This GNU toolchain builds and executes in the Linux or Cygwin environment.
|
||||
|
||||
1. You must have already configured Nuttx in <some-dir>/nuttx.
|
||||
|
||||
cd tools
|
||||
./configure.sh stm3220g-eval/<sub-dir>
|
||||
|
||||
2. Download the latest buildroot package into <some-dir>
|
||||
|
||||
3. unpack the buildroot tarball. The resulting directory may
|
||||
have versioning information on it like buildroot-x.y.z. If so,
|
||||
rename <some-dir>/buildroot-x.y.z to <some-dir>/buildroot.
|
||||
|
||||
4. cd <some-dir>/buildroot
|
||||
|
||||
5. cp configs/cortexm3-defconfig-4.3.3 .config
|
||||
|
||||
6. make oldconfig
|
||||
|
||||
7. make
|
||||
|
||||
8. Edit setenv.h, if necessary, so that the PATH variable includes
|
||||
the path to the newly built binaries.
|
||||
|
||||
See the file configs/README.txt in the buildroot source tree. That has more
|
||||
detailed PLUS some special instructions that you will need to follow if you are
|
||||
building a Cortex-M3 toolchain for Cygwin under Windows.
|
||||
|
||||
Ethernet
|
||||
========
|
||||
|
||||
The Ethernet driver is configured to use the MII interface:
|
||||
|
||||
Board Jumper Settings:
|
||||
|
||||
Jumper Description
|
||||
JP8 To enable MII, JP8 should not be fitted.
|
||||
JP6 2-3: Enable MII interface mode
|
||||
JP5 2-3: Provide 25 MHz clock for MII or 50 MHz clock for RMII by MCO at PA8
|
||||
SB1 Not used with MII
|
||||
|
||||
LEDs
|
||||
====
|
||||
|
||||
The STM3220G-EVAL board has four LEDs labeled LD1, LD2, LD3 and LD4 on the
|
||||
board.. These LEDs are not used by the board port unless CONFIG_ARCH_LEDS is
|
||||
defined. In that case, the usage by the board port is defined in
|
||||
include/board.h and src/up_leds.c. The LEDs are used to encode OS-related\
|
||||
events as follows:
|
||||
|
||||
SYMBOL Meaning LED1* LED2 LED3 LED4
|
||||
------------------- ----------------------- ------- ------- ------- ------
|
||||
LED_STARTED NuttX has been started ON OFF OFF OFF
|
||||
LED_HEAPALLOCATE Heap has been allocated OFF ON OFF OFF
|
||||
LED_IRQSENABLED Interrupts enabled ON ON OFF OFF
|
||||
LED_STACKCREATED Idle stack created OFF OFF ON OFF
|
||||
LED_INIRQ In an interrupt** ON N/C N/C OFF
|
||||
LED_SIGNAL In a signal handler*** N/C ON N/C OFF
|
||||
LED_ASSERTION An assertion failed ON ON N/C OFF
|
||||
LED_PANIC The system has crashed N/C N/C N/C ON
|
||||
LED_IDLE STM32 is is sleep mode (Optional, not used)
|
||||
|
||||
* If LED1, LED2, LED3 are statically on, then NuttX probably failed to boot
|
||||
and these LEDs will give you some indication of where the failure was
|
||||
** The normal state is LED3 ON and LED1 faintly glowing. This faint glow
|
||||
is because of timer interupts that result in the LED being illuminated
|
||||
on a small proportion of the time.
|
||||
*** LED2 may also flicker normally if signals are processed.
|
||||
|
||||
PWM
|
||||
===
|
||||
|
||||
The STM3220G-Eval has no real on-board PWM devices, but the board can be
|
||||
configured to output a pulse train using timer output pins. The following
|
||||
pins have been use to generate PWM output (see board.h for some other
|
||||
candidates):
|
||||
|
||||
TIM4 CH2. Pin PD13 is used by the FSMC (FSMC_A18) and is also connected
|
||||
to the Motor Control Connector (CN5) just for this purpose. If FSMC is
|
||||
not enabled, then FSMC_A18 will not be used (and will be tri-stated from
|
||||
the LCD).
|
||||
|
||||
CONFIGURATION:
|
||||
|
||||
CONFIG_STM32_TIM4=y
|
||||
CONFIG_PWM=n
|
||||
CONFIG_PWM_PULSECOUNT=n
|
||||
CONFIG_STM32_TIM4_PWM=y
|
||||
CONFIG_STM32_TIM4_CHANNEL=2
|
||||
|
||||
ACCESS:
|
||||
|
||||
Daughterboard Extension Connector, CN3, pin 32
|
||||
Ground is available on CN3, pin1
|
||||
|
||||
NOTE: TIM4 hardware will not support pulse counting.
|
||||
|
||||
TIM8 CH4: Pin PC9 is used by the microSD card (MicroSDCard_D1) and I2S
|
||||
(I2S_CKIN) but can be completely disconnected from both by opening JP16.
|
||||
|
||||
CONFIGURATION:
|
||||
|
||||
CONFIG_STM32_TIM8=y
|
||||
CONFIG_PWM=n
|
||||
CONFIG_PWM_PULSECOUNT=y
|
||||
CONFIG_STM32_TIM8_PWM=y
|
||||
CONFIG_STM32_TIM8_CHANNEL=4
|
||||
|
||||
ACCESS:
|
||||
|
||||
Daughterboard Extension Connector, CN3, pin 17
|
||||
Ground is available on CN3, pin1
|
||||
|
||||
CAN
|
||||
===
|
||||
|
||||
Connector 10 (CN10) is DB-9 male connector that can be used with CAN1 or CAN2.
|
||||
|
||||
JP10 connects CAN1_RX or CAN2_RX to the CAN transceiver
|
||||
JP3 connects CAN1_TX or CAN2_TX to the CAN transceiver
|
||||
|
||||
CAN signals are then available on CN10 pins:
|
||||
|
||||
CN10 Pin 7 = CANH
|
||||
CN10 Pin 2 = CANL
|
||||
|
||||
Mapping to STM32 GPIO pins:
|
||||
|
||||
PD0 = FSMC_D2 & CAN1_RX
|
||||
PD1 = FSMC_D3 & CAN1_TX
|
||||
PB13 = ULPI_D6 & CAN2_TX
|
||||
PB5 = ULPI_D7 & CAN2_RX
|
||||
|
||||
Configuration Options:
|
||||
|
||||
CONFIG_CAN - Enables CAN support (one or both of CONFIG_STM32_CAN1 or
|
||||
CONFIG_STM32_CAN2 must also be defined)
|
||||
CONFIG_CAN_EXTID - Enables support for the 29-bit extended ID. Default
|
||||
Standard 11-bit IDs.
|
||||
CONFIG_CAN_FIFOSIZE - The size of the circular buffer of CAN messages.
|
||||
Default: 8
|
||||
CONFIG_CAN_NPENDINGRTR - The size of the list of pending RTR requests.
|
||||
Default: 4
|
||||
|
||||
CONFIG_STM32_CAN1 - Enable support for CAN1
|
||||
CONFIG_CAN1_BAUD - CAN1 BAUD rate. Required if CONFIG_STM32_CAN1 is defined.
|
||||
CONFIG_STM32_CAN2 - Enable support for CAN2
|
||||
CONFIG_CAN2_BAUD - CAN1 BAUD rate. Required if CONFIG_STM32_CAN2 is defined.
|
||||
CONFIG_CAN_TSEG1 - The number of CAN time quanta in segment 1. Default: 6
|
||||
CONFIG_CAN_TSEG2 - the number of CAN time quanta in segment 2. Default: 7
|
||||
CONFIG_CAN_REGDEBUG - If CONFIG_DEBUG is set, this will generate an
|
||||
dump of all CAN registers.
|
||||
|
||||
STM3220G-EVAL-specific Configuration Options
|
||||
============================================
|
||||
|
||||
CONFIG_ARCH - Identifies the arch/ subdirectory. This should
|
||||
be set to:
|
||||
|
||||
CONFIG_ARCH=arm
|
||||
|
||||
CONFIG_ARCH_family - For use in C code:
|
||||
|
||||
CONFIG_ARCH_ARM=y
|
||||
|
||||
CONFIG_ARCH_architecture - For use in C code:
|
||||
|
||||
CONFIG_ARCH_CORTEXM3=y
|
||||
|
||||
CONFIG_ARCH_CHIP - Identifies the arch/*/chip subdirectory
|
||||
|
||||
CONFIG_ARCH_CHIP=stm32
|
||||
|
||||
CONFIG_ARCH_CHIP_name - For use in C code to identify the exact
|
||||
chip:
|
||||
|
||||
CONFIG_ARCH_CHIP_STM32F207IG=y
|
||||
|
||||
CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG - Enables special STM32 clock
|
||||
configuration features.
|
||||
|
||||
CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG=n
|
||||
|
||||
CONFIG_ARCH_BOARD - Identifies the configs subdirectory and
|
||||
hence, the board that supports the particular chip or SoC.
|
||||
|
||||
CONFIG_ARCH_BOARD=stm3220g_eval (for the STM3220G-EVAL development board)
|
||||
|
||||
CONFIG_ARCH_BOARD_name - For use in C code
|
||||
|
||||
CONFIG_ARCH_BOARD_STM3220G_EVAL=y
|
||||
|
||||
CONFIG_ARCH_LOOPSPERMSEC - Must be calibrated for correct operation
|
||||
of delay loops
|
||||
|
||||
CONFIG_ENDIAN_BIG - define if big endian (default is little
|
||||
endian)
|
||||
|
||||
CONFIG_DRAM_SIZE - Describes the installed DRAM (SRAM in this case):
|
||||
|
||||
CONFIG_DRAM_SIZE=0x00010000 (64Kb)
|
||||
|
||||
CONFIG_DRAM_START - The start address of installed DRAM
|
||||
|
||||
CONFIG_DRAM_START=0x20000000
|
||||
|
||||
CONFIG_DRAM_END - Last address+1 of installed RAM
|
||||
|
||||
CONFIG_DRAM_END=(CONFIG_DRAM_START+CONFIG_DRAM_SIZE)
|
||||
|
||||
CONFIG_ARCH_IRQPRIO - The STM3220xxx supports interrupt prioritization
|
||||
|
||||
CONFIG_ARCH_IRQPRIO=y
|
||||
|
||||
CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to boards that
|
||||
have LEDs
|
||||
|
||||
CONFIG_ARCH_INTERRUPTSTACK - This architecture supports an interrupt
|
||||
stack. If defined, this symbol is the size of the interrupt
|
||||
stack in bytes. If not defined, the user task stacks will be
|
||||
used during interrupt handling.
|
||||
|
||||
CONFIG_ARCH_STACKDUMP - Do stack dumps after assertions
|
||||
|
||||
CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to board architecture.
|
||||
|
||||
CONFIG_ARCH_CALIBRATION - Enables some build in instrumentation that
|
||||
cause a 100 second delay during boot-up. This 100 second delay
|
||||
serves no purpose other than it allows you to calibratre
|
||||
CONFIG_ARCH_LOOPSPERMSEC. You simply use a stop watch to measure
|
||||
the 100 second delay then adjust CONFIG_ARCH_LOOPSPERMSEC until
|
||||
the delay actually is 100 seconds.
|
||||
|
||||
Individual subsystems can be enabled:
|
||||
|
||||
AHB1
|
||||
----
|
||||
CONFIG_STM32_CRC
|
||||
CONFIG_STM32_BKPSRAM
|
||||
CONFIG_STM32_CCMDATARAM
|
||||
CONFIG_STM32_DMA1
|
||||
CONFIG_STM32_DMA2
|
||||
CONFIG_STM32_ETHMAC
|
||||
CONFIG_STM32_OTGHS
|
||||
|
||||
AHB2
|
||||
----
|
||||
CONFIG_STM32_DCMI
|
||||
CONFIG_STM32_CRYP
|
||||
CONFIG_STM32_HASH
|
||||
CONFIG_STM32_RNG
|
||||
CONFIG_STM32_OTGFS
|
||||
|
||||
AHB3
|
||||
----
|
||||
CONFIG_STM32_FSMC
|
||||
|
||||
APB1
|
||||
----
|
||||
CONFIG_STM32_TIM2
|
||||
CONFIG_STM32_TIM3
|
||||
CONFIG_STM32_TIM4
|
||||
CONFIG_STM32_TIM5
|
||||
CONFIG_STM32_TIM6
|
||||
CONFIG_STM32_TIM7
|
||||
CONFIG_STM32_TIM12
|
||||
CONFIG_STM32_TIM13
|
||||
CONFIG_STM32_TIM14
|
||||
CONFIG_STM32_WWDG
|
||||
CONFIG_STM32_SPI2
|
||||
CONFIG_STM32_SPI3
|
||||
CONFIG_STM32_USART2
|
||||
CONFIG_STM32_USART3
|
||||
CONFIG_STM32_UART4
|
||||
CONFIG_STM32_UART5
|
||||
CONFIG_STM32_I2C1
|
||||
CONFIG_STM32_I2C2
|
||||
CONFIG_STM32_I2C3
|
||||
CONFIG_STM32_CAN1
|
||||
CONFIG_STM32_CAN2
|
||||
CONFIG_STM32_DAC1
|
||||
CONFIG_STM32_DAC2
|
||||
CONFIG_STM32_PWR -- Required for RTC
|
||||
|
||||
APB2
|
||||
----
|
||||
CONFIG_STM32_TIM1
|
||||
CONFIG_STM32_TIM8
|
||||
CONFIG_STM32_USART1
|
||||
CONFIG_STM32_USART6
|
||||
CONFIG_STM32_ADC1
|
||||
CONFIG_STM32_ADC2
|
||||
CONFIG_STM32_ADC3
|
||||
CONFIG_STM32_SDIO
|
||||
CONFIG_STM32_SPI1
|
||||
CONFIG_STM32_SYSCFG
|
||||
CONFIG_STM32_TIM9
|
||||
CONFIG_STM32_TIM10
|
||||
CONFIG_STM32_TIM11
|
||||
|
||||
Timer and I2C devices may need to the following to force power to be applied
|
||||
unconditionally at power up. (Otherwise, the device is powered when it is
|
||||
initialized).
|
||||
|
||||
CONFIG_STM32_FORCEPOWER
|
||||
|
||||
Timer devices may be used for different purposes. One special purpose is
|
||||
to generate modulated outputs for such things as motor control. If CONFIG_STM32_TIMn
|
||||
is defined (as above) then the following may also be defined to indicate that
|
||||
the timer is intended to be used for pulsed output modulation, ADC conversion,
|
||||
or DAC conversion. Note that ADC/DAC require two definition: Not only do you have
|
||||
to assign the timer (n) for used by the ADC or DAC, but then you also have to
|
||||
configure which ADC or DAC (m) it is assigned to.
|
||||
|
||||
CONFIG_STM32_TIMn_PWM Reserve timer n for use by PWM, n=1,..,14
|
||||
CONFIG_STM32_TIMn_ADC Reserve timer n for use by ADC, n=1,..,14
|
||||
CONFIG_STM32_TIMn_ADCm Reserve timer n to trigger ADCm, n=1,..,14, m=1,..,3
|
||||
CONFIG_STM32_TIMn_DAC Reserve timer n for use by DAC, n=1,..,14
|
||||
CONFIG_STM32_TIMn_DACm Reserve timer n to trigger DACm, n=1,..,14, m=1,..,2
|
||||
|
||||
For each timer that is enabled for PWM usage, we need the following additional
|
||||
configuration settings:
|
||||
|
||||
CONFIG_STM32_TIMx_CHANNEL - Specifies the timer output channel {1,..,4}
|
||||
|
||||
NOTE: The STM32 timers are each capable of generating different signals on
|
||||
each of the four channels with different duty cycles. That capability is
|
||||
not supported by this driver: Only one output channel per timer.
|
||||
|
||||
JTAG Enable settings (by default JTAG-DP and SW-DP are disabled):
|
||||
|
||||
CONFIG_STM32_JTAG_FULL_ENABLE - Enables full SWJ (JTAG-DP + SW-DP)
|
||||
CONFIG_STM32_JTAG_NOJNTRST_ENABLE - Enables full SWJ (JTAG-DP + SW-DP)
|
||||
but without JNTRST.
|
||||
CONFIG_STM32_JTAG_SW_ENABLE - Set JTAG-DP disabled and SW-DP enabled
|
||||
|
||||
STM3220xxx specific device driver settings
|
||||
|
||||
CONFIG_U[S]ARTn_SERIAL_CONSOLE - selects the USARTn (n=1,2,3) or UART
|
||||
m (m=4,5) for the console and ttys0 (default is the USART1).
|
||||
CONFIG_U[S]ARTn_RXBUFSIZE - Characters are buffered as received.
|
||||
This specific the size of the receive buffer
|
||||
CONFIG_U[S]ARTn_TXBUFSIZE - Characters are buffered before
|
||||
being sent. This specific the size of the transmit buffer
|
||||
CONFIG_U[S]ARTn_BAUD - The configure BAUD of the UART. Must be
|
||||
CONFIG_U[S]ARTn_BITS - The number of bits. Must be either 7 or 8.
|
||||
CONFIG_U[S]ARTn_PARTIY - 0=no parity, 1=odd parity, 2=even parity
|
||||
CONFIG_U[S]ARTn_2STOP - Two stop bits
|
||||
|
||||
CONFIG_STM32_SPI_INTERRUPTS - Select to enable interrupt driven SPI
|
||||
support. Non-interrupt-driven, poll-waiting is recommended if the
|
||||
interrupt rate would be to high in the interrupt driven case.
|
||||
CONFIG_STM32_SPI_DMA - Use DMA to improve SPI transfer performance.
|
||||
Cannot be used with CONFIG_STM32_SPI_INTERRUPT.
|
||||
|
||||
CONFIG_SDIO_DMA - Support DMA data transfers. Requires CONFIG_STM32_SDIO
|
||||
and CONFIG_STM32_DMA2.
|
||||
CONFIG_SDIO_PRI - Select SDIO interrupt prority. Default: 128
|
||||
CONFIG_SDIO_DMAPRIO - Select SDIO DMA interrupt priority.
|
||||
Default: Medium
|
||||
CONFIG_SDIO_WIDTH_D1_ONLY - Select 1-bit transfer mode. Default:
|
||||
4-bit transfer mode.
|
||||
|
||||
CONFIG_STM32_PHYADDR - The 5-bit address of the PHY on the board
|
||||
CONFIG_STM32_MII - Support Ethernet MII interface
|
||||
CONFIG_STM32_MII_MCO1 - Use MCO1 to clock the MII interface
|
||||
CONFIG_STM32_MII_MCO2 - Use MCO2 to clock the MII interface
|
||||
CONFIG_STM32_RMII - Support Ethernet RMII interface
|
||||
CONFIG_STM32_AUTONEG - Use PHY autonegotion to determine speed and mode
|
||||
CONFIG_STM32_ETHFD - If CONFIG_STM32_AUTONEG is not defined, then this
|
||||
may be defined to select full duplex mode. Default: half-duplex
|
||||
CONFIG_STM32_ETH100MBPS - If CONFIG_STM32_AUTONEG is not defined, then this
|
||||
may be defined to select 100 MBps speed. Default: 10 Mbps
|
||||
CONFIG_STM32_PHYSR - This must be provided if CONFIG_STM32_AUTONEG is
|
||||
defined. The PHY status register address may diff from PHY to PHY. This
|
||||
configuration sets the address of the PHY status register.
|
||||
CONFIG_STM32_PHYSR_SPEED - This must be provided if CONFIG_STM32_AUTONEG is
|
||||
defined. This provides bit mask indicating 10 or 100MBps speed.
|
||||
CONFIG_STM32_PHYSR_100MBPS - This must be provided if CONFIG_STM32_AUTONEG is
|
||||
defined. This provides the value of the speed bit(s) indicating 100MBps speed.
|
||||
CONFIG_STM32_PHYSR_MODE - This must be provided if CONFIG_STM32_AUTONEG is
|
||||
defined. This provide bit mask indicating full or half duplex modes.
|
||||
CONFIG_STM32_PHYSR_FULLDUPLEX - This must be provided if CONFIG_STM32_AUTONEG is
|
||||
defined. This provides the value of the mode bits indicating full duplex mode.
|
||||
CONFIG_STM32_ETH_PTP - Precision Time Protocol (PTP). Not supported
|
||||
but some hooks are indicated with this condition.
|
||||
|
||||
STM3220G-EVAL CAN Configuration
|
||||
|
||||
CONFIG_CAN - Enables CAN support (one or both of CONFIG_STM32_CAN1 or
|
||||
CONFIG_STM32_CAN2 must also be defined)
|
||||
CONFIG_CAN_FIFOSIZE - The size of the circular buffer of CAN messages.
|
||||
Default: 8
|
||||
CONFIG_CAN_NPENDINGRTR - The size of the list of pending RTR requests.
|
||||
Default: 4
|
||||
CONFIG_CAN_LOOPBACK - A CAN driver may or may not support a loopback
|
||||
mode for testing. The STM32 CAN driver does support loopback mode.
|
||||
CONFIG_CAN1_BAUD - CAN1 BAUD rate. Required if CONFIG_STM32_CAN1 is defined.
|
||||
CONFIG_CAN2_BAUD - CAN1 BAUD rate. Required if CONFIG_STM32_CAN2 is defined.
|
||||
CONFIG_CAN_TSEG1 - The number of CAN time quanta in segment 1. Default: 6
|
||||
CONFIG_CAN_TSEG2 - the number of CAN time quanta in segment 2. Default: 7
|
||||
CONFIG_CAN_REGDEBUG - If CONFIG_DEBUG is set, this will generate an
|
||||
dump of all CAN registers.
|
||||
|
||||
STM3220G-EVAL LCD Hardware Configuration
|
||||
|
||||
Configurations
|
||||
==============
|
||||
|
||||
Each STM3220G-EVAL configuration is maintained in a sudirectory and
|
||||
can be selected as follow:
|
||||
|
||||
cd tools
|
||||
./configure.sh stm3220g-eval/<subdir>
|
||||
cd -
|
||||
. ./setenv.sh
|
||||
|
||||
Where <subdir> is one of the following:
|
||||
|
||||
dhcpd:
|
||||
-----
|
||||
|
||||
This builds the DCHP server using the apps/examples/dhcpd application
|
||||
(for execution from FLASH.) See apps/examples/README.txt for information
|
||||
about the dhcpd example. The server address is 10.0.0.1 and it serves
|
||||
IP addresses in the range 10.0.0.2 through 10.0.0.17 (all of which, of
|
||||
course, are configurable).
|
||||
|
||||
CONFIG_STM32_CODESOURCERYW=y : CodeSourcery under Windows
|
||||
|
||||
nettest:
|
||||
-------
|
||||
|
||||
This configuration directory may be used to verify networking performance
|
||||
using the STM32's Ethernet controller. It uses apps/examples/nettest to excercise the
|
||||
TCP/IP network.
|
||||
|
||||
CONFIG_EXAMPLE_NETTEST_SERVER=n : Target is configured as the client
|
||||
CONFIG_EXAMPLE_NETTEST_PERFORMANCE=y : Only network performance is verified.
|
||||
CONFIG_EXAMPLE_NETTEST_IPADDR=(10<<24|0<<16|0<<8|2) : Target side is IP: 10.0.0.2
|
||||
CONFIG_EXAMPLE_NETTEST_DRIPADDR=(10<<24|0<<16|0<<8|1) : Host side is IP: 10.0.0.1
|
||||
CONFIG_EXAMPLE_NETTEST_CLIENTIP=(10<<24|0<<16|0<<8|1) : Server address used by which ever is client.
|
||||
|
||||
nsh:
|
||||
---
|
||||
Configures the NuttShell (nsh) located at apps/examples/nsh. The
|
||||
Configuration enables both the serial and telnet NSH interfaces.
|
||||
|
||||
CONFIG_STM32_CODESOURCERYW=y : CodeSourcery under Windows
|
||||
CONFIG_NSH_DHCPC=n : DHCP is disabled
|
||||
CONFIG_NSH_IPADDR=(10<<24|0<<16|0<<8|2) : Target IP address 10.0.0.2
|
||||
CONFIG_NSH_DRIPADDR=(10<<24|0<<16|0<<8|1) : Host IP address 10.0.0.1
|
||||
|
||||
NOTES:
|
||||
1. This example assumes that a network is connected. During its
|
||||
initialization, it will try to negotiate the link speed. If you have
|
||||
no network connected when you reset the board, there will be a long
|
||||
delay (maybe 30 seconds?) before anything happens. That is the timeout
|
||||
before the networking finally gives up and decides that no network is
|
||||
available.
|
||||
|
||||
2. This example supports the ADC test (apps/examples/adc) but this must
|
||||
be manually enabled by selecting:
|
||||
|
||||
CONFIG_ADC=y : Enable the generic ADC infrastructure
|
||||
CONFIG_STM32_ADC3=y : Enable ADC3
|
||||
CONFIG_STM32_TIM1=y : Enable Timer 1
|
||||
CONFIG_STM32_TIM1_ADC=y : Indicate that timer 1 will be used to trigger an ADC
|
||||
CONFIG_STM32_TIM1_ADC3=y : Assign timer 1 to drive ADC3 sampling
|
||||
CONFIG_STM32_ADC3_SAMPLE_FREQUENCY=100 : Select a sampling frequency
|
||||
|
||||
See also apps/examples/README.txt
|
||||
|
||||
General debug for analog devices (ADC/DAC):
|
||||
|
||||
CONFIG_DEBUG_ANALOG
|
||||
|
||||
3. This example supports the PWM test (apps/examples/pwm) but this must
|
||||
be manually enabled by selecting eeither
|
||||
|
||||
CONFIG_PWM=y : Enable the generic PWM infrastructure
|
||||
CONFIG_PWM_PULSECOUNT=n : Disable to support for TIM1/8 pulse counts
|
||||
CONFIG_STM32_TIM4=y : Enable TIM4
|
||||
CONFIG_STM32_TIM4_PWM=y : Use TIM4 to generate PWM output
|
||||
CONFIG_STM32_TIM4_CHANNEL=2 : Select output on TIM4, channel 2
|
||||
|
||||
If CONFIG_STM32_FSMC is disabled, output will appear on CN3, pin 32.
|
||||
Ground is available on CN3, pin1.
|
||||
|
||||
Or..
|
||||
|
||||
CONFIG_PWM=y : Enable the generic PWM infrastructure
|
||||
CONFIG_PWM_PULSECOUNT=y : Enable to support for TIM1/8 pulse counts
|
||||
CONFIG_STM32_TIM8=y : Enable TIM8
|
||||
CONFIG_STM32_TIM8_PWM=y : Use TIM8 to generate PWM output
|
||||
CONFIG_STM32_TIM8_CHANNEL=4 : Select output on TIM8, channel 4
|
||||
|
||||
If CONFIG_STM32_FSMC is disabled, output will appear on CN3, pin 17
|
||||
Ground is available on CN23 pin1.
|
||||
|
||||
See also include/board.h and apps/examples/README.txt
|
||||
|
||||
Special PWM-only debug options:
|
||||
|
||||
CONFIG_DEBUG_PWM
|
||||
|
||||
4. This example supports the CAN loopback test (apps/examples/can) but this
|
||||
must be manually enabled by selecting:
|
||||
|
||||
CONFIG_CAN=y : Enable the generic CAN infrastructure
|
||||
CONFIG_CAN_EXID=y or n : Enable to support extended ID frames
|
||||
CONFIG_STM32_CAN1=y : Enable CAN1
|
||||
CONFIG_CAN_LOOPBACK=y : Enable CAN loopback mode
|
||||
|
||||
See also apps/examples/README.txt
|
||||
|
||||
Special CAN-only debug options:
|
||||
|
||||
CONFIG_DEBUG_CAN
|
||||
CONFIG_CAN_REGDEBUG
|
||||
|
||||
5. This example can support an FTP client. In order to build in FTP client
|
||||
support simply uncomment the following lines in the appconfig file (before
|
||||
configuring) or in the apps/.config file (after configuring):
|
||||
|
||||
#CONFIGURED_APPS += netutils/ftpc
|
||||
#CONFIGURED_APPS += examples/ftpc
|
||||
|
||||
6. This example can support an FTP server. In order to build in FTP server
|
||||
support simply uncomment the following lines in the appconfig file (before
|
||||
configuring) or in the apps/.config file (after configuring):
|
||||
|
||||
#CONFIGURED_APPS += netutils/ftpd
|
||||
#CONFIGURED_APPS += examples/ftpd
|
||||
|
||||
And enable poll() support in the NuttX configuration file:
|
||||
|
||||
CONFIG_DISABLE_POLL=n
|
||||
|
||||
7. This configuration requires that jumper JP22 be set to enable RS-232 operation.
|
||||
|
||||
nsh2:
|
||||
-----
|
||||
|
||||
This is an alternaitve NSH configuration. One limitation of the STM3220G-EVAL
|
||||
board is that you cannot have both a UART-based NSH console and SDIO support.
|
||||
The nsh2 differs from the nsh configuration in the following ways:
|
||||
|
||||
-CONFIG_STM32_USART3=y : USART3 is disabled
|
||||
+ CONFIG_STM32_USART3=n
|
||||
|
||||
-CONFIG_STM32_SDIO=n : SDIO is enabled
|
||||
+CONFIG_STM32_SDIO=y
|
||||
|
||||
Logically, that is the only difference: This configuration has SDIO (and
|
||||
the SD card) enabled and the serial console disabled. There is ONLY a
|
||||
Telnet console!.
|
||||
|
||||
There are some special settings to make life with only a Telnet
|
||||
|
||||
CONFIG_SYSLOG=y - Enables the System Logging feature.
|
||||
CONFIG_RAMLOG=y - Enable the RAM-based logging feature.
|
||||
CONFIG_RAMLOG_CONSOLE=y - Use the RAM logger as the default console.
|
||||
This means that any console output from non-Telnet threads will
|
||||
go into the circular buffer in RAM.
|
||||
CONFIG_RAMLOG_SYSLOG - This enables the RAM-based logger as the
|
||||
system logger. This means that (1) in addition to the console
|
||||
output from other tasks, ALL of the debug output will also to
|
||||
to the circular buffer in RAM, and (2) NSH will now support a
|
||||
command called 'dmesg' that can be used to dump the RAM log.
|
||||
|
||||
There are a few other configuration differences as necessary to support
|
||||
this different device configuration. Just the do the 'diff' if you are
|
||||
curious.
|
||||
|
||||
NOTES:
|
||||
1. See the notes for the nsh configuration. Most also apply to the nsh2
|
||||
configuration.
|
||||
|
||||
2. RS-232 is disabled, but Telnet is still available for use as a console.
|
||||
|
||||
3. This configuration requires that jumper JP22 be set to enable SDIO operation.
|
||||
|
||||
ostest:
|
||||
------
|
||||
This configuration directory, performs a simple OS test using
|
||||
examples/ostest. By default, this project assumes that you are
|
||||
using the DFU bootloader.
|
||||
|
||||
CONFIG_STM32_CODESOURCERYW=y : CodeSourcery under Windows
|
||||
|
||||
telnetd:
|
||||
--------
|
||||
|
||||
A simple test of the Telnet daemon(see apps/netutils/README.txt,
|
||||
apps/examples/README.txt, and apps/examples/telnetd). This is
|
||||
the same daemon that is used in the nsh configuration so if you
|
||||
use NSH, then you don't care about this. This test is good for
|
||||
testing the Telnet daemon only because it works in a simpler
|
||||
environment than does the nsh configuration.
|
|
@ -0,0 +1,170 @@
|
|||
############################################################################
|
||||
# configs/stm3220g-eval/dhcpd/Make.defs
|
||||
#
|
||||
# Copyright (C) 2011 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.
|
||||
#
|
||||
############################################################################
|
||||
|
||||
include ${TOPDIR}/.config
|
||||
|
||||
# Setup for the selected toolchain
|
||||
|
||||
ifeq ($(CONFIG_STM32_CODESOURCERYW),y)
|
||||
# CodeSourcery under Windows
|
||||
CROSSDEV = arm-none-eabi-
|
||||
WINTOOL = y
|
||||
ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft
|
||||
endif
|
||||
ifeq ($(CONFIG_STM32_CODESOURCERYL),y)
|
||||
# CodeSourcery under Linux
|
||||
CROSSDEV = arm-none-eabi-
|
||||
ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft
|
||||
MAXOPTIMIZATION = -O2
|
||||
endif
|
||||
ifeq ($(CONFIG_STM32_DEVKITARM),y)
|
||||
# devkitARM under Windows
|
||||
CROSSDEV = arm-eabi-
|
||||
WINTOOL = y
|
||||
ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft
|
||||
endif
|
||||
ifeq ($(CONFIG_STM32_RAISONANCE),y)
|
||||
# Raisonance RIDE7 under Windows
|
||||
CROSSDEV = arm-none-eabi-
|
||||
WINTOOL = y
|
||||
ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft
|
||||
endif
|
||||
ifeq ($(CONFIG_STM32_BUILDROOT),y)
|
||||
# NuttX buildroot under Linux or Cygwin
|
||||
CROSSDEV = arm-elf-
|
||||
ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft
|
||||
MAXOPTIMIZATION = -Os
|
||||
endif
|
||||
|
||||
LDSCRIPT = ld.script
|
||||
|
||||
ifeq ($(WINTOOL),y)
|
||||
# Windows-native toolchains
|
||||
DIRLINK = $(TOPDIR)/tools/winlink.sh
|
||||
DIRUNLINK = $(TOPDIR)/tools/unlink.sh
|
||||
MKDEP = $(TOPDIR)/tools/mknulldeps.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)/dhcpd/$(LDSCRIPT)}"
|
||||
MAXOPTIMIZATION = -O2
|
||||
else
|
||||
# Linux/Cygwin-native toolchain
|
||||
MKDEP = $(TOPDIR)/tools/mkdeps.sh
|
||||
ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
|
||||
ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
|
||||
ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/dhcpd/$(LDSCRIPT)
|
||||
endif
|
||||
|
||||
CC = $(CROSSDEV)gcc
|
||||
CXX = $(CROSSDEV)g++
|
||||
CPP = $(CROSSDEV)gcc -E
|
||||
LD = $(CROSSDEV)ld
|
||||
AR = $(CROSSDEV)ar rcs
|
||||
NM = $(CROSSDEV)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
|
||||
else
|
||||
ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer
|
||||
endif
|
||||
|
||||
ARCHCFLAGS = -fno-builtin
|
||||
ARCHCXXFLAGS = -fno-builtin -fno-exceptions -fno-rtti
|
||||
ARCHWARNINGS = -Wall -Wstrict-prototypes -Wshadow
|
||||
ARCHWARNINGSXX = -Wall -Wshadow
|
||||
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.ld -no-check-sections
|
||||
LDNXFLATFLAGS = -e main -s 2048
|
||||
|
||||
OBJEXT = .o
|
||||
LIBEXT = .a
|
||||
EXEEXT =
|
||||
|
||||
ifneq ($(CROSSDEV),arm-elf-)
|
||||
LDFLAGS += -nostartfiles -nodefaultlibs
|
||||
endif
|
||||
ifeq ($(CONFIG_DEBUG_SYMBOLS),y)
|
||||
LDFLAGS += -g
|
||||
endif
|
||||
|
||||
define PREPROCESS
|
||||
@echo "CPP: $1->$2"
|
||||
@$(CPP) $(CPPFLAGS) $1 -o $2
|
||||
endef
|
||||
|
||||
define COMPILE
|
||||
@echo "CC: $1"
|
||||
@$(CC) -c $(CFLAGS) $1 -o $2
|
||||
endef
|
||||
|
||||
define COMPILEXX
|
||||
@echo "CXX: $1"
|
||||
@$(CXX) -c $(CXXFLAGS) $1 -o $2
|
||||
endef
|
||||
|
||||
define ASSEMBLE
|
||||
@echo "AS: $1"
|
||||
@$(CC) -c $(AFLAGS) $1 -o $2
|
||||
endef
|
||||
|
||||
define ARCHIVE
|
||||
echo "AR: $2"; \
|
||||
$(AR) $1 $2 || { echo "$(AR) $1 $2 FAILED!" ; exit 1 ; }
|
||||
endef
|
||||
|
||||
define CLEAN
|
||||
@rm -f *.o *.a
|
||||
endef
|
||||
|
||||
HOSTCC = gcc
|
||||
HOSTINCLUDES = -I.
|
||||
HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -g -pipe
|
||||
HOSTLDFLAGS =
|
||||
|
|
@ -0,0 +1,43 @@
|
|||
############################################################################
|
||||
# configs/stm3220g-eval/dhcpd/appconfig
|
||||
#
|
||||
# Copyright (C) 2011 Gregory Nutt. All rights reserved.
|
||||
# Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
#
|
||||
# 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.
|
||||
#
|
||||
############################################################################
|
||||
|
||||
# Path to example in apps/examples containing the user_start entry point
|
||||
|
||||
CONFIGURED_APPS += examples/dhcpd
|
||||
|
||||
# Networking support
|
||||
|
||||
CONFIGURED_APPS += netutils/dhcpd
|
||||
CONFIGURED_APPS += netutils/uiplib
|
File diff suppressed because it is too large
Load Diff
File diff suppressed because it is too large
Load Diff
|
@ -0,0 +1,116 @@
|
|||
/****************************************************************************
|
||||
* configs/stm3220g-eval/dhcpd/ld.script
|
||||
*
|
||||
* Copyright (C) 2011 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.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/* The STM32F103ZET6 has 1024Kb of FLASH beginning at address 0x0800:0000 and
|
||||
* 192Kb of SRAM. SRAM is split up into three blocks:
|
||||
*
|
||||
* 1) 112Kb of SRAM beginning at address 0x2000:0000
|
||||
* 2) 16Kb of SRAM beginning at address 0x2001:c000
|
||||
* 3) 64Kb of TCM SRAM beginning at address 0x1000:0000
|
||||
*
|
||||
* 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 = 1024K
|
||||
sram (rwx) : ORIGIN = 0x20000000, LENGTH = 112K
|
||||
}
|
||||
|
||||
OUTPUT_ARCH(arm)
|
||||
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
|
||||
|
||||
__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
|
||||
|
||||
.ARM.extab : {
|
||||
*(.ARM.extab*)
|
||||
} >sram
|
||||
|
||||
.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) }
|
||||
}
|
|
@ -0,0 +1,67 @@
|
|||
#!/bin/bash
|
||||
# configs/stm3220g-eval/dhcpd/setenv.sh
|
||||
#
|
||||
# Copyright (C) 2011 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.
|
||||
#
|
||||
|
||||
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 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 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"
|
||||
|
||||
# This the Cygwin path to the location where I build the buildroot
|
||||
# toolchain.
|
||||
#export TOOLCHAIN_BIN="${WD}/../misc/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}"
|
|
@ -0,0 +1,505 @@
|
|||
/************************************************************************************
|
||||
* configs/stm3220g-eval/include/board.h
|
||||
* include/arch/board/board.h
|
||||
*
|
||||
* Copyright (C) 2011-12 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.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
#ifndef __ARCH_BOARD_BOARD_H
|
||||
#define __ARCH_BOARD_BOARD_H
|
||||
|
||||
/************************************************************************************
|
||||
* Included Files
|
||||
************************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#ifndef __ASSEMBLY__
|
||||
# include <stdint.h>
|
||||
#endif
|
||||
#include "stm32_rcc.h"
|
||||
#include "stm32_sdio.h"
|
||||
#include "stm32_internal.h"
|
||||
|
||||
/************************************************************************************
|
||||
* Definitions
|
||||
************************************************************************************/
|
||||
|
||||
/* Clocking *************************************************************************/
|
||||
/* Four clock sources are available on STM3220G-EVAL evaluation board for
|
||||
* STM32F207IGH6 and RTC embedded:
|
||||
*
|
||||
* X1, 25 MHz crystal for ethernet PHY with socket. It can be removed when clock is
|
||||
* provided by MCO pin of the MCU
|
||||
* X2, 26 MHz crystal for USB OTG HS PHY
|
||||
* X3, 32 kHz crystal for embedded RTC
|
||||
* X4, 25 MHz crystal with socket for STM32F207IGH6 microcontroller (It can be removed
|
||||
* from socket when internal RC clock is used.)
|
||||
*
|
||||
* This is the "standard" configuration as set up by arch/arm/src/stm32f40xx_rcc.c:
|
||||
* System Clock source : PLL (HSE)
|
||||
* SYSCLK(Hz) : 168000000 Determined by PLL configuration
|
||||
* HCLK(Hz) : 168000000 (STM32_RCC_CFGR_HPRE)
|
||||
* AHB Prescaler : 1 (STM32_RCC_CFGR_HPRE)
|
||||
* APB1 Prescaler : 4 (STM32_RCC_CFGR_PPRE1)
|
||||
* APB2 Prescaler : 2 (STM32_RCC_CFGR_PPRE2)
|
||||
* HSE Frequency(Hz) : 25000000 (STM32_BOARD_XTAL)
|
||||
* PLLM : 25 (STM32_PLLCFG_PLLM)
|
||||
* PLLN : 336 (STM32_PLLCFG_PLLN)
|
||||
* PLLP : 2 (STM32_PLLCFG_PLLP)
|
||||
* PLLQ : 7 (STM32_PLLCFG_PPQ)
|
||||
* Main regulator output voltage : Scale1 mode Needed for high speed SYSCLK
|
||||
* Flash Latency(WS) : 5
|
||||
* Prefetch Buffer : OFF
|
||||
* Instruction cache : ON
|
||||
* Data cache : ON
|
||||
* Require 48MHz for USB OTG FS, : Enabled
|
||||
* SDIO and RNG clock
|
||||
*/
|
||||
|
||||
/* HSI - 16 MHz RC factory-trimmed
|
||||
* LSI - 32 KHz RC
|
||||
* HSE - On-board crystal frequency is 25MHz
|
||||
* LSE - 32.768 kHz
|
||||
*/
|
||||
|
||||
#define STM32_BOARD_XTAL 25000000ul
|
||||
|
||||
#define STM32_HSI_FREQUENCY 16000000ul
|
||||
#define STM32_LSI_FREQUENCY 32000
|
||||
#define STM32_HSE_FREQUENCY STM32_BOARD_XTAL
|
||||
#define STM32_LSE_FREQUENCY 32768
|
||||
|
||||
/* Main PLL Configuration.
|
||||
*
|
||||
* PLL source is HSE
|
||||
* PLL_VCO = (STM32_HSE_FREQUENCY / PLLM) * PLLN
|
||||
* = (25,000,000 / 25) * 336
|
||||
* = 336,000,000
|
||||
* SYSCLK = PLL_VCO / PLLP
|
||||
* = 336,000,000 / 2 = 168,000,000
|
||||
* USB OTG FS, SDIO and RNG Clock
|
||||
* = PLL_VCO / PLLQ
|
||||
* = 48,000,000
|
||||
*/
|
||||
|
||||
#define STM32_PLLCFG_PLLM RCC_PLLCFG_PLLM(25)
|
||||
#define STM32_PLLCFG_PLLN RCC_PLLCFG_PLLN(336)
|
||||
#define STM32_PLLCFG_PLLP RCC_PLLCFG_PLLP_2
|
||||
#define STM32_PLLCFG_PPQ RCC_PLLCFG_PLLQ(7)
|
||||
|
||||
#define STM32_SYSCLK_FREQUENCY 168000000ul
|
||||
|
||||
/* AHB clock (HCLK) is SYSCLK (168MHz) */
|
||||
|
||||
#define STM32_RCC_CFGR_HPRE RCC_CFGR_HPRE_SYSCLK /* HCLK = SYSCLK / 1 */
|
||||
#define STM32_HCLK_FREQUENCY STM32_SYSCLK_FREQUENCY
|
||||
#define STM32_BOARD_HCLK STM32_HCLK_FREQUENCY /* same as above, to satisfy compiler */
|
||||
|
||||
/* APB1 clock (PCLK1) is HCLK/4 (42MHz) */
|
||||
|
||||
#define STM32_RCC_CFGR_PPRE1 RCC_CFGR_PPRE1_HCLKd4 /* PCLK1 = HCLK / 4 */
|
||||
#define STM32_PCLK1_FREQUENCY (STM32_HCLK_FREQUENCY/4)
|
||||
|
||||
/* Timers driven from APB1 will be twice PCLK1 */
|
||||
|
||||
#define STM32_APB1_TIM2_CLKIN (2*STM32_PCLK1_FREQUENCY)
|
||||
#define STM32_APB1_TIM3_CLKIN (2*STM32_PCLK1_FREQUENCY)
|
||||
#define STM32_APB1_TIM4_CLKIN (2*STM32_PCLK1_FREQUENCY)
|
||||
#define STM32_APB1_TIM5_CLKIN (2*STM32_PCLK1_FREQUENCY)
|
||||
#define STM32_APB1_TIM6_CLKIN (2*STM32_PCLK1_FREQUENCY)
|
||||
#define STM32_APB1_TIM7_CLKIN (2*STM32_PCLK1_FREQUENCY)
|
||||
#define STM32_APB1_TIM12_CLKIN (2*STM32_PCLK1_FREQUENCY)
|
||||
#define STM32_APB1_TIM13_CLKIN (2*STM32_PCLK1_FREQUENCY)
|
||||
#define STM32_APB1_TIM14_CLKIN (2*STM32_PCLK1_FREQUENCY)
|
||||
|
||||
/* APB2 clock (PCLK2) is HCLK/2 (84MHz) */
|
||||
|
||||
#define STM32_RCC_CFGR_PPRE2 RCC_CFGR_PPRE2_HCLKd2 /* PCLK2 = HCLK / 2 */
|
||||
#define STM32_PCLK2_FREQUENCY (STM32_HCLK_FREQUENCY/2)
|
||||
|
||||
/* Timers driven from APB2 will be twice PCLK2 */
|
||||
|
||||
#define STM32_APB2_TIM1_CLKIN (2*STM32_PCLK2_FREQUENCY)
|
||||
#define STM32_APB2_TIM8_CLKIN (2*STM32_PCLK2_FREQUENCY)
|
||||
#define STM32_APB2_TIM9_CLKIN (2*STM32_PCLK2_FREQUENCY)
|
||||
#define STM32_APB2_TIM10_CLKIN (2*STM32_PCLK2_FREQUENCY)
|
||||
#define STM32_APB2_TIM11_CLKIN (2*STM32_PCLK2_FREQUENCY)
|
||||
|
||||
/* Timer Frequencies, if APBx is set to 1, frequency is same to APBx
|
||||
* otherwise frequency is 2xAPBx.
|
||||
* Note: TIM1,8 are on APB2, others on APB1
|
||||
*/
|
||||
|
||||
#define STM32_TIM18_FREQUENCY STM32_HCLK_FREQUENCY
|
||||
#define STM32_TIM27_FREQUENCY STM32_HCLK_FREQUENCY
|
||||
|
||||
/* SDIO dividers. Note that slower clocking is required when DMA is disabled
|
||||
* in order to avoid RX overrun/TX underrun errors due to delayed responses
|
||||
* to service FIFOs in interrupt driven mode. These values have not been
|
||||
* tuned!!!
|
||||
*
|
||||
* HCLK=72MHz, SDIOCLK=72MHz, SDIO_CK=HCLK/(178+2)=400 KHz
|
||||
*/
|
||||
|
||||
#define SDIO_INIT_CLKDIV (178 << SDIO_CLKCR_CLKDIV_SHIFT)
|
||||
|
||||
/* DMA ON: HCLK=72 MHz, SDIOCLK=72MHz, SDIO_CK=HCLK/(2+2)=18 MHz
|
||||
* DMA OFF: HCLK=72 MHz, SDIOCLK=72MHz, SDIO_CK=HCLK/(3+2)=14.4 MHz
|
||||
*/
|
||||
|
||||
#ifdef CONFIG_SDIO_DMA
|
||||
# define SDIO_MMCXFR_CLKDIV (2 << SDIO_CLKCR_CLKDIV_SHIFT)
|
||||
#else
|
||||
# define SDIO_MMCXFR_CLKDIV (3 << SDIO_CLKCR_CLKDIV_SHIFT)
|
||||
#endif
|
||||
|
||||
/* DMA ON: HCLK=72 MHz, SDIOCLK=72MHz, SDIO_CK=HCLK/(1+2)=24 MHz
|
||||
* DMA OFF: HCLK=72 MHz, SDIOCLK=72MHz, SDIO_CK=HCLK/(3+2)=14.4 MHz
|
||||
*/
|
||||
|
||||
#ifdef CONFIG_SDIO_DMA
|
||||
# define SDIO_SDXFR_CLKDIV (1 << SDIO_CLKCR_CLKDIV_SHIFT)
|
||||
#else
|
||||
# define SDIO_SDXFR_CLKDIV (3 << SDIO_CLKCR_CLKDIV_SHIFT)
|
||||
#endif
|
||||
|
||||
/* Ethernet *************************************************************************/
|
||||
/* We need to provide clocking to the MII PHY via MCO1 (PA8) */
|
||||
|
||||
#if defined(CONFIG_NET) && defined(CONFIG_STM32_ETHMAC)
|
||||
|
||||
# if !defined(CONFIG_STM32_MII)
|
||||
# warning "CONFIG_STM32_MII required for Ethernet"
|
||||
# elif !defined(CONFIG_STM32_MII_MCO1)
|
||||
# warning "CONFIG_STM32_MII_MCO1 required for Ethernet MII"
|
||||
# else
|
||||
|
||||
/* Output HSE clock (25MHz) on MCO1 pin (PA8) to clock the PHY */
|
||||
|
||||
# define BOARD_CFGR_MC01_SOURCE RCC_CFGR_MCO1_HSE
|
||||
# define BOARD_CFGR_MC01_DIVIDER RCC_CFGR_MCO1PRE_NONE
|
||||
|
||||
# endif
|
||||
#endif
|
||||
|
||||
/* LED definitions ******************************************************************/
|
||||
/* 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 stm32_setled() */
|
||||
|
||||
#define BOARD_LED1 0
|
||||
#define BOARD_LED2 1
|
||||
#define BOARD_LED3 2
|
||||
#define BOARD_LED4 3
|
||||
#define BOARD_NLEDS 4
|
||||
|
||||
/* LED bits for use with stm32_setleds() */
|
||||
|
||||
#define BOARD_LED1_BIT (1 << BOARD_LED1)
|
||||
#define BOARD_LED2_BIT (1 << BOARD_LED2)
|
||||
#define BOARD_LED3_BIT (1 << BOARD_LED3)
|
||||
#define BOARD_LED4_BIT (1 << BOARD_LED4)
|
||||
|
||||
/* If CONFIG_ARCH_LEDs is defined, then NuttX will control the 4 LEDs on board the
|
||||
* STM3220G-EVAL. The following definitions describe how NuttX controls the LEDs:
|
||||
*/
|
||||
|
||||
#define LED_STARTED 0 /* LED1 */
|
||||
#define LED_HEAPALLOCATE 1 /* LED2 */
|
||||
#define LED_IRQSENABLED 2 /* LED1 + LED2 */
|
||||
#define LED_STACKCREATED 3 /* LED3 */
|
||||
#define LED_INIRQ 4 /* LED1 + LED3 */
|
||||
#define LED_SIGNAL 5 /* LED2 + LED3 */
|
||||
#define LED_ASSERTION 6 /* LED1 + LED2 + LED3 */
|
||||
#define LED_PANIC 7 /* N/C + N/C + N/C + LED4 */
|
||||
|
||||
/* Button definitions ***************************************************************/
|
||||
/* The STM3220G-EVAL supports three buttons: */
|
||||
|
||||
#define BUTTON_WAKEUP 0
|
||||
#define BUTTON_TAMPER 1
|
||||
#define BUTTON_USER 2
|
||||
|
||||
#define NUM_BUTTONS 3
|
||||
|
||||
#define BUTTON_WAKEUP_BIT (1 << BUTTON_WAKEUP)
|
||||
#define BUTTON_TAMPER_BIT (1 << BUTTON_TAMPER)
|
||||
#define BUTTON_USER_BIT (1 << BUTTON_USER)
|
||||
|
||||
/* Alternate function pin selections ************************************************/
|
||||
|
||||
/* UART3:
|
||||
*
|
||||
* - PC11 is MicroSDCard_D3 & RS232/IrDA_RX (JP22 open)
|
||||
* - PC10 is MicroSDCard_D2 & RSS232/IrDA_TX
|
||||
*/
|
||||
|
||||
#define GPIO_USART3_RX GPIO_USART3_RX_2
|
||||
#define GPIO_USART3_TX GPIO_USART3_TX_2
|
||||
|
||||
/* Ethernet:
|
||||
*
|
||||
* - PA2 is ETH_MDIO
|
||||
* - PC1 is ETH_MDC
|
||||
* - PB5 is ETH_PPS_OUT
|
||||
* - PH2 is ETH_MII_CRS
|
||||
* - PH3 is ETH_MII_COL
|
||||
* - PI10 is ETH_MII_RX_ER
|
||||
* - PH6 is ETH_MII_RXD2
|
||||
* - PH7 is ETH_MII_RXD3
|
||||
* - PC3 is ETH_MII_TX_CLK
|
||||
* - PC2 is ETH_MII_TXD2
|
||||
* - PB8 is ETH_MII_TXD3
|
||||
* - PA1 is ETH_MII_RX_CLK/ETH_RMII_REF_CLK
|
||||
* - PA7 is ETH_MII_RX_DV/ETH_RMII_CRS_DV
|
||||
* - PC4 is ETH_MII_RXD0/ETH_RMII_RXD0
|
||||
* - PC5 is ETH_MII_RXD1/ETH_RMII_RXD1
|
||||
* - PG11 is ETH_MII_TX_EN/ETH_RMII_TX_EN
|
||||
* - PG13 is ETH_MII_TXD0/ETH_RMII_TXD0
|
||||
* - PG14 is ETH_MII_TXD1/ETH_RMII_TXD1
|
||||
*/
|
||||
|
||||
#define GPIO_ETH_PPS_OUT GPIO_ETH_PPS_OUT_1
|
||||
#define GPIO_ETH_MII_CRS GPIO_ETH_MII_CRS_2
|
||||
#define GPIO_ETH_MII_COL GPIO_ETH_MII_COL_2
|
||||
#define GPIO_ETH_MII_RX_ER GPIO_ETH_MII_RX_ER_2
|
||||
#define GPIO_ETH_MII_RXD2 GPIO_ETH_MII_RXD2_2
|
||||
#define GPIO_ETH_MII_RXD3 GPIO_ETH_MII_RXD3_2
|
||||
#define GPIO_ETH_MII_TXD3 GPIO_ETH_MII_TXD3_1
|
||||
#define GPIO_ETH_MII_TX_EN GPIO_ETH_MII_TX_EN_2
|
||||
#define GPIO_ETH_MII_TXD0 GPIO_ETH_MII_TXD0_2
|
||||
#define GPIO_ETH_MII_TXD1 GPIO_ETH_MII_TXD1_2
|
||||
#define GPIO_ETH_RMII_TX_EN GPIO_ETH_RMII_TX_EN_2
|
||||
#define GPIO_ETH_RMII_TXD0 GPIO_ETH_RMII_TXD0_2
|
||||
#define GPIO_ETH_RMII_TXD1 GPIO_ETH_RMII_TXD1_2
|
||||
|
||||
/* PWM
|
||||
*
|
||||
* The STM3220G-Eval has no real on-board PWM devices, but the board can be
|
||||
* configured to output a pulse train using the following:
|
||||
*
|
||||
* If FSMC is not used:
|
||||
* TIM4 CH2OUT: PD13 FSMC_A18 / MC_TIM4_CH2OUT
|
||||
* Daughterboard Extension Connector, CN3, pin 32
|
||||
* Motor Control Connector CN15, pin 33 -- not available unless you bridge SB14.
|
||||
*
|
||||
* TIM1 CH1OUT: PE9 FSMC_D6
|
||||
* Daughterboard Extension Connector, CN2, pin 24
|
||||
*
|
||||
* TIM1_CH2OUT: PE11 FSMC_D8
|
||||
* Daughterboard Extension Connector, CN2, pin 26
|
||||
*
|
||||
* TIM1_CH3OUT: PE13 FSMC_D10
|
||||
* Daughterboard Extension Connector, CN2, pin 28
|
||||
*
|
||||
* TIM1_CH4OUT: PE14 FSMC_D11
|
||||
* Daughterboard Extension Connector, CN2, pin 29
|
||||
*
|
||||
* If OTG FS is not used
|
||||
*
|
||||
* TIM1_CH3OUT: PA10 OTG_FS_ID
|
||||
* Daughterboard Extension Connector, CN3, pin 14
|
||||
*
|
||||
* TIM1_CH4OUT: PA11 OTG_FS_DM
|
||||
* Daughterboard Extension Connector, CN3, pin 11
|
||||
*
|
||||
* If DMCI is not used
|
||||
*
|
||||
* TIM8 CH1OUT: PI5 DCMI_VSYNC & MC
|
||||
* Daughterboard Extension Connector, CN4, pin 4
|
||||
*
|
||||
* TIM8_CH2OUT: PI6 DCMI_D6 & MC
|
||||
* Daughterboard Extension Connector, CN4, pin 3
|
||||
*
|
||||
* TIM8_CH3OUT: PI7 DCMI_D7 & MC
|
||||
* Daughterboard Extension Connector, CN4, pin 2
|
||||
*
|
||||
* If SDIO is not used
|
||||
*
|
||||
* TIM8_CH3OUT: PC8 MicroSDCard_D0 & MC
|
||||
* Daughterboard Extension Connector, CN3, pin 18
|
||||
*
|
||||
* TIM8_CH4OUT: PC9 MicroSDCard_D1 & I2S_CKIN (Need JP16 open)
|
||||
* Daughterboard Extension Connector, CN3, pin 17
|
||||
*
|
||||
* Others
|
||||
*
|
||||
* TIM8 CH1OUT: PC6 I2S_MCK & Smartcard_IO (JP21 open)
|
||||
*/
|
||||
|
||||
#if !defined(CONFIG_STM32_FSMC)
|
||||
# define GPIO_TIM4_CH2OUT GPIO_TIM4_CH2OUT_2
|
||||
# define GPIO_TIM1_CH1OUT GPIO_TIM1_CH1OUT_2
|
||||
# define GPIO_TIM1_CH2OUT GPIO_TIM1_CH2OUT_2
|
||||
# define GPIO_TIM1_CH3OUT GPIO_TIM1_CH3OUT_2
|
||||
# define GPIO_TIM1_CH4OUT GPIO_TIM1_CH4OUT_2
|
||||
#elif !defined(CONFIG_STM32_OTGFS)
|
||||
# define GPIO_TIM1_CH3OUT GPIO_TIM1_CH3OUT_1
|
||||
# define GPIO_TIM1_CH4OUT GPIO_TIM1_CH4OUT_1
|
||||
#endif
|
||||
|
||||
#if !defined(CONFIG_STM32_DCMI)
|
||||
# define GPIO_TIM8_CH1OUT GPIO_TIM8_CH1OUT_2
|
||||
# define GPIO_TIM8_CH2OUT GPIO_TIM8_CH2OUT_2
|
||||
# define GPIO_TIM8_CH3OUT GPIO_TIM8_CH3OUT_2
|
||||
#else
|
||||
# define GPIO_TIM8_CH1OUT GPIO_TIM8_CH1OUT_1
|
||||
# if !defined(CONFIG_STM32_SDIO)
|
||||
# define GPIO_TIM8_CH3OUT GPIO_TIM8_CH3OUT_1
|
||||
# endif
|
||||
#endif
|
||||
|
||||
#if !defined(CONFIG_STM32_SDIO)
|
||||
# define GPIO_TIM8_CH4OUT GPIO_TIM8_CH4OUT_1
|
||||
#endif
|
||||
|
||||
/* CAN
|
||||
*
|
||||
* Connector 10 (CN10) is DB-9 male connector that can be used with CAN1 or CAN2.
|
||||
*
|
||||
* JP10 connects CAN1_RX or CAN2_RX to the CAN transceiver
|
||||
* JP3 connects CAN1_TX or CAN2_TX to the CAN transceiver
|
||||
*
|
||||
* CAN signals are then available on CN10 pins:
|
||||
*
|
||||
* CN10 Pin 7 = CANH
|
||||
* CN10 Pin 2 = CANL
|
||||
*
|
||||
* Mapping to STM32 GPIO pins:
|
||||
*
|
||||
* PD0 = FSMC_D2 & CAN1_RX
|
||||
* PD1 = FSMC_D3 & CAN1_TX
|
||||
* PB13 = ULPI_D6 & CAN2_TX
|
||||
* PB5 = ULPI_D7 & CAN2_RX
|
||||
*/
|
||||
|
||||
#define GPIO_CAN1_RX GPIO_CAN1_RX_3
|
||||
#define GPIO_CAN1_TX GPIO_CAN1_TX_3
|
||||
|
||||
#define GPIO_CAN2_RX GPIO_CAN2_RX_2
|
||||
#define GPIO_CAN2_TX GPIO_CAN2_TX_1
|
||||
|
||||
/* I2C. Only I2C1 is available on the STM3220G-EVAL. I2C1_SCL and I2C1_SDA are
|
||||
* available on the following pins:
|
||||
*
|
||||
* - PB6 is I2C1_SCL
|
||||
* - PB9 is I2C1_SDA
|
||||
*/
|
||||
|
||||
#define GPIO_I2C1_SCL GPIO_I2C1_SCL_1
|
||||
#define GPIO_I2C1_SDA GPIO_I2C1_SDA_2
|
||||
|
||||
/************************************************************************************
|
||||
* Public Data
|
||||
************************************************************************************/
|
||||
|
||||
#ifndef __ASSEMBLY__
|
||||
|
||||
#undef EXTERN
|
||||
#if defined(__cplusplus)
|
||||
#define EXTERN extern "C"
|
||||
extern "C" {
|
||||
#else
|
||||
#define EXTERN extern
|
||||
#endif
|
||||
|
||||
/************************************************************************************
|
||||
* Public Function Prototypes
|
||||
************************************************************************************/
|
||||
/************************************************************************************
|
||||
* Name: stm32_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.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
EXTERN void stm32_boardinitialize(void);
|
||||
|
||||
/************************************************************************************
|
||||
* Name: stm32_ledinit, stm32_setled, and stm32_setleds
|
||||
*
|
||||
* Description:
|
||||
* If CONFIG_ARCH_LEDS is defined, then NuttX will control the on-board LEDs. If
|
||||
* CONFIG_ARCH_LEDS is not defined, then the following interfacesare available to
|
||||
* control the LEDs from user applications.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
#ifndef CONFIG_ARCH_LEDS
|
||||
EXTERN void stm32_ledinit(void);
|
||||
EXTERN void stm32_setled(int led, bool ledon);
|
||||
EXTERN void stm32_setleds(uint8_t ledset);
|
||||
#endif
|
||||
|
||||
/************************************************************************************
|
||||
* Button support.
|
||||
*
|
||||
* Description:
|
||||
* up_buttoninit() must be called to initialize button resources. After
|
||||
* that, up_buttons() may be called to collect the current state of all
|
||||
* buttons or up_irqbutton() may be called to register button interrupt
|
||||
* handlers.
|
||||
*
|
||||
* After up_buttoninit() has been called, up_buttons() may be called to
|
||||
* collect the state of all buttons. up_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.
|
||||
*
|
||||
* up_irqbutton() 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. The previous interrupt handler address is returned (so that it may
|
||||
* restored, if so desired).
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
#ifdef CONFIG_ARCH_BUTTONS
|
||||
EXTERN void up_buttoninit(void);
|
||||
EXTERN uint8_t up_buttons(void);
|
||||
#ifdef CONFIG_ARCH_IRQBUTTONS
|
||||
EXTERN xcpt_t up_irqbutton(int id, xcpt_t irqhandler);
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#undef EXTERN
|
||||
#if defined(__cplusplus)
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif /* __ASSEMBLY__ */
|
||||
#endif /* __ARCH_BOARD_BOARD_H */
|
|
@ -0,0 +1,170 @@
|
|||
############################################################################
|
||||
# configs/stm3220g-eval/nettest/Make.defs
|
||||
#
|
||||
# Copyright (C) 2011 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.
|
||||
#
|
||||
############################################################################
|
||||
|
||||
include ${TOPDIR}/.config
|
||||
|
||||
# Setup for the selected toolchain
|
||||
|
||||
ifeq ($(CONFIG_STM32_CODESOURCERYW),y)
|
||||
# CodeSourcery under Windows
|
||||
CROSSDEV = arm-none-eabi-
|
||||
WINTOOL = y
|
||||
ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft
|
||||
endif
|
||||
ifeq ($(CONFIG_STM32_CODESOURCERYL),y)
|
||||
# CodeSourcery under Linux
|
||||
CROSSDEV = arm-none-eabi-
|
||||
ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft
|
||||
MAXOPTIMIZATION = -O2
|
||||
endif
|
||||
ifeq ($(CONFIG_STM32_DEVKITARM),y)
|
||||
# devkitARM under Windows
|
||||
CROSSDEV = arm-eabi-
|
||||
WINTOOL = y
|
||||
ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft
|
||||
endif
|
||||
ifeq ($(CONFIG_STM32_RAISONANCE),y)
|
||||
# Raisonance RIDE7 under Windows
|
||||
CROSSDEV = arm-none-eabi-
|
||||
WINTOOL = y
|
||||
ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft
|
||||
endif
|
||||
ifeq ($(CONFIG_STM32_BUILDROOT),y)
|
||||
# NuttX buildroot under Linux or Cygwin
|
||||
CROSSDEV = arm-elf-
|
||||
ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft
|
||||
MAXOPTIMIZATION = -Os
|
||||
endif
|
||||
|
||||
LDSCRIPT = ld.script
|
||||
|
||||
ifeq ($(WINTOOL),y)
|
||||
# Windows-native toolchains
|
||||
DIRLINK = $(TOPDIR)/tools/winlink.sh
|
||||
DIRUNLINK = $(TOPDIR)/tools/unlink.sh
|
||||
MKDEP = $(TOPDIR)/tools/mknulldeps.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)/nettest/$(LDSCRIPT)}"
|
||||
MAXOPTIMIZATION = -O2
|
||||
else
|
||||
# Linux/Cygwin-native toolchain
|
||||
MKDEP = $(TOPDIR)/tools/mkdeps.sh
|
||||
ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
|
||||
ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
|
||||
ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/nettest/$(LDSCRIPT)
|
||||
endif
|
||||
|
||||
CC = $(CROSSDEV)gcc
|
||||
CXX = $(CROSSDEV)g++
|
||||
CPP = $(CROSSDEV)gcc -E
|
||||
LD = $(CROSSDEV)ld
|
||||
AR = $(CROSSDEV)ar rcs
|
||||
NM = $(CROSSDEV)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
|
||||
else
|
||||
ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer
|
||||
endif
|
||||
|
||||
ARCHCFLAGS = -fno-builtin
|
||||
ARCHCXXFLAGS = -fno-builtin -fno-exceptions -fno-rtti
|
||||
ARCHWARNINGS = -Wall -Wstrict-prototypes -Wshadow
|
||||
ARCHWARNINGSXX = -Wall -Wshadow
|
||||
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.ld -no-check-sections
|
||||
LDNXFLATFLAGS = -e main -s 2048
|
||||
|
||||
OBJEXT = .o
|
||||
LIBEXT = .a
|
||||
EXEEXT =
|
||||
|
||||
ifneq ($(CROSSDEV),arm-elf-)
|
||||
LDFLAGS += -nostartfiles -nodefaultlibs
|
||||
endif
|
||||
ifeq ($(CONFIG_DEBUG_SYMBOLS),y)
|
||||
LDFLAGS += -g
|
||||
endif
|
||||
|
||||
define PREPROCESS
|
||||
@echo "CPP: $1->$2"
|
||||
@$(CPP) $(CPPFLAGS) $1 -o $2
|
||||
endef
|
||||
|
||||
define COMPILE
|
||||
@echo "CC: $1"
|
||||
@$(CC) -c $(CFLAGS) $1 -o $2
|
||||
endef
|
||||
|
||||
define COMPILEXX
|
||||
@echo "CXX: $1"
|
||||
@$(CXX) -c $(CXXFLAGS) $1 -o $2
|
||||
endef
|
||||
|
||||
define ASSEMBLE
|
||||
@echo "AS: $1"
|
||||
@$(CC) -c $(AFLAGS) $1 -o $2
|
||||
endef
|
||||
|
||||
define ARCHIVE
|
||||
echo "AR: $2"; \
|
||||
$(AR) $1 $2 || { echo "$(AR) $1 $2 FAILED!" ; exit 1 ; }
|
||||
endef
|
||||
|
||||
define CLEAN
|
||||
@rm -f *.o *.a
|
||||
endef
|
||||
|
||||
HOSTCC = gcc
|
||||
HOSTINCLUDES = -I.
|
||||
HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -g -pipe
|
||||
HOSTLDFLAGS =
|
||||
|
|
@ -0,0 +1,42 @@
|
|||
############################################################################
|
||||
# configs/nettest/nettest/appconfig
|
||||
#
|
||||
# Copyright (C) 2011 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.
|
||||
#
|
||||
############################################################################
|
||||
|
||||
# Path to example in apps/examples containing the user_start entry point
|
||||
|
||||
CONFIGURED_APPS += examples/nettest
|
||||
|
||||
# Networking support
|
||||
|
||||
CONFIGURED_APPS += netutils/uiplib
|
File diff suppressed because it is too large
Load Diff
File diff suppressed because it is too large
Load Diff
|
@ -0,0 +1,116 @@
|
|||
/****************************************************************************
|
||||
* configs/stm3220g-eval/nettest/ld.script
|
||||
*
|
||||
* Copyright (C) 2011 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.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/* The STM32F103ZET6 has 1024Kb of FLASH beginning at address 0x0800:0000 and
|
||||
* 192Kb of SRAM. SRAM is split up into three blocks:
|
||||
*
|
||||
* 1) 112Kb of SRAM beginning at address 0x2000:0000
|
||||
* 2) 16Kb of SRAM beginning at address 0x2001:c000
|
||||
* 3) 64Kb of TCM SRAM beginning at address 0x1000:0000
|
||||
*
|
||||
* 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 = 1024K
|
||||
sram (rwx) : ORIGIN = 0x20000000, LENGTH = 112K
|
||||
}
|
||||
|
||||
OUTPUT_ARCH(arm)
|
||||
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
|
||||
|
||||
__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
|
||||
|
||||
.ARM.extab : {
|
||||
*(.ARM.extab*)
|
||||
} >sram
|
||||
|
||||
.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) }
|
||||
}
|
|
@ -0,0 +1,67 @@
|
|||
#!/bin/bash
|
||||
# configs/stm3220g-eval/nettest/setenv.sh
|
||||
#
|
||||
# Copyright (C) 2011 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.
|
||||
#
|
||||
|
||||
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 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 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"
|
||||
|
||||
# This the Cygwin path to the location where I build the buildroot
|
||||
# toolchain.
|
||||
#export TOOLCHAIN_BIN="${WD}/../misc/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}"
|
|
@ -0,0 +1,170 @@
|
|||
############################################################################
|
||||
# configs/stm3220g-eval/nsh/Make.defs
|
||||
#
|
||||
# Copyright (C) 2011 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.
|
||||
#
|
||||
############################################################################
|
||||
|
||||
include ${TOPDIR}/.config
|
||||
|
||||
# Setup for the selected toolchain
|
||||
|
||||
ifeq ($(CONFIG_STM32_CODESOURCERYW),y)
|
||||
# CodeSourcery under Windows
|
||||
CROSSDEV = arm-none-eabi-
|
||||
WINTOOL = y
|
||||
ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft
|
||||
endif
|
||||
ifeq ($(CONFIG_STM32_CODESOURCERYL),y)
|
||||
# CodeSourcery under Linux
|
||||
CROSSDEV = arm-none-eabi-
|
||||
ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft
|
||||
MAXOPTIMIZATION = -O2
|
||||
endif
|
||||
ifeq ($(CONFIG_STM32_DEVKITARM),y)
|
||||
# devkitARM under Windows
|
||||
CROSSDEV = arm-eabi-
|
||||
WINTOOL = y
|
||||
ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft
|
||||
endif
|
||||
ifeq ($(CONFIG_STM32_RAISONANCE),y)
|
||||
# Raisonance RIDE7 under Windows
|
||||
CROSSDEV = arm-none-eabi-
|
||||
WINTOOL = y
|
||||
ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft
|
||||
endif
|
||||
ifeq ($(CONFIG_STM32_BUILDROOT),y)
|
||||
# NuttX buildroot under Linux or Cygwin
|
||||
CROSSDEV = arm-elf-
|
||||
ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft
|
||||
MAXOPTIMIZATION = -Os
|
||||
endif
|
||||
|
||||
LDSCRIPT = ld.script
|
||||
|
||||
ifeq ($(WINTOOL),y)
|
||||
# Windows-native toolchains
|
||||
DIRLINK = $(TOPDIR)/tools/winlink.sh
|
||||
DIRUNLINK = $(TOPDIR)/tools/unlink.sh
|
||||
MKDEP = $(TOPDIR)/tools/mknulldeps.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)/nsh/$(LDSCRIPT)}"
|
||||
MAXOPTIMIZATION = -O2
|
||||
else
|
||||
# Linux/Cygwin-native toolchain
|
||||
MKDEP = $(TOPDIR)/tools/mkdeps.sh
|
||||
ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
|
||||
ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
|
||||
ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/nsh/$(LDSCRIPT)
|
||||
endif
|
||||
|
||||
CC = $(CROSSDEV)gcc
|
||||
CXX = $(CROSSDEV)g++
|
||||
CPP = $(CROSSDEV)gcc -E
|
||||
LD = $(CROSSDEV)ld
|
||||
AR = $(CROSSDEV)ar rcs
|
||||
NM = $(CROSSDEV)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
|
||||
else
|
||||
ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer
|
||||
endif
|
||||
|
||||
ARCHCFLAGS = -fno-builtin
|
||||
ARCHCXXFLAGS = -fno-builtin -fno-exceptions -fno-rtti
|
||||
ARCHWARNINGS = -Wall -Wstrict-prototypes -Wshadow
|
||||
ARCHWARNINGSXX = -Wall -Wshadow
|
||||
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.ld -no-check-sections
|
||||
LDNXFLATFLAGS = -e main -s 2048
|
||||
|
||||
OBJEXT = .o
|
||||
LIBEXT = .a
|
||||
EXEEXT =
|
||||
|
||||
ifneq ($(CROSSDEV),arm-elf-)
|
||||
LDFLAGS += -nostartfiles -nodefaultlibs
|
||||
endif
|
||||
ifeq ($(CONFIG_DEBUG_SYMBOLS),y)
|
||||
LDFLAGS += -g
|
||||
endif
|
||||
|
||||
define PREPROCESS
|
||||
@echo "CPP: $1->$2"
|
||||
@$(CPP) $(CPPFLAGS) $1 -o $2
|
||||
endef
|
||||
|
||||
define COMPILE
|
||||
@echo "CC: $1"
|
||||
@$(CC) -c $(CFLAGS) $1 -o $2
|
||||
endef
|
||||
|
||||
define COMPILEXX
|
||||
@echo "CXX: $1"
|
||||
@$(CXX) -c $(CXXFLAGS) $1 -o $2
|
||||
endef
|
||||
|
||||
define ASSEMBLE
|
||||
@echo "AS: $1"
|
||||
@$(CC) -c $(AFLAGS) $1 -o $2
|
||||
endef
|
||||
|
||||
define ARCHIVE
|
||||
echo "AR: $2"; \
|
||||
$(AR) $1 $2 || { echo "$(AR) $1 $2 FAILED!" ; exit 1 ; }
|
||||
endef
|
||||
|
||||
define CLEAN
|
||||
@rm -f *.o *.a
|
||||
endef
|
||||
|
||||
HOSTCC = gcc
|
||||
HOSTINCLUDES = -I.
|
||||
HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -g -pipe
|
||||
HOSTLDFLAGS =
|
||||
|
|
@ -0,0 +1,85 @@
|
|||
############################################################################
|
||||
# configs/stm3220g-eval/nsh/appconfig
|
||||
#
|
||||
# Copyright (C) 2011-2012 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.
|
||||
#
|
||||
############################################################################
|
||||
|
||||
# Path to example in apps/examples containing the user_start entry point
|
||||
|
||||
CONFIGURED_APPS += examples/nsh
|
||||
|
||||
# The NSH application library
|
||||
|
||||
CONFIGURED_APPS += system/readline
|
||||
CONFIGURED_APPS += nshlib
|
||||
|
||||
# Networking libraries.
|
||||
# Uncomment netutils/ftpc to include an FTP client library
|
||||
# Uncomment netutils/ftpd to include an FTP server library
|
||||
|
||||
ifeq ($(CONFIG_NET),y)
|
||||
CONFIGURED_APPS += netutils/uiplib
|
||||
CONFIGURED_APPS += netutils/resolv
|
||||
CONFIGURED_APPS += netutils/webclient
|
||||
CONFIGURED_APPS += netutils/tftpc
|
||||
#CONFIGURED_APPS += netutils/ftpc
|
||||
#CONFIGURED_APPS += netutils/ftpd
|
||||
ifeq ($(CONFIG_NSH_TELNET),y)
|
||||
CONFIGURED_APPS += netutils/telnetd
|
||||
endif
|
||||
endif
|
||||
|
||||
# Applications configured as an NX built-in commands
|
||||
|
||||
ifeq ($(CONFIG_ADC),y)
|
||||
CONFIGURED_APPS += examples/adc
|
||||
endif
|
||||
|
||||
ifeq ($(CONFIG_PWM),y)
|
||||
CONFIGURED_APPS += examples/pwm
|
||||
endif
|
||||
|
||||
ifeq ($(CONFIG_CAN),y)
|
||||
CONFIGURED_APPS += examples/can
|
||||
endif
|
||||
|
||||
ifeq ($(CONFIG_I2C),y)
|
||||
CONFIGURED_APPS += system/i2c
|
||||
endif
|
||||
|
||||
# Uncomment examples/ftpc to include the FTP client example
|
||||
# Uncomment examples/ftpd to include the FTP daemon example
|
||||
|
||||
ifeq ($(CONFIG_NET),y)
|
||||
#CONFIGURED_APPS += examples/ftpc
|
||||
#CONFIGURED_APPS += examples/ftpd
|
||||
endif
|
File diff suppressed because it is too large
Load Diff
File diff suppressed because it is too large
Load Diff
|
@ -0,0 +1,116 @@
|
|||
/****************************************************************************
|
||||
* configs/stm3220g-eval/nsh/ld.script
|
||||
*
|
||||
* Copyright (C) 2011 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.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/* The STM32F103ZET6 has 1024Kb of FLASH beginning at address 0x0800:0000 and
|
||||
* 192Kb of SRAM. SRAM is split up into three blocks:
|
||||
*
|
||||
* 1) 112Kb of SRAM beginning at address 0x2000:0000
|
||||
* 2) 16Kb of SRAM beginning at address 0x2001:c000
|
||||
* 3) 64Kb of TCM SRAM beginning at address 0x1000:0000
|
||||
*
|
||||
* 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 = 1024K
|
||||
sram (rwx) : ORIGIN = 0x20000000, LENGTH = 112K
|
||||
}
|
||||
|
||||
OUTPUT_ARCH(arm)
|
||||
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
|
||||
|
||||
__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
|
||||
|
||||
.ARM.extab : {
|
||||
*(.ARM.extab*)
|
||||
} >sram
|
||||
|
||||
.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) }
|
||||
}
|
|
@ -0,0 +1,67 @@
|
|||
#!/bin/bash
|
||||
# configs/stm3210e-eval/nsh2/setenv.sh
|
||||
#
|
||||
# Copyright (C) 2011 Gregory Nutt. All rights reserved.
|
||||
# Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
#
|
||||
# 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 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 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"
|
||||
|
||||
# This 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}"
|
|
@ -0,0 +1,170 @@
|
|||
############################################################################
|
||||
# configs/stm3220g-eval/nsh2/Make.defs
|
||||
#
|
||||
# Copyright (C) 2012 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.
|
||||
#
|
||||
############################################################################
|
||||
|
||||
include ${TOPDIR}/.config
|
||||
|
||||
# Setup for the selected toolchain
|
||||
|
||||
ifeq ($(CONFIG_STM32_CODESOURCERYW),y)
|
||||
# CodeSourcery under Windows
|
||||
CROSSDEV = arm-none-eabi-
|
||||
WINTOOL = y
|
||||
ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft
|
||||
endif
|
||||
ifeq ($(CONFIG_STM32_CODESOURCERYL),y)
|
||||
# CodeSourcery under Linux
|
||||
CROSSDEV = arm-none-eabi-
|
||||
ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft
|
||||
MAXOPTIMIZATION = -O2
|
||||
endif
|
||||
ifeq ($(CONFIG_STM32_DEVKITARM),y)
|
||||
# devkitARM under Windows
|
||||
CROSSDEV = arm-eabi-
|
||||
WINTOOL = y
|
||||
ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft
|
||||
endif
|
||||
ifeq ($(CONFIG_STM32_RAISONANCE),y)
|
||||
# Raisonance RIDE7 under Windows
|
||||
CROSSDEV = arm-none-eabi-
|
||||
WINTOOL = y
|
||||
ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft
|
||||
endif
|
||||
ifeq ($(CONFIG_STM32_BUILDROOT),y)
|
||||
# NuttX buildroot under Linux or Cygwin
|
||||
CROSSDEV = arm-elf-
|
||||
ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft
|
||||
MAXOPTIMIZATION = -Os
|
||||
endif
|
||||
|
||||
LDSCRIPT = ld.script
|
||||
|
||||
ifeq ($(WINTOOL),y)
|
||||
# Windows-native toolchains
|
||||
DIRLINK = $(TOPDIR)/tools/winlink.sh
|
||||
DIRUNLINK = $(TOPDIR)/tools/unlink.sh
|
||||
MKDEP = $(TOPDIR)/tools/mknulldeps.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)/nsh2/$(LDSCRIPT)}"
|
||||
MAXOPTIMIZATION = -O2
|
||||
else
|
||||
# Linux/Cygwin-native toolchain
|
||||
MKDEP = $(TOPDIR)/tools/mkdeps.sh
|
||||
ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
|
||||
ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
|
||||
ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/nsh2/$(LDSCRIPT)
|
||||
endif
|
||||
|
||||
CC = $(CROSSDEV)gcc
|
||||
CXX = $(CROSSDEV)g++
|
||||
CPP = $(CROSSDEV)gcc -E
|
||||
LD = $(CROSSDEV)ld
|
||||
AR = $(CROSSDEV)ar rcs
|
||||
NM = $(CROSSDEV)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
|
||||
else
|
||||
ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer
|
||||
endif
|
||||
|
||||
ARCHCFLAGS = -fno-builtin
|
||||
ARCHCXXFLAGS = -fno-builtin -fno-exceptions -fno-rtti
|
||||
ARCHWARNINGS = -Wall -Wstrict-prototypes -Wshadow
|
||||
ARCHWARNINGSXX = -Wall -Wshadow
|
||||
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.ld -no-check-sections
|
||||
LDNXFLATFLAGS = -e main -s 2048
|
||||
|
||||
OBJEXT = .o
|
||||
LIBEXT = .a
|
||||
EXEEXT =
|
||||
|
||||
ifneq ($(CROSSDEV),arm-elf-)
|
||||
LDFLAGS += -nostartfiles -nodefaultlibs
|
||||
endif
|
||||
ifeq ($(CONFIG_DEBUG_SYMBOLS),y)
|
||||
LDFLAGS += -g
|
||||
endif
|
||||
|
||||
define PREPROCESS
|
||||
@echo "CPP: $1->$2"
|
||||
@$(CPP) $(CPPFLAGS) $1 -o $2
|
||||
endef
|
||||
|
||||
define COMPILE
|
||||
@echo "CC: $1"
|
||||
@$(CC) -c $(CFLAGS) $1 -o $2
|
||||
endef
|
||||
|
||||
define COMPILEXX
|
||||
@echo "CXX: $1"
|
||||
@$(CXX) -c $(CXXFLAGS) $1 -o $2
|
||||
endef
|
||||
|
||||
define ASSEMBLE
|
||||
@echo "AS: $1"
|
||||
@$(CC) -c $(AFLAGS) $1 -o $2
|
||||
endef
|
||||
|
||||
define ARCHIVE
|
||||
echo "AR: $2"; \
|
||||
$(AR) $1 $2 || { echo "$(AR) $1 $2 FAILED!" ; exit 1 ; }
|
||||
endef
|
||||
|
||||
define CLEAN
|
||||
@rm -f *.o *.a
|
||||
endef
|
||||
|
||||
HOSTCC = gcc
|
||||
HOSTINCLUDES = -I.
|
||||
HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -g -pipe
|
||||
HOSTLDFLAGS =
|
||||
|
|
@ -0,0 +1,85 @@
|
|||
############################################################################
|
||||
# configs/stm3220g-eval/nsh2/appconfig
|
||||
#
|
||||
# Copyright (C) 2012 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.
|
||||
#
|
||||
############################################################################
|
||||
|
||||
# Path to example in apps/examples containing the user_start entry point
|
||||
|
||||
CONFIGURED_APPS += examples/nsh
|
||||
|
||||
# The NSH application library
|
||||
|
||||
CONFIGURED_APPS += system/readline
|
||||
CONFIGURED_APPS += nshlib
|
||||
|
||||
# Networking libraries.
|
||||
# Uncomment netutils/ftpc to include an FTP client library
|
||||
# Uncomment netutils/ftpd to include an FTP server library
|
||||
|
||||
ifeq ($(CONFIG_NET),y)
|
||||
CONFIGURED_APPS += netutils/uiplib
|
||||
CONFIGURED_APPS += netutils/resolv
|
||||
CONFIGURED_APPS += netutils/webclient
|
||||
CONFIGURED_APPS += netutils/tftpc
|
||||
#CONFIGURED_APPS += netutils/ftpc
|
||||
#CONFIGURED_APPS += netutils/ftpd
|
||||
ifeq ($(CONFIG_NSH_TELNET),y)
|
||||
CONFIGURED_APPS += netutils/telnetd
|
||||
endif
|
||||
endif
|
||||
|
||||
# Applications configured as an NX built-in commands
|
||||
|
||||
ifeq ($(CONFIG_ADC),y)
|
||||
CONFIGURED_APPS += examples/adc
|
||||
endif
|
||||
|
||||
ifeq ($(CONFIG_PWM),y)
|
||||
CONFIGURED_APPS += examples/pwm
|
||||
endif
|
||||
|
||||
ifeq ($(CONFIG_CAN),y)
|
||||
CONFIGURED_APPS += examples/can
|
||||
endif
|
||||
|
||||
ifeq ($(CONFIG_I2C),y)
|
||||
CONFIGURED_APPS += system/i2c
|
||||
endif
|
||||
|
||||
# Uncomment examples/ftpc to include the FTP client example
|
||||
# Uncomment examples/ftpd to include the FTP daemon example
|
||||
|
||||
ifeq ($(CONFIG_NET),y)
|
||||
#CONFIGURED_APPS += examples/ftpc
|
||||
#CONFIGURED_APPS += examples/ftpd
|
||||
endif
|
File diff suppressed because it is too large
Load Diff
File diff suppressed because it is too large
Load Diff
File diff suppressed because it is too large
Load Diff
|
@ -0,0 +1,116 @@
|
|||
/****************************************************************************
|
||||
* configs/stm3220g-eval/nsh2/ld.script
|
||||
*
|
||||
* Copyright (C) 2012 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.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/* The STM32F103ZET6 has 1024Kb of FLASH beginning at address 0x0800:0000 and
|
||||
* 192Kb of SRAM. SRAM is split up into three blocks:
|
||||
*
|
||||
* 1) 112Kb of SRAM beginning at address 0x2000:0000
|
||||
* 2) 16Kb of SRAM beginning at address 0x2001:c000
|
||||
* 3) 64Kb of TCM SRAM beginning at address 0x1000:0000
|
||||
*
|
||||
* 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 = 1024K
|
||||
sram (rwx) : ORIGIN = 0x20000000, LENGTH = 112K
|
||||
}
|
||||
|
||||
OUTPUT_ARCH(arm)
|
||||
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
|
||||
|
||||
__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
|
||||
|
||||
.ARM.extab : {
|
||||
*(.ARM.extab*)
|
||||
} >sram
|
||||
|
||||
.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) }
|
||||
}
|
|
@ -0,0 +1,67 @@
|
|||
#!/bin/bash
|
||||
# configs/stm3210e-eval/nsh2/setenv.sh
|
||||
#
|
||||
# Copyright (C) 2011 Gregory Nutt. All rights reserved.
|
||||
# Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
#
|
||||
# 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 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 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"
|
||||
|
||||
# This 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}"
|
|
@ -0,0 +1,170 @@
|
|||
############################################################################
|
||||
# configs/stm3220g-eval/ostest/Make.defs
|
||||
#
|
||||
# Copyright (C) 2011 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.
|
||||
#
|
||||
############################################################################
|
||||
|
||||
include ${TOPDIR}/.config
|
||||
|
||||
# Setup for the selected toolchain
|
||||
|
||||
ifeq ($(CONFIG_STM32_CODESOURCERYW),y)
|
||||
# CodeSourcery under Windows
|
||||
CROSSDEV = arm-none-eabi-
|
||||
WINTOOL = y
|
||||
ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft
|
||||
endif
|
||||
ifeq ($(CONFIG_STM32_CODESOURCERYL),y)
|
||||
# CodeSourcery under Linux
|
||||
CROSSDEV = arm-none-eabi-
|
||||
ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft
|
||||
MAXOPTIMIZATION = -O2
|
||||
endif
|
||||
ifeq ($(CONFIG_STM32_DEVKITARM),y)
|
||||
# devkitARM under Windows
|
||||
CROSSDEV = arm-eabi-
|
||||
WINTOOL = y
|
||||
ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft
|
||||
endif
|
||||
ifeq ($(CONFIG_STM32_RAISONANCE),y)
|
||||
# Raisonance RIDE7 under Windows
|
||||
CROSSDEV = arm-none-eabi-
|
||||
WINTOOL = y
|
||||
ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft
|
||||
endif
|
||||
ifeq ($(CONFIG_STM32_BUILDROOT),y)
|
||||
# NuttX buildroot under Linux or Cygwin
|
||||
CROSSDEV = arm-elf-
|
||||
ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft
|
||||
MAXOPTIMIZATION = -Os
|
||||
endif
|
||||
|
||||
LDSCRIPT = ld.script
|
||||
|
||||
ifeq ($(WINTOOL),y)
|
||||
# Windows-native toolchains
|
||||
DIRLINK = $(TOPDIR)/tools/winlink.sh
|
||||
DIRUNLINK = $(TOPDIR)/tools/unlink.sh
|
||||
MKDEP = $(TOPDIR)/tools/mknulldeps.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)/ostest/$(LDSCRIPT)}"
|
||||
MAXOPTIMIZATION = -O2
|
||||
else
|
||||
# Linux/Cygwin-native toolchain
|
||||
MKDEP = $(TOPDIR)/tools/mkdeps.sh
|
||||
ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
|
||||
ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
|
||||
ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/ostest/$(LDSCRIPT)
|
||||
endif
|
||||
|
||||
CC = $(CROSSDEV)gcc
|
||||
CXX = $(CROSSDEV)g++
|
||||
CPP = $(CROSSDEV)gcc -E
|
||||
LD = $(CROSSDEV)ld
|
||||
AR = $(CROSSDEV)ar rcs
|
||||
NM = $(CROSSDEV)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
|
||||
else
|
||||
ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer
|
||||
endif
|
||||
|
||||
ARCHCFLAGS = -fno-builtin
|
||||
ARCHCXXFLAGS = -fno-builtin -fno-exceptions -fno-rtti
|
||||
ARCHWARNINGS = -Wall -Wstrict-prototypes -Wshadow
|
||||
ARCHWARNINGSXX = -Wall -Wshadow
|
||||
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.ld -no-check-sections
|
||||
LDNXFLATFLAGS = -e main -s 2048
|
||||
|
||||
OBJEXT = .o
|
||||
LIBEXT = .a
|
||||
EXEEXT =
|
||||
|
||||
ifneq ($(CROSSDEV),arm-elf-)
|
||||
LDFLAGS += -nostartfiles -nodefaultlibs
|
||||
endif
|
||||
ifeq ($(CONFIG_DEBUG_SYMBOLS),y)
|
||||
LDFLAGS += -g
|
||||
endif
|
||||
|
||||
define PREPROCESS
|
||||
@echo "CPP: $1->$2"
|
||||
@$(CPP) $(CPPFLAGS) $1 -o $2
|
||||
endef
|
||||
|
||||
define COMPILE
|
||||
@echo "CC: $1"
|
||||
@$(CC) -c $(CFLAGS) $1 -o $2
|
||||
endef
|
||||
|
||||
define COMPILEXX
|
||||
@echo "CXX: $1"
|
||||
@$(CXX) -c $(CXXFLAGS) $1 -o $2
|
||||
endef
|
||||
|
||||
define ASSEMBLE
|
||||
@echo "AS: $1"
|
||||
@$(CC) -c $(AFLAGS) $1 -o $2
|
||||
endef
|
||||
|
||||
define ARCHIVE
|
||||
echo "AR: $2"; \
|
||||
$(AR) $1 $2 || { echo "$(AR) $1 $2 FAILED!" ; exit 1 ; }
|
||||
endef
|
||||
|
||||
define CLEAN
|
||||
@rm -f *.o *.a
|
||||
endef
|
||||
|
||||
HOSTCC = gcc
|
||||
HOSTINCLUDES = -I.
|
||||
HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -g -pipe
|
||||
HOSTLDFLAGS =
|
||||
|
|
@ -0,0 +1,39 @@
|
|||
############################################################################
|
||||
# configs/stm3220g-eval/ostest/appconfig
|
||||
#
|
||||
# Copyright (C) 2011 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.
|
||||
#
|
||||
############################################################################
|
||||
|
||||
# Path to example in apps/examples containing the user_start entry point
|
||||
|
||||
CONFIGURED_APPS += examples/ostest
|
||||
|
File diff suppressed because it is too large
Load Diff
File diff suppressed because it is too large
Load Diff
|
@ -0,0 +1,116 @@
|
|||
/****************************************************************************
|
||||
* configs/stm3220g-eval/ostest/ld.script
|
||||
*
|
||||
* Copyright (C) 2011 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.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/* The STM32F103ZET6 has 1024Kb of FLASH beginning at address 0x0800:0000 and
|
||||
* 192Kb of SRAM. SRAM is split up into three blocks:
|
||||
*
|
||||
* 1) 112Kb of SRAM beginning at address 0x2000:0000
|
||||
* 2) 16Kb of SRAM beginning at address 0x2001:c000
|
||||
* 3) 64Kb of TCM SRAM beginning at address 0x1000:0000
|
||||
*
|
||||
* 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 = 1024K
|
||||
sram (rwx) : ORIGIN = 0x20000000, LENGTH = 112K
|
||||
}
|
||||
|
||||
OUTPUT_ARCH(arm)
|
||||
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
|
||||
|
||||
__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
|
||||
|
||||
.ARM.extab : {
|
||||
*(.ARM.extab*)
|
||||
} >sram
|
||||
|
||||
.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) }
|
||||
}
|
|
@ -0,0 +1,67 @@
|
|||
#!/bin/bash
|
||||
# configs/stm3220g-eval/ostest/setenv.sh
|
||||
#
|
||||
# Copyright (C) 2011 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.
|
||||
#
|
||||
|
||||
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 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 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"
|
||||
|
||||
# This the Cygwin path to the location where I build the buildroot
|
||||
# toolchain.
|
||||
#export TOOLCHAIN_BIN="${WD}/../misc/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}"
|
|
@ -0,0 +1,111 @@
|
|||
############################################################################
|
||||
# configs/stm3220g-eval/src/Makefile
|
||||
#
|
||||
# Copyright (C) 2011-2012 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.
|
||||
#
|
||||
############################################################################
|
||||
|
||||
-include $(TOPDIR)/Make.defs
|
||||
|
||||
CFLAGS += -I$(TOPDIR)/sched
|
||||
|
||||
ASRCS =
|
||||
AOBJS = $(ASRCS:.S=$(OBJEXT))
|
||||
|
||||
CSRCS = up_boot.c up_spi.c
|
||||
|
||||
ifeq ($(CONFIG_ARCH_LEDS),y)
|
||||
CSRCS += up_autoleds.c
|
||||
else
|
||||
CSRCS += up_userleds.c
|
||||
endif
|
||||
|
||||
ifeq ($(CONFIG_ARCH_BUTTONS),y)
|
||||
CSRCS += up_buttons.c
|
||||
endif
|
||||
|
||||
ifeq ($(CONFIG_ADC),y)
|
||||
CSRCS += up_adc.c
|
||||
endif
|
||||
|
||||
ifeq ($(CONFIG_PWM),y)
|
||||
CSRCS += up_pwm.c
|
||||
endif
|
||||
|
||||
ifeq ($(CONFIG_CAN),y)
|
||||
CSRCS += up_can.c
|
||||
endif
|
||||
|
||||
ifeq ($(CONFIG_NSH_ARCHINIT),y)
|
||||
CSRCS += up_nsh.c
|
||||
endif
|
||||
|
||||
COBJS = $(CSRCS:.c=$(OBJEXT))
|
||||
|
||||
SRCS = $(ASRCS) $(CSRCS)
|
||||
OBJS = $(AOBJS) $(COBJS)
|
||||
|
||||
ARCH_SRCDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src
|
||||
ifeq ($(WINTOOL),y)
|
||||
CFLAGS += -I "${shell cygpath -w $(ARCH_SRCDIR)/chip}" \
|
||||
-I "${shell cygpath -w $(ARCH_SRCDIR)/common}" \
|
||||
-I "${shell cygpath -w $(ARCH_SRCDIR)/armv7-m}"
|
||||
else
|
||||
CFLAGS += -I$(ARCH_SRCDIR)/chip -I$(ARCH_SRCDIR)/common -I$(ARCH_SRCDIR)/armv7-m
|
||||
endif
|
||||
|
||||
all: libboard$(LIBEXT)
|
||||
|
||||
$(AOBJS): %$(OBJEXT): %.S
|
||||
$(call ASSEMBLE, $<, $@)
|
||||
|
||||
$(COBJS) $(LINKOBJS): %$(OBJEXT): %.c
|
||||
$(call COMPILE, $<, $@)
|
||||
|
||||
libboard$(LIBEXT): $(OBJS)
|
||||
@( for obj in $(OBJS) ; do \
|
||||
$(call ARCHIVE, $@, $${obj}); \
|
||||
done ; )
|
||||
|
||||
.depend: Makefile $(SRCS)
|
||||
@$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
|
||||
@touch $@
|
||||
|
||||
depend: .depend
|
||||
|
||||
clean:
|
||||
@rm -f libboard$(LIBEXT) *~ .*.swp
|
||||
$(call CLEAN)
|
||||
|
||||
distclean: clean
|
||||
@rm -f Make.dep .depend
|
||||
|
||||
-include Make.dep
|
|
@ -0,0 +1,171 @@
|
|||
/****************************************************************************************************
|
||||
* configs/stm3220g_eval/src/stm3220g_internal.h
|
||||
* arch/arm/src/board/stm3220g_internal.n
|
||||
*
|
||||
* Copyright (C) 2011 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.
|
||||
*
|
||||
****************************************************************************************************/
|
||||
|
||||
#ifndef __CONFIGS_STM3220G_EVAL_SRC_STM3220G_INTERNAL_H
|
||||
#define __CONFIGS_STM3220G_EVAL_SRC_STM3220G_INTERNAL_H
|
||||
|
||||
/****************************************************************************************************
|
||||
* Included Files
|
||||
****************************************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <nuttx/compiler.h>
|
||||
#include <stdint.h>
|
||||
|
||||
/****************************************************************************************************
|
||||
* Definitions
|
||||
****************************************************************************************************/
|
||||
/* Configuration ************************************************************************************/
|
||||
/* How many SPI modules does this chip support? */
|
||||
|
||||
#if STM32_NSPI < 1
|
||||
# undef CONFIG_STM32_SPI1
|
||||
# undef CONFIG_STM32_SPI2
|
||||
# undef CONFIG_STM32_SPI3
|
||||
#elif STM32_NSPI < 2
|
||||
# undef CONFIG_STM32_SPI2
|
||||
# undef CONFIG_STM32_SPI3
|
||||
#elif STM32_NSPI < 3
|
||||
# undef CONFIG_STM32_SPI3
|
||||
#endif
|
||||
|
||||
/* You can use either CAN1 or CAN2, but you can't use both because they share the same transceiver */
|
||||
|
||||
#if defined(CONFIG_STM32_CAN1) && defined(CONFIG_STM32_CAN2)
|
||||
# warning "The STM3250G-EVAL will only support one of CAN1 and CAN2"
|
||||
#endif
|
||||
|
||||
/* You can't use CAN1 with FSMC:
|
||||
*
|
||||
* PD0 = FSMC_D2 & CAN1_RX
|
||||
* PD1 = FSMC_D3 & CAN1_TX
|
||||
*/
|
||||
|
||||
#if defined(CONFIG_STM32_CAN1) && defined(CONFIG_STM32_FSMC)
|
||||
# warning "The STM3250G-EVAL will only support one of CAN1 and FSMC"
|
||||
#endif
|
||||
|
||||
/* The USB OTG HS ULPI bus is shared with CAN2 bus:
|
||||
*
|
||||
* PB13 = ULPI_D6 & CAN2_TX
|
||||
* PB5 = ULPI_D7 & CAN2_RX
|
||||
*/
|
||||
|
||||
#if defined(CONFIG_STM32_CAN2) && defined(CONFIG_STM32_OTGHS)
|
||||
# warning "The STM3250G-EVAL will only support one of CAN2 and USB OTG HS"
|
||||
#endif
|
||||
|
||||
/* STM3220G-EVAL GPIOs ******************************************************************************/
|
||||
/* LEDs */
|
||||
|
||||
#define GPIO_LED1 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|\
|
||||
GPIO_OUTPUT_CLEAR|GPIO_PORTG|GPIO_PIN6)
|
||||
#define GPIO_LED2 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|\
|
||||
GPIO_OUTPUT_CLEAR|GPIO_PORTG|GPIO_PIN8)
|
||||
#define GPIO_LED3 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|\
|
||||
GPIO_OUTPUT_CLEAR|GPIO_PORTI|GPIO_PIN9)
|
||||
#define GPIO_LED4 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|\
|
||||
GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN7)
|
||||
|
||||
/* BUTTONS -- NOTE that all have EXTI interrupts configured */
|
||||
|
||||
#define MIN_IRQBUTTON BUTTON_WAKEUP
|
||||
#define MAX_IRQBUTTON BUTTON_USER
|
||||
#define NUM_IRQBUTTONS (BUTTON_USER - BUTTON_WAKEUP + 1)
|
||||
|
||||
#define GPIO_BTN_WAKEUP (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTA|GPIO_PIN0)
|
||||
#define GPIO_BTN_TAMPER (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTC|GPIO_PIN13)
|
||||
#define GPIO_BTN_USER (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTG|GPIO_PIN15)
|
||||
|
||||
/* PWM
|
||||
*
|
||||
* The STM3220G-Eval has no real on-board PWM devices, but the board can be
|
||||
* configured to output a pulse train using TIM4, TIM1, or TIM8 (see board.h).
|
||||
* Let's figure out which the user has configured.
|
||||
*/
|
||||
|
||||
#ifdef CONFIG_PWM
|
||||
# if defined(CONFIG_STM32_TIM1_PWM)
|
||||
# define STM3220G_EVAL_PWMTIMER 1
|
||||
# elif defined(CONFIG_STM32_TIM4_PWM)
|
||||
# define STM3220G_EVAL_PWMTIMER 4
|
||||
# elif defined(CONFIG_STM32_TIM8_PWM)
|
||||
# define STM3220G_EVAL_PWMTIMER 8
|
||||
# endif
|
||||
#endif
|
||||
|
||||
/****************************************************************************************************
|
||||
* Public Types
|
||||
****************************************************************************************************/
|
||||
|
||||
/* GPIO settings that will be altered when external memory is selected:
|
||||
*
|
||||
* ----- ------- -------- ------------ ------- ------------ -------- ----------- -------- -------------
|
||||
* PB7: FSMC NL PD0-1: FSMC D2-D3 PE0: FSMC NBL0 PF0-5: FSMC A0-A5 PG0-5: FSMC A10-A15
|
||||
* PD3: FSMC CLK PE1: FSMC BLN1 PF6: FSMC NIORD PG6-7: FSMC INT2-3
|
||||
* PD4: FSMC NOE PE2: FSMC A23 PF7: FSMC NREG PG9: FSMC NCE3
|
||||
* PD5: FSMC NWE PE3-6: FSMC A19-A22 PF8: FSMC NIOWR PG9-10: FSMC NE2-3
|
||||
* PD6: FSMC NWAIT PE7-15: FSMC D4-D12 PF9: FSMC CD PG10: FSMC NCE4 (1)
|
||||
* PD7: FSMC NE1 PF10: FSMC INTR PG11: FSMC NCE4 (2)
|
||||
* PD7: FSMC NCE2 PF12-15: FSMC A6-A9 PG12: FSMC NE4
|
||||
* PD8-10: FSMC D13-D15 PG13-14: FSMC A24-A25
|
||||
* PD11-13: FSMC_A16-A18
|
||||
* PD14-15: FSMC D0-D1
|
||||
*/
|
||||
|
||||
/****************************************************************************************************
|
||||
* Public data
|
||||
****************************************************************************************************/
|
||||
|
||||
#ifndef __ASSEMBLY__
|
||||
|
||||
/****************************************************************************************************
|
||||
* Public Functions
|
||||
****************************************************************************************************/
|
||||
|
||||
/****************************************************************************************************
|
||||
* Name: stm32_spiinitialize
|
||||
*
|
||||
* Description:
|
||||
* Called to configure SPI chip select GPIO pins for the STM3220G-EVAL board.
|
||||
*
|
||||
****************************************************************************************************/
|
||||
|
||||
extern void weak_function stm32_spiinitialize(void);
|
||||
|
||||
#endif /* __ASSEMBLY__ */
|
||||
#endif /* __CONFIGS_STM3220G_EVAL_SRC_STM3220G_INTERNAL_H */
|
||||
|
|
@ -0,0 +1,168 @@
|
|||
/************************************************************************************
|
||||
* configs/stm3220g-eval/src/up_adc.c
|
||||
* arch/arm/src/board/up_adc.c
|
||||
*
|
||||
* Copyright (C) 2011-2012 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 <errno.h>
|
||||
#include <debug.h>
|
||||
|
||||
#include <nuttx/analog/adc.h>
|
||||
#include <arch/board/board.h>
|
||||
|
||||
#include "chip.h"
|
||||
#include "up_arch.h"
|
||||
|
||||
#include "stm32_pwm.h"
|
||||
#include "stm3220g-internal.h"
|
||||
|
||||
#ifdef CONFIG_ADC
|
||||
|
||||
/************************************************************************************
|
||||
* Definitions
|
||||
************************************************************************************/
|
||||
|
||||
/* Configuration ************************************************************/
|
||||
/* Up to 3 ADC interfaces are supported */
|
||||
|
||||
#if STM32_NADC < 3
|
||||
# undef CONFIG_STM32_ADC3
|
||||
#endif
|
||||
|
||||
#if STM32_NADC < 2
|
||||
# undef CONFIG_STM32_ADC2
|
||||
#endif
|
||||
|
||||
#if STM32_NADC < 1
|
||||
# undef CONFIG_STM32_ADC1
|
||||
#endif
|
||||
|
||||
#if defined(CONFIG_STM32_ADC1) || defined(CONFIG_STM32_ADC2) || defined(CONFIG_STM32_ADC3)
|
||||
#ifndef CONFIG_STM32_ADC3
|
||||
# warning "Channel information only available for ADC3"
|
||||
#endif
|
||||
|
||||
/* The number of ADC channels in the conversion list */
|
||||
|
||||
#define ADC3_NCHANNELS 1
|
||||
|
||||
/************************************************************************************
|
||||
* Private Data
|
||||
************************************************************************************/
|
||||
/* The STM3220G-EVAL has a 10 Kohm potentiometer RV1 connected to PF9 of
|
||||
* STM32F207IGH6 on the board: TIM14_CH1/FSMC_CD/ADC3_IN7
|
||||
*/
|
||||
|
||||
/* Identifying number of each ADC channel: Variable Resistor. */
|
||||
|
||||
#ifdef CONFIG_STM32_ADC3
|
||||
static const uint8_t g_chanlist[ADC3_NCHANNELS] = {7};
|
||||
|
||||
/* Configurations of pins used byte each ADC channels */
|
||||
|
||||
static const uint32_t g_pinlist[ADC3_NCHANNELS] = {GPIO_ADC3_IN7};
|
||||
#endif
|
||||
|
||||
/************************************************************************************
|
||||
* Private Functions
|
||||
************************************************************************************/
|
||||
|
||||
/************************************************************************************
|
||||
* Public Functions
|
||||
************************************************************************************/
|
||||
|
||||
/************************************************************************************
|
||||
* Name: adc_devinit
|
||||
*
|
||||
* Description:
|
||||
* All STM32 architectures must provide the following interface to work with
|
||||
* examples/adc.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
int adc_devinit(void)
|
||||
{
|
||||
#ifdef CONFIG_STM32_ADC3
|
||||
static bool initialized = false;
|
||||
struct adc_dev_s *adc;
|
||||
int ret;
|
||||
int i;
|
||||
|
||||
/* Check if we have already initialized */
|
||||
|
||||
if (!initialized)
|
||||
{
|
||||
/* Configure the pins as analog inputs for the selected channels */
|
||||
|
||||
for (i = 0; i < ADC3_NCHANNELS; i++)
|
||||
{
|
||||
stm32_configgpio(g_pinlist[i]);
|
||||
}
|
||||
|
||||
/* Call stm32_adcinitialize() to get an instance of the ADC interface */
|
||||
|
||||
adc = stm32_adcinitialize(3, g_chanlist, ADC3_NCHANNELS);
|
||||
if (adc == NULL)
|
||||
{
|
||||
adbg("ERROR: Failed to get ADC interface\n");
|
||||
return -ENODEV;
|
||||
}
|
||||
|
||||
/* Register the ADC driver at "/dev/adc0" */
|
||||
|
||||
ret = adc_register("/dev/adc0", adc);
|
||||
if (ret < 0)
|
||||
{
|
||||
adbg("adc_register failed: %d\n", ret);
|
||||
return ret;
|
||||
}
|
||||
|
||||
/* Now we are initialized */
|
||||
|
||||
initialized = true;
|
||||
}
|
||||
|
||||
return OK;
|
||||
#else
|
||||
return -ENOSYS;
|
||||
#endif
|
||||
}
|
||||
|
||||
#endif /* CONFIG_STM32_ADC1 || CONFIG_STM32_ADC2 || CONFIG_STM32_ADC3 */
|
||||
#endif /* CONFIG_ADC */
|
|
@ -0,0 +1,260 @@
|
|||
/****************************************************************************
|
||||
* configs/stm3220g_eval/src/up_autoleds.c
|
||||
* arch/arm/src/board/up_autoleds.c
|
||||
*
|
||||
* Copyright (C) 2011 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 <stdint.h>
|
||||
#include <stdbool.h>
|
||||
#include <debug.h>
|
||||
|
||||
#include <arch/board/board.h>
|
||||
|
||||
#include "chip.h"
|
||||
#include "up_arch.h"
|
||||
#include "up_internal.h"
|
||||
#include "stm32_internal.h"
|
||||
#include "stm3220g-internal.h"
|
||||
|
||||
#ifdef CONFIG_ARCH_LEDS
|
||||
|
||||
/****************************************************************************
|
||||
* Definitions
|
||||
****************************************************************************/
|
||||
|
||||
/* Enables debug output from this file (needs CONFIG_DEBUG with
|
||||
* CONFIG_DEBUG_VERBOSE too)
|
||||
*/
|
||||
|
||||
#undef LED_DEBUG /* Define to enable debug */
|
||||
|
||||
#ifdef LED_DEBUG
|
||||
# define leddbg lldbg
|
||||
# define ledvdbg llvdbg
|
||||
#else
|
||||
# define leddbg(x...)
|
||||
# define ledvdbg(x...)
|
||||
#endif
|
||||
|
||||
/* The following definitions map the encoded LED setting to GPIO settings */
|
||||
|
||||
#define STM3210E_LED1 (1 << 0)
|
||||
#define STM3210E_LED2 (1 << 1)
|
||||
#define STM3210E_LED3 (1 << 2)
|
||||
#define STM3210E_LED4 (1 << 3)
|
||||
|
||||
#define ON_SETBITS_SHIFT (0)
|
||||
#define ON_CLRBITS_SHIFT (4)
|
||||
#define OFF_SETBITS_SHIFT (8)
|
||||
#define OFF_CLRBITS_SHIFT (12)
|
||||
|
||||
#define ON_BITS(v) ((v) & 0xff)
|
||||
#define OFF_BITS(v) (((v) >> 8) & 0x0ff)
|
||||
#define SETBITS(b) ((b) & 0x0f)
|
||||
#define CLRBITS(b) (((b) >> 4) & 0x0f)
|
||||
|
||||
#define ON_SETBITS(v) (SETBITS(ON_BITS(v))
|
||||
#define ON_CLRBITS(v) (CLRBITS(ON_BITS(v))
|
||||
#define OFF_SETBITS(v) (SETBITS(OFF_BITS(v))
|
||||
#define OFF_CLRBITS(v) (CLRBITS(OFF_BITS(v))
|
||||
|
||||
#define LED_STARTED_ON_SETBITS ((STM3210E_LED1) << ON_SETBITS_SHIFT)
|
||||
#define LED_STARTED_ON_CLRBITS ((STM3210E_LED2|STM3210E_LED3|STM3210E_LED4) << ON_CLRBITS_SHIFT)
|
||||
#define LED_STARTED_OFF_SETBITS (0 << OFF_SETBITS_SHIFT)
|
||||
#define LED_STARTED_OFF_CLRBITS ((STM3210E_LED1|STM3210E_LED2|STM3210E_LED3|STM3210E_LED4) << OFF_CLRBITS_SHIFT)
|
||||
|
||||
#define LED_HEAPALLOCATE_ON_SETBITS ((STM3210E_LED2) << ON_SETBITS_SHIFT)
|
||||
#define LED_HEAPALLOCATE_ON_CLRBITS ((STM3210E_LED1|STM3210E_LED3|STM3210E_LED4) << ON_CLRBITS_SHIFT)
|
||||
#define LED_HEAPALLOCATE_OFF_SETBITS ((STM3210E_LED1) << OFF_SETBITS_SHIFT)
|
||||
#define LED_HEAPALLOCATE_OFF_CLRBITS ((STM3210E_LED2|STM3210E_LED3|STM3210E_LED4) << OFF_CLRBITS_SHIFT)
|
||||
|
||||
#define LED_IRQSENABLED_ON_SETBITS ((STM3210E_LED1|STM3210E_LED2) << ON_SETBITS_SHIFT)
|
||||
#define LED_IRQSENABLED_ON_CLRBITS ((STM3210E_LED3|STM3210E_LED4) << ON_CLRBITS_SHIFT)
|
||||
#define LED_IRQSENABLED_OFF_SETBITS ((STM3210E_LED2) << OFF_SETBITS_SHIFT)
|
||||
#define LED_IRQSENABLED_OFF_CLRBITS ((STM3210E_LED1|STM3210E_LED3|STM3210E_LED4) << OFF_CLRBITS_SHIFT)
|
||||
|
||||
#define LED_STACKCREATED_ON_SETBITS ((STM3210E_LED3) << ON_SETBITS_SHIFT)
|
||||
#define LED_STACKCREATED_ON_CLRBITS ((STM3210E_LED1|STM3210E_LED2|STM3210E_LED4) << ON_CLRBITS_SHIFT)
|
||||
#define LED_STACKCREATED_OFF_SETBITS ((STM3210E_LED1|STM3210E_LED2) << OFF_SETBITS_SHIFT)
|
||||
#define LED_STACKCREATED_OFF_CLRBITS ((STM3210E_LED3|STM3210E_LED4) << OFF_CLRBITS_SHIFT)
|
||||
|
||||
#define LED_INIRQ_ON_SETBITS ((STM3210E_LED1) << ON_SETBITS_SHIFT)
|
||||
#define LED_INIRQ_ON_CLRBITS ((0) << ON_CLRBITS_SHIFT)
|
||||
#define LED_INIRQ_OFF_SETBITS ((0) << OFF_SETBITS_SHIFT)
|
||||
#define LED_INIRQ_OFF_CLRBITS ((STM3210E_LED1) << OFF_CLRBITS_SHIFT)
|
||||
|
||||
#define LED_SIGNAL_ON_SETBITS ((STM3210E_LED2) << ON_SETBITS_SHIFT)
|
||||
#define LED_SIGNAL_ON_CLRBITS ((0) << ON_CLRBITS_SHIFT)
|
||||
#define LED_SIGNAL_OFF_SETBITS ((0) << OFF_SETBITS_SHIFT)
|
||||
#define LED_SIGNAL_OFF_CLRBITS ((STM3210E_LED2) << OFF_CLRBITS_SHIFT)
|
||||
|
||||
#define LED_ASSERTION_ON_SETBITS ((STM3210E_LED4) << ON_SETBITS_SHIFT)
|
||||
#define LED_ASSERTION_ON_CLRBITS ((0) << ON_CLRBITS_SHIFT)
|
||||
#define LED_ASSERTION_OFF_SETBITS ((0) << OFF_SETBITS_SHIFT)
|
||||
#define LED_ASSERTION_OFF_CLRBITS ((STM3210E_LED4) << OFF_CLRBITS_SHIFT)
|
||||
|
||||
#define LED_PANIC_ON_SETBITS ((STM3210E_LED4) << ON_SETBITS_SHIFT)
|
||||
#define LED_PANIC_ON_CLRBITS ((0) << ON_CLRBITS_SHIFT)
|
||||
#define LED_PANIC_OFF_SETBITS ((0) << OFF_SETBITS_SHIFT)
|
||||
#define LED_PANIC_OFF_CLRBITS ((STM3210E_LED4) << OFF_CLRBITS_SHIFT)
|
||||
|
||||
/****************************************************************************
|
||||
* Private Data
|
||||
****************************************************************************/
|
||||
|
||||
static const uint16_t g_ledbits[8] =
|
||||
{
|
||||
(LED_STARTED_ON_SETBITS | LED_STARTED_ON_CLRBITS |
|
||||
LED_STARTED_OFF_SETBITS | LED_STARTED_OFF_CLRBITS),
|
||||
|
||||
(LED_HEAPALLOCATE_ON_SETBITS | LED_HEAPALLOCATE_ON_CLRBITS |
|
||||
LED_HEAPALLOCATE_OFF_SETBITS | LED_HEAPALLOCATE_OFF_CLRBITS),
|
||||
|
||||
(LED_IRQSENABLED_ON_SETBITS | LED_IRQSENABLED_ON_CLRBITS |
|
||||
LED_IRQSENABLED_OFF_SETBITS | LED_IRQSENABLED_OFF_CLRBITS),
|
||||
|
||||
(LED_STACKCREATED_ON_SETBITS | LED_STACKCREATED_ON_CLRBITS |
|
||||
LED_STACKCREATED_OFF_SETBITS | LED_STACKCREATED_OFF_CLRBITS),
|
||||
|
||||
(LED_INIRQ_ON_SETBITS | LED_INIRQ_ON_CLRBITS |
|
||||
LED_INIRQ_OFF_SETBITS | LED_INIRQ_OFF_CLRBITS),
|
||||
|
||||
(LED_SIGNAL_ON_SETBITS | LED_SIGNAL_ON_CLRBITS |
|
||||
LED_SIGNAL_OFF_SETBITS | LED_SIGNAL_OFF_CLRBITS),
|
||||
|
||||
(LED_ASSERTION_ON_SETBITS | LED_ASSERTION_ON_CLRBITS |
|
||||
LED_ASSERTION_OFF_SETBITS | LED_ASSERTION_OFF_CLRBITS),
|
||||
|
||||
(LED_PANIC_ON_SETBITS | LED_PANIC_ON_CLRBITS |
|
||||
LED_PANIC_OFF_SETBITS | LED_PANIC_OFF_CLRBITS)
|
||||
};
|
||||
|
||||
/****************************************************************************
|
||||
* Private Functions
|
||||
****************************************************************************/
|
||||
|
||||
static inline void led_clrbits(unsigned int clrbits)
|
||||
{
|
||||
if ((clrbits & STM3210E_LED1) != 0)
|
||||
{
|
||||
stm32_gpiowrite(GPIO_LED1, false);
|
||||
}
|
||||
|
||||
if ((clrbits & STM3210E_LED2) != 0)
|
||||
{
|
||||
stm32_gpiowrite(GPIO_LED2, false);
|
||||
}
|
||||
|
||||
if ((clrbits & STM3210E_LED3) != 0)
|
||||
{
|
||||
stm32_gpiowrite(GPIO_LED3, false);
|
||||
}
|
||||
|
||||
if ((clrbits & STM3210E_LED4) != 0)
|
||||
{
|
||||
stm32_gpiowrite(GPIO_LED4, false);
|
||||
}
|
||||
}
|
||||
|
||||
static inline void led_setbits(unsigned int setbits)
|
||||
{
|
||||
if ((setbits & STM3210E_LED1) != 0)
|
||||
{
|
||||
stm32_gpiowrite(GPIO_LED1, true);
|
||||
}
|
||||
|
||||
if ((setbits & STM3210E_LED2) != 0)
|
||||
{
|
||||
stm32_gpiowrite(GPIO_LED2, true);
|
||||
}
|
||||
|
||||
if ((setbits & STM3210E_LED3) != 0)
|
||||
{
|
||||
stm32_gpiowrite(GPIO_LED3, true);
|
||||
}
|
||||
|
||||
if ((setbits & STM3210E_LED4) != 0)
|
||||
{
|
||||
stm32_gpiowrite(GPIO_LED4, true);
|
||||
}
|
||||
}
|
||||
|
||||
static void led_setonoff(unsigned int bits)
|
||||
{
|
||||
led_clrbits(CLRBITS(bits));
|
||||
led_setbits(SETBITS(bits));
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Public Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Name: up_ledinit
|
||||
****************************************************************************/
|
||||
|
||||
void up_ledinit(void)
|
||||
{
|
||||
/* Configure LED1-4 GPIOs for output */
|
||||
|
||||
stm32_configgpio(GPIO_LED1);
|
||||
stm32_configgpio(GPIO_LED2);
|
||||
stm32_configgpio(GPIO_LED3);
|
||||
stm32_configgpio(GPIO_LED4);
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: up_ledon
|
||||
****************************************************************************/
|
||||
|
||||
void up_ledon(int led)
|
||||
{
|
||||
led_setonoff(ON_BITS(g_ledbits[led]));
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: up_ledoff
|
||||
****************************************************************************/
|
||||
|
||||
void up_ledoff(int led)
|
||||
{
|
||||
led_setonoff(OFF_BITS(g_ledbits[led]));
|
||||
}
|
||||
|
||||
#endif /* CONFIG_ARCH_LEDS */
|
|
@ -0,0 +1,90 @@
|
|||
/************************************************************************************
|
||||
* configs/stm3220g-eval/src/up_boot.c
|
||||
* arch/arm/src/board/up_boot.c
|
||||
*
|
||||
* Copyright (C) 2011 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 <debug.h>
|
||||
|
||||
#include <arch/board/board.h>
|
||||
|
||||
#include "up_arch.h"
|
||||
#include "stm3220g-internal.h"
|
||||
|
||||
/************************************************************************************
|
||||
* Definitions
|
||||
************************************************************************************/
|
||||
|
||||
/************************************************************************************
|
||||
* Private Functions
|
||||
************************************************************************************/
|
||||
|
||||
/************************************************************************************
|
||||
* Public Functions
|
||||
************************************************************************************/
|
||||
|
||||
/************************************************************************************
|
||||
* Name: stm32_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 stm32_boardinitialize(void)
|
||||
{
|
||||
/* Configure SPI chip selects if 1) SPI is not disabled, and 2) the weak function
|
||||
* stm32_spiinitialize() has been brought into the link.
|
||||
*/
|
||||
|
||||
#if defined(CONFIG_STM32_SPI1) || defined(CONFIG_STM32_SPI2) || defined(CONFIG_STM32_SPI3)
|
||||
if (stm32_spiinitialize)
|
||||
{
|
||||
stm32_spiinitialize();
|
||||
}
|
||||
#endif
|
||||
|
||||
/* Configure on-board LEDs if LED support has been selected. */
|
||||
|
||||
#ifdef CONFIG_ARCH_LEDS
|
||||
up_ledinit();
|
||||
#endif
|
||||
}
|
|
@ -0,0 +1,170 @@
|
|||
/****************************************************************************
|
||||
* configs/stm3220g-eval/src/up_buttons.c
|
||||
*
|
||||
* Copyright (C) 2011 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 <stdint.h>
|
||||
|
||||
#include <arch/board/board.h>
|
||||
#include "stm3220g-internal.h"
|
||||
|
||||
#ifdef CONFIG_ARCH_BUTTONS
|
||||
|
||||
/****************************************************************************
|
||||
* Definitions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Private Data
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Private Functions
|
||||
****************************************************************************/
|
||||
|
||||
/* Pin configuration for each STM3210E-EVAL button. This array is indexed by
|
||||
* the BUTTON_* and JOYSTICK_* definitions in board.h
|
||||
*/
|
||||
|
||||
static const uint16_t g_buttons[NUM_BUTTONS] =
|
||||
{
|
||||
GPIO_BTN_WAKEUP, GPIO_BTN_TAMPER, GPIO_BTN_USER
|
||||
};
|
||||
|
||||
/****************************************************************************
|
||||
* Public Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Name: up_buttoninit
|
||||
*
|
||||
* Description:
|
||||
* up_buttoninit() must be called to initialize button resources. After
|
||||
* that, up_buttons() may be called to collect the current state of all
|
||||
* buttons or up_irqbutton() may be called to register button interrupt
|
||||
* handlers.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
void up_buttoninit(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: up_buttons
|
||||
****************************************************************************/
|
||||
|
||||
uint8_t up_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 for most keys. The exception
|
||||
* is the WAKEUP button.
|
||||
*/
|
||||
|
||||
bool released = stm32_gpioread(g_buttons[i]);
|
||||
if (i == BUTTON_WAKEUP)
|
||||
{
|
||||
released = !released;
|
||||
}
|
||||
|
||||
/* Accumulate the set of depressed (not released) keys */
|
||||
|
||||
if (!released)
|
||||
{
|
||||
ret |= (1 << i);
|
||||
}
|
||||
}
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
/************************************************************************************
|
||||
* Button support.
|
||||
*
|
||||
* Description:
|
||||
* up_buttoninit() must be called to initialize button resources. After
|
||||
* that, up_buttons() may be called to collect the current state of all
|
||||
* buttons or up_irqbutton() may be called to register button interrupt
|
||||
* handlers.
|
||||
*
|
||||
* After up_buttoninit() has been called, up_buttons() may be called to
|
||||
* collect the state of all buttons. up_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.
|
||||
*
|
||||
* up_irqbutton() 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. The previous interrupt handler address is returned (so that it may
|
||||
* restored, if so desired).
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
#ifdef CONFIG_ARCH_IRQBUTTONS
|
||||
xcpt_t up_irqbutton(int id, xcpt_t irqhandler)
|
||||
{
|
||||
xcpt_t oldhandler = NULL;
|
||||
|
||||
/* The following should be atomic */
|
||||
|
||||
if (id >= MIN_IRQBUTTON && id <= MAX_IRQBUTTON)
|
||||
{
|
||||
oldhandler = stm32_gpiosetevent(g_buttons[id], true, true, true, irqhandler);
|
||||
}
|
||||
return oldhandler;
|
||||
}
|
||||
#endif
|
||||
#endif /* CONFIG_ARCH_BUTTONS */
|
|
@ -0,0 +1,142 @@
|
|||
/************************************************************************************
|
||||
* configs/stm3220g-eval/src/up_can.c
|
||||
* arch/arm/src/board/up_can.c
|
||||
*
|
||||
* Copyright (C) 2011 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 <errno.h>
|
||||
#include <debug.h>
|
||||
|
||||
#include <nuttx/can.h>
|
||||
#include <arch/board/board.h>
|
||||
|
||||
#include "chip.h"
|
||||
#include "up_arch.h"
|
||||
|
||||
#include "stm32.h"
|
||||
#include "stm32_can.h"
|
||||
#include "stm3220g-internal.h"
|
||||
|
||||
#if defined(CONFIG_CAN) && (defined(CONFIG_STM32_CAN1) || defined(CONFIG_STM32_CAN2))
|
||||
|
||||
/************************************************************************************
|
||||
* Pre-processor Definitions
|
||||
************************************************************************************/
|
||||
/* Configuration ********************************************************************/
|
||||
|
||||
#if defined(CONFIG_STM32_CAN1) && defined(CONFIG_STM32_CAN2)
|
||||
# warning "Both CAN1 and CAN2 are enabled. Assuming only CAN1."
|
||||
# undef CONFIG_STM32_CAN2
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_STM32_CAN1
|
||||
# define CAN_PORT 1
|
||||
#else
|
||||
# define CAN_PORT 2
|
||||
#endif
|
||||
|
||||
/* Debug ***************************************************************************/
|
||||
/* Non-standard debug that may be enabled just for testing CAN */
|
||||
|
||||
#ifdef CONFIG_DEBUG_CAN
|
||||
# define candbg dbg
|
||||
# define canvdbg vdbg
|
||||
# define canlldbg lldbg
|
||||
# define canllvdbg llvdbg
|
||||
#else
|
||||
# define candbg(x...)
|
||||
# define canvdbg(x...)
|
||||
# define canlldbg(x...)
|
||||
# define canllvdbg(x...)
|
||||
#endif
|
||||
|
||||
/************************************************************************************
|
||||
* Private Functions
|
||||
************************************************************************************/
|
||||
|
||||
/************************************************************************************
|
||||
* Public Functions
|
||||
************************************************************************************/
|
||||
|
||||
/************************************************************************************
|
||||
* Name: can_devinit
|
||||
*
|
||||
* Description:
|
||||
* All STM32 architectures must provide the following interface to work with
|
||||
* examples/can.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
int can_devinit(void)
|
||||
{
|
||||
static bool initialized = false;
|
||||
struct can_dev_s *can;
|
||||
int ret;
|
||||
|
||||
/* Check if we have already initialized */
|
||||
|
||||
if (!initialized)
|
||||
{
|
||||
/* Call stm32_caninitialize() to get an instance of the CAN interface */
|
||||
|
||||
can = stm32_caninitialize(CAN_PORT);
|
||||
if (can == NULL)
|
||||
{
|
||||
candbg("ERROR: Failed to get CAN interface\n");
|
||||
return -ENODEV;
|
||||
}
|
||||
|
||||
/* Register the CAN driver at "/dev/can0" */
|
||||
|
||||
ret = can_register("/dev/can0", can);
|
||||
if (ret < 0)
|
||||
{
|
||||
candbg("ERROR: can_register failed: %d\n", ret);
|
||||
return ret;
|
||||
}
|
||||
|
||||
/* Now we are initialized */
|
||||
|
||||
initialized = true;
|
||||
}
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
||||
#endif /* CONFIG_CAN && (CONFIG_STM32_CAN2 || CONFIG_STM32_CAN3) */
|
|
@ -0,0 +1,208 @@
|
|||
/****************************************************************************
|
||||
* config/stm3220g_eval/src/up_nsh.c
|
||||
* arch/arm/src/board/up_nsh.c
|
||||
*
|
||||
* Copyright (C) 2012 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 <stdbool.h>
|
||||
#include <stdio.h>
|
||||
#include <debug.h>
|
||||
#include <errno.h>
|
||||
|
||||
#ifdef CONFIG_STM32_SPI1
|
||||
# include <nuttx/spi.h>
|
||||
# include <nuttx/mtd.h>
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_STM32_SDIO
|
||||
# include <nuttx/sdio.h>
|
||||
# include <nuttx/mmcsd.h>
|
||||
#endif
|
||||
|
||||
#include "stm32_internal.h"
|
||||
|
||||
/****************************************************************************
|
||||
* Pre-Processor Definitions
|
||||
****************************************************************************/
|
||||
|
||||
/* Configuration ************************************************************/
|
||||
|
||||
/* For now, don't build in any SPI1 support -- NSH is not using it */
|
||||
|
||||
#undef CONFIG_STM32_SPI1
|
||||
|
||||
/* PORT and SLOT number probably depend on the board configuration */
|
||||
|
||||
#ifdef CONFIG_ARCH_BOARD_STM3220G_EVAL
|
||||
# define CONFIG_NSH_HAVEUSBDEV 1
|
||||
# define CONFIG_NSH_HAVEMMCSD 1
|
||||
# if defined(CONFIG_NSH_MMCSDSLOTNO) && CONFIG_NSH_MMCSDSLOTNO != 0
|
||||
# error "Only one MMC/SD slot"
|
||||
# undef CONFIG_NSH_MMCSDSLOTNO
|
||||
# endif
|
||||
# ifndef CONFIG_NSH_MMCSDSLOTNO
|
||||
# define CONFIG_NSH_MMCSDSLOTNO 0
|
||||
# endif
|
||||
#else
|
||||
/* Add configuration for new STM32 boards here */
|
||||
# error "Unrecognized STM32 board"
|
||||
# undef CONFIG_NSH_HAVEUSBDEV
|
||||
# undef CONFIG_NSH_HAVEMMCSD
|
||||
#endif
|
||||
|
||||
/* Can't support USB features if USB is not enabled */
|
||||
|
||||
#ifndef CONFIG_USBDEV
|
||||
# undef CONFIG_NSH_HAVEUSBDEV
|
||||
#endif
|
||||
|
||||
/* Can't support MMC/SD features if mountpoints are disabled or if SDIO support
|
||||
* is not enabled.
|
||||
*/
|
||||
|
||||
#if defined(CONFIG_DISABLE_MOUNTPOINT) || !defined(CONFIG_STM32_SDIO)
|
||||
# undef CONFIG_NSH_HAVEMMCSD
|
||||
#endif
|
||||
|
||||
#ifndef CONFIG_NSH_MMCSDMINOR
|
||||
# define CONFIG_NSH_MMCSDMINOR 0
|
||||
#endif
|
||||
|
||||
/* Debug ********************************************************************/
|
||||
|
||||
#ifdef CONFIG_CPP_HAVE_VARARGS
|
||||
# ifdef CONFIG_DEBUG
|
||||
# define message(...) lib_lowprintf(__VA_ARGS__)
|
||||
# else
|
||||
# define message(...) printf(__VA_ARGS__)
|
||||
# endif
|
||||
#else
|
||||
# ifdef CONFIG_DEBUG
|
||||
# define message lib_lowprintf
|
||||
# else
|
||||
# define message printf
|
||||
# endif
|
||||
#endif
|
||||
|
||||
/****************************************************************************
|
||||
* Public Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Name: nsh_archinitialize
|
||||
*
|
||||
* Description:
|
||||
* Perform architecture specific initialization
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
int nsh_archinitialize(void)
|
||||
{
|
||||
#ifdef CONFIG_STM32_SPI1
|
||||
FAR struct spi_dev_s *spi;
|
||||
FAR struct mtd_dev_s *mtd;
|
||||
#endif
|
||||
#ifdef CONFIG_NSH_HAVEMMCSD
|
||||
FAR struct sdio_dev_s *sdio;
|
||||
int ret;
|
||||
#endif
|
||||
|
||||
/* Configure SPI-based devices */
|
||||
|
||||
#ifdef CONFIG_STM32_SPI1
|
||||
/* Get the SPI port */
|
||||
|
||||
message("nsh_archinitialize: Initializing SPI port 1\n");
|
||||
spi = up_spiinitialize(1);
|
||||
if (!spi)
|
||||
{
|
||||
message("nsh_archinitialize: Failed to initialize SPI port 0\n");
|
||||
return -ENODEV;
|
||||
}
|
||||
message("nsh_archinitialize: Successfully initialized SPI port 0\n");
|
||||
|
||||
/* Now bind the SPI interface to the M25P64/128 SPI FLASH driver */
|
||||
|
||||
message("nsh_archinitialize: Bind SPI to the SPI flash driver\n");
|
||||
mtd = m25p_initialize(spi);
|
||||
if (!mtd)
|
||||
{
|
||||
message("nsh_archinitialize: Failed to bind SPI port 0 to the SPI FLASH driver\n");
|
||||
return -ENODEV;
|
||||
}
|
||||
message("nsh_archinitialize: Successfully bound SPI port 0 to the SPI FLASH driver\n");
|
||||
#warning "Now what are we going to do with this SPI FLASH driver?"
|
||||
#endif
|
||||
|
||||
/* Mount the SDIO-based MMC/SD block driver */
|
||||
|
||||
#ifdef CONFIG_NSH_HAVEMMCSD
|
||||
/* First, get an instance of the SDIO interface */
|
||||
|
||||
message("nsh_archinitialize: Initializing SDIO slot %d\n",
|
||||
CONFIG_NSH_MMCSDSLOTNO);
|
||||
sdio = sdio_initialize(CONFIG_NSH_MMCSDSLOTNO);
|
||||
if (!sdio)
|
||||
{
|
||||
message("nsh_archinitialize: Failed to initialize SDIO slot %d\n",
|
||||
CONFIG_NSH_MMCSDSLOTNO);
|
||||
return -ENODEV;
|
||||
}
|
||||
|
||||
/* Now bind the SDIO interface to the MMC/SD driver */
|
||||
|
||||
message("nsh_archinitialize: Bind SDIO to the MMC/SD driver, minor=%d\n",
|
||||
CONFIG_NSH_MMCSDMINOR);
|
||||
ret = mmcsd_slotinitialize(CONFIG_NSH_MMCSDMINOR, sdio);
|
||||
if (ret != OK)
|
||||
{
|
||||
message("nsh_archinitialize: Failed to bind SDIO to the MMC/SD driver: %d\n", ret);
|
||||
return ret;
|
||||
}
|
||||
message("nsh_archinitialize: Successfully bound SDIO to the MMC/SD driver\n");
|
||||
|
||||
/* Then let's guess and say that there is a card in the slot. I need to check to
|
||||
* see if the STM3220G-EVAL board supports a GPIO to detect if there is a card in
|
||||
* the slot.
|
||||
*/
|
||||
|
||||
sdio_mediachange(sdio, true);
|
||||
#endif
|
||||
return OK;
|
||||
}
|
|
@ -0,0 +1,120 @@
|
|||
/************************************************************************************
|
||||
* configs/stm3220g-eval/src/up_pwm.c
|
||||
* arch/arm/src/board/up_pwm.c
|
||||
*
|
||||
* Copyright (C) 2011 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 <errno.h>
|
||||
#include <debug.h>
|
||||
|
||||
#include <nuttx/pwm.h>
|
||||
#include <arch/board/board.h>
|
||||
|
||||
#include "chip.h"
|
||||
#include "up_arch.h"
|
||||
#include "stm32_pwm.h"
|
||||
#include "stm3220g-internal.h"
|
||||
|
||||
/************************************************************************************
|
||||
* Definitions
|
||||
************************************************************************************/
|
||||
/* Configuration *******************************************************************/
|
||||
/* PWM
|
||||
*
|
||||
* The STM3220G-Eval has no real on-board PWM devices, but the board can be
|
||||
* configured to output a pulse train using variously unused pins on the board for
|
||||
* PWM output (see board.h for details of pins).
|
||||
*/
|
||||
|
||||
#ifdef CONFIG_PWM
|
||||
|
||||
/************************************************************************************
|
||||
* Private Functions
|
||||
************************************************************************************/
|
||||
|
||||
/************************************************************************************
|
||||
* Public Functions
|
||||
************************************************************************************/
|
||||
|
||||
/************************************************************************************
|
||||
* Name: pwm_devinit
|
||||
*
|
||||
* Description:
|
||||
* All STM32 architectures must provide the following interface to work with
|
||||
* examples/pwm.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
int pwm_devinit(void)
|
||||
{
|
||||
static bool initialized = false;
|
||||
struct pwm_lowerhalf_s *pwm;
|
||||
int ret;
|
||||
|
||||
/* Have we already initialized? */
|
||||
|
||||
if (!initialized)
|
||||
{
|
||||
/* Call stm32_pwminitialize() to get an instance of the PWM interface */
|
||||
|
||||
pwm = stm32_pwminitialize(STM3220G_EVAL_PWMTIMER);
|
||||
if (!pwm)
|
||||
{
|
||||
dbg("Failed to get the STM32 PWM lower half\n");
|
||||
return -ENODEV;
|
||||
}
|
||||
|
||||
/* Register the PWM driver at "/dev/pwm0" */
|
||||
|
||||
ret = pwm_register("/dev/pwm0", pwm);
|
||||
if (ret < 0)
|
||||
{
|
||||
adbg("pwm_register failed: %d\n", ret);
|
||||
return ret;
|
||||
}
|
||||
|
||||
/* Now we are initialized */
|
||||
|
||||
initialized = true;
|
||||
}
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
||||
#endif /* CONFIG_PWM */
|
|
@ -0,0 +1,161 @@
|
|||
/************************************************************************************
|
||||
* configs/stm3220g_eval/src/up_spi.c
|
||||
* arch/arm/src/board/up_spi.c
|
||||
*
|
||||
* Copyright (C) 2011 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 <stdint.h>
|
||||
#include <stdbool.h>
|
||||
#include <debug.h>
|
||||
|
||||
#include <nuttx/spi.h>
|
||||
#include <arch/board/board.h>
|
||||
|
||||
#include "up_arch.h"
|
||||
#include "chip.h"
|
||||
#include "stm32_internal.h"
|
||||
#include "stm3220g-internal.h"
|
||||
|
||||
#if defined(CONFIG_STM32_SPI1) || defined(CONFIG_STM32_SPI2) || defined(CONFIG_STM32_SPI3)
|
||||
|
||||
/************************************************************************************
|
||||
* Definitions
|
||||
************************************************************************************/
|
||||
|
||||
/* Enables debug output from this file (needs CONFIG_DEBUG too) */
|
||||
|
||||
#undef SPI_DEBUG /* Define to enable debug */
|
||||
#undef SPI_VERBOSE /* Define to enable verbose debug */
|
||||
|
||||
#ifdef SPI_DEBUG
|
||||
# define spidbg lldbg
|
||||
# ifdef SPI_VERBOSE
|
||||
# define spivdbg lldbg
|
||||
# else
|
||||
# define spivdbg(x...)
|
||||
# endif
|
||||
#else
|
||||
# undef SPI_VERBOSE
|
||||
# define spidbg(x...)
|
||||
# define spivdbg(x...)
|
||||
#endif
|
||||
|
||||
/************************************************************************************
|
||||
* Private Functions
|
||||
************************************************************************************/
|
||||
|
||||
/************************************************************************************
|
||||
* Public Functions
|
||||
************************************************************************************/
|
||||
|
||||
/************************************************************************************
|
||||
* Name: stm32_spiinitialize
|
||||
*
|
||||
* Description:
|
||||
* Called to configure SPI chip select GPIO pins for the STM3220G-EVAL board.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
void weak_function stm32_spiinitialize(void)
|
||||
{
|
||||
#warning "Missing logic"
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: stm32_spi1/2/3select and stm32_spi1/2/3status
|
||||
*
|
||||
* Description:
|
||||
* The external functions, stm32_spi1/2/3select and stm32_spi1/2/3status must be
|
||||
* provided by board-specific logic. They are implementations of the select
|
||||
* and status methods of the SPI interface defined by struct spi_ops_s (see
|
||||
* include/nuttx/spi.h). All other methods (including up_spiinitialize())
|
||||
* are provided by common STM32 logic. To use this common SPI logic on your
|
||||
* board:
|
||||
*
|
||||
* 1. Provide logic in stm32_boardinitialize() to configure SPI chip select
|
||||
* pins.
|
||||
* 2. Provide stm32_spi1/2/3select() and stm32_spi1/2/3status() functions in your
|
||||
* board-specific logic. These functions will perform chip selection and
|
||||
* status operations using GPIOs in the way your board is configured.
|
||||
* 3. Add a calls to up_spiinitialize() in your low level application
|
||||
* initialization logic
|
||||
* 4. The handle returned by up_spiinitialize() may then be used to bind the
|
||||
* SPI driver to higher level logic (e.g., calling
|
||||
* mmcsd_spislotinitialize(), for example, will bind the SPI driver to
|
||||
* the SPI MMC/SD driver).
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#ifdef CONFIG_STM32_SPI1
|
||||
void stm32_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected)
|
||||
{
|
||||
spidbg("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert");
|
||||
}
|
||||
|
||||
uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
|
||||
{
|
||||
return SPI_STATUS_PRESENT;
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_STM32_SPI2
|
||||
void stm32_spi2select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected)
|
||||
{
|
||||
spidbg("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert");
|
||||
}
|
||||
|
||||
uint8_t stm32_spi2status(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
|
||||
{
|
||||
return SPI_STATUS_PRESENT;
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_STM32_SPI3
|
||||
void stm32_spi3select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected)
|
||||
{
|
||||
spidbg("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert");
|
||||
}
|
||||
|
||||
uint8_t stm32_spi3status(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
|
||||
{
|
||||
return SPI_STATUS_PRESENT;
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif /* CONFIG_STM32_SPI1 || CONFIG_STM32_SPI2 */
|
|
@ -0,0 +1,131 @@
|
|||
/****************************************************************************
|
||||
* configs/stm3220g_eval/src/up_leds.c
|
||||
* arch/arm/src/board/up_leds.c
|
||||
*
|
||||
* Copyright (C) 2011 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 <stdint.h>
|
||||
#include <stdbool.h>
|
||||
#include <debug.h>
|
||||
|
||||
#include <arch/board/board.h>
|
||||
|
||||
#include "chip.h"
|
||||
#include "up_arch.h"
|
||||
#include "up_internal.h"
|
||||
#include "stm32_internal.h"
|
||||
#include "stm3220g-internal.h"
|
||||
|
||||
#ifndef CONFIG_ARCH_LEDS
|
||||
|
||||
/****************************************************************************
|
||||
* Definitions
|
||||
****************************************************************************/
|
||||
|
||||
/* Enables debug output from this file (needs CONFIG_DEBUG with
|
||||
* CONFIG_DEBUG_VERBOSE too)
|
||||
*/
|
||||
|
||||
#undef LED_DEBUG /* Define to enable debug */
|
||||
|
||||
#ifdef LED_DEBUG
|
||||
# define leddbg lldbg
|
||||
# define ledvdbg llvdbg
|
||||
#else
|
||||
# define leddbg(x...)
|
||||
# define ledvdbg(x...)
|
||||
#endif
|
||||
|
||||
/****************************************************************************
|
||||
* Private Data
|
||||
****************************************************************************/
|
||||
/* This array maps an LED number to GPIO pin configuration */
|
||||
|
||||
static uint32_t g_ledcfg[BOARD_NLEDS] =
|
||||
{
|
||||
GPIO_LED1, GPIO_LED2, GPIO_LED3, GPIO_LED4
|
||||
};
|
||||
|
||||
/****************************************************************************
|
||||
* Private Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Public Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Name: stm32_ledinit
|
||||
****************************************************************************/
|
||||
|
||||
void stm32_ledinit(void)
|
||||
{
|
||||
/* Configure LED1-4 GPIOs for output */
|
||||
|
||||
stm32_configgpio(GPIO_LED1);
|
||||
stm32_configgpio(GPIO_LED2);
|
||||
stm32_configgpio(GPIO_LED3);
|
||||
stm32_configgpio(GPIO_LED4);
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: stm32_setled
|
||||
****************************************************************************/
|
||||
|
||||
void stm32_setled(int led, bool ledon)
|
||||
{
|
||||
if ((unsigned)led < BOARD_NLEDS)
|
||||
{
|
||||
stm32_gpiowrite(g_ledcfg[led], ledon);
|
||||
}
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: stm32_setleds
|
||||
****************************************************************************/
|
||||
|
||||
void stm32_setleds(uint8_t ledset)
|
||||
{
|
||||
stm32_gpiowrite(BOARD_LED1, (ledset & BOARD_LED1_BIT) == 0);
|
||||
stm32_gpiowrite(BOARD_LED2, (ledset & BOARD_LED2_BIT) == 0);
|
||||
stm32_gpiowrite(BOARD_LED3, (ledset & BOARD_LED3_BIT) == 0);
|
||||
stm32_gpiowrite(BOARD_LED4, (ledset & BOARD_LED4_BIT) == 0);
|
||||
}
|
||||
|
||||
#endif /* !CONFIG_ARCH_LEDS */
|
|
@ -0,0 +1,170 @@
|
|||
############################################################################
|
||||
# configs/stm3220g-eval/telnetd/Make.defs
|
||||
#
|
||||
# Copyright (C) 2012 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.
|
||||
#
|
||||
############################################################################
|
||||
|
||||
include ${TOPDIR}/.config
|
||||
|
||||
# Setup for the selected toolchain
|
||||
|
||||
ifeq ($(CONFIG_STM32_CODESOURCERYW),y)
|
||||
# CodeSourcery under Windows
|
||||
CROSSDEV = arm-none-eabi-
|
||||
WINTOOL = y
|
||||
ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft
|
||||
endif
|
||||
ifeq ($(CONFIG_STM32_CODESOURCERYL),y)
|
||||
# CodeSourcery under Linux
|
||||
CROSSDEV = arm-none-eabi-
|
||||
ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft
|
||||
MAXOPTIMIZATION = -O2
|
||||
endif
|
||||
ifeq ($(CONFIG_STM32_DEVKITARM),y)
|
||||
# devkitARM under Windows
|
||||
CROSSDEV = arm-eabi-
|
||||
WINTOOL = y
|
||||
ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft
|
||||
endif
|
||||
ifeq ($(CONFIG_STM32_RAISONANCE),y)
|
||||
# Raisonance RIDE7 under Windows
|
||||
CROSSDEV = arm-none-eabi-
|
||||
WINTOOL = y
|
||||
ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft
|
||||
endif
|
||||
ifeq ($(CONFIG_STM32_BUILDROOT),y)
|
||||
# NuttX buildroot under Linux or Cygwin
|
||||
CROSSDEV = arm-elf-
|
||||
ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft
|
||||
MAXOPTIMIZATION = -Os
|
||||
endif
|
||||
|
||||
LDSCRIPT = ld.script
|
||||
|
||||
ifeq ($(WINTOOL),y)
|
||||
# Windows-native toolchains
|
||||
DIRLINK = $(TOPDIR)/tools/winlink.sh
|
||||
DIRUNLINK = $(TOPDIR)/tools/unlink.sh
|
||||
MKDEP = $(TOPDIR)/tools/mknulldeps.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)/telnetd/$(LDSCRIPT)}"
|
||||
MAXOPTIMIZATION = -O2
|
||||
else
|
||||
# Linux/Cygwin-native toolchain
|
||||
MKDEP = $(TOPDIR)/tools/mkdeps.sh
|
||||
ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
|
||||
ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
|
||||
ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/telnetd/$(LDSCRIPT)
|
||||
endif
|
||||
|
||||
CC = $(CROSSDEV)gcc
|
||||
CXX = $(CROSSDEV)g++
|
||||
CPP = $(CROSSDEV)gcc -E
|
||||
LD = $(CROSSDEV)ld
|
||||
AR = $(CROSSDEV)ar rcs
|
||||
NM = $(CROSSDEV)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
|
||||
else
|
||||
ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer
|
||||
endif
|
||||
|
||||
ARCHCFLAGS = -fno-builtin
|
||||
ARCHCXXFLAGS = -fno-builtin -fno-exceptions -fno-rtti
|
||||
ARCHWARNINGS = -Wall -Wstrict-prototypes -Wshadow
|
||||
ARCHWARNINGSXX = -Wall -Wshadow
|
||||
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.ld -no-check-sections
|
||||
LDNXFLATFLAGS = -e main -s 2048
|
||||
|
||||
OBJEXT = .o
|
||||
LIBEXT = .a
|
||||
EXEEXT =
|
||||
|
||||
ifneq ($(CROSSDEV),arm-elf-)
|
||||
LDFLAGS += -nostartfiles -nodefaultlibs
|
||||
endif
|
||||
ifeq ($(CONFIG_DEBUG_SYMBOLS),y)
|
||||
LDFLAGS += -g
|
||||
endif
|
||||
|
||||
define PREPROCESS
|
||||
@echo "CPP: $1->$2"
|
||||
@$(CPP) $(CPPFLAGS) $1 -o $2
|
||||
endef
|
||||
|
||||
define COMPILE
|
||||
@echo "CC: $1"
|
||||
@$(CC) -c $(CFLAGS) $1 -o $2
|
||||
endef
|
||||
|
||||
define COMPILEXX
|
||||
@echo "CXX: $1"
|
||||
@$(CXX) -c $(CXXFLAGS) $1 -o $2
|
||||
endef
|
||||
|
||||
define ASSEMBLE
|
||||
@echo "AS: $1"
|
||||
@$(CC) -c $(AFLAGS) $1 -o $2
|
||||
endef
|
||||
|
||||
define ARCHIVE
|
||||
echo "AR: $2"; \
|
||||
$(AR) $1 $2 || { echo "$(AR) $1 $2 FAILED!" ; exit 1 ; }
|
||||
endef
|
||||
|
||||
define CLEAN
|
||||
@rm -f *.o *.a
|
||||
endef
|
||||
|
||||
HOSTCC = gcc
|
||||
HOSTINCLUDES = -I.
|
||||
HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -g -pipe
|
||||
HOSTLDFLAGS =
|
||||
|
|
@ -0,0 +1,44 @@
|
|||
############################################################################
|
||||
# configs/stm3220g-eval/telnetd/appconfig
|
||||
#
|
||||
# Copyright (C) 2012 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.
|
||||
#
|
||||
############################################################################
|
||||
|
||||
# Path to example in apps/examples containing the user_start entry point
|
||||
|
||||
CONFIGURED_APPS += examples/telnetd
|
||||
|
||||
# Networking support
|
||||
|
||||
CONFIGURED_APPS += netutils/uiplib
|
||||
CONFIGURED_APPS += netutils/telnetd
|
||||
|
File diff suppressed because it is too large
Load Diff
File diff suppressed because it is too large
Load Diff
|
@ -0,0 +1,116 @@
|
|||
/****************************************************************************
|
||||
* configs/stm3220g-eval/telnetd/ld.script
|
||||
*
|
||||
* Copyright (C) 2012 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.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/* The STM32F103ZET6 has 1024Kb of FLASH beginning at address 0x0800:0000 and
|
||||
* 192Kb of SRAM. SRAM is split up into three blocks:
|
||||
*
|
||||
* 1) 112Kb of SRAM beginning at address 0x2000:0000
|
||||
* 2) 16Kb of SRAM beginning at address 0x2001:c000
|
||||
* 3) 64Kb of TCM SRAM beginning at address 0x1000:0000
|
||||
*
|
||||
* 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 = 1024K
|
||||
sram (rwx) : ORIGIN = 0x20000000, LENGTH = 112K
|
||||
}
|
||||
|
||||
OUTPUT_ARCH(arm)
|
||||
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
|
||||
|
||||
__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
|
||||
|
||||
.ARM.extab : {
|
||||
*(.ARM.extab*)
|
||||
} >sram
|
||||
|
||||
.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) }
|
||||
}
|
|
@ -0,0 +1,67 @@
|
|||
#!/bin/bash
|
||||
# configs/stm3220g-eval/telnetd/setenv.sh
|
||||
#
|
||||
# Copyright (C) 2012 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.
|
||||
#
|
||||
|
||||
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 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 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"
|
||||
|
||||
# This the Cygwin path to the location where I build the buildroot
|
||||
# toolchain.
|
||||
#export TOOLCHAIN_BIN="${WD}/../misc/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}"
|
|
@ -0,0 +1,13 @@
|
|||
#
|
||||
# Olimex ARM-USB-OCD
|
||||
#
|
||||
# http://www.olimex.com/dev/arm-usb-ocd.html
|
||||
#
|
||||
|
||||
interface ft2232
|
||||
ft2232_device_desc "Olimex OpenOCD JTAG"
|
||||
ft2232_layout olimex-jtag
|
||||
ft2232_vid_pid 0x15ba 0x0003
|
||||
|
||||
#jtag_khz 600
|
||||
|
|
@ -0,0 +1,90 @@
|
|||
#!/bin/sh
|
||||
|
||||
# Get command line parameters
|
||||
|
||||
USAGE="USAGE: $0 [-dh] <TOPDIR>"
|
||||
ADVICE="Try '$0 -h' for more information"
|
||||
|
||||
|
||||
while [ ! -z "$1" ]; do
|
||||
case $1 in
|
||||
-d )
|
||||
set -x
|
||||
;;
|
||||
-h )
|
||||
echo "$0 is a tool for generation of proper version files for the NuttX build"
|
||||
echo ""
|
||||
echo $USAGE
|
||||
echo ""
|
||||
echo "Where:"
|
||||
echo " -d"
|
||||
echo " Enable script debug"
|
||||
echo " -h"
|
||||
echo " show this help message and exit"
|
||||
echo " Use the OpenOCD 0.4.0"
|
||||
echo " <TOPDIR>"
|
||||
echo " The full path to the top-level NuttX directory"
|
||||
exit 0
|
||||
;;
|
||||
* )
|
||||
break;
|
||||
;;
|
||||
esac
|
||||
shift
|
||||
done
|
||||
|
||||
TOPDIR=$1
|
||||
if [ -z "${TOPDIR}" ]; then
|
||||
echo "Missing argument"
|
||||
echo $USAGE
|
||||
echo $ADVICE
|
||||
exit 1
|
||||
fi
|
||||
|
||||
# This script *probably* only works with the following versions of OpenOCD:
|
||||
|
||||
# Local search directory and configurations
|
||||
|
||||
OPENOCD_SEARCHDIR="${TOPDIR}/configs/stm3210e-eval/tools"
|
||||
OPENOCD_WSEARCHDIR="`cygpath -w ${OPENOCD_SEARCHDIR}`"
|
||||
|
||||
OPENOCD_PATH="/cygdrive/c/Program Files (x86)/OpenOCD/0.4.0/bin"
|
||||
OPENOCD_EXE=openocd.exe
|
||||
OPENOCD_INTERFACE="olimex-arm-usb-ocd.cfg"
|
||||
|
||||
|
||||
OPENOCD_TARGET="stm32.cfg"
|
||||
OPENOCD_ARGS="-s ${OPENOCD_WSEARCHDIR} -f ${OPENOCD_INTERFACE} -f ${OPENOCD_TARGET}"
|
||||
|
||||
echo "Trying OpenOCD 0.4.0 path: ${OPENOCD_PATH}/${OPENOCD_EXE}"
|
||||
|
||||
# Verify that everything is what it claims it is and is located where it claims it is.
|
||||
|
||||
if [ ! -x "${OPENOCD_PATH}/${OPENOCD_EXE}" ]; then
|
||||
echo "OpenOCD executable does not exist: ${OPENOCD_PATH}/${OPENOCD_EXE}"
|
||||
exit 1
|
||||
fi
|
||||
if [ ! -f "${OPENOCD_SEARCHDIR}/${OPENOCD_TARGET}" ]; then
|
||||
echo "OpenOCD target config file does not exist: ${OPENOCD_SEARCHDIR}/${OPENOCD_TARGET}"
|
||||
exit 1
|
||||
fi
|
||||
if [ ! -f "${OPENOCD_SEARCHDIR}/${OPENOCD_INTERFACE}" ]; then
|
||||
echo "OpenOCD interface config file does not exist: ${OPENOCD_SEARCHDIR}/${OPENOCD_INTERFACE}"
|
||||
exit 1
|
||||
fi
|
||||
|
||||
# Enable debug if so requested
|
||||
|
||||
if [ "X$2" = "X-d" ]; then
|
||||
OPENOCD_ARGS=$OPENOCD_ARGS" -d3"
|
||||
set -x
|
||||
fi
|
||||
|
||||
# Okay... do it!
|
||||
|
||||
echo "Starting OpenOCD"
|
||||
"${OPENOCD_PATH}/${OPENOCD_EXE}" ${OPENOCD_ARGS} &
|
||||
echo "OpenOCD daemon started"
|
||||
ps -ef | grep openocd
|
||||
echo "In GDB: target remote localhost:3333"
|
||||
|
|
@ -0,0 +1,69 @@
|
|||
# script for stm32
|
||||
|
||||
if { [info exists CHIPNAME] } {
|
||||
set _CHIPNAME $CHIPNAME
|
||||
} else {
|
||||
set _CHIPNAME stm32
|
||||
}
|
||||
|
||||
if { [info exists ENDIAN] } {
|
||||
set _ENDIAN $ENDIAN
|
||||
} else {
|
||||
set _ENDIAN little
|
||||
}
|
||||
|
||||
# Work-area is a space in RAM used for flash programming
|
||||
# By default use 16kB
|
||||
if { [info exists WORKAREASIZE] } {
|
||||
set _WORKAREASIZE $WORKAREASIZE
|
||||
} else {
|
||||
set _WORKAREASIZE 0x4000
|
||||
}
|
||||
|
||||
# JTAG speed should be <= F_CPU/6. F_CPU after reset is 8MHz, so use F_JTAG = 1MHz
|
||||
jtag_khz 1000
|
||||
|
||||
jtag_nsrst_delay 100
|
||||
jtag_ntrst_delay 100
|
||||
|
||||
#jtag scan chain
|
||||
if { [info exists CPUTAPID ] } {
|
||||
set _CPUTAPID $CPUTAPID
|
||||
} else {
|
||||
# See STM Document RM0008
|
||||
# Section 26.6.3
|
||||
set _CPUTAPID 0x3ba00477
|
||||
}
|
||||
jtag newtap $_CHIPNAME cpu -irlen 4 -ircapture 0x1 -irmask 0xf -expected-id $_CPUTAPID
|
||||
|
||||
if { [info exists BSTAPID ] } {
|
||||
# FIXME this never gets used to override defaults...
|
||||
set _BSTAPID $BSTAPID
|
||||
} else {
|
||||
# See STM Document RM0008
|
||||
# Section 29.6.2
|
||||
# Low density devices, Rev A
|
||||
set _BSTAPID1 0x06412041
|
||||
# Medium density devices, Rev A
|
||||
set _BSTAPID2 0x06410041
|
||||
# Medium density devices, Rev B and Rev Z
|
||||
set _BSTAPID3 0x16410041
|
||||
# High density devices, Rev A
|
||||
set _BSTAPID4 0x06414041
|
||||
# Connectivity line devices, Rev A and Rev Z
|
||||
set _BSTAPID5 0x06418041
|
||||
}
|
||||
jtag newtap $_CHIPNAME bs -irlen 5 -expected-id $_BSTAPID1 \
|
||||
-expected-id $_BSTAPID2 -expected-id $_BSTAPID3 \
|
||||
-expected-id $_BSTAPID4 -expected-id $_BSTAPID5
|
||||
|
||||
set _TARGETNAME $_CHIPNAME.cpu
|
||||
target create $_TARGETNAME cortex_m3 -endian $_ENDIAN -chain-position $_TARGETNAME
|
||||
|
||||
$_TARGETNAME configure -work-area-phys 0x20000000 -work-area-size $_WORKAREASIZE -work-area-backup 0
|
||||
|
||||
set _FLASHNAME $_CHIPNAME.flash
|
||||
flash bank $_FLASHNAME stm32x 0 0 0 0 $_TARGETNAME
|
||||
|
||||
# For more information about the configuration files, take a look at:
|
||||
# openocd.texi
|
Loading…
Reference in New Issue