From 74a16b2ced4a5884d45b9b6d756a690ce1d8c6c0 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Tue, 30 Apr 2013 18:28:10 -0600 Subject: Add support for the MikroElektronika Mikromedia for STM32F4 development board. From Ken Petit --- nuttx/configs/mikroe-stm32f4/src/Makefile | 140 ++ .../mikroe-stm32f4/src/mikroe-stm32f4-internal.h | 170 +++ nuttx/configs/mikroe-stm32f4/src/up_boot.c | 98 ++ nuttx/configs/mikroe-stm32f4/src/up_clockconfig.c | 151 ++ .../configs/mikroe-stm32f4/src/up_cxxinitialize.c | 155 +++ nuttx/configs/mikroe-stm32f4/src/up_extmem.c | 188 +++ nuttx/configs/mikroe-stm32f4/src/up_idle.c | 277 ++++ nuttx/configs/mikroe-stm32f4/src/up_mio283qt2.c | 553 ++++++++ nuttx/configs/mikroe-stm32f4/src/up_nsh.c | 286 ++++ nuttx/configs/mikroe-stm32f4/src/up_pm.c | 107 ++ nuttx/configs/mikroe-stm32f4/src/up_pwm.c | 142 ++ nuttx/configs/mikroe-stm32f4/src/up_qencoder.c | 187 +++ nuttx/configs/mikroe-stm32f4/src/up_spi.c | 279 ++++ nuttx/configs/mikroe-stm32f4/src/up_touchscreen.c | 1462 ++++++++++++++++++++ nuttx/configs/mikroe-stm32f4/src/up_usb.c | 294 ++++ nuttx/configs/mikroe-stm32f4/src/up_watchdog.c | 136 ++ 16 files changed, 4625 insertions(+) create mode 100644 nuttx/configs/mikroe-stm32f4/src/Makefile create mode 100644 nuttx/configs/mikroe-stm32f4/src/mikroe-stm32f4-internal.h create mode 100644 nuttx/configs/mikroe-stm32f4/src/up_boot.c create mode 100644 nuttx/configs/mikroe-stm32f4/src/up_clockconfig.c create mode 100644 nuttx/configs/mikroe-stm32f4/src/up_cxxinitialize.c create mode 100644 nuttx/configs/mikroe-stm32f4/src/up_extmem.c create mode 100644 nuttx/configs/mikroe-stm32f4/src/up_idle.c create mode 100644 nuttx/configs/mikroe-stm32f4/src/up_mio283qt2.c create mode 100644 nuttx/configs/mikroe-stm32f4/src/up_nsh.c create mode 100644 nuttx/configs/mikroe-stm32f4/src/up_pm.c create mode 100644 nuttx/configs/mikroe-stm32f4/src/up_pwm.c create mode 100644 nuttx/configs/mikroe-stm32f4/src/up_qencoder.c create mode 100644 nuttx/configs/mikroe-stm32f4/src/up_spi.c create mode 100644 nuttx/configs/mikroe-stm32f4/src/up_touchscreen.c create mode 100644 nuttx/configs/mikroe-stm32f4/src/up_usb.c create mode 100644 nuttx/configs/mikroe-stm32f4/src/up_watchdog.c (limited to 'nuttx/configs/mikroe-stm32f4/src') diff --git a/nuttx/configs/mikroe-stm32f4/src/Makefile b/nuttx/configs/mikroe-stm32f4/src/Makefile new file mode 100644 index 000000000..1164a1850 --- /dev/null +++ b/nuttx/configs/mikroe-stm32f4/src/Makefile @@ -0,0 +1,140 @@ +############################################################################ +# configs/mikroe-stm32f4/src/Makefile +# +# Copyright (C) 2011-2012 Gregory Nutt. All rights reserved. +# Author: Gregory Nutt +# +# Updates: 04/15/2013 - Ken Pettit +# - Modifications for port to Mikroe for STM32F4 +# - Added support for LCD, Serial Flash, SD Card +# +# 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_HAVE_CXX),y) +CSRCS += up_cxxinitialize.c +endif + +ifeq ($(CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG),y) +CSRCS += up_clockconfig.c +endif + +ifeq ($(CONFIG_STM32_OTGFS),y) +CSRCS += up_usb.c +endif + +ifeq ($(CONFIG_PWM),y) +CSRCS += up_pwm.c +endif + +ifeq ($(CONFIG_QENCODER),y) +CSRCS += up_qencoder.c +endif + +ifeq ($(CONFIG_WATCHDOG),y) +CSRCS += up_watchdog.c +endif + +ifeq ($(CONFIG_NSH_ARCHINIT),y) +CSRCS += up_nsh.c +endif + +ifeq ($(CONFIG_PM_CUSTOMINIT),y) +CSRCS += up_pm.c +endif + +ifeq ($(CONFIG_IDLE_CUSTOM),y) +CSRCS += up_idle.c +endif + +ifeq ($(CONFIG_STM32_FSMC),y) +CSRCS += up_extmem.c +endif + +ifeq ($(CONFIG_INPUT),y) +CSRCS += up_touchscreen.c +endif + +ifeq ($(ARCH_CONFIG_LCD_MIO283QT2),y) +CSRCS += up_mio283qt2.c +endif + +COBJS = $(CSRCS:.c=$(OBJEXT)) + +SRCS = $(ASRCS) $(CSRCS) +OBJS = $(AOBJS) $(COBJS) + +ARCH_SRCDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src +ifeq ($(CONFIG_WINDOWS_NATIVE),y) + CFLAGS += -I$(ARCH_SRCDIR)\chip -I$(ARCH_SRCDIR)\common -I$(ARCH_SRCDIR)\armv7-m +else +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 +endif + +all: libboard$(LIBEXT) + +$(AOBJS): %$(OBJEXT): %.S + $(call ASSEMBLE, $<, $@) + +$(COBJS) $(LINKOBJS): %$(OBJEXT): %.c + $(call COMPILE, $<, $@) + +libboard$(LIBEXT): $(OBJS) + $(call ARCHIVE, $@, $(OBJS)) + +.depend: Makefile $(SRCS) + $(Q) $(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ + +depend: .depend + +clean: + $(call DELFILE, libboard$(LIBEXT)) + $(call CLEAN) + +distclean: clean + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) + +-include Make.dep diff --git a/nuttx/configs/mikroe-stm32f4/src/mikroe-stm32f4-internal.h b/nuttx/configs/mikroe-stm32f4/src/mikroe-stm32f4-internal.h new file mode 100644 index 000000000..a43d52d51 --- /dev/null +++ b/nuttx/configs/mikroe-stm32f4/src/mikroe-stm32f4-internal.h @@ -0,0 +1,170 @@ +/**************************************************************************************************** + * configs/mikroe-stm32f4/src/mikroe-stm32f4-internal.h + * arch/arm/src/board/mikroe-stm32f4-internal.n + * + * Copyright (C) 2011-2012 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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_MIKROE_STM32F4_SRC_MIKROE_STM32F4_INTERNAL_H +#define __CONFIGS_MIKROE_STM32F4_SRC_MIKROE_STM32F4_INTERNAL_H + +/**************************************************************************************************** + * Included Files + ****************************************************************************************************/ + +#include +#include +#include + +/**************************************************************************************************** + * 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 + +/* Mikroe STM32F4 GPIOs **************************************************************************/ +/* LEDs - There are no user LEDs on this board unless you add some manually. */ + +#define GPIO_LED1 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|\ + GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN12) + +/* BUTTONS -- NOTE that all have EXTI interrupts configured */ +/* There are no user buttons on this board unless you add some externally. */ + +#define MIN_IRQBUTTON BUTTON_USER +#define MAX_IRQBUTTON BUTTON_USER +#define NUM_IRQBUTTONS 1 + +#define GPIO_BTN_USER (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTA|GPIO_PIN0) + +/* PWM + * + * The Mikroe-STM32F4 has no real on-board PWM devices, but the board can be + * configured to output a pulse train using TIM4 CH2 on PD13. + */ + +#define STM32F4DISCOVERY_PWMTIMER 4 +#define STM32F4DISCOVERY_PWMCHANNEL 2 + +/* SPI chip selects */ + +#define GPIO_CS_MMCSD (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|\ + GPIO_OUTPUT_SET|GPIO_PORTD|GPIO_PIN3) +#define GPIO_CS_FLASH (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|\ + GPIO_OUTPUT_SET|GPIO_PORTD|GPIO_PIN7) +#define GPIO_CS_MP3 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|\ + GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN8) +#define GPIO_CS_EXP_SPI3 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|\ + GPIO_OUTPUT_SET|GPIO_PORTD|GPIO_PIN0) +#define GPIO_SD_CD (GPIO_INPUT|GPIO_PORTD|GPIO_PIN15) + +/* USB OTG FS + * + * PA9 OTG_FS_VBUS VBUS sensing (also connected to the green LED) + * PC0 OTG_FS_PowerSwitchOn + * PD5 OTG_FS_Overcurrent + */ + +#define GPIO_OTGFS_VBUS (GPIO_INPUT|GPIO_FLOAT|GPIO_SPEED_100MHz|GPIO_OPENDRAIN|GPIO_PORTA|GPIO_PIN9) +#define GPIO_OTGFS_PWRON (GPIO_OUTPUT|GPIO_FLOAT|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN0) + +#ifdef CONFIG_USBHOST +# define GPIO_OTGFS_OVER (GPIO_INPUT|GPIO_EXTI|GPIO_FLOAT|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTD|GPIO_PIN5) + +#else +# define GPIO_OTGFS_OVER (GPIO_INPUT|GPIO_FLOAT|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTD|GPIO_PIN5) +#endif + +/**************************************************************************************************** + * Public Types + ****************************************************************************************************/ + +/**************************************************************************************************** + * Public data + ****************************************************************************************************/ + +#ifndef __ASSEMBLY__ + +/**************************************************************************************************** + * Public Functions + ****************************************************************************************************/ + +/**************************************************************************************************** + * Name: stm32_spiinitialize + * + * Description: + * Called to configure SPI chip select GPIO pins for the mikroe-stm32f4 board. + * + ****************************************************************************************************/ + +void weak_function stm32_spiinitialize(void); + +/**************************************************************************************************** + * Name: stm32_usbinitialize + * + * Description: + * Called from stm32_usbinitialize very early in inialization to setup USB-related + * GPIO pins for the Mikroe-stm32f4 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) +#error "The Mikroe-STM32F4 board does not support HOST OTG, only device!" +#endif + +#endif /* __ASSEMBLY__ */ +#endif /* __CONFIGS_MIKROE_STM32F4_SRC_MIKROE_STM32F4_INTERNAL_H */ + diff --git a/nuttx/configs/mikroe-stm32f4/src/up_boot.c b/nuttx/configs/mikroe-stm32f4/src/up_boot.c new file mode 100644 index 000000000..1c7cd5b80 --- /dev/null +++ b/nuttx/configs/mikroe-stm32f4/src/up_boot.c @@ -0,0 +1,98 @@ +/************************************************************************************ + * configs/mikroe_stm32f4/src/up_boot.c + * arch/arm/src/board/up_boot.c + * + * Copyright (C) 2011-2012 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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 + +#include + +#include + +#include "up_arch.h" +#include "mikroe-stm32f4-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 + + /* 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 + * into the build. Presumeably either CONFIG_USBDEV or CONFIG_USBHOST is also + * selected. + */ + +#ifdef CONFIG_STM32_OTGFS + if (stm32_usbinitialize) + { + stm32_usbinitialize(); + } +#endif + +} diff --git a/nuttx/configs/mikroe-stm32f4/src/up_clockconfig.c b/nuttx/configs/mikroe-stm32f4/src/up_clockconfig.c new file mode 100644 index 000000000..8b4af3181 --- /dev/null +++ b/nuttx/configs/mikroe-stm32f4/src/up_clockconfig.c @@ -0,0 +1,151 @@ +/************************************************************************************ + * configs/mikroe_stm32f4/src/up_clockconfig.c + * + * Copyright (C) 2011-2012 Gregory Nutt. All rights reserved. + * Author: Ken Pettit + * + * 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 + +#include + +#include + +#include "up_arch.h" +#include "mikroe-stm32f4-internal.h" + +/************************************************************************************ + * Definitions + ************************************************************************************/ + +/************************************************************************************ + * Private Functions + ************************************************************************************/ + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +/************************************************************************************ + * Name: stm32_board_clockconfig + * + * Description: + * The Mikroe-STM32F4 board does not have an external crystal, so it must rely + * on the internal 16Mhz RC oscillator. The default clock configuration in the + * OS for the STM32 architecture assumes an external crystal, so we must provide + * a board specific clock configuration routine. + * + ************************************************************************************/ + +#if defined(CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG) +void stm32_board_clockconfig(void) +{ + uint32_t regval; + + /* Configure chip clocking to use the internal 16Mhz RC oscillator. + + NOTE: We will assume the HSIRDY (High Speed Internal RC Ready) bit is + set, otherwise we wouldn't be here executing code. + */ + + 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_HSI | STM32_PLLCFG_PLLQ); + 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 */ + +#ifdef STM32_FLASH_PREFETCH + regval = (FLASH_ACR_LATENCY_5 | FLASH_ACR_ICEN | FLASH_ACR_DCEN | FLASH_ACR_PRFTEN); +#else + regval = (FLASH_ACR_LATENCY_5 | FLASH_ACR_ICEN | FLASH_ACR_DCEN); +#endif + 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 +} diff --git a/nuttx/configs/mikroe-stm32f4/src/up_cxxinitialize.c b/nuttx/configs/mikroe-stm32f4/src/up_cxxinitialize.c new file mode 100644 index 000000000..590b641ac --- /dev/null +++ b/nuttx/configs/mikroe-stm32f4/src/up_cxxinitialize.c @@ -0,0 +1,155 @@ +/************************************************************************************ + * configs/mikroe_stm32f4/src/up_cxxinitialize.c + * arch/arm/src/board/up_cxxinitialize.c + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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 + +#include + +#include + +#include +#include "chip.h" + +#if defined(CONFIG_HAVE_CXX) && defined(CONFIG_HAVE_CXXINITIALIZE) + +/************************************************************************************ + * Definitions + ************************************************************************************/ +/* Debug ****************************************************************************/ +/* Non-standard debug that may be enabled just for testing the static constructors */ + +#ifndef CONFIG_DEBUG +# undef CONFIG_DEBUG_CXX +#endif + +#ifdef CONFIG_DEBUG_CXX +# define cxxdbg dbg +# define cxxlldbg lldbg +# ifdef CONFIG_DEBUG_VERBOSE +# define cxxvdbg vdbg +# define cxxllvdbg llvdbg +# else +# define cxxvdbg(x...) +# define cxxllvdbg(x...) +# endif +#else +# define cxxdbg(x...) +# define cxxlldbg(x...) +# define cxxvdbg(x...) +# define cxxllvdbg(x...) +#endif + +/************************************************************************************ + * Private Types + ************************************************************************************/ +/* This type defines one entry in initialization array */ + +typedef void (*initializer_t)(void); + +/************************************************************************************ + * External references + ************************************************************************************/ +/* _sinit and _einit are symbols exported by the linker script that mark the + * beginning and the end of the C++ initialization section. + */ + +extern initializer_t _sinit; +extern initializer_t _einit; + +/* _stext and _etext are symbols exported by the linker script that mark the + * beginning and the end of text. + */ + +extern uint32_t _stext; +extern uint32_t _etext; + +/************************************************************************************ + * Private Functions + ************************************************************************************/ + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +/**************************************************************************** + * Name: up_cxxinitialize + * + * Description: + * If C++ and C++ static constructors are supported, then this function + * must be provided by board-specific logic in order to perform + * initialization of the static C++ class instances. + * + * This function should then be called in the application-specific + * user_start logic in order to perform the C++ initialization. NOTE + * that no component of the core NuttX RTOS logic is involved; This + * function defintion only provides the 'contract' between application + * specific C++ code and platform-specific toolchain support + * + ***************************************************************************/ + +void up_cxxinitialize(void) +{ + initializer_t *initp; + + cxxdbg("_sinit: %p _einit: %p _stext: %p _etext: %p\n", + &_sinit, &_einit, &_stext, &_etext); + + /* Visit each entry in the initialzation table */ + + for (initp = &_sinit; initp != &_einit; initp++) + { + initializer_t initializer = *initp; + cxxdbg("initp: %p initializer: %p\n", initp, initializer); + + /* Make sure that the address is non-NULL and lies in the text region + * defined by the linker script. Some toolchains may put NULL values + * or counts in the initialization table + */ + + if ((void*)initializer > (void*)&_stext && (void*)initializer < (void*)&_etext) + { + cxxdbg("Calling %p\n", initializer); + initializer(); + } + } +} + +#endif /* CONFIG_HAVE_CXX && CONFIG_HAVE_CXXINITIALIZE */ + diff --git a/nuttx/configs/mikroe-stm32f4/src/up_extmem.c b/nuttx/configs/mikroe-stm32f4/src/up_extmem.c new file mode 100644 index 000000000..162ffb825 --- /dev/null +++ b/nuttx/configs/mikroe-stm32f4/src/up_extmem.c @@ -0,0 +1,188 @@ +/************************************************************************************ + * configs/stm32f4disovery/src/up_extmem.c + * arch/arm/src/board/up_extmem.c + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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 + +#include +#include +#include + +#include + +#include "chip.h" +#include "up_arch.h" + +#include "stm32_fsmc.h" +#include "stm32_gpio.h" +#include "stm32.h" +#include "mikroe-stm32f4-internal.h" + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +#ifndef CONFIG_STM32_FSMC +# warning "FSMC is not enabled" +#endif + +#if STM32_NGPIO_PORTS < 6 +# error "Required GPIO ports not enabled" +#endif + +#define STM32_FSMC_NADDRCONFIGS 26 +#define STM32_FSMC_NDATACONFIGS 16 + +/************************************************************************************ + * Public Data + ************************************************************************************/ + +/* GPIO configurations common to most external memories */ + +static const uint32_t g_addressconfig[STM32_FSMC_NADDRCONFIGS] = +{ + GPIO_FSMC_A0, GPIO_FSMC_A1 , GPIO_FSMC_A2, GPIO_FSMC_A3, GPIO_FSMC_A4 , GPIO_FSMC_A5, + GPIO_FSMC_A6, GPIO_FSMC_A7, GPIO_FSMC_A8, GPIO_FSMC_A9, GPIO_FSMC_A10, GPIO_FSMC_A11, + GPIO_FSMC_A12, GPIO_FSMC_A13, GPIO_FSMC_A14, GPIO_FSMC_A15, GPIO_FSMC_A16, GPIO_FSMC_A17, + GPIO_FSMC_A18, GPIO_FSMC_A19, GPIO_FSMC_A20, GPIO_FSMC_A21, GPIO_FSMC_A22, GPIO_FSMC_A23, + GPIO_FSMC_A24, GPIO_FSMC_A25 +}; + +static const uint32_t g_dataconfig[STM32_FSMC_NDATACONFIGS] = +{ + GPIO_FSMC_D0, GPIO_FSMC_D1 , GPIO_FSMC_D2, GPIO_FSMC_D3, GPIO_FSMC_D4 , GPIO_FSMC_D5, + GPIO_FSMC_D6, GPIO_FSMC_D7, GPIO_FSMC_D8, GPIO_FSMC_D9, GPIO_FSMC_D10, GPIO_FSMC_D11, + GPIO_FSMC_D12, GPIO_FSMC_D13, GPIO_FSMC_D14, GPIO_FSMC_D15 +}; + +/************************************************************************************ + * Private Data + ************************************************************************************/ + +/************************************************************************************ + * Private Functions + ************************************************************************************/ + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +/************************************************************************************ + * Name: stm32_extmemgpios + * + * Description: + * Initialize GPIOs for external memory usage + * + ************************************************************************************/ + +void stm32_extmemgpios(const uint32_t *gpios, int ngpios) +{ + int i; + + /* Configure GPIOs */ + + for (i = 0; i < ngpios; i++) + { + stm32_configgpio(gpios[i]); + } +} + +/************************************************************************************ + * Name: stm32_extmemaddr + * + * Description: + * Initialize adress line GPIOs for external memory access + * + ************************************************************************************/ + +void stm32_extmemaddr(int naddrs) +{ + stm32_extmemgpios(g_addressconfig, naddrs); +} + +/************************************************************************************ + * Name: stm32_extmemdata + * + * Description: + * Initialize data line GPIOs for external memory access + * + ************************************************************************************/ + +void stm32_extmemdata(int ndata) +{ + stm32_extmemgpios(g_dataconfig, ndata); +} + +/************************************************************************************ + * Name: stm32_enablefsmc + * + * Description: + * enable clocking to the FSMC module + * + ************************************************************************************/ + +void stm32_enablefsmc(void) +{ + uint32_t regval; + + /* Enable AHB clocking to the FSMC */ + + regval = getreg32( STM32_RCC_AHB3ENR); + regval |= RCC_AHB3ENR_FSMCEN; + putreg32(regval, STM32_RCC_AHB3ENR); +} + +/************************************************************************************ + * Name: stm32_disablefsmc + * + * Description: + * enable clocking to the FSMC module + * + ************************************************************************************/ + +void stm32_disablefsmc(void) +{ + uint32_t regval; + + /* Disable AHB clocking to the FSMC */ + + regval = getreg32(STM32_RCC_AHB3ENR); + regval &= ~RCC_AHB3ENR_FSMCEN; + putreg32(regval, STM32_RCC_AHB3ENR); +} diff --git a/nuttx/configs/mikroe-stm32f4/src/up_idle.c b/nuttx/configs/mikroe-stm32f4/src/up_idle.c new file mode 100644 index 000000000..915180638 --- /dev/null +++ b/nuttx/configs/mikroe-stm32f4/src/up_idle.c @@ -0,0 +1,277 @@ +/**************************************************************************** + * configs/mikroe_stm32f4/src/up_idle.c + * arch/arm/src/board/up_idle.c + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Authors: Gregory Nutt + * Diego Sanchez + * + * 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 +#include + +#include +#include +#include + +#include +#include +#include + +#include "up_internal.h" +#include "stm32_pm.h" +#include "stm32_rcc.h" +#include "stm32_exti.h" + +#include "mikroe-stm32f4-internal.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ +/* Configuration ************************************************************/ +/* Does the board support an IDLE LED to indicate that the board is in the + * IDLE state? + */ + +#if defined(CONFIG_ARCH_LEDS) && defined(LED_IDLE) +# define BEGIN_IDLE() up_ledon(LED_IDLE) +# define END_IDLE() up_ledoff(LED_IDLE) +#else +# define BEGIN_IDLE() +# define END_IDLE() +#endif + +/* Values for the RTC Alarm to wake up from the PM_STANDBY mode */ + +#ifndef CONFIG_PM_ALARM_SEC +# define CONFIG_PM_ALARM_SEC 3 +#endif + +#ifndef CONFIG_PM_ALARM_NSEC +# define CONFIG_PM_ALARM_NSEC 0 +#endif + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +#if defined(CONFIG_PM) && defined(CONFIG_RTC_ALARM) +static void up_alarmcb(void); +#endif + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: up_idlepm + * + * Description: + * Perform IDLE state power management. + * + ****************************************************************************/ + +#ifdef CONFIG_PM +static void up_idlepm(void) +{ +#ifdef CONFIG_RTC_ALARM + struct timespec alarmtime; +#endif + static enum pm_state_e oldstate = PM_NORMAL; + enum pm_state_e newstate; + irqstate_t flags; + int ret; + + /* Decide, which power saving level can be obtained */ + + newstate = pm_checkstate(); + + /* Check for state changes */ + + if (newstate != oldstate) + { + lldbg("newstate= %d oldstate=%d\n", newstate, oldstate); + + flags = irqsave(); + + /* Force the global state change */ + + ret = pm_changestate(newstate); + if (ret < 0) + { + /* The new state change failed, revert to the preceding state */ + + (void)pm_changestate(oldstate); + + /* No state change... */ + + goto errout; + } + + /* Then perform board-specific, state-dependent logic here */ + + switch (newstate) + { + case PM_NORMAL: + { + } + break; + + case PM_IDLE: + { + } + break; + + case PM_STANDBY: + { +#ifdef CONFIG_RTC_ALARM + /* Disable RTC Alarm interrupt */ + +#warning "missing logic" + + /* Configure the RTC alarm to Auto Wake the system */ + +#warning "missing logic" + + /* The tv_nsec value must not exceed 1,000,000,000. That + * would be an invalid time. + */ + +#warning "missing logic" + + /* Set the alarm */ + +#warning "missing logic" +#endif + /* Call the STM32 stop mode */ + + stm32_pmstop(true); + + /* We have been re-awakened by some even: A button press? + * An alarm? Cancel any pending alarm and resume the normal + * operation. + */ + +#ifdef CONFIG_RTC_ALARM +#warning "missing logic" +#endif + /* Resume normal operation */ + + pm_changestate(PM_NORMAL); + newstate = PM_NORMAL; + } + break; + + case PM_SLEEP: + { + /* We should not return from standby mode. The only way out + * of standby is via the reset path. + */ + + (void)stm32_pmstandby(); + } + break; + + default: + break; + } + + /* Save the new state */ + + oldstate = newstate; + +errout: + irqrestore(flags); + } +} +#else +# define up_idlepm() +#endif + +/************************************************************************************ + * Name: up_alarmcb + * + * Description: + * RTC alarm service routine + * + ************************************************************************************/ + +#if defined(CONFIG_PM) && defined(CONFIG_RTC_ALARM) +static void up_alarmcb(void) +{ + /* This alarm occurs because there wasn't any EXTI interrupt during the + * PM_STANDBY period. So just go to sleep. + */ + + pm_changestate(PM_SLEEP); +} +#endif + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: up_idle + * + * Description: + * up_idle() is the logic that will be executed when their is no other + * ready-to-run task. This is processor idle time and will continue until + * some interrupt occurs to cause a context switch from the idle task. + * + * Processing in this state may be processor-specific. e.g., this is where + * power management operations might be performed. + * + ****************************************************************************/ + +void up_idle(void) +{ +#if defined(CONFIG_SUPPRESS_INTERRUPTS) || defined(CONFIG_SUPPRESS_TIMER_INTS) + /* If the system is idle and there are no timer interrupts, then process + * "fake" timer interrupts. Hopefully, something will wake up. + */ + + sched_process_timer(); +#else + + /* Perform IDLE mode power management */ + + BEGIN_IDLE(); + up_idlepm(); + END_IDLE(); +#endif +} + diff --git a/nuttx/configs/mikroe-stm32f4/src/up_mio283qt2.c b/nuttx/configs/mikroe-stm32f4/src/up_mio283qt2.c new file mode 100644 index 000000000..3071a4245 --- /dev/null +++ b/nuttx/configs/mikroe-stm32f4/src/up_mio283qt2.c @@ -0,0 +1,553 @@ +/************************************************************************************** + * configs/mikroe-stm32f4/src/up_mio283qt2.c + * arch/arm/src/board/up_mio283qt2.c + * + * Interface definition for the MI0283QT-2 LCD from Multi-Inno Technology Co., Ltd. + * This LCD is based on the Himax HX8347-D LCD controller. + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Authors: Gregory Nutt + * + * 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 + +#include +#include +#include +#include +#include + +#include +#include +#include + +#include + +#include "up_arch.h" +#include "stm32.h" +#include "mikroe-stm32f4-internal.h" + +#ifdef CONFIG_LCD_MIO283QT2 + +/************************************************************************************** + * Pre-processor Definitions + **************************************************************************************/ +/* Configuration **********************************************************************/ + +#ifndef CONFIG_PIC32MX_PMP +# error "CONFIG_PIC32MX_PMP is required to use the LCD" +#endif + +/* Define CONFIG_DEBUG_LCD to enable detailed LCD debug output. Verbose debug must + * also be enabled. + */ + +#ifndef CONFIG_DEBUG +# undef CONFIG_DEBUG_VERBOSE +# undef CONFIG_DEBUG_GRAPHICS +# undef CONFIG_DEBUG_LCD +#endif + +#ifndef CONFIG_DEBUG_VERBOSE +# undef CONFIG_DEBUG_LCD +#endif + +/* PIC32MX7MMB LCD Hardware Definitions ***********************************************/ +/* --- ---------------------------------- -------------------- ------------------------ + * PIN CONFIGURATIONS SIGNAL NAME ON-BOARD CONNECTIONS + * (Family Data Sheet Table 1-1) (PIC32MX7 Schematic) + * --- ---------------------------------- -------------------- ------------------------ + * 6 RC1/T2CK LCD_RST TFT display + * 43 PMA1/AETXD3/AN14/ERXD2/PMALH/RB14 LCD-CS# TFT display, HDR2 pin 3 + * 77 OC3/RD2 LCD_BLED LCD backlight LED + * 44 PMA0/AETXD2/AN15/CN12/ERXD3/OCFB/ LCD-RS TFT display + * PMALL/RB15 + * + * 34 PMA13/AN10/RB10/CVREFOUT LCD-YD TFT display + * 35 PMA12/AETXERR/AN11/ERXERR/RB11 LCD-XR TFT display + * 41 PMA11/AECRS/AN12/ERXD0/RB12 LCD-YU TFT display + * 42 PMA10/AECOL/AN13/ERXD1/RB13 LCD-XL TFT display + * + * 93 PMD0/RE0 PMPD0 TFT display, HDR1 pin 18 + * 94 PMD1/RE1 PMPD1 TFT display, HDR1 pin 17 + * 98 PMD2/RE2 PMPD2 TFT display, HDR1 pin 16 + * 99 PMD3/RE3 PMPD3 TFT display, HDR1 pin 15 + * 100 PMD4/RE4 PMPD4 TFT display, HDR1 pin 14 + * 3 PMD5/RE5 PMPD5 TFT display, HDR1 pin 13 + * 4 PMD6/RE6 PMPD6 TFT display, HDR1 pin 12 + * 5 PMD7/RE7 PMPD7 TFT display, HDR1 pin 11 + * 90 PMD8/C2RX/RG0 PMPD8 TFT display, HDR1 pin 10 + * 89 PMD9/C2TX/ETXERR/RG1 PMPD9 TFT display, HDR1 pin 9 + * 88 PMD10/C1TX/ETXD0/RF1 PMPD10 TFT display, HDR1 pin 8 + * 87 PMD11/C1RX/ETXD1/RF0 PMPD11 TFT display, HDR1 pin 7 + * 79 PMD12/ETXD2/IC5/RD12 PMPD12 TFT display, HDR1 pin 6 + * 80 PMD13/CN19/ETXD3/RD13 PMPD13 TFT display, HDR1 pin 5 + * 83 PMD14/CN15/ETXEN/RD6 PMPD14 TFT display, HDR1 pin 4 + * 84 PMD15/CN16/ETXCLK/RD7 PMPD15 TFT display, HDR1 pin 3 + * + * 82 CN14/PMRD/RD5 PMPRD + * 81 CN13/OC5/PMWR/RD4 PMPWR + */ + +/* RC1, Reset -- Low value holds in reset */ + +#define GPIO_LCD_RST (GPIO_OUTPUT|GPIO_VALUE_ZERO|GPIO_PORTC|GPIO_PIN1) + +/* RB14, LCD select -- Low value selects LCD */ + +#define GPIO_LCD_CS (GPIO_OUTPUT|GPIO_VALUE_ONE|GPIO_PORTB|GPIO_PIN14) + +/* RD2, Backlight -- Low value turns off */ + +#define GPIO_LCD_BLED (GPIO_OUTPUT|GPIO_VALUE_ZERO|GPIO_PORTD|GPIO_PIN2) + +/* RB15, RS -- High values selects data */ + +#define GPIO_LCD_RS (GPIO_OUTPUT|GPIO_VALUE_ZERO|GPIO_PORTB|GPIO_PIN15) + +/* Debug ******************************************************************************/ + +#ifdef CONFIG_DEBUG_LCD +# define lcddbg dbg +# define lcdvdbg vdbg +#else +# define lcddbg(x...) +# define lcdvdbg(x...) +#endif + +/************************************************************************************** + * Private Type Definition + **************************************************************************************/ + +struct pic32mx7mmb_dev_s +{ + struct mio283qt2_lcd_s dev; /* The externally visible part of the driver */ + bool data; /* true=data selected */ + bool selected; /* true=LCD selected */ + bool reading; /* true=We are in a read sequence */ + FAR struct lcd_dev_s *drvr; /* The saved instance of the LCD driver */ +}; + +/************************************************************************************** + * Private Function Protototypes + **************************************************************************************/ +/* Low Level LCD access */ + +static void pic32mx_select(FAR struct mio283qt2_lcd_s *dev); +static void pic32mx_deselect(FAR struct mio283qt2_lcd_s *dev); +static void pic32mx_index(FAR struct mio283qt2_lcd_s *dev, uint8_t index); +#ifndef CONFIG_MIO283QT2_WRONLY +static uint16_t pic32mx_read(FAR struct mio283qt2_lcd_s *dev); +#endif +static void pic32mx_write(FAR struct mio283qt2_lcd_s *dev, uint16_t data); +static void pic32mx_backlight(FAR struct mio283qt2_lcd_s *dev, int power); + +/************************************************************************************** + * Private Data + **************************************************************************************/ + +/* This is the driver state structure (there is no retained state information) */ + +static struct pic32mx7mmb_dev_s g_pic32mx7mmb_lcd = +{ + { + .select = pic32mx_select, + .deselect = pic32mx_deselect, + .index = pic32mx_index, +#ifndef CONFIG_MIO283QT2_WRONLY + .read = pic32mx_read, +#endif + .write = pic32mx_write, + .backlight = pic32mx_backlight + } +}; + +/************************************************************************************** + * Private Functions + **************************************************************************************/ + +/************************************************************************************** + * Name: pic32mx_command + * + * Description: + * Configure to write an LCD command + * + **************************************************************************************/ + +static void pic32mx_command(FAR struct pic32mx7mmb_dev_s *priv) +{ + /* Low selects command */ + + if (priv->data) + { + pic32mx_gpiowrite(GPIO_LCD_RS, false); + + priv->data = false; /* Command, not data */ + priv->reading = false; /* No read sequence in progress */ + } +} + +/************************************************************************************** + * Name: pic32mx_data + * + * Description: + * Configure to read or write LCD data + * + **************************************************************************************/ + +static void pic32mx_data(FAR struct pic32mx7mmb_dev_s *priv) +{ + /* Hi selects data */ + + if (!priv->data) + { + pic32mx_gpiowrite(GPIO_LCD_RS, true); + + priv->data = true; /* Data, not command */ + priv->reading = false; /* No read sequence in progress */ + } +} + +/************************************************************************************** + * Name: pic32mx_data + * + * Description: + * Wait until the PMP is no longer busy + * + **************************************************************************************/ + +static void pic32mx_busywait(void) +{ + while ((getreg32(PIC32MX_PMP_MODE) & PMP_MODE_BUSY) != 0); +} + +/************************************************************************************** + * Name: pic32mx_select + * + * Description: + * Select the LCD device + * + **************************************************************************************/ + +static void pic32mx_select(FAR struct mio283qt2_lcd_s *dev) +{ + FAR struct pic32mx7mmb_dev_s *priv = (FAR struct pic32mx7mmb_dev_s *)dev; + + /* CS low selects */ + + if (!priv->selected) + { + pic32mx_gpiowrite(GPIO_LCD_CS, false); + + priv->selected = true; /* LCD selected */ + priv->reading = false; /* No read sequence in progress */ + } +} + +/************************************************************************************** + * Name: pic32mx_deselect + * + * Description: + * De-select the LCD device + * + **************************************************************************************/ + +static void pic32mx_deselect(FAR struct mio283qt2_lcd_s *dev) +{ + FAR struct pic32mx7mmb_dev_s *priv = (FAR struct pic32mx7mmb_dev_s *)dev; + + /* CS high de-selects */ + + if (priv->selected) + { + pic32mx_gpiowrite(GPIO_LCD_CS, true); + + priv->selected = false; /* LCD not selected */ + priv->reading = false; /* No read sequence in progress */ + } +} + +/************************************************************************************** + * Name: pic32mx_index + * + * Description: + * Set the index register + * + **************************************************************************************/ + +static void pic32mx_index(FAR struct mio283qt2_lcd_s *dev, uint8_t index) +{ + FAR struct pic32mx7mmb_dev_s *priv = (FAR struct pic32mx7mmb_dev_s *)dev; + + /* Make sure that the PMP is not busy from the last transaction. Read data is not + * available until the busy bit becomes zero. + */ + + pic32mx_busywait(); + + /* Write the 8-bit command (on the 16-bit data bus) */ + + pic32mx_command(priv); + putreg16((uint16_t)index, PIC32MX_PMP_DIN); +} + +/************************************************************************************** + * Name: pic32mx_read + * + * Description: + * Read LCD data (GRAM data or register contents) + * + **************************************************************************************/ + +#ifndef CONFIG_MIO283QT2_WRONLY +static uint16_t pic32mx_read(FAR struct mio283qt2_lcd_s *dev) +{ + FAR struct pic32mx7mmb_dev_s *priv = (FAR struct pic32mx7mmb_dev_s *)dev; + uint16_t data; + + /* Make sure that the PMP is not busy from the last transaction. Read data is not + * available until the busy bit becomes zero. + */ + + pic32mx_busywait(); + + /* Read 16-bits of data */ + + pic32mx_data(priv); + data = getreg16(PIC32MX_PMP_DIN); + + /* We need to discard the first 16-bits of data that we read and re-read inorder + * to get valid data (that is just the way that the PMP works). + */ + + if (!priv->reading) + { + data = getreg16(PIC32MX_PMP_DIN); + } + + return data; +} +#endif + +/************************************************************************************** + * Name: pic32mx_write + * + * Description: + * Write LCD data (GRAM data or register contents) + * + **************************************************************************************/ + +static void pic32mx_write(FAR struct mio283qt2_lcd_s *dev, uint16_t data) +{ + FAR struct pic32mx7mmb_dev_s *priv = (FAR struct pic32mx7mmb_dev_s *)dev; + + /* Make sure that the PMP is not busy from the last transaction */ + + pic32mx_busywait(); + + /* Write 16-bits of data */ + + pic32mx_data(priv); + putreg16(data, PIC32MX_PMP_DIN); + + /* We are not in a write sequence */ + + priv->reading = false; +} + +/************************************************************************************** + * Name: pic32mx_write + * + * Description: + * Write LCD data (GRAM data or register contents) + * + **************************************************************************************/ + +static void pic32mx_backlight(FAR struct mio283qt2_lcd_s *dev, int power) +{ + /* For now, we just control the backlight as a discrete. Pulse width modulation + * would be required to vary the backlight level. A low value turns the backlight + * off. + */ + + pic32mx_gpiowrite(GPIO_LCD_BLED, power > 0); +} + +/************************************************************************************** + * Public Functions + **************************************************************************************/ + +/************************************************************************************** + * Name: up_lcdinitialize + * + * Description: + * Initialize the LCD video hardware. The initial state of the LCD is fully + * initialized, display memory cleared, and the LCD ready to use, but with the power + * setting at 0 (full off). + * + **************************************************************************************/ + +int up_lcdinitialize(void) +{ + uint32_t regval; + + /* Only initialize the driver once. NOTE: The LCD GPIOs were already configured + * by pic32mx_lcdinitialize. + */ + + if (!g_pic32mx7mmb_lcd.drvr) + { + lcdvdbg("Initializing\n"); + + /* Hold the LCD in reset (active low) */ + + pic32mx_gpiowrite(GPIO_LCD_RST, false); + + /* Configure PMP to support the LCD */ + + putreg32(0, PIC32MX_PMP_MODE); + putreg32(0, PIC32MX_PMP_AEN); + putreg32(0, PIC32MX_PMP_CON); + + /* Set LCD timing values, PMP master mode 2, 16-bit mode, no address + * increment, and no interrupts. + */ + + regval = (PMP_MODE_WAITE_RD(0) | PMP_MODE_WAITM(3) | PMP_MODE_WAITB_1TPB | + PMP_MODE_MODE_MODE2 | PMP_MODE_MODE16 | PMP_MODE_INCM_NONE | + PMP_MODE_IRQM_NONE); + putreg32(regval, PIC32MX_PMP_MODE); + + /* Enable the PMP for reading and writing */ + + regval = (PMP_CON_CSF_ADDR1415 | PMP_CON_PTRDEN | PMP_CON_PTWREN | + PMP_CON_ADRMUX_NONE | PMP_CON_ON); + putreg32(regval, PIC32MX_PMP_CON); + + /* Bring the LCD out of reset */ + + up_mdelay(5); + pic32mx_gpiowrite(GPIO_LCD_RST, true); + + /* Configure and enable the LCD */ + + up_mdelay(50); + g_pic32mx7mmb_lcd.drvr = mio283qt2_lcdinitialize(&g_pic32mx7mmb_lcd.dev); + if (!g_pic32mx7mmb_lcd.drvr) + { + lcddbg("ERROR: mio283qt2_lcdinitialize failed\n"); + return -ENODEV; + } + } + + /* Clear the display (setting it to the color 0=black) */ + +#if 0 /* Already done in the driver */ + mio283qt2_clear(g_pic32mx7mmb_lcd.drvr, 0); +#endif + + /* Turn the display off */ + + g_pic32mx7mmb_lcd.drvr->setpower(g_pic32mx7mmb_lcd.drvr, 0); + return OK; +} + +/************************************************************************************** + * Name: up_lcdgetdev + * + * Description: + * Return a a reference to the LCD object for the specified LCD. This allows support + * for multiple LCD devices. + * + **************************************************************************************/ + +FAR struct lcd_dev_s *up_lcdgetdev(int lcddev) +{ + DEBUGASSERT(lcddev == 0); + return g_pic32mx7mmb_lcd.drvr; +} + +/************************************************************************************** + * Name: up_lcduninitialize + * + * Description: + * Unitialize the LCD support + * + **************************************************************************************/ + +void up_lcduninitialize(void) +{ + /* Turn the display off */ + + g_pic32mx7mmb_lcd.drvr->setpower(g_pic32mx7mmb_lcd.drvr, 0); +} + +#endif /* CONFIG_LCD_MIO283QT2 */ + +/**************************************************************************** + * Name: pic32mx_lcdinitialize + * + * Description: + * Initialize the LCD. This function should be called early in the boot + * sequendce -- Even if the LCD is not enabled. In that case we should + * at a minimum at least disable the LCD backlight. + * + ****************************************************************************/ + +void pic32mx_lcdinitialize(void) +{ + /* Configure all LCD discrete controls. LCD will be left in this state: + * 1. Held in reset, + * 2. Not selected, + * 3. Backlight off, + * 4. Command selected. + */ + +#ifdef CONFIG_LCD_MIO283QT2 + pic32mx_configgpio(GPIO_LCD_RST); + pic32mx_configgpio(GPIO_LCD_CS); + pic32mx_configgpio(GPIO_LCD_BLED); + pic32mx_configgpio(GPIO_LCD_RS); + +#else + /* Just configure the backlight control as an output and turn off the + * backlight for now. + */ + + pic32mx_configgpio(GPIO_LCD_BLED); +#endif +} + + diff --git a/nuttx/configs/mikroe-stm32f4/src/up_nsh.c b/nuttx/configs/mikroe-stm32f4/src/up_nsh.c new file mode 100644 index 000000000..58351f539 --- /dev/null +++ b/nuttx/configs/mikroe-stm32f4/src/up_nsh.c @@ -0,0 +1,286 @@ +/**************************************************************************** + * config/mikroe_stm32f4/src/up_nsh.c + * arch/arm/src/board/up_nsh.c + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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 + +#include +#include +#include +#include + +#include + +#ifdef CONFIG_STM32_SPI3 +# include +#endif + +#ifdef CONFIG_MTD_MP25P +# include +#endif + +#ifdef CONFIG_SYSTEM_USBMONITOR +# include +#endif + +#ifdef CONFIG_STM32_OTGFS +# include "stm32_usbhost.h" +#endif + +#include "stm32.h" +#include "mikroe-stm32f4-internal.h" + +/**************************************************************************** + * Pre-Processor Definitions + ****************************************************************************/ + +/* Configuration ************************************************************/ + +#define HAVE_USBDEV 1 +#define HAVE_USBHOST 1 +#define HAVE_USBMONITOR 1 +#define NSH_HAVEMMCSD 1 + +/* Can't support USB host or device features if USB OTG FS is not enabled */ + +#ifndef CONFIG_STM32_OTGFS +# undef HAVE_USBDEV +# undef HAVE_USBHOST +# undef HAVE_USBMONITOR +#endif + +/* Can't support USB device is USB device is not enabled */ + +#ifndef CONFIG_USBDEV +# undef HAVE_USBDEV +# undef HAVE_USBMONITOR +#endif + +/* Can't support USB host is USB host is not enabled */ + +#ifndef CONFIG_USBHOST +# undef HAVE_USBHOST +#endif + +/* Check if we should enable the USB monitor before starting NSH */ + +#if !defined(CONFIG_USBDEV_TRACE) || !defined(CONFIG_SYSTEM_USBMONITOR) +# undef HAVE_USBMONITOR +#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_SPI3) +# undef NSH_HAVEMMCSD +#endif + +#ifndef CONFIG_NSH_MMCSDMINOR +# define CONFIG_NSH_MMCSDMINOR 0 +#endif + +# ifndef CONFIG_RAMMTD_BLOCKSIZE +# define CONFIG_RAMMTD_BLOCKSIZE 512 +# endif + +# ifndef CONFIG_RAMMTD_ERASESIZE +# define CONFIG_RAMMTD_ERASESIZE 4096 +# endif + +# ifndef CONFIG_EXAMPLES_SMART_NEBLOCKS +# define CONFIG_EXAMPLES_SMART_NEBLOCKS (22) +# endif + +# undef CONFIG_EXAMPLES_SMART_BUFSIZE +# define CONFIG_EXAMPLES_SMART_BUFSIZE \ + (CONFIG_RAMMTD_ERASESIZE * CONFIG_EXAMPLES_SMART_NEBLOCKS) + +/* Debug ********************************************************************/ + +#ifdef CONFIG_CPP_HAVE_VARARGS +# ifdef CONFIG_DEBUG +# define message(...) lowsyslog(__VA_ARGS__) +# else +# define message(...) printf(__VA_ARGS__) +# endif +#else +# ifdef CONFIG_DEBUG +# define message lowsyslog +# else +# define message printf +# endif +#endif + +/**************************************************************************** + * Private Data + ****************************************************************************/ +/* Pre-allocated simulated flash */ + +#ifdef CONFIG_MTD_RAM +//static uint8_t g_simflash[CONFIG_EXAMPLES_SMART_BUFSIZE]; +#endif + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: nsh_archinitialize + * + * Description: + * Perform architecture specific initialization + * + ****************************************************************************/ + +int nsh_archinitialize(void) +{ +#if defined(HAVE_USBHOST) || defined(HAVE_USBMONITOR) + int ret; +#endif +#ifdef CONFIG_STM32_SPI3 + FAR struct spi_dev_s *spi; + FAR struct mtd_dev_s *mtd; +#endif + int ret; + + /* Configure SPI-based devices */ + +#ifdef CONFIG_STM32_SPI3 + /* Get the SPI port */ + + message("nsh_archinitialize: Initializing SPI port 3\n"); + spi = up_spiinitialize(3); + if (!spi) + { + message("nsh_archinitialize: Failed to initialize SPI port 3\n"); + return -ENODEV; + } + message("nsh_archinitialize: Successfully initialized SPI port 3\n"); + + /* Now bind the SPI interface to the M25P8 SPI FLASH driver */ + +#ifdef CONFIG_MTD + 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 3 to the SPI FLASH driver\n"); + } + else + { + message("nsh_archinitialize: Successfully bound SPI port 3 to the SPI FLASH driver\n"); + + /* Now initialize a SMART Flash block device and bind it to the MTD device */ +#if defined(CONFIG_MTD_SMART) && defined(CONFIG_FS_SMARTFS) + smart_initialize(0, mtd); +#endif + } + + /* Create a RAM MTD device if configured */ + +#ifdef CONFIG_MTD_RAM + + { + uint8_t *start = (uint8_t *) kmalloc(CONFIG_EXAMPLES_SMART_BUFSIZE); + mtd = rammtd_initialize(start, CONFIG_EXAMPLES_SMART_BUFSIZE); + mtd->ioctl(mtd, MTDIOC_BULKERASE, 0); + + /* Now initialize a SMART Flash block device and bind it to the MTD device */ +#if defined(CONFIG_MTD_SMART) && defined(CONFIG_FS_SMARTFS) + smart_initialize(1, mtd); +#endif + } + +#endif /* CONFIG_MTD_RAM */ + +#endif /* CONFIG_MTD */ + +//#warning "Now what are we going to do with this SPI FLASH driver?" +#endif + + /* Create the SPI FLASH MTD instance */ + /* The M25Pxx is not a good media to implement a file system.. + * its block sizes are too large + */ + + /* Mount the SDIO-based MMC/SD block driver */ + +#ifdef NSH_HAVEMMCSD + /* Bind the spi interface to the MMC/SD driver */ + + message("nsh_archinitialize: Bind SDIO to the MMC/SD driver, minor=%d\n", + CONFIG_NSH_MMCSDMINOR); + ret = mmcsd_spislotinitialize(CONFIG_NSH_MMCSDMINOR, CONFIG_NSH_MMCSDSLOTNO, spi); + if (ret != OK) + { + message("nsh_archinitialize: Failed to bind SPI to the MMC/SD driver: %d\n", ret); + } + else + { + message("nsh_archinitialize: Successfully bound SPI to the MMC/SD driver\n"); + + } +#endif + +#ifdef HAVE_USBHOST + /* Initialize USB host operation. stm32_usbhost_initialize() starts a thread + * will monitor for USB connection and disconnection events. + */ + + ret = stm32_usbhost_initialize(); + if (ret != OK) + { + message("nsh_archinitialize: Failed to initialize USB host: %d\n", ret); + return ret; + } +#endif + +#ifdef HAVE_USBMONITOR + /* Start the USB Monitor */ + + ret = usbmonitor_start(0, NULL); + if (ret != OK) + { + message("nsh_archinitialize: Start USB monitor: %d\n", ret); + } +#endif + + return OK; +} diff --git a/nuttx/configs/mikroe-stm32f4/src/up_pm.c b/nuttx/configs/mikroe-stm32f4/src/up_pm.c new file mode 100644 index 000000000..2be67b11a --- /dev/null +++ b/nuttx/configs/mikroe-stm32f4/src/up_pm.c @@ -0,0 +1,107 @@ +/**************************************************************************** + * configs/mikroe_stm32f4/src/up_pm.c + * arch/arm/src/board/up_pm.c + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Authors: Gregory Nutt + * Diego Sanchez + * + * 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 + +#include + +#include "up_internal.h" +#include "stm32_pm.h" +#include "mikroe-stm32f4-internal.h" + +#ifdef CONFIG_PM + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: up_pminitialize + * + * Description: + * This function is called by MCU-specific logic at power-on reset in + * order to provide one-time initialization the power management subystem. + * This function must be called *very* early in the intialization sequence + * *before* any other device drivers are initialized (since they may + * attempt to register with the power management subsystem). + * + * Input parameters: + * None. + * + * Returned value: + * None. + * + ****************************************************************************/ + +void up_pminitialize(void) +{ + /* Then initialize the NuttX power management subsystem proper */ + + pm_initialize(); + +#if defined(CONFIG_IDLE_CUSTOM) && defined(CONFIG_PM_BUTTONS) + /* Initialize the buttons to wake up the system from low power modes */ + + up_pmbuttons(); +#endif + + /* Initialize the LED PM */ + + up_ledpminitialize(); +} + +#endif /* CONFIG_PM */ diff --git a/nuttx/configs/mikroe-stm32f4/src/up_pwm.c b/nuttx/configs/mikroe-stm32f4/src/up_pwm.c new file mode 100644 index 000000000..4726e6c85 --- /dev/null +++ b/nuttx/configs/mikroe-stm32f4/src/up_pwm.c @@ -0,0 +1,142 @@ +/************************************************************************************ + * configs/mikroe_stm32f4/src/up_pwm.c + * arch/arm/src/board/up_pwm.c + * + * Copyright (C) 2011 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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 + +#include +#include + +#include +#include + +#include "chip.h" +#include "up_arch.h" +#include "stm32_pwm.h" +#include "mikroe-stm32f4-internal.h" + +/************************************************************************************ + * Definitions + ************************************************************************************/ +/* Configuration *******************************************************************/ +/* PWM + * + * The mikroe_stm32f4 has no real on-board PWM devices, but the board can be configured to output + * a pulse train using TIM4 CH2. This pin is used by FSMC is connect to CN5 just for this + * purpose: + * + * PD13 FSMC_A18 / MC_TIM4_CH2OUT pin 33 (EnB) + * + * FSMC must be disabled in this case! + */ + +#define HAVE_PWM 1 + +#ifndef CONFIG_PWM +# undef HAVE_PWM +#endif + +#ifndef CONFIG_STM32_TIM4 +# undef HAVE_PWM +#endif + +#ifndef CONFIG_STM32_TIM4_PWM +# undef HAVE_PWM +#endif + +#if CONFIG_STM32_TIM4_CHANNEL != STM32F4DISCOVERY_PWMCHANNEL +# undef HAVE_PWM +#endif + +#ifdef HAVE_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(STM32F4DISCOVERY_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 /* HAVE_PWM */ diff --git a/nuttx/configs/mikroe-stm32f4/src/up_qencoder.c b/nuttx/configs/mikroe-stm32f4/src/up_qencoder.c new file mode 100644 index 000000000..62ef53834 --- /dev/null +++ b/nuttx/configs/mikroe-stm32f4/src/up_qencoder.c @@ -0,0 +1,187 @@ +/************************************************************************************ + * configs/mikroe_stm32f4/src/up_qencoder.c + * arch/arm/src/board/up_qencoder.c + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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 + +#include +#include + +#include +#include + +#include "chip.h" +#include "up_arch.h" +#include "stm32_qencoder.h" +#include "mikroe-stm32f4-internal.h" + +/************************************************************************************ + * Definitions + ************************************************************************************/ +/* Configuration *******************************************************************/ +/* Check if we have a timer configured for quadrature encoder -- assume YES. */ + +#define HAVE_QENCODER 1 + +/* If TIMn is not enabled (via CONFIG_STM32_TIMn), then the configuration cannot + * specify TIMn as a quadrature encoder (via CONFIG_STM32_TIMn_QE). + */ + +#ifndef CONFIG_STM32_TIM1 +# undef CONFIG_STM32_TIM1_QE +#endif +#ifndef CONFIG_STM32_TIM2 +# undef CONFIG_STM32_TIM2_QE +#endif +#ifndef CONFIG_STM32_TIM3 +# undef CONFIG_STM32_TIM3_QE +#endif +#ifndef CONFIG_STM32_TIM4 +# undef CONFIG_STM32_TIM4_QE +#endif +#ifndef CONFIG_STM32_TIM5 +# undef CONFIG_STM32_TIM5_QE +#endif +#ifndef CONFIG_STM32_TIM8 +# undef CONFIG_STM32_TIM8_QE +#endif + +/* If the upper-half quadrature encoder driver is not enabled, then we cannot + * support the quadrature encoder. + */ + +#ifndef CONFIG_QENCODER +# undef HAVE_QENCODER +#endif + +/* Which Timer should we use, TIMID={1,2,3,4,5,8}. If multiple timers are + * configured as quadrature encoders, this logic will arbitrarily select + * the lowest numbered timer. + * + * At least one TIMn, n={1,2,3,4,5,8}, must be both enabled and configured + * as a quadrature encoder in order to support the lower half quadrature + * encoder driver. The above check assures that if CONFIG_STM32_TIMn_QE + * is defined, then the correspdonding TIMn is also enabled. + */ + +#if defined CONFIG_STM32_TIM1_QE +# define TIMID 1 +#elif defined CONFIG_STM32_TIM2_QE +# define TIMID 2 +#elif defined CONFIG_STM32_TIM3_QE +# define TIMID 3 +#elif defined CONFIG_STM32_TIM4_QE +# define TIMID 4 +#elif defined CONFIG_STM32_TIM5_QE +# define TIMID 5 +#elif defined CONFIG_STM32_TIM8_QE +# define TIMID 8 +#else +# undef HAVE_QENCODER +#endif + +#ifdef HAVE_QENCODER + +/* Debug ***************************************************************************/ +/* Non-standard debug that may be enabled just for testing the quadrature encoder */ + +#ifndef CONFIG_DEBUG +# undef CONFIG_DEBUG_QENCODER +#endif + +#ifdef CONFIG_DEBUG_QENCODER +# define qedbg dbg +# define qelldbg lldbg +# ifdef CONFIG_DEBUG_VERBOSE +# define qevdbg vdbg +# define qellvdbg llvdbg +# else +# define qevdbg(x...) +# define qellvdbg(x...) +# endif +#else +# define qedbg(x...) +# define qelldbg(x...) +# define qevdbg(x...) +# define qellvdbg(x...) +#endif + +/************************************************************************************ + * Private Functions + ************************************************************************************/ + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +/************************************************************************************ + * Name: qe_devinit + * + * Description: + * All STM32 architectures must provide the following interface to work with + * examples/qencoder. + * + ************************************************************************************/ + +int qe_devinit(void) +{ + static bool initialized = false; + int ret; + + /* Check if we are already initialized */ + + if (!initialized) + { + /* Initialize a quadrature encoder interface. */ + + qevdbg("Initializing the quadrature encoder using TIM%d\n", TIMID); + ret = stm32_qeinitialize("/dev/qe0", TIMID); + if (ret < 0) + { + qedbg("stm32_qeinitialize failed: %d\n", ret); + return ret; + } + + initialized = true; + } + + return OK; +} + +#endif /* HAVE_QENCODER */ diff --git a/nuttx/configs/mikroe-stm32f4/src/up_spi.c b/nuttx/configs/mikroe-stm32f4/src/up_spi.c new file mode 100644 index 000000000..9da926ef6 --- /dev/null +++ b/nuttx/configs/mikroe-stm32f4/src/up_spi.c @@ -0,0 +1,279 @@ +/************************************************************************************ + * configs/mikroe_stm32f4/src/up_spi.c + * arch/arm/src/board/up_spi.c + * + * Copyright (C) 2011-2012 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Modifications: + * + * - 4/16/2013: Ken Pettit + * - Modified to support SPI3 on Mikroe-STM32F4 board. + * + * 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 + +#include +#include +#include +#include + +#include +#include + +#include "up_arch.h" +#include "chip.h" +#include "stm32.h" +#include "mikroe-stm32f4-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 mikroe_stm32f4 board. + * + ************************************************************************************/ + +void weak_function stm32_spiinitialize(void) +{ +#ifdef CONFIG_STM32_SPI3 + +#ifdef CONFIG_MTD_MP25P + (void)stm32_configgpio(GPIO_CS_FLASH); /* FLASH chip select */ + stm32_gpiowrite(GPIO_CS_FLASH, 1); /* Ensure the CS is inactive */ +#endif + +#if defined(CONFIG_MMCSD) + (void)stm32_configgpio(GPIO_CS_MMCSD); /* MMC/SD chip select */ + (void)stm32_configgpio(GPIO_SD_CD); /* MMC/SD card detect */ + stm32_gpiowrite(GPIO_CS_MMCSD, 1); /* Ensure the CS is inactive */ +#endif + +#ifdef CONFIG_AUDIO_MP3_CODEC + (void)stm32_configgpio(GPIO_CS_MP3); /* MP3 codec chip select */ + stm32_gpiowrite(GPIO_CS_MP3, 1); /* Ensure the CS is inactive */ +#endif + + /* Configure the EXP I/O cs for SPI3 */ + (void)stm32_configgpio(GPIO_CS_EXP_SPI3); /* Expander chip select */ + stm32_gpiowrite(GPIO_CS_EXP_SPI3, 1); /* Ensure the CS is inactive */ + +#endif +} + +/**************************************************************************** + * 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_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"); + +#if defined(CONFIG_MTD_MP25P) + if (devid == SPIDEV_FLASH) + { + stm32_gpiowrite(GPIO_CS_FLASH, !selected); + } + else +#endif + +#if defined(CONFIG_MMCSD) + if (devid == SPIDEV_MMCSD) + { + stm32_gpiowrite(GPIO_CS_MMCSD, !selected); + } + else +#endif + +#if defined(CONFIG_AUDIO_MP3_CODEC) + if (devid == SPIDEV_AUDIO) + { + stm32_gpiowrite(GPIO_CS_MP3, !selected); + } + else +#endif + + /* Must be the expansion header device */ + if (devid == SPIDEV_EXPANDER) + { + stm32_gpiowrite(GPIO_CS_EXP_SPI3, !selected); + } +} + +uint8_t stm32_spi3status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +{ + uint8_t ret = 0; + +#if defined(CONFIG_MMCSD) + if (devid == SPIDEV_MMCSD) + { + /* A low value indicates the card is present */ + if (!stm32_gpioread(GPIO_SD_CD)) + { + ret = SPI_STATUS_PRESENT; + } + } +#endif + + return ret; +} +#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 0; +} +#endif + +#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 0; +} +#endif + +/**************************************************************************** + * Name: stm32_spi1cmddata + * + * Description: + * Set or clear the SH1101A A0 or SD1306 D/C n bit to select data (true) + * or command (false). This function must be provided by platform-specific + * logic. This is an implementation of the cmddata method of the SPI + * interface defined by struct spi_ops_s (see include/nuttx/spi.h). + * + * Input Parameters: + * + * spi - SPI device that controls the bus the device that requires the CMD/ + * DATA selection. + * devid - If there are multiple devices on the bus, this selects which one + * to select cmd or data. NOTE: This design restricts, for example, + * one one SPI display per SPI bus. + * cmd - true: select command; false: select data + * + * Returned Value: + * None + * + ****************************************************************************/ + +#ifdef CONFIG_SPI_CMDDATA +#ifdef CONFIG_STM32_SPI1 +int stm32_spi1cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +{ + return -ENODEV; +} +#endif + +#ifdef CONFIG_STM32_SPI2 +int stm32_spi2cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +{ + return OK; +} +#endif + +#ifdef CONFIG_STM32_SPI3 +int stm32_spi3cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +{ + return OK; +} +#endif +#endif /* CONFIG_SPI_CMDDATA */ + +#endif /* CONFIG_STM32_SPI1 || CONFIG_STM32_SPI2 */ + diff --git a/nuttx/configs/mikroe-stm32f4/src/up_touchscreen.c b/nuttx/configs/mikroe-stm32f4/src/up_touchscreen.c new file mode 100644 index 000000000..6ef70b1f7 --- /dev/null +++ b/nuttx/configs/mikroe-stm32f4/src/up_touchscreen.c @@ -0,0 +1,1462 @@ +/************************************************************************************ + * configs/pic32mx7mmb/src/up_boot.c + * arch/mips/src/board/up_boot.c + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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 + +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include + +#include +#include "up_arch.h" +#include "up_internal.h" + +#include "stm32_adc.h" +#include "stm32_gpio.h" +#include "mikroe-stm32f4-internal.h" + +#ifdef CONFIG_INPUT + +/************************************************************************************ + * Definitions + ************************************************************************************/ +/* Configuration ********************************************************************/ +/* Reference counting is partially implemented, but not needed in the current design. + */ + +#undef CONFIG_TOUCHSCREEN_REFCNT + +/* Should we try again on bad samples? */ + +#undef CONFIG_TOUCHSCREEN_RESAMPLE + +/* Work queue support is required */ + +#ifndef CONFIG_SCHED_WORKQUEUE +# warning "Work queue support is required (CONFIG_SCHED_WORKQUEUE=y) +#endif + +/* CONFIG_TOUCHSCREEN_THRESHX and CONFIG_TOUCHSCREEN_THRESHY + * Touchscreen data comes in a a very high rate. New touch positions + * will only be reported when the X or Y data changes by these thresholds. + * This trades reduces data rate for some loss in dragging accuracy. The + * touchscreen is configure for 10-bit values so the raw ranges are 0-1023. So + * for example, if your display is 320x240, then THRESHX=3 and THRESHY=4 + * would correspond to one pixel. Default: 4 + */ + +#ifndef CONFIG_TOUCHSCREEN_THRESHX +# define CONFIG_TOUCHSCREEN_THRESHX 4 +#endif + +#ifndef CONFIG_TOUCHSCREEN_THRESHY +# define CONFIG_TOUCHSCREEN_THRESHY 4 +#endif + +/* Driver support *******************************************************************/ +/* This format is used to construct the /dev/input[n] device driver path. It is + * defined here so that it will be used consistently in all places. + */ + +#define DEV_FORMAT "/dev/input%d" +#define DEV_NAMELEN 16 + +/* PIC32MX7MMB Touchscreen Hardware Definitions *************************************/ +/* ----- ------ -------------------- + * GPIO ADC IN TFT Signal Name + * ----- ------ -------------------- + * RB10 AN10 LCD-YD + * RB11 AN11 LCD-XR + * RB12 AN12 LCD-YU + * RB13 AN13 LCD-XL + */ + +#define LCD_XPLUS_PIN (11) +#define LCD_YPLUS_PIN (12) +#define LCD_XMINUS_PIN (13) +#define LCD_YMINUS_PIN (10) + +#define LCD_XPLUS_BIT (1 << LCD_XPLUS_PIN) +#define LCD_YPLUS_BIT (1 << LCD_YPLUS_PIN) +#define LCD_XMINUS_BIT (1 << LCD_XMINUS_PIN) +#define LCD_YMINUS_BIT (1 << LCD_YMINUS_PIN) +#define LCD_ALL_BITS (LCD_XPLUS_BIT | LCD_YPLUS_BIT | LCD_XMINUS_BIT | LCD_YMINUS_BIT) + +/* Conversions are performed as 10-bit samples represented as 16-bit unsigned integers: */ + +#define MAX_ADC (1023) + +/* A measured value has to be within this range to be considered */ + +#define UPPER_THRESHOLD (MAX_ADC-1) +#define LOWER_THRESHOLD (1) + +/* Delays ***************************************************************************/ +/* All values will be increased by one system timer tick (probably 10MS). */ + +#define TC_PENUP_POLL_TICKS (100 / MSEC_PER_TICK) /* IDLE polling rate: 100 MSec */ +#define TC_PENDOWN_POLL_TICKS (60 / MSEC_PER_TICK) /* Active polling rate: 60 MSec */ +#define TC_DEBOUNCE_TICKS (30 / MSEC_PER_TICK) /* Delay before re-sampling: 30 MSec */ +#define TC_SAMPLE_TICKS (4 / MSEC_PER_TICK) /* Delay for A/D sampling: 4 MSec */ +#define TC_RESAMPLE_TICKS TC_SAMPLE_TICKS + +/************************************************************************************ + * Private Types + ************************************************************************************/ +/* This enumeration describes the state of touchscreen state machine */ + +enum tc_state_e +{ + TC_READY = 0, /* Ready to begin next sample */ + TC_YMPENDOWN, /* Allowing time for the Y- pen down sampling */ + TC_DEBOUNCE, /* Allowing a debounce time for the first sample */ + TC_RESAMPLE, /* Restart sampling on a bad measurement */ + TC_YMSAMPLE, /* Allowing time for the Y- sampling */ + TC_YPSAMPLE, /* Allowing time for the Y+ sampling */ + TC_XPSAMPLE, /* Allowing time for the X+ sampling */ + TC_XMSAMPLE, /* Allowing time for the X- sampling */ + TC_PENDOWN, /* Conversion is complete -- pen down */ + TC_PENUP /* Conversion is complete -- pen up */ +}; + +/* This describes the state of one contact */ + +enum tc_contact_e +{ + CONTACT_NONE = 0, /* No contact */ + CONTACT_DOWN, /* First contact */ + CONTACT_MOVE, /* Same contact, possibly different position */ + CONTACT_UP, /* Contact lost */ +}; + +/* This structure describes the results of one touchscreen sample */ + +struct tc_sample_s +{ + uint8_t id; /* Sampled touch point ID */ + uint8_t contact; /* Contact state (see enum tc_contact_e) */ + bool valid; /* True: x,y contain valid, sampled data */ + uint16_t x; /* Thresholded X position */ + uint16_t y; /* Thresholded Y position */ +}; + +/* This structure describes the state of one touchscreen driver instance */ + +struct tc_dev_s +{ +#ifdef CONFIG_TOUCHSCREEN_REFCNT + uint8_t crefs; /* Number of times the device has been opened */ +#endif + uint8_t state; /* See enum tc_state_e */ + uint8_t nwaiters; /* Number of threads waiting for touchscreen data */ + uint8_t id; /* Current touch point ID */ + volatile bool penchange; /* An unreported event is buffered */ + uint16_t value; /* Partial sample value (Y+ or X-) */ + uint16_t newy; /* New, un-thresholded Y value */ + sem_t devsem; /* Manages exclusive access to this structure */ + sem_t waitsem; /* Used to wait for the availability of data */ + struct tc_sample_s sample; /* Last sampled touch point data */ + struct work_s work; /* Supports the state machine delayed processing */ + + /* The following is a list if poll structures of threads waiting for + * driver events. The 'struct pollfd' reference for each open is also + * retained in the f_priv field of the 'struct file'. + */ + +#ifndef CONFIG_DISABLE_POLL + struct pollfd *fds[CONFIG_TOUCHSCREEN_NPOLLWAITERS]; +#endif +}; + +/************************************************************************************ + * Private Function Prototypes + ************************************************************************************/ + +static void tc_adc_sample(int pin); +static uint16_t tc_adc_convert(void); +static void tc_yminus_sample(void); +static void tc_yplus_sample(void); +static void tc_xplus_sample(void); +static void tc_xminus_sample(void); +static inline bool tc_valid_sample(uint16_t sample); + +static void tc_notify(FAR struct tc_dev_s *priv); +static int tc_sample(FAR struct tc_dev_s *priv, + FAR struct tc_sample_s *sample); +static int tc_waitsample(FAR struct tc_dev_s *priv, + FAR struct tc_sample_s *sample); +static void tc_worker(FAR void *arg); + +/* Character driver methods */ + +static int tc_open(FAR struct file *filep); +static int tc_close(FAR struct file *filep); +static ssize_t tc_read(FAR struct file *filep, FAR char *buffer, size_t len); +static int tc_ioctl(FAR struct file *filep, int cmd, unsigned long arg); +#ifndef CONFIG_DISABLE_POLL +static int tc_poll(FAR struct file *filep, struct pollfd *fds, bool setup); +#endif + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/* This the the vtable that supports the character driver interface */ + +static const struct file_operations tc_fops = +{ + tc_open, /* open */ + tc_close, /* close */ + tc_read, /* read */ + 0, /* write */ + 0, /* seek */ + tc_ioctl /* ioctl */ +#ifndef CONFIG_DISABLE_POLL + , tc_poll /* poll */ +#endif +}; + +/* If only a single touchscreen device is supported, then the driver state + * structure may as well be pre-allocated. + */ + +#ifndef CONFIG_TOUCHSCREEN_MULTIPLE +static struct tc_dev_s g_touchscreen; +#endif + +/************************************************************************************ + * Private Functions + ************************************************************************************/ +/************************************************************************************ + * Name: tc_adc_sample + * + * Description: + * Perform A/D sampling. Time must be allowed betwen the start of sampling + * and conversion (approx. 100Ms). + * + ************************************************************************************/ + +static void tc_adc_sample(int pin) +{ + /* Configure the pins for as an analog input. AD1PCFG specifies the + * configuration of device pins to be used as analog inputs. A pin + * is configured as an analog input when the corresponding PCFGn bit + * is 0. + */ + + putreg32(ADC_CFG(pin), PIC32MX_ADC_CFGCLR); + + /* Set SAMP=0, format 16-bit unsigned integer, manual conversion, + * SAMP=1 will trigger. + */ + + putreg32(0, PIC32MX_ADC_CON1); + + /* Select the pin as the MUXA CH0 input (positive) */ + + putreg32(ADC_CHS_CH0SA(pin), PIC32MX_ADC_CHS); + + /* No input scan */ + + putreg32(0, PIC32MX_ADC_CSSL); + + /* Manual sample, TAD = internal, 6 TPB */ + + putreg32(ADC_CON3_ADCS(6) | ADC_CON3_SAMC(0), PIC32MX_ADC_CON3); + + /* No interrrupts, no scan, internal voltage reference */ + + putreg32(ADC_CON2_VCFG_AVDDAVSS, PIC32MX_ADC_CON2); + + /* Turn on the ADC */ + + putreg32(ADC_CON1_ON, PIC32MX_ADC_CON1SET); + + /* Start sampling */ + + putreg32(ADC_CON1_SAMP, PIC32MX_ADC_CON1SET); +} + +/************************************************************************************ + * Name: tc_adc_convert + * + * Description: + * Begin A/D conversion. Time must be allowed betwen the start of sampling + * and conversion (approx. 100Ms). + * + * Assumptions: + * 1) All output pins configured as outputs: + * 2) Approprite pins are driven high and low + * + ************************************************************************************/ + +static uint16_t tc_adc_convert(void) +{ + uint32_t retval; + + /* Start conversion */ + + putreg32(ADC_CON1_SAMP, PIC32MX_ADC_CON1CLR); + + /* Wait for the conversion to complete */ + + while ((getreg32(PIC32MX_ADC_CON1) & ADC_CON1_DONE) == 0); + + /* Then read the converted ADC value */ + + retval = getreg32(PIC32MX_ADC_BUF0); + + /* Disable the ADC */ + + putreg32(ADC_CON1_ON, PIC32MX_ADC_CON1CLR); + + /* Reset all pins to digital function */ + + putreg32(LCD_ALL_BITS, PIC32MX_ADC_CFGSET); + return (uint16_t)retval; +} + +/************************************************************************************ + * Name: tc_yminus_sample + * + * Description: + * Initiate sampling on Y- + * + ************************************************************************************/ + +static void tc_yminus_sample(void) +{ + /* Configure X- as an input and X+, Y+, and Y- as outputs */ + + putreg32(LCD_XPLUS_BIT | LCD_YPLUS_BIT | LCD_YMINUS_BIT, PIC32MX_IOPORTB_TRISCLR); + putreg32(LCD_XMINUS_BIT, PIC32MX_IOPORTB_TRISSET); + + /* Energize the X plate: Y+ and Y- high, X+ low */ + + putreg32(LCD_XPLUS_BIT, PIC32MX_IOPORTB_PORTCLR); + putreg32(LCD_YPLUS_BIT | LCD_YMINUS_BIT, PIC32MX_IOPORTB_PORTSET); + + /* Start the Y axis sampling */ + + tc_adc_sample(LCD_XMINUS_PIN); +} + +/************************************************************************************ + * Name: tc_yplus_sample + * + * Description: + * Initiate sampling on Y+ + * + ************************************************************************************/ + +static void tc_yplus_sample(void) +{ + /* Configure X+ as an input and X-, Y+, and Y- as outputs */ + + putreg32(LCD_XMINUS_BIT | LCD_YPLUS_BIT | LCD_YMINUS_BIT, PIC32MX_IOPORTB_TRISCLR); + putreg32(LCD_XPLUS_BIT, PIC32MX_IOPORTB_TRISSET); + + /* Energize the X plate: Y+ and Y- High, X- low (X+ is an input) */ + + putreg32(LCD_XMINUS_BIT, PIC32MX_IOPORTB_PORTCLR); + putreg32(LCD_YPLUS_BIT | LCD_YMINUS_BIT, PIC32MX_IOPORTB_PORTSET); + + /* Start the Y axis sampling */ + + tc_adc_sample(LCD_XPLUS_PIN); +} + +/************************************************************************************ + * Name: tc_xplus_sample + * + * Description: + * Initiate sampling on X+ + * + ************************************************************************************/ + +static void tc_xplus_sample(void) +{ + /* Configure Y+ as an input and X+, X-, and Y- as outputs */ + + putreg32(LCD_XPLUS_BIT | LCD_XMINUS_BIT | LCD_YMINUS_BIT, PIC32MX_IOPORTB_TRISCLR); + putreg32(LCD_YPLUS_BIT, PIC32MX_IOPORTB_TRISSET); + + /* Energize the Y plate: X+ and X- high, Y- low (Y+ is an input) */ + + putreg32(LCD_YMINUS_BIT, PIC32MX_IOPORTB_PORTCLR); + putreg32(LCD_XPLUS_BIT | LCD_XMINUS_BIT, PIC32MX_IOPORTB_PORTSET); + + /* Read the X axis value */ + + tc_adc_sample(LCD_YPLUS_PIN); +} + +/************************************************************************************ + * Name: tc_xminus_sample + * + * Description: + * Initiate sampling on X- + * + ************************************************************************************/ + +static void tc_xminus_sample(void) +{ + /* Configure Y- as an input and X+, Y+, and X- as outputs */ + + putreg32(LCD_XPLUS_BIT | LCD_XMINUS_BIT | LCD_YPLUS_BIT, PIC32MX_IOPORTB_TRISCLR); + putreg32(LCD_YMINUS_BIT, PIC32MX_IOPORTB_TRISSET); + + /* Energize the Y plate: X+ and X- high, Y+ low (Y- is an input) */ + + putreg32(LCD_YPLUS_BIT, PIC32MX_IOPORTB_PORTCLR); + putreg32(LCD_XPLUS_BIT | LCD_XMINUS_BIT, PIC32MX_IOPORTB_PORTSET); + + /* Start X axis sampling */ + + tc_adc_sample(LCD_YMINUS_PIN); +} + +/**************************************************************************** + * Name: tc_valid_sample + ****************************************************************************/ + +static inline bool tc_valid_sample(uint16_t sample) +{ + return (sample > LOWER_THRESHOLD /* && sample < UPPER_THRESHOLD */); +} + +/**************************************************************************** + * Name: tc_notify + ****************************************************************************/ + +static void tc_notify(FAR struct tc_dev_s *priv) +{ +#ifndef CONFIG_DISABLE_POLL + int i; +#endif + + /* If there are threads waiting for read data, then signal one of them + * that the read data is available. + */ + + if (priv->nwaiters > 0) + { + /* After posting this semaphore, we need to exit because the touchscreen + * is no longer available. + */ + + sem_post(&priv->waitsem); + } + + /* If there are threads waiting on poll() for touchscreen data to become available, + * then wake them up now. NOTE: we wake up all waiting threads because we + * do not know that they are going to do. If they all try to read the data, + * then some make end up blocking after all. + */ + +#ifndef CONFIG_DISABLE_POLL + for (i = 0; i < CONFIG_TOUCHSCREEN_NPOLLWAITERS; i++) + { + struct pollfd *fds = priv->fds[i]; + if (fds) + { + fds->revents |= POLLIN; + ivdbg("Report events: %02x\n", fds->revents); + sem_post(fds->sem); + } + } +#endif +} + +/**************************************************************************** + * Name: tc_sample + * + * Assumptions: pre-emption is disabled + * + ****************************************************************************/ + +static int tc_sample(FAR struct tc_dev_s *priv, + FAR struct tc_sample_s *sample) +{ + int ret = -EAGAIN; + + /* Is there new touchscreen sample data available? */ + + if (priv->penchange) + { + /* Yes.. the state has changed in some way. Return a copy of the + * sampled data. + */ + + memcpy(sample, &priv->sample, sizeof(struct tc_sample_s )); + + /* Now manage state transitions */ + + if (sample->contact == CONTACT_UP) + { + /* Next.. no contact. Increment the ID so that next contact ID + * will be unique. X/Y positions are no longer valid. + */ + + priv->sample.contact = CONTACT_NONE; + priv->sample.valid = false; + priv->id++; + } + else if (sample->contact == CONTACT_DOWN) + { + /* First report -- next report will be a movement */ + + priv->sample.contact = CONTACT_MOVE; + } + + priv->penchange = false; + ret = OK; + } + + return ret; +} + +/**************************************************************************** + * Name: tc_waitsample + ****************************************************************************/ + +static int tc_waitsample(FAR struct tc_dev_s *priv, + FAR struct tc_sample_s *sample) +{ + int ret; + + /* Pre-emption must be disabled when this is called to to prevent sampled + * data from changing until it has been reported. + */ + + sched_lock(); + + /* Now release the semaphore that manages mutually exclusive access to + * the device structure. This may cause other tasks to become ready to + * run, but they cannot run yet because pre-emption is disabled. + */ + + sem_post(&priv->devsem); + + /* Try to get the a sample... if we cannot, then wait on the semaphore + * that is posted when new sample data is availble. + */ + + while (tc_sample(priv, sample) < 0) + { + /* Wait for a change in the touchscreen state */ + + priv->nwaiters++; + ret = sem_wait(&priv->waitsem); + priv->nwaiters--; + + if (ret < 0) + { + /* If we are awakened by a signal, then we need to return + * the failure now. + */ + + DEBUGASSERT(errno == EINTR); + ret = -EINTR; + goto errout; + } + } + + /* Re-acquire the the semaphore that manages mutually exclusive access to + * the device structure. We may have to wait here. But we have our sample. + * Interrupts and pre-emption will be re-enabled while we wait. + */ + + ret = sem_wait(&priv->devsem); + +errout: + /* Restore pre-emption. We might get suspended here but that is okay + * because we already have our sample. Note: this means that if there + * were two threads reading from the touchscreen for some reason, the data + * might be read out of order. + */ + + sched_unlock(); + return ret; +} + +/**************************************************************************** + * Name: tc_worker + ****************************************************************************/ + +static void tc_worker(FAR void *arg) +{ + FAR struct tc_dev_s *priv = (FAR struct tc_dev_s *)arg; + uint32_t delay; + uint16_t value; + uint16_t newx; + int16_t xdiff; + int16_t ydiff; + int ret; + + ASSERT(priv != NULL); + + /* Perform the next action based on the state of the conversions */ + + switch (priv->state) + { + /* The touchscreen is IDLE and we are ready to begin the next sample */ + + case TC_READY: + { + /* Start Y- sampling */ + + tc_yminus_sample(); + + /* Allow time for the Y- pend down sampling */ + + priv->state = TC_YMPENDOWN; + delay = TC_SAMPLE_TICKS; + } + break; + + /* The Y- sampling time has elapsed and the Y- value should be ready + * for conversion + */ + + case TC_YMPENDOWN: + { + /* Convert the Y- sample value */ + + value = tc_adc_convert(); + + /* A converted value at the minimum would mean that there is no touch + * and that the sampling period is complete. + */ + + if (!tc_valid_sample(value)) + { + priv->state = TC_PENUP; + } + else + { + /* Allow time for touch inputs to stabilize */ + + priv->state = TC_DEBOUNCE; + delay = TC_DEBOUNCE_TICKS; + } + } + break; + + /* The debounce time period has elapsed and we are ready to re-sample + * the touchscreen. + */ + + case TC_RESAMPLE: + case TC_DEBOUNCE: + { + /* (Re-)start Y- sampling */ + + tc_yminus_sample(); + + /* Allow time for the Y- sampling */ + + priv->state = TC_YMSAMPLE; + delay = TC_SAMPLE_TICKS; + } + break; + + /* The Y- sampling period has elapsed and we are ready to perform the + * conversion. + */ + + case TC_YMSAMPLE: + { + /* Convert and save the Y- sample value */ + + value = tc_adc_convert(); + + /* A converted value at the minimum would mean that there is no touch + * and that the sampling period is complete. At converted value at + * the maximum value is probably bad too. + */ + + if (!tc_valid_sample(value)) + { + priv->state = TC_PENUP; + } + else + { + /* Save the Y- sample and start Y+ sampling */ + + priv->value = value; + tc_yplus_sample(); + + /* Allow time for the Y+ sampling */ + + priv->state = TC_YPSAMPLE; + delay = TC_SAMPLE_TICKS; + } + } + break; + + /* The Y+ sampling period has elapsed and we are ready to perform the + * conversion. + */ + + case TC_YPSAMPLE: /* Allowing time for the Y+ sampling */ + { + /* Read the Y+ axis position */ + + value = tc_adc_convert(); + + /* A converted value at the minimum would mean that we lost the contact + * before all of the conversions were completed. At converted value at + * the maximum value is probably bad too. + */ + + if (!tc_valid_sample(value)) + { +#ifdef CONFIG_TOUCHSCREEN_RESAMPLE + priv->state = TC_RESAMPLE; + delay = TC_RESAMPLE_TICKS; +#else + priv->state = TC_PENUP; +#endif + } + else + { + value = MAX_ADC - value; + priv->newy = (value + priv->value) >> 1; + ivdbg("Y-=%d Y+=%d[%d] Y=%d\n", priv->value, value, MAX_ADC - value, priv->newy); + + /* Start X+ sampling */ + + tc_xplus_sample(); + + /* Allow time for the X+ sampling */ + + priv->state = TC_XPSAMPLE; + delay = TC_SAMPLE_TICKS; + } + } + break; + + /* The X+ sampling period has elapsed and we are ready to perform the + * conversion. + */ + + case TC_XPSAMPLE: + { + /* Convert the X+ sample value */ + + value = tc_adc_convert(); + + /* A converted value at the minimum would mean that we lost the contact + * before all of the conversions were completed. At converted value at + * the maximum value is probably bad too. + */ + + if (!tc_valid_sample(value)) + { +#ifdef CONFIG_TOUCHSCREEN_RESAMPLE + priv->state = TC_RESAMPLE; + delay = TC_RESAMPLE_TICKS; +#else + priv->state = TC_PENUP; +#endif + } + else + { + /* Save the X+ sample value */ + + priv->value = value; + + /* Start X- sampling */ + + tc_xminus_sample(); + + /* Allow time for the X- pend down sampling */ + + priv->state = TC_XMSAMPLE; + delay = TC_SAMPLE_TICKS; + } + } + break; + + /* The X+ sampling period has elapsed and we are ready to perform the + * conversion. + */ + + case TC_XMSAMPLE: /* Allowing time for the X- sampling */ + { + /* Read the converted X- axis position */ + + value = tc_adc_convert(); + + /* A converted value at the minimum would mean that we lost the contact + * before all of the conversions were completed. At converted value at + * the maximum value is probably bad too. + */ + + if (!tc_valid_sample(value)) + { +#ifdef CONFIG_TOUCHSCREEN_RESAMPLE + priv->state = TC_RESAMPLE; + delay = TC_RESAMPLE_TICKS; +#else + priv->state = TC_PENUP; +#endif + } + else + { + /* Calculate the X- axis position */ + + value = MAX_ADC - value; + newx = (value + priv->value) >> 1; + ivdbg("X+=%d X-=%d[%d] X=%d\n", priv->value, value, MAX_ADC - value, newx); + + /* Samples are available */ + + priv->state = TC_PENDOWN; + } + } + break; + } + + /* Check for terminal conditions.. */ + + /* Check if the sampling resulted in a pen up decision. If so, we need to + * handle the change from pen down to pen up. + */ + + if (priv->state == TC_PENUP) + { + /* Ignore if the pen was already down (CONTACT_NONE == pen up and already + * reported. CONTACT_UP == pen up, but not reported) + */ + + if (priv->sample.contact != CONTACT_NONE) + { + /* The pen is up. We know from the above test, that this is a + * loss of contact condition. This will be changed to CONTACT_NONE + * after the loss of contact is sampled. + */ + + priv->sample.contact = CONTACT_UP; + + /* Indicate the availability of new sample data for this ID */ + + priv->sample.id = priv->id; + priv->penchange = true; + + /* Notify any waiters that nes touchscreen data is available */ + + tc_notify(priv); + } + + /* Set up for the next poll */ + + priv->sample.valid = false; + priv->state = TC_READY; + delay = TC_PENUP_POLL_TICKS; + } + + /* Check if the sampling resulted in a pen down decision. */ + + else if (priv->state == TC_PENDOWN) + { + /* It is a pen down event. If the last loss-of-contact event has not been + * processed yet, then we have to ignore the pen down event (or else it will + * look like a drag event) + */ + + if (priv->sample.contact != CONTACT_UP) + { + /* Perform a thresholding operation so that the results will be more stable. + * If the difference from the last sample is small, then ignore the event. + */ + + xdiff = (int16_t)priv->sample.x - (int16_t)newx; + if (xdiff < 0) + { + xdiff = -xdiff; + } + + ydiff = (int16_t)priv->sample.y - (int16_t)priv->newy; + if (ydiff < 0) + { + ydiff = -ydiff; + } + + if (xdiff >= CONFIG_TOUCHSCREEN_THRESHX || + ydiff >= CONFIG_TOUCHSCREEN_THRESHY) + { + /* There is some change above the threshold... Report the change. */ + + priv->sample.x = newx; + priv->sample.y = priv->newy; + priv->sample.valid = true; + + /* If this is the first (acknowledged) penddown report, then report + * this as the first contact. If contact == CONTACT_DOWN, it will be + * set to set to CONTACT_MOVE after the contact is first sampled. + */ + + if (priv->sample.contact != CONTACT_MOVE) + { + /* First contact */ + + priv->sample.contact = CONTACT_DOWN; + } + + /* Indicate the availability of new sample data for this ID */ + + priv->sample.id = priv->id; + priv->penchange = true; + + /* Notify any waiters that nes touchscreen data is available */ + + tc_notify(priv); + } + } + + /* Set up for the next poll */ + + priv->state = TC_READY; + delay = TC_PENDOWN_POLL_TICKS; + } + + /* Set up the next sample event */ + + ret = work_queue(HPWORK, &priv->work, tc_worker, priv, delay); + ASSERT(ret == 0); +} + +/**************************************************************************** + * Name: tc_open + ****************************************************************************/ + +static int tc_open(FAR struct file *filep) +{ +#ifdef CONFIG_TOUCHSCREEN_REFCNT + FAR struct inode *inode; + FAR struct tc_dev_s *priv; + uint8_t tmp; + int ret; + + DEBUGASSERT(filep); + inode = filep->f_inode; + + DEBUGASSERT(inode && inode->i_private); + priv = (FAR struct tc_dev_s *)inode->i_private; + + /* Get exclusive access to the driver data structure */ + + ret = sem_wait(&priv->devsem); + if (ret < 0) + { + /* This should only happen if the wait was canceled by an signal */ + + DEBUGASSERT(errno == EINTR); + return -EINTR; + } + + /* Increment the reference count */ + + tmp = priv->crefs + 1; + if (tmp == 0) + { + /* More than 255 opens; uint8_t overflows to zero */ + + ret = -EMFILE; + goto errout_with_sem; + } + + /* When the reference increments to 1, this is the first open event + * on the driver.. and an opportunity to do any one-time initialization. + */ + + /* Save the new open count on success */ + + priv->crefs = tmp; + +errout_with_sem: + sem_post(&priv->devsem); + return ret; +#else + return OK; +#endif +} + +/**************************************************************************** + * Name: tc_close + ****************************************************************************/ + +static int tc_close(FAR struct file *filep) +{ +#ifdef CONFIG_TOUCHSCREEN_REFCNT + FAR struct inode *inode; + FAR struct tc_dev_s *priv; + int ret; + + DEBUGASSERT(filep); + inode = filep->f_inode; + + DEBUGASSERT(inode && inode->i_private); + priv = (FAR struct tc_dev_s *)inode->i_private; + + /* Get exclusive access to the driver data structure */ + + ret = sem_wait(&priv->devsem); + if (ret < 0) + { + /* This should only happen if the wait was canceled by an signal */ + + DEBUGASSERT(errno == EINTR); + return -EINTR; + } + + /* Decrement the reference count unless it would decrement a negative + * value. When the count decrements to zero, there are no further + * open references to the driver. + */ + + if (priv->crefs >= 1) + { + priv->crefs--; + } + + sem_post(&priv->devsem); +#endif + return OK; +} + +/**************************************************************************** + * Name: tc_read + ****************************************************************************/ + +static ssize_t tc_read(FAR struct file *filep, FAR char *buffer, size_t len) +{ + FAR struct inode *inode; + FAR struct tc_dev_s *priv; + FAR struct touch_sample_s *report; + struct tc_sample_s sample; + int ret; + + DEBUGASSERT(filep); + inode = filep->f_inode; + + DEBUGASSERT(inode && inode->i_private); + priv = (FAR struct tc_dev_s *)inode->i_private; + + /* Verify that the caller has provided a buffer large enough to receive + * the touch data. + */ + + if (len < SIZEOF_TOUCH_SAMPLE_S(1)) + { + /* We could provide logic to break up a touch report into segments and + * handle smaller reads... but why? + */ + + return -ENOSYS; + } + + /* Get exclusive access to the driver data structure */ + + ret = sem_wait(&priv->devsem); + if (ret < 0) + { + /* This should only happen if the wait was canceled by an signal */ + + DEBUGASSERT(errno == EINTR); + return -EINTR; + } + + /* Try to read sample data. */ + + ret = tc_sample(priv, &sample); + if (ret < 0) + { + /* Sample data is not available now. We would ave to wait to get + * receive sample data. If the user has specified the O_NONBLOCK + * option, then just return an error. + */ + + if (filep->f_oflags & O_NONBLOCK) + { + ret = -EAGAIN; + goto errout; + } + + /* Wait for sample data */ + + ret = tc_waitsample(priv, &sample); + if (ret < 0) + { + /* We might have been awakened by a signal */ + + goto errout; + } + } + + /* In any event, we now have sampled touchscreen data that we can report + * to the caller. + */ + + report = (FAR struct touch_sample_s *)buffer; + memset(report, 0, SIZEOF_TOUCH_SAMPLE_S(1)); + report->npoints = 1; + report->point[0].id = sample.id; + report->point[0].x = sample.x; + report->point[0].y = sample.y; + + /* Report the appropriate flags */ + + if (sample.contact == CONTACT_UP) + { + /* Pen is now up. Is the positional data valid? This is important to + * know because the release will be sent to the window based on its + * last positional data. + */ + + if (sample.valid) + { + report->point[0].flags = TOUCH_UP | TOUCH_ID_VALID | + TOUCH_POS_VALID | TOUCH_PRESSURE_VALID; + } + else + { + report->point[0].flags = TOUCH_UP | TOUCH_ID_VALID; + } + } + else + { + if (sample.contact == CONTACT_DOWN) + { + /* First contact */ + + report->point[0].flags = TOUCH_DOWN | TOUCH_ID_VALID | TOUCH_POS_VALID; + } + else /* if (sample->contact == CONTACT_MOVE) */ + { + /* Movement of the same contact */ + + report->point[0].flags = TOUCH_MOVE | TOUCH_ID_VALID | TOUCH_POS_VALID; + } + } + + ret = SIZEOF_TOUCH_SAMPLE_S(1); + +errout: + sem_post(&priv->devsem); + return ret; +} + +/**************************************************************************** + * Name:tc_ioctl + ****************************************************************************/ + +static int tc_ioctl(FAR struct file *filep, int cmd, unsigned long arg) +{ +#if 1 + ivdbg("cmd: %d arg: %ld\n", cmd, arg); + return -ENOTTY; /* None yet supported */ +#else + FAR struct inode *inode; + FAR struct tc_dev_s *priv; + int ret; + + ivdbg("cmd: %d arg: %ld\n", cmd, arg); + DEBUGASSERT(filep); + inode = filep->f_inode; + + DEBUGASSERT(inode && inode->i_private); + priv = (FAR struct tc_dev_s *)inode->i_private; + + /* Get exclusive access to the driver data structure */ + + ret = sem_wait(&priv->devsem); + if (ret < 0) + { + /* This should only happen if the wait was canceled by an signal */ + + DEBUGASSERT(errno == EINTR); + return -EINTR; + } + + /* Process the IOCTL by command */ + + switch (cmd) + { + /* ADD IOCTL COMMAND CASES HERE */ + + default: + ret = -ENOTTY; + break; + } + + sem_post(&priv->devsem); + return ret; +#endif +} + +/**************************************************************************** + * Name: tc_poll + ****************************************************************************/ + +#ifndef CONFIG_DISABLE_POLL +static int tc_poll(FAR struct file *filep, FAR struct pollfd *fds, + bool setup) +{ + FAR struct inode *inode; + FAR struct tc_dev_s *priv; + int ret; + int i; + + ivdbg("setup: %d\n", (int)setup); + DEBUGASSERT(filep && fds); + inode = filep->f_inode; + + DEBUGASSERT(inode && inode->i_private); + priv = (FAR struct tc_dev_s *)inode->i_private; + + /* Are we setting up the poll? Or tearing it down? */ + + ret = sem_wait(&priv->devsem); + if (ret < 0) + { + /* This should only happen if the wait was canceled by an signal */ + + DEBUGASSERT(errno == EINTR); + return -EINTR; + } + + if (setup) + { + /* Ignore waits that do not include POLLIN */ + + if ((fds->events & POLLIN) == 0) + { + idbg("Missing POLLIN: revents: %08x\n", fds->revents); + ret = -EDEADLK; + goto errout; + } + + /* This is a request to set up the poll. Find an available + * slot for the poll structure reference + */ + + for (i = 0; i < CONFIG_TOUCHSCREEN_NPOLLWAITERS; i++) + { + /* Find an available slot */ + + if (!priv->fds[i]) + { + /* Bind the poll structure and this slot */ + + priv->fds[i] = fds; + fds->priv = &priv->fds[i]; + break; + } + } + + if (i >= CONFIG_TOUCHSCREEN_NPOLLWAITERS) + { + idbg("No availabled slot found: %d\n", i); + fds->priv = NULL; + ret = -EBUSY; + goto errout; + } + + /* Should we immediately notify on any of the requested events? */ + + if (priv->penchange) + { + tc_notify(priv); + } + } + else if (fds->priv) + { + /* This is a request to tear down the poll. */ + + struct pollfd **slot = (struct pollfd **)fds->priv; + DEBUGASSERT(slot != NULL); + + /* Remove all memory of the poll setup */ + + *slot = NULL; + fds->priv = NULL; + } + +errout: + sem_post(&priv->devsem); + return ret; +} +#endif + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +/**************************************************************************** + * Name: arch_tcinitialize + * + * Description: + * Each board that supports a touchscreen device must provide this function. + * This function is called by application-specific, setup logic to + * configure the touchscreen device. This function will register the driver + * as /dev/inputN where N is the minor device number. + * + * Input Parameters: + * minor - The input device minor number + * + * Returned Value: + * Zero is returned on success. Otherwise, a negated errno value is + * returned to indicate the nature of the failure. + * + ****************************************************************************/ + +int arch_tcinitialize(int minor) +{ + FAR struct tc_dev_s *priv; + char devname[DEV_NAMELEN]; +#ifdef CONFIG_TOUCHSCREEN_MULTIPLE + irqstate_t flags; +#endif + int ret; + + ivdbg("minor: %d\n", minor); + DEBUGASSERT(minor >= 0 && minor < 100); + + /* Configure all touchscreen pins as inputs, undriven */ + + putreg32(LCD_ALL_BITS, PIC32MX_IOPORTB_TRISSET); + + /* Configure all pins for as digital. AD1PCFG specifies the configuration + * of device pins to be used as analog inputs. A pin is configured as an + * analog input when the corresponding PCFGn bit is 0. + */ + + putreg32(LCD_ALL_BITS, PIC32MX_ADC_CFGSET); + + /* Create and initialize a touchscreen device driver instance */ + +#ifndef CONFIG_TOUCHSCREEN_MULTIPLE + priv = &g_touchscreen; +#else + priv = (FAR struct tc_dev_s *)kmalloc(sizeof(struct tc_dev_s)); + if (!priv) + { + idbg("kmalloc(%d) failed\n", sizeof(struct tc_dev_s)); + return -ENOMEM; + } +#endif + + /* Initialize the touchscreen device driver instance */ + + memset(priv, 0, sizeof(struct tc_dev_s)); + sem_init(&priv->devsem, 0, 1); /* Initialize device structure semaphore */ + sem_init(&priv->waitsem, 0, 0); /* Initialize pen event wait semaphore */ + + /* Register the device as an input device */ + + (void)snprintf(devname, DEV_NAMELEN, DEV_FORMAT, minor); + ivdbg("Registering %s\n", devname); + + ret = register_driver(devname, &tc_fops, 0666, priv); + if (ret < 0) + { + idbg("register_driver() failed: %d\n", ret); + goto errout_with_priv; + } + + /* Schedule work to perform the initial sampling and to set the data + * availability conditions. + */ + + priv->state = TC_READY; + ret = work_queue(HPWORK, &priv->work, tc_worker, priv, 0); + if (ret != 0) + { + idbg("Failed to queue work: %d\n", ret); + goto errout_with_priv; + } + + /* And return success (?) */ + + return OK; + +errout_with_priv: + sem_destroy(&priv->devsem); +#ifdef CONFIG_TOUCHSCREEN_MULTIPLE + kfree(priv); +#endif + return ret; +} + +/**************************************************************************** + * Name: arch_tcuninitialize + * + * Description: + * Each board that supports a touchscreen device must provide this function. + * This function is called by application-specific, setup logic to + * uninitialize the touchscreen device. + * + * Input Parameters: + * None + * + * Returned Value: + * None. + * + ****************************************************************************/ + +void arch_tcuninitialize(void) +{ + /* Need to unregister the /dev/inputN device here. */ +} + +#endif /* CONFIG_INPUT */ diff --git a/nuttx/configs/mikroe-stm32f4/src/up_usb.c b/nuttx/configs/mikroe-stm32f4/src/up_usb.c new file mode 100644 index 000000000..5639c3824 --- /dev/null +++ b/nuttx/configs/mikroe-stm32f4/src/up_usb.c @@ -0,0 +1,294 @@ +/************************************************************************************ + * configs/mikroe_stm32f4/src/up_usbdev.c + * arch/arm/src/board/up_boot.c + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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 + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "up_arch.h" +#include "stm32.h" +#include "mikroe-stm32f4-internal.h" + +#ifdef CONFIG_STM32_OTGFS + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +#if defined(CONFIG_USBDEV) || defined(CONFIG_USBHOST) +# define HAVE_USB 1 +#else +# warning "CONFIG_STM32_OTGFS is enabled but neither CONFIG_USBDEV nor CONFIG_USBHOST" +# undef HAVE_USB +#endif + +#ifndef CONFIG_USBHOST_DEFPRIO +# define CONFIG_USBHOST_DEFPRIO 50 +#endif + +#ifndef CONFIG_USBHOST_STACKSIZE +# define CONFIG_USBHOST_STACKSIZE 1024 +#endif + +/************************************************************************************ + * Private Data + ************************************************************************************/ + +#ifdef CONFIG_USBHOST +static struct usbhost_driver_s *g_drvr; +#endif + +/************************************************************************************ + * Private Functions + ************************************************************************************/ + +/************************************************************************************ + * Name: usbhost_waiter + * + * Description: + * Wait for USB devices to be connected. + * + ************************************************************************************/ + +#ifdef CONFIG_USBHOST +static int usbhost_waiter(int argc, char *argv[]) +{ + bool connected = false; + int ret; + + uvdbg("Running\n"); + for (;;) + { + /* Wait for the device to change state */ + + ret = DRVR_WAIT(g_drvr, connected); + DEBUGASSERT(ret == OK); + + connected = !connected; + uvdbg("%s\n", connected ? "connected" : "disconnected"); + + /* Did we just become connected? */ + + if (connected) + { + /* Yes.. enumerate the newly connected device */ + + (void)DRVR_ENUMERATE(g_drvr); + } + } + + /* Keep the compiler from complaining */ + + return 0; +} +#endif + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +/************************************************************************************ + * Name: stm32_usbinitialize + * + * Description: + * Called from stm32_usbinitialize very early in inialization to setup USB-related + * GPIO pins for the STM32F4Discovery board. + * + ************************************************************************************/ + +void stm32_usbinitialize(void) +{ + /* The OTG FS has an internal soft pull-up. No GPIO configuration is required */ + + /* Configure the OTG FS VBUS sensing GPIO, Power On, and Overcurrent GPIOs */ + +#ifdef CONFIG_STM32_OTGFS + stm32_configgpio(GPIO_OTGFS_VBUS); + stm32_configgpio(GPIO_OTGFS_PWRON); + stm32_configgpio(GPIO_OTGFS_OVER); +#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. + * + ***********************************************************************************/ + +#ifdef CONFIG_USBHOST +int stm32_usbhost_initialize(void) +{ + int pid; + int ret; + + /* First, register all of the class drivers needed to support the drivers + * that we care about: + */ + + uvdbg("Register class drivers\n"); + ret = usbhost_storageinit(); + if (ret != OK) + { + udbg("Failed to register the mass storage class\n"); + } + + /* Then get an instance of the USB host interface */ + + uvdbg("Initialize USB host\n"); + g_drvr = usbhost_initialize(0); + if (g_drvr) + { + /* Start a thread to handle device connection. */ + + uvdbg("Start usbhost_waiter\n"); + + pid = TASK_CREATE("usbhost", CONFIG_USBHOST_DEFPRIO, + CONFIG_USBHOST_STACKSIZE, + (main_t)usbhost_waiter, (FAR char * const *)NULL); + return pid < 0 ? -ENOEXEC : OK; + } + + return -ENODEV; +} +#endif + +/*********************************************************************************** + * Name: stm32_usbhost_vbusdrive + * + * Description: + * 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 + * control and status register (PPWR bit in OTG_FS_HPRT). + * + * "The application uses this field to control power to this port, and the core + * clears this bit on an overcurrent condition." + * + * Input Parameters: + * iface - For future growth to handle multiple USB host interface. Should be zero. + * enable - true: enable VBUS power; false: disable VBUS power + * + * Returned Value: + * None + * + ***********************************************************************************/ + +#ifdef CONFIG_USBHOST +void stm32_usbhost_vbusdrive(int iface, bool enable) +{ + DEBUGASSERT(iface == 0); + + if (enable) + { + /* Enable the Power Switch by driving the enable pin low */ + + stm32_gpiowrite(GPIO_OTGFS_PWRON, false); + } + else + { + /* Disable the Power Switch by driving the enable pin high */ + + stm32_gpiowrite(GPIO_OTGFS_PWRON, true); + } +} +#endif + +/************************************************************************************ + * Name: stm32_setup_overcurrent + * + * Description: + * Setup to receive an interrupt-level callback if an overcurrent condition is + * detected. + * + * Input paramter: + * handler - New overcurrent interrupt handler + * + * Returned value: + * Old overcurrent interrupt handler + * + ************************************************************************************/ + +#ifdef CONFIG_USBHOST +xcpt_t stm32_setup_overcurrent(xcpt_t handler) +{ + return stm32_gpiosetevent(GPIO_OTGFS_OVER, true, true, true, handler); +} +#endif + +/************************************************************************************ + * Name: stm32_usbsuspend + * + * Description: + * Board logic must provide the stm32_usbsuspend logic if the USBDEV driver is + * used. This function is called whenever the USB enters or leaves suspend mode. + * This is an opportunity for the board logic to shutdown clocks, power, etc. + * while the USB is suspended. + * + ************************************************************************************/ + +#ifdef CONFIG_USBDEV +void stm32_usbsuspend(FAR struct usbdev_s *dev, bool resume) +{ + ulldbg("resume: %d\n", resume); +} +#endif + +#endif /* CONFIG_STM32_OTGFS */ + + + diff --git a/nuttx/configs/mikroe-stm32f4/src/up_watchdog.c b/nuttx/configs/mikroe-stm32f4/src/up_watchdog.c new file mode 100644 index 000000000..c248d4ac2 --- /dev/null +++ b/nuttx/configs/mikroe-stm32f4/src/up_watchdog.c @@ -0,0 +1,136 @@ +/************************************************************************************ + * configs/mikroe_stm32f4/src/up_watchdog.c + * arch/arm/src/board/up_watchdog.c + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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 + +#include +#include + +#include +#include + +#include "stm32_wdg.h" + +#ifdef CONFIG_WATCHDOG + +/************************************************************************************ + * Definitions + ************************************************************************************/ +/* Configuration *******************************************************************/ +/* Wathdog hardware should be enabled */ + +#if !defined(CONFIG_STM32_WWDG) && !defined(CONFIG_STM32_IWDG) +# warning "One of CONFIG_STM32_WWDG or CONFIG_STM32_IWDG must be defined" +#endif + +/* Select the path to the registered watchdog timer device */ + +#ifndef CONFIG_STM32_WDG_DEVPATH +# ifdef CONFIG_EXAMPLES_WATCHDOG_DEVPATH +# define CONFIG_STM32_WDG_DEVPATH CONFIG_EXAMPLES_WATCHDOG_DEVPATH +# else +# define CONFIG_STM32_WDG_DEVPATH "/dev/watchdog0" +# endif +#endif + +/* Use the un-calibrated LSI frequency if we have nothing better */ + +#if defined(CONFIG_STM32_IWDG) && !defined(CONFIG_STM32_LSIFREQ) +# define CONFIG_STM32_LSIFREQ STM32_LSI_FREQUENCY +#endif + +/* Debug ***************************************************************************/ +/* Non-standard debug that may be enabled just for testing the watchdog timer */ + +#ifndef CONFIG_DEBUG +# undef CONFIG_DEBUG_WATCHDOG +#endif + +#ifdef CONFIG_DEBUG_WATCHDOG +# define wdgdbg dbg +# define wdglldbg lldbg +# ifdef CONFIG_DEBUG_VERBOSE +# define wdgvdbg vdbg +# define wdgllvdbg llvdbg +# else +# define wdgvdbg(x...) +# define wdgllvdbg(x...) +# endif +#else +# define wdgdbg(x...) +# define wdglldbg(x...) +# define wdgvdbg(x...) +# define wdgllvdbg(x...) +#endif + +/************************************************************************************ + * Private Functions + ************************************************************************************/ + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +/**************************************************************************** + * Name: up_wdginitialize() + * + * Description: + * Perform architecuture-specific initialization of the Watchdog hardware. + * This interface must be provided by all configurations using + * apps/examples/watchdog + * + ****************************************************************************/ + +int up_wdginitialize(void) +{ + /* Initialize tha register the watchdog timer device */ + +#if defined(CONFIG_STM32_WWDG) + stm32_wwdginitialize(CONFIG_STM32_WDG_DEVPATH); + return OK; +#elif defined(CONFIG_STM32_IWDG) + stm32_iwdginitialize(CONFIG_STM32_WDG_DEVPATH, CONFIG_STM32_LSIFREQ); + return OK; +#else + return -ENODEV; +#endif +} + +#endif /* CONFIG_WATCHDOG */ -- cgit v1.2.3