From bd5634083301f3fc7070ec26fef3340aeeba8d28 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Thu, 24 Oct 2013 08:48:04 -0600 Subject: Added support for the Olimex STM32 P207 board. From Martin Lederhilger --- nuttx/configs/Kconfig | 19 ++- nuttx/configs/README.txt | 8 +- nuttx/configs/olimex-stm32-p207/include/board.h | 28 ++-- nuttx/configs/olimex-stm32-p207/nsh/Make.defs | 2 - .../olimex-stm32-p207/src/olimex-stm32-p207.h | 171 +++++++++++++++++++++ .../configs/olimex-stm32-p207/src/p207-internal.h | 170 -------------------- nuttx/configs/olimex-stm32-p207/src/up_adc.c | 10 +- nuttx/configs/olimex-stm32-p207/src/up_autoleds.c | 2 +- nuttx/configs/olimex-stm32-p207/src/up_boot.c | 11 +- nuttx/configs/olimex-stm32-p207/src/up_buttons.c | 60 +++++--- nuttx/configs/olimex-stm32-p207/src/up_can.c | 2 +- .../olimex-stm32-p207/src/up_cxxinitialize.c | 1 - nuttx/configs/olimex-stm32-p207/src/up_nsh.c | 10 +- nuttx/configs/olimex-stm32-p207/src/up_usb.c | 23 ++- nuttx/configs/olimex-stm32-p207/src/up_userleds.c | 7 +- 15 files changed, 277 insertions(+), 247 deletions(-) create mode 100644 nuttx/configs/olimex-stm32-p207/src/olimex-stm32-p207.h delete mode 100644 nuttx/configs/olimex-stm32-p207/src/p207-internal.h (limited to 'nuttx/configs') diff --git a/nuttx/configs/Kconfig b/nuttx/configs/Kconfig index 6580c96af..56ff89dce 100644 --- a/nuttx/configs/Kconfig +++ b/nuttx/configs/Kconfig @@ -57,7 +57,7 @@ config ARCH_BOARD_CLOUDCTRL bool "Darcy's CloudController stm32f10x board" depends on ARCH_CHIP_STM32F107VC ---help--- - Small network relay development board. Based on the Shenzhou IV development + Small network relay development board. Based on the Shenzhou IV development board design. config ARCH_BOARD_COMPALE86 @@ -359,7 +359,7 @@ config ARCH_BOARD_NUTINY_NUC120 depends on ARCH_CHIP_NUC120LE3AN select ARCH_HAVE_LEDS ---help--- - This is the port to the Nuvoton NuTiny EVB 120 board. This board uses a + This is the port to the Nuvoton NuTiny EVB 120 board. This board uses a Nuvoton NUC120 chip, specifically the NUC120LE3AN. See http://www.nuvoton.com/ for further information. @@ -391,6 +391,17 @@ config ARCH_BOARD_OLIMEX_STM32P107 Linux or Cygwin. See the http://www.olimex.com for further information. This board features the STMicro STM32F107VC MCU +config ARCH_BOARD_OLIMEX_STM32P207 + bool "Olimex STM32 P207 board" + depends on ARCH_CHIP_STM32F207ZE + select ARCH_HAVE_LEDS + select ARCH_HAVE_BUTTONS + select ARCH_HAVE_IRQBUTTONS + ---help--- + This port uses the Olimex STM32 P207 board and a GNU arm-nuttx-elf toolchain* under + Linux or Cygwin. See the http://www.olimex.com for further information. This + board features the STMicro STM32F207ZE MCU + config ARCH_BOARD_OPEN1788 bool "Wave Share Open1788" depends on ARCH_CHIP_LPC1788 @@ -829,6 +840,7 @@ config ARCH_BOARD default "olimex-lpc1766stk" if ARCH_BOARD_LPC1766STK default "olimex-lpc2378" if ARCH_BOARD_OLIMEXLPC2378 default "olimex-stm32-p107" if ARCH_BOARD_OLIMEX_STM32P107 + default "olimex-stm32-p207" if ARCH_BOARD_OLIMEX_STM32P207 default "olimex-strp711" if ARCH_BOARD_OLIMEX_STRP711 default "open1788" if ARCH_BOARD_OPEN1788 default "p112" if ARCH_BOARD_P112 @@ -1043,6 +1055,9 @@ endif if ARCH_BOARD_OLIMEX_STM32P107 source "configs/olimex-stm32-p107/Kconfig" endif +if ARCH_BOARD_OLIMEX_STM32P207 +source "configs/olimex-stm32-p207/Kconfig" +endif if ARCH_BOARD_OLIMEX_STRP711 source "configs/olimex-strp711/Kconfig" endif diff --git a/nuttx/configs/README.txt b/nuttx/configs/README.txt index b34b7bc96..dc94380ca 100644 --- a/nuttx/configs/README.txt +++ b/nuttx/configs/README.txt @@ -1892,8 +1892,12 @@ configs/olimex-lpc2378 configs/olimex-stm32-p107 This port uses the Olimex STM32-P107 board (STM32F107VC) and a GNU arm-nuttx-elf toolchain* under Linux or Cygwin. See the https://www.olimex.com/dev/stm32-p107.html - for further information. Contributed by Max Holtzberg. STATUS: Configurations - for the basic OS test and NSH are available and verified. + for further information. Contributed by Max Holtzberg. + +configs/olimex-stm32-p207 + This port uses the Olimex STM32-P207 board (STM32F207ZE) and a GNU arm-nuttx-elf + toolchain* under Linux or Cygwin. See the https://www.olimex.com/dev/stm32-p207.html + for further information. Contributed by Martin Lederhilger. configs/olimex-strp711 This port uses the Olimex STR-P711 board and a GNU arm-nuttx-elf toolchain* under diff --git a/nuttx/configs/olimex-stm32-p207/include/board.h b/nuttx/configs/olimex-stm32-p207/include/board.h index d91fdc652..0c5538351 100644 --- a/nuttx/configs/olimex-stm32-p207/include/board.h +++ b/nuttx/configs/olimex-stm32-p207/include/board.h @@ -183,25 +183,25 @@ #define NUM_BUTTONS 7 -#define BUTTON_TAMPER_BIT (1 << BUTTON_TAMPER) -#define BUTTON_WKUP_BIT (1 << BUTTON_WKUP) -#define BUTTON_RIGHT_BIT (1 << BUTTON_RIGHT) -#define BUTTON_UP_BIT (1 << BUTTON_UP) -#define BUTTON_LEFT_BIT (1 << BUTTON_LEFT) -#define BUTTON_DOWN_BIT (1 << BUTTON_DOWN) -#define BUTTON_CENTER_BIT (1 << BUTTON_CENTER) +#define BUTTON_TAMPER_BIT (1 << BUTTON_TAMPER) +#define BUTTON_WKUP_BIT (1 << BUTTON_WKUP) +#define BUTTON_RIGHT_BIT (1 << BUTTON_RIGHT) +#define BUTTON_UP_BIT (1 << BUTTON_UP) +#define BUTTON_LEFT_BIT (1 << BUTTON_LEFT) +#define BUTTON_DOWN_BIT (1 << BUTTON_DOWN) +#define BUTTON_CENTER_BIT (1 << BUTTON_CENTER) /* Alternate function pin selections ************************************************/ //USART3: -#define GPIO_USART3_RX GPIO_USART3_RX_3 //PD9 -#define GPIO_USART3_TX GPIO_USART3_TX_3 //PD8 -#define GPIO_USART3_CTS GPIO_USART3_CTS_2 //PD11 -#define GPIO_USART3_RTS GPIO_USART3_RTS_2 //PD12 +#define GPIO_USART3_RX GPIO_USART3_RX_3 //PD9 +#define GPIO_USART3_TX GPIO_USART3_TX_3 //PD8 +#define GPIO_USART3_CTS GPIO_USART3_CTS_2 //PD11 +#define GPIO_USART3_RTS GPIO_USART3_RTS_2 //PD12 //CAN: -#define GPIO_CAN1_RX GPIO_CAN1_RX_2 //PB8 -#define GPIO_CAN1_TX GPIO_CAN1_TX_2 //PB9 +#define GPIO_CAN1_RX GPIO_CAN1_RX_2 //PB8 +#define GPIO_CAN1_TX GPIO_CAN1_TX_2 //PB9 //Ethernet: /* @@ -266,7 +266,7 @@ extern "C" { * ************************************************************************************/ -EXTERN void stm32_boardinitialize(void); +void stm32_boardinitialize(void); /************************************************************************************ * Name: stm32_ledinit, stm32_setled, and stm32_setleds diff --git a/nuttx/configs/olimex-stm32-p207/nsh/Make.defs b/nuttx/configs/olimex-stm32-p207/nsh/Make.defs index 341e3a146..65354b823 100644 --- a/nuttx/configs/olimex-stm32-p207/nsh/Make.defs +++ b/nuttx/configs/olimex-stm32-p207/nsh/Make.defs @@ -103,9 +103,7 @@ ifeq ($(CONFIG_DEBUG_SYMBOLS),y) LDFLAGS += -g endif - HOSTCC = gcc HOSTINCLUDES = -I. HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -g -pipe HOSTLDFLAGS = - diff --git a/nuttx/configs/olimex-stm32-p207/src/olimex-stm32-p207.h b/nuttx/configs/olimex-stm32-p207/src/olimex-stm32-p207.h new file mode 100644 index 000000000..4769fed3f --- /dev/null +++ b/nuttx/configs/olimex-stm32-p207/src/olimex-stm32-p207.h @@ -0,0 +1,171 @@ +/****************************************************************************** + * configs/olimex-stm32-p107/src/olimex-stm32-p207.h + * + * Copyright (C) 2013 Max Holtzberg. All rights reserved. + * Author: Max Holtzberg + * + * 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_OLIMEX_STM32_P207_SRC_INTERNAL_H +#define __CONFIGS_OLIMEX_STM32_P207_SRC_INTERNAL_H + +/****************************************************************************** + * Included Files + ******************************************************************************/ + +#include +#include +#include + +/****************************************************************************** + * Definitions + ******************************************************************************/ + +/* Olimex-STM32-P207 GPIOs ****************************************************/ +/* LEDs */ + +#define GPIO_LED1 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|\ + GPIO_OUTPUT_CLEAR|GPIO_PORTF|GPIO_PIN6) +#define GPIO_LED2 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|\ + GPIO_OUTPUT_CLEAR|GPIO_PORTF|GPIO_PIN7) +#define GPIO_LED3 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|\ + GPIO_OUTPUT_CLEAR|GPIO_PORTF|GPIO_PIN8) +#define GPIO_LED4 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|\ + GPIO_OUTPUT_CLEAR|GPIO_PORTF|GPIO_PIN9) + +/* BUTTONS -- NOTE that all have EXTI interrupts configured */ + +#define MIN_IRQBUTTON BUTTON_TAMPER +#define MAX_IRQBUTTON BUTTON_CENTER +#define NUM_IRQBUTTONS 7 + +#define GPIO_BTN_TAMPER (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTC|GPIO_PIN13) +#define GPIO_BTN_WKUP (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTA|GPIO_PIN0) +#define GPIO_BTN_RIGHT (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTG|GPIO_PIN6) +#define GPIO_BTN_UP (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTG|GPIO_PIN7) +#define GPIO_BTN_LEFT (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTG|GPIO_PIN11) +#define GPIO_BTN_DOWN (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTG|GPIO_PIN8) +#define GPIO_BTN_CENTER (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTG|GPIO_PIN15) + +/* USB OTG FS + * + * PA9 OTG_FS_VBUS VBUS sensing (also connected to the green LED) + * PC2 OTG_FS_PowerSwitchOn + * PB10 OTG_FS_Overcurrent + */ + +#define GPIO_OTGFS_VBUS (GPIO_INPUT|GPIO_FLOAT|GPIO_PORTA|GPIO_PIN9) +#define GPIO_OTGFS_PWRON (GPIO_OUTPUT|GPIO_FLOAT|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN2) + +#ifdef CONFIG_USBHOST +# define GPIO_OTGFS_OVER (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTB|GPIO_PIN10) + +#else +# define GPIO_OTGFS_OVER (GPIO_INPUT|GPIO_FLOAT|GPIO_PORTB|GPIO_PIN10) +#endif + +#ifndef __ASSEMBLY__ + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +/************************************************************************************ + * Name: stm32_usbinitialize + * + * Description: + * Called from stm32_usbinitialize very early in inialization to setup USB-related + * GPIO pins for the STM32F4Discovery board. + * + ************************************************************************************/ + +#ifdef CONFIG_STM32_OTGFS +void weak_function stm32_usbinitialize(void); +#endif + +/************************************************************************************ + * Name: stm32_usbhost_initialize + * + * Description: + * Called at application startup time to initialize the USB host functionality. + * This function will start a thread that will monitor for device connection/ + * disconnection events. + * + ************************************************************************************/ + +#if defined(CONFIG_STM32_OTGFS) && defined(CONFIG_USBHOST) +int stm32_usbhost_initialize(void); +#endif + +/************************************************************************************ + * Name: nsh_archinitialize + * + * Description: + * Perform architecture specific initialization for NSH. + * + * CONFIG_NSH_ARCHINIT=y : + * Called from the NSH library + * + * CONFIG_BOARD_INITIALIZE=y, CONFIG_NSH_LIBRARY=y, && + * CONFIG_NSH_ARCHINIT=n : + * Called from board_initialize(). + * + ************************************************************************************/ + +#ifdef CONFIG_NSH_LIBRARY +int nsh_archinitialize(void); +#endif + +/************************************************************************************ + * Name: stm32_adc_initialize + * + * Description: + * Called at application startup time to initialize the ADC functionality. + * + ************************************************************************************/ + +#ifdef CONFIG_ADC +int stm32_adc_initialize(void); +#endif + +/************************************************************************************ + * Name: stm32_can_initialize + * + * Description: + * Called at application startup time to initialize the CAN functionality. + * + ************************************************************************************/ + +#if defined(CONFIG_CAN) && (defined(CONFIG_STM32_CAN1) || defined(CONFIG_STM32_CAN2)) +int stm32_can_initialize(void); +#endif + +#endif /* __ASSEMBLY__ */ +#endif /* __CONFIGS_OLIMEX_STM32_P207_SRC_INTERNAL_H */ diff --git a/nuttx/configs/olimex-stm32-p207/src/p207-internal.h b/nuttx/configs/olimex-stm32-p207/src/p207-internal.h deleted file mode 100644 index ebfca8dd6..000000000 --- a/nuttx/configs/olimex-stm32-p207/src/p207-internal.h +++ /dev/null @@ -1,170 +0,0 @@ -/****************************************************************************** - * configs/olimex-stm32-p107/src/p207-internal.h - * - * Copyright (C) 2013 Max Holtzberg. All rights reserved. - * Author: Max Holtzberg - * - * 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_OLIMEX_STM32_P207_SRC_INTERNAL_H -#define __CONFIGS_OLIMEX_STM32_P207_SRC_INTERNAL_H - -/****************************************************************************** - * Included Files - ******************************************************************************/ - -#include -#include -#include - -/****************************************************************************** - * Definitions - ******************************************************************************/ - -/* Olimex-STM32-P207 GPIOs **************************************************************************/ -/* LEDs */ - -#define GPIO_LED1 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|\ - GPIO_OUTPUT_CLEAR|GPIO_PORTF|GPIO_PIN6) -#define GPIO_LED2 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|\ - GPIO_OUTPUT_CLEAR|GPIO_PORTF|GPIO_PIN7) -#define GPIO_LED3 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|\ - GPIO_OUTPUT_CLEAR|GPIO_PORTF|GPIO_PIN8) -#define GPIO_LED4 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|\ - GPIO_OUTPUT_CLEAR|GPIO_PORTF|GPIO_PIN9) - -/* BUTTONS -- NOTE that all have EXTI interrupts configured */ - -#define MIN_IRQBUTTON BUTTON_TAMPER -#define MAX_IRQBUTTON BUTTON_CENTER -#define NUM_IRQBUTTONS 7 - -#define GPIO_BTN_TAMPER (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTC|GPIO_PIN13) -#define GPIO_BTN_WKUP (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTA|GPIO_PIN0) -#define GPIO_BTN_RIGHT (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTG|GPIO_PIN6) -#define GPIO_BTN_UP (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTG|GPIO_PIN7) -#define GPIO_BTN_LEFT (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTG|GPIO_PIN11) -#define GPIO_BTN_DOWN (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTG|GPIO_PIN8) -#define GPIO_BTN_CENTER (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTG|GPIO_PIN15) - -/* USB OTG FS - * - * PA9 OTG_FS_VBUS VBUS sensing (also connected to the green LED) - * PC2 OTG_FS_PowerSwitchOn - * PB10 OTG_FS_Overcurrent - */ - -#define GPIO_OTGFS_VBUS (GPIO_INPUT|GPIO_FLOAT|GPIO_PORTA|GPIO_PIN9) -#define GPIO_OTGFS_PWRON (GPIO_OUTPUT|GPIO_FLOAT|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN2) - -#ifdef CONFIG_USBHOST -# define GPIO_OTGFS_OVER (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTB|GPIO_PIN10) - -#else -# define GPIO_OTGFS_OVER (GPIO_INPUT|GPIO_FLOAT|GPIO_PORTB|GPIO_PIN10) -#endif - -#ifndef __ASSEMBLY__ - -/************************************************************************************ - * Public Functions - ************************************************************************************/ - -/**************************************************************************************************** - * Name: stm32_usbinitialize - * - * Description: - * Called from stm32_usbinitialize very early in inialization to setup USB-related - * GPIO pins for the STM32F4Discovery board. - * - ****************************************************************************************************/ - -#ifdef CONFIG_STM32_OTGFS -void weak_function stm32_usbinitialize(void); -#endif - -/**************************************************************************************************** - * Name: stm32_usbhost_initialize - * - * Description: - * Called at application startup time to initialize the USB host functionality. This function will - * start a thread that will monitor for device connection/disconnection events. - * - ****************************************************************************************************/ - -#if defined(CONFIG_STM32_OTGFS) && defined(CONFIG_USBHOST) -int stm32_usbhost_initialize(void); -#endif - -/**************************************************************************** - * Name: nsh_archinitialize - * - * Description: - * Perform architecture specific initialization for NSH. - * - * CONFIG_NSH_ARCHINIT=y : - * Called from the NSH library - * - * CONFIG_BOARD_INITIALIZE=y, CONFIG_NSH_LIBRARY=y, && - * CONFIG_NSH_ARCHINIT=n : - * Called from board_initialize(). - * - ****************************************************************************/ - -#ifdef CONFIG_NSH_LIBRARY -int nsh_archinitialize(void); -#endif - - -/**************************************************************************************************** - * Name: stm32_adc_initialize - * - * Description: - * Called at application startup time to initialize the ADC functionality. - * - ****************************************************************************************************/ - -#ifdef CONFIG_ADC -int stm32_adc_initialize(void); -#endif - -/**************************************************************************************************** - * Name: stm32_can_initialize - * - * Description: - * Called at application startup time to initialize the CAN functionality. - * - ****************************************************************************************************/ - -#if defined(CONFIG_CAN) && (defined(CONFIG_STM32_CAN1) || defined(CONFIG_STM32_CAN2)) -int stm32_can_initialize(void); -#endif - -#endif /* __ASSEMBLY__ */ -#endif /* __CONFIGS_OLIMEX_STM32_P207_SRC_INTERNAL_H */ diff --git a/nuttx/configs/olimex-stm32-p207/src/up_adc.c b/nuttx/configs/olimex-stm32-p207/src/up_adc.c index 7121c00ab..3bde8bea6 100644 --- a/nuttx/configs/olimex-stm32-p207/src/up_adc.c +++ b/nuttx/configs/olimex-stm32-p207/src/up_adc.c @@ -46,7 +46,7 @@ #include #include "chip.h" #include "stm32_adc.h" -#include "p207-internal.h" +#include "olimex-stm32-p207.h" #ifdef CONFIG_ADC @@ -54,7 +54,7 @@ * Definitions ************************************************************************************/ -/* Configuration ************************************************************/ +/* Configuration ********************************************************************/ /* Up to 3 ADC interfaces are supported */ #if STM32_NADC < 3 @@ -81,7 +81,7 @@ /************************************************************************************ * Private Data ************************************************************************************/ -/* The Olimex STM32-P207 has a 10 Kohm potentiometer AN_TR connected to PC0 +/* The Olimex STM32-P207 has a 10 Kohm potentiometer AN_TR connected to PC0 * ADC123_IN10 */ @@ -117,13 +117,13 @@ int adc_devinit(void) return stm32_adc_initialize(); } -/**************************************************************************************************** +/************************************************************************************ * Name: stm32_adc_initialize * * Description: * Called at application startup time to initialize the ADC functionality. * - ****************************************************************************************************/ + ************************************************************************************/ int stm32_adc_initialize(void) { diff --git a/nuttx/configs/olimex-stm32-p207/src/up_autoleds.c b/nuttx/configs/olimex-stm32-p207/src/up_autoleds.c index 12a61e34f..a8128fdc2 100644 --- a/nuttx/configs/olimex-stm32-p207/src/up_autoleds.c +++ b/nuttx/configs/olimex-stm32-p207/src/up_autoleds.c @@ -45,7 +45,7 @@ #include #include #include "stm32.h" -#include "p207-internal.h" +#include "olimex-stm32-p207.h" #ifdef CONFIG_ARCH_LEDS diff --git a/nuttx/configs/olimex-stm32-p207/src/up_boot.c b/nuttx/configs/olimex-stm32-p207/src/up_boot.c index f9aaaa720..6f37eb090 100644 --- a/nuttx/configs/olimex-stm32-p207/src/up_boot.c +++ b/nuttx/configs/olimex-stm32-p207/src/up_boot.c @@ -42,7 +42,7 @@ #include #include #include -#include "p207-internal.h" +#include "olimex-stm32-p207.h" /************************************************************************************ * Definitions @@ -69,7 +69,7 @@ void stm32_boardinitialize(void) { /* Initialize USB if the 1) OTG FS controller is in the configuration and 2) - * disabled, and 3) the weak function stm32_usbinitialize() has been brought + * disabled, and 3) the weak function stm32_usbinitialize() has been brought * into the build. Presumeably either CONFIG_USBDEV or CONFIG_USBHOST is also * selected. */ @@ -86,13 +86,12 @@ void stm32_boardinitialize(void) #ifdef CONFIG_ARCH_LEDS up_ledinit(); #endif - + /* Configure on-board BUTTONs if BUTTON support has been selected. */ - + #ifdef CONFIG_ARCH_BUTTONS up_buttoninit(); #endif - } /**************************************************************************** @@ -119,7 +118,5 @@ void board_initialize(void) #if defined(CONFIG_NSH_LIBRARY) && !defined(CONFIG_NSH_ARCHINIT) nsh_archinitialize(); #endif - } #endif - diff --git a/nuttx/configs/olimex-stm32-p207/src/up_buttons.c b/nuttx/configs/olimex-stm32-p207/src/up_buttons.c index efce8f4ca..87e24f364 100644 --- a/nuttx/configs/olimex-stm32-p207/src/up_buttons.c +++ b/nuttx/configs/olimex-stm32-p207/src/up_buttons.c @@ -41,12 +41,12 @@ #include #include -#include "p207-internal.h" +#include "olimex-stm32-p207.h" #ifdef CONFIG_ARCH_BUTTONS /**************************************************************************** - * Definitions + * Pre-processor Definitions ****************************************************************************/ /**************************************************************************** @@ -91,7 +91,7 @@ void up_buttoninit(void) { int i; - /* Configure the GPIO pins as inputs. NOTE that EXTI interrupts are + /* Configure the GPIO pins as inputs. NOTE that EXTI interrupts are * configured for all pins. */ @@ -108,23 +108,44 @@ void up_buttoninit(void) uint8_t up_buttons(void) { uint8_t ret = 0; - + /* Check that state of each key */ - if(!stm32_gpioread(g_buttons[BUTTON_TAMPER])) - ret |= BUTTON_TAMPER_BIT; - if(stm32_gpioread(g_buttons[BUTTON_WKUP])) - ret |= BUTTON_WKUP_BIT; - if(stm32_gpioread(g_buttons[BUTTON_RIGHT])) - ret |= BUTTON_RIGHT_BIT; - if(stm32_gpioread(g_buttons[BUTTON_UP])) - ret |= BUTTON_UP_BIT; - if(stm32_gpioread(g_buttons[BUTTON_LEFT])) - ret |= BUTTON_LEFT_BIT; - if(stm32_gpioread(g_buttons[BUTTON_DOWN])) - ret |= BUTTON_DOWN_BIT; - if(stm32_gpioread(g_buttons[BUTTON_CENTER])) - ret |= BUTTON_CENTER_BIT; - + + if (!stm32_gpioread(g_buttons[BUTTON_TAMPER])) + { + ret |= BUTTON_TAMPER_BIT; + } + + if (stm32_gpioread(g_buttons[BUTTON_WKUP])) + { + ret |= BUTTON_WKUP_BIT; + } + + if (stm32_gpioread(g_buttons[BUTTON_RIGHT])) + { + ret |= BUTTON_RIGHT_BIT; + } + + if (stm32_gpioread(g_buttons[BUTTON_UP])) + { + ret |= BUTTON_UP_BIT; + } + + if (stm32_gpioread(g_buttons[BUTTON_LEFT])) + { + ret |= BUTTON_LEFT_BIT; + } + + if (stm32_gpioread(g_buttons[BUTTON_DOWN])) + { + ret |= BUTTON_DOWN_BIT; + } + + if (stm32_gpioread(g_buttons[BUTTON_CENTER])) + { + ret |= BUTTON_CENTER_BIT; + } + return ret; } @@ -162,6 +183,7 @@ xcpt_t up_irqbutton(int id, xcpt_t irqhandler) { oldhandler = stm32_gpiosetevent(g_buttons[id], true, true, true, irqhandler); } + return oldhandler; } #endif diff --git a/nuttx/configs/olimex-stm32-p207/src/up_can.c b/nuttx/configs/olimex-stm32-p207/src/up_can.c index 1ea62b811..8b2ca6d18 100644 --- a/nuttx/configs/olimex-stm32-p207/src/up_can.c +++ b/nuttx/configs/olimex-stm32-p207/src/up_can.c @@ -46,7 +46,7 @@ #include #include "stm32.h" #include "stm32_can.h" -#include "p207-internal.h" +#include "olimex-stm32-p207.h" #if defined(CONFIG_CAN) && (defined(CONFIG_STM32_CAN1) || defined(CONFIG_STM32_CAN2)) diff --git a/nuttx/configs/olimex-stm32-p207/src/up_cxxinitialize.c b/nuttx/configs/olimex-stm32-p207/src/up_cxxinitialize.c index 422ae3259..3291cdcdb 100644 --- a/nuttx/configs/olimex-stm32-p207/src/up_cxxinitialize.c +++ b/nuttx/configs/olimex-stm32-p207/src/up_cxxinitialize.c @@ -152,4 +152,3 @@ void up_cxxinitialize(void) } #endif /* CONFIG_HAVE_CXX && CONFIG_HAVE_CXXINITIALIZE */ - diff --git a/nuttx/configs/olimex-stm32-p207/src/up_nsh.c b/nuttx/configs/olimex-stm32-p207/src/up_nsh.c index 84b3022c0..49f481c15 100644 --- a/nuttx/configs/olimex-stm32-p207/src/up_nsh.c +++ b/nuttx/configs/olimex-stm32-p207/src/up_nsh.c @@ -54,7 +54,7 @@ #endif #include "stm32.h" -#include "p207-internal.h" +#include "olimex-stm32-p207.h" /**************************************************************************** * Pre-Processor Definitions @@ -133,20 +133,20 @@ int nsh_archinitialize(void) #if defined(HAVE_USBHOST) || defined(HAVE_USBMONITOR) || defined(CONFIG_ADC) int ret; #endif - + #if defined(CONFIG_CAN) && (defined(CONFIG_STM32_CAN1) || defined(CONFIG_STM32_CAN2)) /* Configure on-board CAN if CAN support has been selected. */ - + ret = stm32_can_initialize(); if (ret != OK) { message("nsh_archinitialize: Failed to initialize CAN: %d\n", ret); } #endif - + #ifdef CONFIG_ADC /* Configure on-board ADCs if ADC support has been selected. */ - + ret = stm32_adc_initialize(); if (ret != OK) { diff --git a/nuttx/configs/olimex-stm32-p207/src/up_usb.c b/nuttx/configs/olimex-stm32-p207/src/up_usb.c index 52bb7adef..60d6f72f7 100644 --- a/nuttx/configs/olimex-stm32-p207/src/up_usb.c +++ b/nuttx/configs/olimex-stm32-p207/src/up_usb.c @@ -51,7 +51,7 @@ #include #include "stm32.h" #include "stm32_otgfs.h" -#include "p207-internal.h" +#include "olimex-stm32-p207.h" #ifdef CONFIG_STM32_OTGFS @@ -229,14 +229,14 @@ xcpt_t stm32_setup_overcurrent(xcpt_t handler) * Enable/disable driving of VBUS 5V output. This function must be provided be * each platform that implements the STM32 OTG FS host interface * - * "On-chip 5 V VBUS generation is not supported. For this reason, a charge pump - * or, if 5 V are available on the application board, a basic power switch, must - * be added externally to drive the 5 V VBUS line. The external charge pump can - * be driven by any GPIO output. When the application decides to power on VBUS - * using the chosen GPIO, it must also set the port power bit in the host port + * "On-chip 5 V VBUS generation is not supported. For this reason, a charge pump + * or, if 5 V are available on the application board, a basic power switch, must + * be added externally to drive the 5 V VBUS line. The external charge pump can + * be driven by any GPIO output. When the application decides to power on VBUS + * using the chosen GPIO, it must also set the port power bit in the host port * control and status register (PPWR bit in OTG_FS_HPRT). * - * "The application uses this field to control power to this port, and the core + * "The application uses this field to control power to this port, and the core * clears this bit on an overcurrent condition." * * Input Parameters: @@ -252,7 +252,7 @@ xcpt_t stm32_setup_overcurrent(xcpt_t handler) void stm32_usbhost_vbusdrive(int iface, bool enable) { DEBUGASSERT(iface == 0); - + if (enable) { /* Enable the Power Switch by driving the enable pin low */ @@ -260,9 +260,9 @@ void stm32_usbhost_vbusdrive(int iface, bool enable) stm32_gpiowrite(GPIO_OTGFS_PWRON, false); } else - { + { /* Disable the Power Switch by driving the enable pin high */ - + stm32_gpiowrite(GPIO_OTGFS_PWRON, true); } } @@ -287,6 +287,3 @@ void stm32_usbsuspend(FAR struct usbdev_s *dev, bool resume) #endif #endif /* CONFIG_STM32_OTGFS */ - - - diff --git a/nuttx/configs/olimex-stm32-p207/src/up_userleds.c b/nuttx/configs/olimex-stm32-p207/src/up_userleds.c index dbce9357f..518a1e1f7 100644 --- a/nuttx/configs/olimex-stm32-p207/src/up_userleds.c +++ b/nuttx/configs/olimex-stm32-p207/src/up_userleds.c @@ -45,7 +45,7 @@ #include #include #include "stm32.h" -#include "p207-internal.h" +#include "olimex-stm32-p207.h" #ifndef CONFIG_ARCH_LEDS @@ -70,7 +70,7 @@ ****************************************************************************/ /* This array maps an LED number to GPIO pin configuration */ -static uint32_t g_ledcfg[BOARD_NLEDS] = +static uint32_t g_ledcfg[BOARD_NLEDS] = { GPIO_LED1, GPIO_LED2, GPIO_LED3, GPIO_LED4 }; @@ -79,17 +79,14 @@ static uint32_t g_ledcfg[BOARD_NLEDS] = * Private Function Protototypes ****************************************************************************/ - /**************************************************************************** * Private Data ****************************************************************************/ - /**************************************************************************** * Private Functions ****************************************************************************/ - /**************************************************************************** * Public Functions ****************************************************************************/ -- cgit v1.2.3