Removed stm32_internal.h; Changes for clean compile of STM32F3Discovery configuration with SPI and USB

git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@5630 42af7a65-404d-4744-a932-0658087f49c3
This commit is contained in:
patacongo 2013-02-09 15:03:49 +00:00
parent 19c205e9da
commit 3458ee74a4
106 changed files with 235 additions and 355 deletions

View file

@ -2420,3 +2420,18 @@ config STM32_USBHOST_PKTDUMP
Dump all incoming and outgoing USB packets. Depends on DEBUG.
endmenu
menu "USB Device Configuration"
config STM32_USB_ITRMP
bool "Re-map USB interrupt"
default n if !STM32_CAN1
default y if STM32_CAN1
depends on STM32_USB && STM32_STM32F30XX
---help---
The legacy USB in the F1 series shared interrupt lines with USB
device and CAN1. In the F3 series, a hardware options was added to
either retain the legacy F1 behavior or to map the USB interupts to
there own dedicated vectors. The option is available only for the
F3 family and selects the use of the dedicated USB interrupts.

View file

@ -43,7 +43,7 @@
#include <nuttx/config.h>
#include <chip.h>
#ifdef CONFIG_STM32_STM32F10XX
#if defined(CONFIG_STM32_STM32F10XX) || defined(CONFIG_STM32_STM32F30XX)
/************************************************************************************
* Definitions
@ -108,7 +108,7 @@
/* Buffer Descriptor Table (Relatative to BTABLE address) */
#define STM32_USB_BTABLE_ADDR(ep,o) (STM32_USBCANRAM_BASE+STM32_USB_BTABLE_RADDR(ep,o))
#define STM32_USB_BTABLE_ADDR(ep,o) (STM32_USBRAM_BASE+STM32_USB_BTABLE_RADDR(ep,o))
#define STM32_USB_ADDR_TX(ep) STM32_USB_BTABLE_ADDR(ep,STM32_USB_ADDR_TX_WOFFSET)
#define STM32_USB_COUNT_TX(ep) STM32_USB_BTABLE_ADDR(ep,STM32_USB_COUNT_TX_WOFFSET)
#define STM32_USB_ADDR_RX(ep) STM32_USB_BTABLE_ADDR(ep,STM32_USB_ADDR_RX_WOFFSET)
@ -231,6 +231,6 @@
#define USB_COUNT_RX_SHIFT (0) /* Bits 9-0: Reception Byte Count */
#define USB_COUNT_RX_MASK (0x03ff << USB_COUNT_RX_SHIFT)
#endif /* CONFIG_STM32_STM32F10XX */
#endif /* CONFIG_STM32_STM32F10XX || CONFIG_STM32_STM32F10XX */
#endif /* __ARCH_ARM_SRC_STM32_CHIP_STM32_USBDEV_H */

View file

@ -1,7 +1,7 @@
/************************************************************************************
* arch/arm/src/stm32/chip/stm32f10xxx_memorymap.h
*
* Copyright (C) 2009, 2011 Gregory Nutt. All rights reserved.
* Copyright (C) 2009, 2011, 3013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@ -79,7 +79,8 @@
#define STM32_I2C1_BASE 0x40005400 /* 0x40005400 - 0x400057ff: I2C1 */
#define STM32_I2C2_BASE 0x40005800 /* 0x40005800 - 0x40005Bff: I2C2 */
#define STM32_USB_BASE 0x40005c00 /* 0x40005c00 - 0x40005fff: USB device FS registers */
#define STM32_USBCANRAM_BASE 0x40006000 /* 0x40006000 - 0x400063ff: Shared USB/CAN SRAM 512 bytes */
#define STM32_USBRAM_BASE 0x40006000 /* 0x40006000 - 0x400063ff: Shared USB/CAN SRAM 512 bytes */
#define STM32_CANRAM_BASE 0x40006000 /* 0x40006000 - 0x400063ff: Shared USB/CAN SRAM 512 bytes */
#define STM32_CAN1_BASE 0x40006400 /* 0x40006400 - 0x400067ff: bxCAN1 */
#define STM32_CAN2_BASE 0x40006800 /* 0x40006800 - 0x40006bff: bxCAN2 */
#define STM32_BKP_BASE 0x40006c00 /* 0x40006c00 - 0x40006fff: Backup registers (BKP) */

View file

@ -99,7 +99,7 @@
#define STM32_I2C1_BASE 0x40005400 /* 0x40005400-0x400057ff I2C1 */
#define STM32_I2C2_BASE 0x40005800 /* 0x40005800-0x40005bff I2C2 */
#define STM32_USB_BASE 0x40005c00 /* 0x40005c00-0x40005fff USB device FS */
#define STM32_USBSRAM_BASE 0x40006000 /* 0x40006000-0x400063ff USB SRAM 512B */
#define STM32_USBRAM_BASE 0x40006000 /* 0x40006000-0x400063ff USB SRAM 512B */
#define STM32_CAN1_BASE 0x40006400 /* 0x40006400-0x400067ff bxCAN */
#define STM32_PWR_BASE 0x40007000 /* 0x40007000-0x400073ff PWR */
#define STM32_DAC_BASE 0x40007400 /* 0x40007400-0x400077ff DAC (dual) */

View file

@ -92,8 +92,8 @@
#define SYSCFG_CFGR1_TIM17_DMARMP (1 << 12) /* Bit 12: TIM17 DMA request remapping bit */
#define SYSCFG_CFGR1_TIM6_DMARMP (1 << 13) /* Bit 13: TIM6 DMA remap, or */
#define SYSCFG_CFGR1_DAC1_DMARMP (1 << 13) /* Bit 13: DAC channel DMA remap */
#define SYSCFG_CFGR1_TIM7_DMARMP (1 << 14) /* Bit 14: : TIM7 DMA remap */
#define SYSCFG_CFGR1_DAC2_DMARMP (1 << 14) /* Bit 14: : DAC channel2 DMA remap */
#define SYSCFG_CFGR1_TIM7_DMARMP (1 << 14) /* Bit 14: TIM7 DMA remap */
#define SYSCFG_CFGR1_DAC2_DMARMP (1 << 14) /* Bit 14: DAC channel2 DMA remap */
#define SYSCFG_CFGR1_I2C_PBXFMP_SHIFT (0) /* Bits 16-19: Fast Mode Plus (FM+) driving capability */
#define SYSCFG_CFGR1_I2C_PBXFMP_MASK (15 << SYSCFG_CFGR1_I2C_PBXFMP_SHIFT)
#define SYSCFG_CFGR1_I2C1_FMP (1 << 20) /* Bit 20: I2C1 fast mode Plus driving capability */

View file

@ -60,7 +60,7 @@
#include "up_arch.h"
#include "chip.h"
#include "stm32_internal.h"
#include "stm32.h"
#include "stm32_adc.h"
#ifdef CONFIG_ADC

View file

@ -57,7 +57,7 @@
#include "os_internal.h"
#include "chip.h"
#include "stm32_internal.h"
#include "stm32.h"
#include "stm32_can.h"
#if defined(CONFIG_CAN) && (defined(CONFIG_STM32_CAN1) || defined(CONFIG_STM32_CAN2))

View file

@ -55,7 +55,7 @@
#include "up_arch.h"
#include "chip.h"
#include "stm32_internal.h"
#include "stm32.h"
#include "stm32_dac.h"
#ifdef CONFIG_DAC

View file

@ -1,45 +0,0 @@
/************************************************************************************
* arch/arm/src/stm32/stm32_internal.h
*
* Copyright (C) 2009-2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
************************************************************************************/
#ifndef __ARCH_ARM_SRC_STM32_STM32_INTERNAL_H
#define __ARCH_ARM_SRC_STM32_STM32_INTERNAL_H
/************************************************************************************
* Included Files
************************************************************************************/
#include "stm32.h"
#endif /* __ARCH_ARM_SRC_STM32_STM32_INTERNAL_H */

View file

@ -51,7 +51,7 @@
#include "up_arch.h"
#include "os_internal.h"
#include "up_internal.h"
#include "stm32_internal.h"
#include "stm32.h"
/****************************************************************************
* Definitions

View file

@ -48,10 +48,10 @@
#include "chip.h"
#include "stm32.h"
#include "stm32_rcc.h"
#include "stm32_gpio.h"
#include "stm32_uart.h"
#include "stm32_internal.h"
/**************************************************************************
* Private Definitions
@ -255,14 +255,14 @@
# define STM32_USARTDIV16 \
((STM32_APBCLOCK + (STM32_CONSOLE_BAUD >> 1)) / STM32_CONSOLE_BAUD)
/* Use oversamply by 8 only if the divisor is small */
/* Use oversamply by 8 only if the divisor is small. But what is small? */
# if STM32_USARTDIV8 > 100
# define STM32_BRR_VALUE STM32_USARTDIV16
# else
# define USE_OVER8 1
# define STM32_BRR_VALUE \
((STM32_USARTDIV8 && 0xfff0) | ((STM32_USARTDIV8 & 0x000f) >> 1)
((STM32_USARTDIV8 & 0xfff0) | ((STM32_USARTDIV8 & 0x000f) >> 1))
# endif
#else

View file

@ -54,7 +54,7 @@
#include "chip.h"
#include "stm32_pwm.h"
#include "stm32_internal.h"
#include "stm32.h"
/* This module then only compiles if there is at least one enabled timer
* intended for use with the PWM upper half driver.

View file

@ -55,7 +55,7 @@
#include "up_internal.h"
#include "up_arch.h"
#include "stm32_internal.h"
#include "stm32.h"
#include "stm32_gpio.h"
#include "stm32_tim.h"
#include "stm32_qencoder.h"

View file

@ -52,7 +52,7 @@
#include "chip.h"
#include "stm32_rcc.h"
#include "stm32_flash.h"
#include "stm32_internal.h"
#include "stm32.h"
#include "stm32_waste.h"
/****************************************************************************

View file

@ -60,7 +60,7 @@
#include "chip.h"
#include "up_arch.h"
#include "stm32_internal.h"
#include "stm32.h"
#include "stm32_dma.h"
#include "stm32_sdio.h"

View file

@ -939,6 +939,66 @@ static int up_dma_nextrx(struct up_dev_s *priv)
#ifndef CONFIG_SUPPRESS_UART_CONFIG
static void up_setspeed(struct uart_dev_s *dev)
{
#ifdef CONFIG_STM32_STM32F30XX
/* This first implementation is for U[S]ARTs that support oversampling
* by 8 in additional to the standard oversampling by 16.
*/
struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
uint32_t usartdiv8;
uint32_t cr1;
uint32_t brr;
/* In case of oversampling by 8, the equation is:
*
* baud = 2 * fCK / usartdiv8
* usartdiv8 = 2 * fCK / baud
*/
usartdiv8 = ((priv->apbclock << 1) + (priv->baud >> 1)) / priv->baud;
/* Baud rate for standard USART (SPI mode included):
*
* In case of oversampling by 16, the equation is:
* baud = fCK / usartdiv16
* usartdiv16 = fCK / baud
* = 2 * usartdiv8
*/
/* Use oversamply by 8 only if the divisor is small. But what is small? */
cr1 = up_serialin(priv, STM32_USART_CR1_OFFSET);
if (usartdiv8 > 100)
{
/* Use usartdiv16 */
brr = (usartdiv8 + 1) >> 1;
/* Clear oversampling by 8 to enable oversampling by 16 */
cr1 &= ~USART_CR1_OVER8;
}
else
{
/* Perform mysterious operations on bits 0-3 */
brr = ((usartdiv8 & 0xfff0) | ((usartdiv8 & 0x000f) >> 1));
/* Set oversampling by 8 */
cr1 |= USART_CR1_OVER8;
}
up_serialout(priv, STM32_USART_CR1_OFFSET, cr1);
up_serialout(priv, STM32_USART_BRR_OFFSET, brr);
#else
/* This second implementation is for U[S]ARTs that support fractional
* dividers.
*/
struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
uint32_t usartdiv32;
uint32_t mantissa;
@ -973,6 +1033,8 @@ static void up_setspeed(struct uart_dev_s *dev)
fraction = (usartdiv32 - (mantissa << 5) + 1) >> 1;
brr |= fraction << USART_BRR_FRAC_SHIFT;
up_serialout(priv, STM32_USART_BRR_OFFSET, brr);
#endif
}
#endif
@ -1031,6 +1093,7 @@ static int up_setup(struct uart_dev_s *dev)
{
regval |= USART_CR2_STOP2;
}
up_serialout(priv, STM32_USART_CR2_OFFSET, regval);
/* Configure CR1 */
@ -1077,6 +1140,7 @@ static int up_setup(struct uart_dev_s *dev)
regval = up_serialin(priv, STM32_USART_CR1_OFFSET);
regval |= (USART_CR1_UE|USART_CR1_TE|USART_CR1_RE);
up_serialout(priv, STM32_USART_CR1_OFFSET, regval);
#endif
/* Set up the cached interrupt enables value */
@ -1119,7 +1183,7 @@ static int up_dma_setup(struct uart_dev_s *dev)
/* Configure for circular DMA reception into the RX fifo */
stm32_dmasetup(priv->rxdma,
priv->usartbase + STM32_USART_DR_OFFSET,
priv->usartbase + STM32_USART_RDR_OFFSET,
(uint32_t)priv->rxfifo,
RXDMA_BUFFER_SIZE,
SERIAL_DMA_CONTROL_WORD);
@ -1351,7 +1415,7 @@ static int up_interrupt_common(struct up_dev_s *priv)
* good byte will be lost.
*/
(void)up_serialin(priv, STM32_USART_DR_OFFSET);
(void)up_serialin(priv, STM32_USART_RDR_OFFSET);
}
/* Handle outgoing, transmit bytes */
@ -1510,20 +1574,20 @@ static int up_ioctl(struct file *filep, int cmd, unsigned long arg)
static int up_receive(struct uart_dev_s *dev, uint32_t *status)
{
struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
uint32_t dr;
uint32_t rdr;
/* Get the Rx byte */
dr = up_serialin(priv, STM32_USART_DR_OFFSET);
rdr = up_serialin(priv, STM32_USART_RDR_OFFSET);
/* Get the Rx byte plux error information. Return those in status */
*status = priv->sr << 16 | dr;
*status = priv->sr << 16 | rdr;
priv->sr = 0;
/* Then return the actual received byte */
return dr & 0xff;
return rdr & 0xff;
}
#endif
@ -1693,7 +1757,7 @@ static void up_send(struct uart_dev_s *dev, int ch)
if (priv->rs485_dir_gpio != 0)
stm32_gpiowrite(priv->rs485_dir_gpio, priv->rs485_dir_polarity);
#endif
up_serialout(priv, STM32_USART_DR_OFFSET, (uint32_t)ch);
up_serialout(priv, STM32_USART_TDR_OFFSET, (uint32_t)ch);
}
/****************************************************************************

View file

@ -77,7 +77,7 @@
#include "up_arch.h"
#include "chip.h"
#include "stm32_internal.h"
#include "stm32.h"
#include "stm32_gpio.h"
#include "stm32_dma.h"
#include "stm32_spi.h"
@ -130,7 +130,7 @@
/* DMA channel configuration */
#if defined(CONFIG_STM32_STM32F10XX)
#if defined(CONFIG_STM32_STM32F10XX) || defined(CONFIG_STM32_STM32F30XX)
# define SPI_RXDMA16_CONFIG (SPI_DMA_PRIO|DMA_CCR_MSIZE_16BITS|DMA_CCR_PSIZE_16BITS|DMA_CCR_MINC )
# define SPI_RXDMA8_CONFIG (SPI_DMA_PRIO|DMA_CCR_MSIZE_8BITS |DMA_CCR_PSIZE_8BITS |DMA_CCR_MINC )
# define SPI_RXDMA16NULL_CONFIG (SPI_DMA_PRIO|DMA_CCR_MSIZE_8BITS |DMA_CCR_PSIZE_16BITS )

View file

@ -46,7 +46,7 @@
#include "up_arch.h"
#include "up_internal.h"
#include "stm32_internal.h"
#include "stm32.h"
#include "stm32_gpio.h"
#ifdef CONFIG_ARCH_FPU

View file

@ -59,7 +59,7 @@
#include "up_internal.h"
#include "up_arch.h"
#include "stm32_internal.h"
#include "stm32.h"
#include "stm32_gpio.h"
#include "stm32_tim.h"

View file

@ -51,7 +51,7 @@
#include "up_arch.h"
#include "chip.h"
#include "stm32_internal.h"
#include "stm32.h"
/****************************************************************************
* Definitions

View file

@ -59,7 +59,8 @@
#include <arch/irq.h>
#include "up_arch.h"
#include "stm32_internal.h"
#include "stm32.h"
#include "stm32_syscfg.h"
#include "stm32_usbdev.h"
#if defined(CONFIG_USBDEV) && defined(CONFIG_STM32_USB)
@ -78,6 +79,20 @@
# define CONFIG_USB_PRI NVIC_SYSH_PRIORITY_DEFAULT
#endif
/* USB Interrupts. Should be re-mapped if CAN is used. */
#ifdef CONFIG_STM32_STM32F30XX
# ifdef CONFIG_STM32_USB_ITRMP
# define STM32_IRQ_USBHP STM32_IRQ_USBHP_1
# define STM32_IRQ_USBLP STM32_IRQ_USBLP_1
# define STM32_IRQ_USBWKUP STM32_IRQ_USBWKUP_1
# else
# define STM32_IRQ_USBHP STM32_IRQ_USBHP_2
# define STM32_IRQ_USBLP STM32_IRQ_USBLP_2
# define STM32_IRQ_USBWKUP STM32_IRQ_USBWKUP_2
# endif
#endif
/* Extremely detailed register debug that you would normally never want
* enabled.
*/
@ -1014,7 +1029,7 @@ static void stm32_copytopma(const uint8_t *buffer, uint16_t pma, uint16_t nbytes
/* Copy loop. Source=user buffer, Dest=packet memory */
dest = (uint16_t*)(STM32_USBCANRAM_BASE + ((uint32_t)pma << 1));
dest = (uint16_t*)(STM32_USBRAM_BASE + ((uint32_t)pma << 1));
for (i = nwords; i != 0; i--)
{
/* Read two bytes and pack into on 16-bit word */
@ -1044,7 +1059,7 @@ stm32_copyfrompma(uint8_t *buffer, uint16_t pma, uint16_t nbytes)
/* Copy loop. Source=packet memory, Dest=user buffer */
src = (uint32_t*)(STM32_USBCANRAM_BASE + ((uint32_t)pma << 1));
src = (uint32_t*)(STM32_USBRAM_BASE + ((uint32_t)pma << 1));
for (i = nwords; i != 0; i--)
{
/* Copy 16-bits from packet memory to user buffer. */
@ -3470,6 +3485,20 @@ void up_usbinitialize(void)
stm32_hwsetup(priv);
/* Remap the USB interrupt as needed (Only supported by the STM32 F3 family) */
#ifdef CONFIG_STM32_STM32F30XX
# ifdef CONFIG_STM32_USB_ITRMP
/* Clear the ITRMP bit to use the legacy, shared USB/CAN interrupts */
modifyreg32(STM32_RCC_APB1ENR, SYSCFG_CFGR1_USB_ITRMP, 0);
# else
/* Set the ITRMP bit to use the STM32 F3's dedicated USB interrupts */
modifyreg32(STM32_RCC_APB1ENR, 0, SYSCFG_CFGR1_USB_ITRMP);
# endif
#endif
/* Attach USB controller interrupt handlers. The hardware will not be
* initialized and interrupts will not be enabled until the class device
* driver is bound. Getting the IRQs here only makes sure that we have

View file

@ -54,7 +54,7 @@
#include "os_internal.h"
#include "chip.h"
#include "stm32_dma.h"
#include "stm32_internal.h"
#include "stm32.h"
/* Only for the STM32F10xx family for now */

View file

@ -54,7 +54,7 @@
#include "os_internal.h"
#include "chip.h"
#include "stm32_dma.h"
#include "stm32_internal.h"
#include "stm32.h"
/* This file supports only the STM32 F2 family (although it is identical to
* the corresponding F4 file).

View file

@ -54,7 +54,7 @@
#include "os_internal.h"
#include "chip.h"
#include "stm32_dma.h"
#include "stm32_internal.h"
#include "stm32.h"
/* This file supports only the STM32 F4 family (an probably the F2 family
* as well?)

View file

@ -48,7 +48,7 @@
#endif
#include "stm32_rcc.h"
#include "stm32_sdio.h"
#include "stm32_internal.h"
#include "stm32.h"
#include <nuttx/arch.h>

View file

@ -51,7 +51,7 @@
#include "chip.h"
#include "up_arch.h"
#include "up_internal.h"
#include "stm32_internal.h"
#include "stm32.h"
#include "cloudctrl-internal.h"
/****************************************************************************

View file

@ -46,7 +46,7 @@
#include <debug.h>
#include <errno.h>
#include "stm32_internal.h"
#include "stm32.h"
#include "cloudctrl-internal.h"
/****************************************************************************

View file

@ -50,7 +50,7 @@
#include "up_arch.h"
#include "chip.h"
#include "stm32_internal.h"
#include "stm32.h"
#include "cloudctrl-internal.h"
#if defined(CONFIG_STM32_SPI1) || defined(CONFIG_STM32_SPI3)

View file

@ -53,7 +53,7 @@
#include <nuttx/usb/usbdev_trace.h>
#include "up_arch.h"
#include "stm32_internal.h"
#include "stm32.h"
#include "cloudctrl-internal.h"
#ifdef CONFIG_STM32_OTGFS

View file

@ -46,7 +46,7 @@
#include <debug.h>
#include <errno.h>
#include "stm32_internal.h"
#include "stm32.h"
/****************************************************************************
* Pre-Processor Definitions

View file

@ -50,7 +50,7 @@
#include "chip.h"
#include "up_arch.h"
#include "up_internal.h"
#include "stm32_internal.h"
#include "stm32.h"
#include "cloudctrl-internal.h"
#ifndef CONFIG_ARCH_LEDS

View file

@ -47,7 +47,7 @@
#endif
#include "stm32_rcc.h"
#include "stm32_sdio.h"
#include "stm32_internal.h"
#include "stm32.h"
/************************************************************************************
* Definitions

View file

@ -50,7 +50,7 @@
#include "chip.h"
#include "up_arch.h"
#include "up_internal.h"
#include "stm32_internal.h"
#include "stm32.h"
#include "fire-internal.h"
/****************************************************************************

View file

@ -45,7 +45,7 @@
#include <debug.h>
#include <errno.h>
#include "stm32_internal.h"
#include "stm32.h"
#include "fire-internal.h"
/****************************************************************************

View file

@ -51,7 +51,7 @@
#include "stm32_fsmc.h"
#include "stm32_gpio.h"
#include "stm32_internal.h"
#include "stm32.h"
#include "fire-internal.h"
#ifdef CONFIG_STM32_FSMC

View file

@ -49,7 +49,7 @@
#include "up_arch.h"
#include "chip.h"
#include "stm32_internal.h"
#include "stm32.h"
#include "fire-internal.h"
#if defined(CONFIG_STM32_SPI1) || defined(CONFIG_STM32_SPI2)

View file

@ -49,7 +49,7 @@
#include <nuttx/usb/usbdev_trace.h>
#include "up_arch.h"
#include "stm32_internal.h"
#include "stm32.h"
#include "fire-internal.h"
/************************************************************************************

View file

@ -45,7 +45,7 @@
#include <debug.h>
#include <errno.h>
#include "stm32_internal.h"
#include "stm32.h"
/****************************************************************************
* Pre-Processor Definitions

View file

@ -49,7 +49,7 @@
#include "chip.h"
#include "up_arch.h"
#include "up_internal.h"
#include "stm32_internal.h"
#include "stm32.h"
#include "fire-internal.h"
#ifndef CONFIG_ARCH_LEDS

View file

@ -52,7 +52,7 @@
#endif
#include "stm32_rcc.h"
#include "stm32_sdio.h"
#include "stm32_internal.h"
#include "stm32.h"
/************************************************************************************
* Definitions

View file

@ -51,7 +51,6 @@
#include "up_arch.h"
#include "stm32.h"
#include "stm32_internal.h"
#include "hymini_stm32v-internal.h"
#include "ssd1289.h"

View file

@ -50,7 +50,7 @@
#include "chip.h"
#include "up_arch.h"
#include "up_internal.h"
#include "stm32_internal.h"
#include "stm32.h"
#include "hymini_stm32v-internal.h"
/****************************************************************************

View file

@ -55,7 +55,7 @@
# include <nuttx/mmcsd.h>
#endif
#include "stm32_internal.h"
#include "stm32.h"
#include "hymini_stm32v-internal.h"
/****************************************************************************

View file

@ -50,7 +50,7 @@
#include "up_arch.h"
#include "chip.h"
#include "stm32_internal.h"
#include "stm32.h"
#include "hymini_stm32v-internal.h"
#if defined(CONFIG_STM32_SPI1) || defined(CONFIG_STM32_SPI2)

View file

@ -43,7 +43,6 @@
#include <debug.h>
#include "stm32.h"
#include "stm32_internal.h"
#include "hymini_stm32v-internal.h"
#include <nuttx/input/touchscreen.h>

View file

@ -49,7 +49,7 @@
#include <nuttx/usb/usbdev_trace.h>
#include "up_arch.h"
#include "stm32_internal.h"
#include "stm32.h"
#include "hymini_stm32v-internal.h"
/************************************************************************************

View file

@ -48,7 +48,7 @@
#include <nuttx/sdio.h>
#include <nuttx/mmcsd.h>
#include "stm32_internal.h"
#include "stm32.h"
/* There is nothing to do here if SDIO support is not selected. */

View file

@ -47,7 +47,7 @@
#endif
#include "stm32_rcc.h"
#include "stm32_sdio.h"
#include "stm32_internal.h"
#include "stm32.h"
/************************************************************************************
* Pre-processor Definitions

View file

@ -47,7 +47,7 @@
#endif
#include "stm32_rcc.h"
#include "stm32_sdio.h"
#include "stm32_internal.h"
#include "stm32.h"
#include <nuttx/arch.h>

View file

@ -50,7 +50,7 @@
#include "chip.h"
#include "up_arch.h"
#include "up_internal.h"
#include "stm32_internal.h"
#include "stm32.h"
#include "shenzhou-internal.h"
/****************************************************************************

View file

@ -128,7 +128,6 @@
#include "up_arch.h"
#include "stm32.h"
#include "stm32_internal.h"
#include "shenzhou-internal.h"
/************************************************************************************

View file

@ -45,7 +45,7 @@
#include <debug.h>
#include <errno.h>
#include "stm32_internal.h"
#include "stm32.h"
#include "shenzhou-internal.h"
/****************************************************************************

View file

@ -49,7 +49,7 @@
#include "up_arch.h"
#include "chip.h"
#include "stm32_internal.h"
#include "stm32.h"
#include "shenzhou-internal.h"
#if defined(CONFIG_STM32_SPI1) || defined(CONFIG_STM32_SPI3)

View file

@ -59,7 +59,6 @@
#include "up_arch.h"
#include "stm32.h"
#include "stm32_internal.h"
#include "shenzhou-internal.h"
#ifdef CONFIG_LCD_SSD1289

View file

@ -51,7 +51,7 @@
#include <nuttx/input/touchscreen.h>
#include <nuttx/input/ads7843e.h>
#include "stm32_internal.h"
#include "stm32.h"
#include "shenzhou-internal.h"
/****************************************************************************

View file

@ -52,7 +52,7 @@
#include <nuttx/usb/usbdev_trace.h>
#include "up_arch.h"
#include "stm32_internal.h"
#include "stm32.h"
#include "shenshou-internal.h"
#ifdef CONFIG_STM32_OTGFS

View file

@ -45,7 +45,7 @@
#include <debug.h>
#include <errno.h>
#include "stm32_internal.h"
#include "stm32.h"
/****************************************************************************
* Pre-Processor Definitions

View file

@ -49,7 +49,7 @@
#include "chip.h"
#include "up_arch.h"
#include "up_internal.h"
#include "stm32_internal.h"
#include "stm32.h"
#include "shenzhou-internal.h"
#ifndef CONFIG_ARCH_LEDS

View file

@ -47,7 +47,7 @@
#endif
#include "stm32_rcc.h"
#include "stm32_sdio.h"
#include "stm32_internal.h"
#include "stm32.h"
/************************************************************************************
* Definitions

View file

@ -49,7 +49,7 @@
#include <nuttx/mmcsd.h>
#include <nuttx/usb/composite.h>
#include "stm32_internal.h"
#include "stm32.h"
/* There is nothing to do here if SDIO support is not selected. */

View file

@ -51,7 +51,7 @@
#include "stm32_fsmc.h"
#include "stm32_gpio.h"
#include "stm32_internal.h"
#include "stm32.h"
#include "stm3210e-internal.h"
/************************************************************************************

View file

@ -76,7 +76,6 @@
#include "up_arch.h"
#include "stm32.h"
#include "stm32_internal.h"
#include "stm3210e-internal.h"
/**************************************************************************************

View file

@ -50,7 +50,7 @@
#include "chip.h"
#include "up_arch.h"
#include "up_internal.h"
#include "stm32_internal.h"
#include "stm32.h"
#include "stm3210e-internal.h"
/****************************************************************************

View file

@ -55,7 +55,7 @@
# include <nuttx/mmcsd.h>
#endif
#include "stm32_internal.h"
#include "stm32.h"
/****************************************************************************
* Pre-Processor Definitions

View file

@ -49,7 +49,7 @@
#include "up_arch.h"
#include "chip.h"
#include "stm32_internal.h"
#include "stm32.h"
#include "stm3210e-internal.h"
#if defined(CONFIG_STM32_SPI1) || defined(CONFIG_STM32_SPI2)

View file

@ -49,7 +49,7 @@
#include <nuttx/usb/usbdev_trace.h>
#include "up_arch.h"
#include "stm32_internal.h"
#include "stm32.h"
#include "stm3210e-internal.h"
/************************************************************************************

View file

@ -48,7 +48,7 @@
#include <nuttx/sdio.h>
#include <nuttx/mmcsd.h>
#include "stm32_internal.h"
#include "stm32.h"
/* There is nothing to do here if SDIO support is not selected. */

View file

@ -49,7 +49,7 @@
#include "stm32_rcc.h"
#include "stm32_sdio.h"
#include "stm32_internal.h"
#include "stm32.h"
/************************************************************************************
* Definitions

View file

@ -49,7 +49,7 @@
#include "chip.h"
#include "up_arch.h"
#include "up_internal.h"
#include "stm32_internal.h"
#include "stm32.h"
#include "stm3220g-internal.h"
#ifdef CONFIG_ARCH_LEDS

View file

@ -51,7 +51,7 @@
#include "stm32_fsmc.h"
#include "stm32_gpio.h"
#include "stm32_internal.h"
#include "stm32.h"
#include "stm3220g-internal.h"
/************************************************************************************

View file

@ -61,7 +61,6 @@
#include "up_arch.h"
#include "stm32.h"
#include "stm32_internal.h"
#include "stm3220g-internal.h"
#if !defined(CONFIG_STM32_ILI9320_DISABLE) || !defined(CONFIG_STM32_ILI9325_DISABLE)

View file

@ -59,7 +59,7 @@
# include "stm32_usbhost.h"
#endif
#include "stm32_internal.h"
#include "stm32.h"
#include "stm3220g-internal.h"
/****************************************************************************

View file

@ -49,7 +49,7 @@
#include "up_arch.h"
#include "chip.h"
#include "stm32_internal.h"
#include "stm32.h"
#include "stm3220g-internal.h"
#if defined(CONFIG_STM32_SPI1) || defined(CONFIG_STM32_SPI2) || defined(CONFIG_STM32_SPI3)

View file

@ -51,7 +51,7 @@
#include <arch/irq.h>
#include "stm32_internal.h"
#include "stm32.h"
#include "stm3220g-internal.h"
/****************************************************************************

View file

@ -52,7 +52,7 @@
#include <nuttx/usb/usbdev_trace.h>
#include "up_arch.h"
#include "stm32_internal.h"
#include "stm32.h"
#include "stm3220g-internal.h"
#ifdef CONFIG_STM32_OTGFS

View file

@ -49,7 +49,7 @@
#include "chip.h"
#include "up_arch.h"
#include "up_internal.h"
#include "stm32_internal.h"
#include "stm32.h"
#include "stm3220g-internal.h"
#ifndef CONFIG_ARCH_LEDS

View file

@ -47,7 +47,7 @@
#endif
#include "stm32_rcc.h"
#include "stm32_sdio.h"
#include "stm32_internal.h"
#include "stm32.h"
/************************************************************************************
* Definitions

View file

@ -49,7 +49,7 @@
#include "chip.h"
#include "up_arch.h"
#include "up_internal.h"
#include "stm32_internal.h"
#include "stm32.h"
#include "stm3240g-internal.h"
#ifdef CONFIG_ARCH_LEDS

View file

@ -51,7 +51,7 @@
#include "stm32_fsmc.h"
#include "stm32_gpio.h"
#include "stm32_internal.h"
#include "stm32.h"
#include "stm3240g-internal.h"
/************************************************************************************

View file

@ -61,7 +61,6 @@
#include "up_arch.h"
#include "stm32.h"
#include "stm32_internal.h"
#include "stm3240g-internal.h"
#if !defined(CONFIG_STM32_ILI9320_DISABLE) || !defined(CONFIG_STM32_ILI9325_DISABLE)

View file

@ -59,7 +59,7 @@
# include "stm32_usbhost.h"
#endif
#include "stm32_internal.h"
#include "stm32.h"
#include "stm3240g-internal.h"
/****************************************************************************

View file

@ -49,7 +49,7 @@
#include "up_arch.h"
#include "chip.h"
#include "stm32_internal.h"
#include "stm32.h"
#include "stm3240g-internal.h"
#if defined(CONFIG_STM32_SPI1) || defined(CONFIG_STM32_SPI2) || defined(CONFIG_STM32_SPI3)

View file

@ -51,7 +51,7 @@
#include <arch/irq.h>
#include "stm32_internal.h"
#include "stm32.h"
#include "stm3240g-internal.h"
/****************************************************************************

View file

@ -52,7 +52,7 @@
#include <nuttx/usb/usbdev_trace.h>
#include "up_arch.h"
#include "stm32_internal.h"
#include "stm32.h"
#include "stm3240g-internal.h"
#ifdef CONFIG_STM32_OTGFS

View file

@ -49,7 +49,7 @@
#include "chip.h"
#include "up_arch.h"
#include "up_internal.h"
#include "stm32_internal.h"
#include "stm32.h"
#include "stm3240g-internal.h"
#ifndef CONFIG_ARCH_LEDS

View file

@ -46,7 +46,7 @@
# include <stdint.h>
#endif
#include "stm32_rcc.h"
#include "stm32_internal.h"
#include "stm32.h"
/************************************************************************************
* Definitions

View file

@ -50,7 +50,7 @@
#include "chip.h"
#include "up_arch.h"
#include "up_internal.h"
#include "stm32_internal.h"
#include "stm32.h"
#include "stm32f100rc_internal.h"
/****************************************************************************

View file

@ -49,7 +49,7 @@
#include "stm32_rcc.h"
#include "stm32_sdio.h"
#include "stm32_internal.h"
#include "stm32.h"
/************************************************************************************
* Definitions

View file

@ -56,7 +56,7 @@ ifeq ($(CONFIG_ARCH_BUTTONS),y)
CSRCS += up_buttons.c
endif
ifeq ($(CONFIG_STM32_OTGFS),y)
ifeq ($(CONFIG_STM32_USB),y)
CSRCS += up_usb.c
endif

View file

@ -158,23 +158,10 @@ void weak_function stm32_spiinitialize(void);
*
****************************************************************************************************/
#ifdef CONFIG_STM32_OTGFS
#ifdef CONFIG_STM32_USB
void weak_function stm32_usbinitialize(void);
#endif
/****************************************************************************************************
* Name: stm32_usbhost_initialize
*
* Description:
* Called at application startup time to initialize the USB host functionality. This function will
* start a thread that will monitor for device connection/disconnection events.
*
****************************************************************************************************/
#if defined(CONFIG_STM32_OTGFS) && defined(CONFIG_USBHOST)
int stm32_usbhost_initialize(void);
#endif
#endif /* __ASSEMBLY__ */
#endif /* __CONFIGS_STM32F3DISCOVERY_SRC_STM32F3DISCOVERY_INTERNAL_H */

View file

@ -82,13 +82,12 @@ void stm32_boardinitialize(void)
}
#endif
/* Initialize USB if the 1) OTG FS controller is in the configuration and 2)
/* Initialize USB if the 1) USB device controller is in the configuration and 2)
* disabled, and 3) the weak function stm32_usbinitialize() has been brought
* the weak function stm32_usbinitialize() has been brought into the build.
* Presumeably either CONFIG_USBDEV or CONFIG_USBHOST is also selected.
* into the build. Presumeably either CONFIG_USBDEV is also selected.
*/
#ifdef CONFIG_STM32_OTGFS
#ifdef CONFIG_STM32_USB
if (stm32_usbinitialize)
{
stm32_usbinitialize();

View file

@ -58,7 +58,7 @@
# include "stm32_usbhost.h"
#endif
#include "stm32_internal.h"
#include "stm32.h"
#include "stm32f3discovery-internal.h"
/****************************************************************************

View file

@ -50,7 +50,7 @@
#include "up_arch.h"
#include "chip.h"
#include "stm32_internal.h"
#include "stm32.h"
#include "stm32f3discovery-internal.h"
#if defined(CONFIG_STM32_SPI1) || defined(CONFIG_STM32_SPI2) || defined(CONFIG_STM32_SPI3)

View file

@ -52,83 +52,30 @@
#include <nuttx/usb/usbdev_trace.h>
#include "up_arch.h"
#include "stm32_internal.h"
#include "stm32.h"
#include "stm32f3discovery-internal.h"
#ifdef CONFIG_STM32_OTGFS
#ifdef CONFIG_STM32_USB
/************************************************************************************
* Pre-processor Definitions
************************************************************************************/
#if defined(CONFIG_USBDEV) || defined(CONFIG_USBHOST)
#ifdef CONFIG_USBDEV
# define HAVE_USB 1
#else
# warning "CONFIG_STM32_OTGFS is enabled but neither CONFIG_USBDEV nor CONFIG_USBHOST"
# warning "CONFIG_STM32_USB is enabled but CONFIG_USBDEV is not"
# 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
************************************************************************************/
@ -144,131 +91,24 @@ static int usbhost_waiter(int argc, char *argv[])
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
/* Does the STM32 F3 hava an external soft pull-up? */
}
/***********************************************************************************
* 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
* Name: stm32_usbpullup
*
* 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
* If USB is supported and the board supports a pullup via GPIO (for USB software
* connect and disconnect), then the board software must provide stm32_pullup.
* See include/nuttx/usb/usbdev.h for additional description of this method.
*
************************************************************************************/
#ifdef CONFIG_USBHOST
xcpt_t stm32_setup_overcurrent(xcpt_t handler)
int stm32_usbpullup(FAR struct usbdev_s *dev, bool enable)
{
return stm32_gpiosetevent(GPIO_OTGFS_OVER, true, true, true, handler);
usbtrace(TRACE_DEVPULLUP, (uint16_t)enable);
return OK;
}
#endif
/************************************************************************************
* Name: stm32_usbsuspend
@ -281,14 +121,12 @@ xcpt_t stm32_setup_overcurrent(xcpt_t handler)
*
************************************************************************************/
#ifdef CONFIG_USBDEV
void stm32_usbsuspend(FAR struct usbdev_s *dev, bool resume)
{
ulldbg("resume: %d\n", resume);
}
#endif
#endif /* CONFIG_STM32_OTGFS */
#endif /* CONFIG_STM32_USB */

View file

@ -49,7 +49,7 @@
#include "stm32_rcc.h"
#include "stm32_sdio.h"
#include "stm32_internal.h"
#include "stm32.h"
/************************************************************************************
* Definitions

View file

@ -49,7 +49,7 @@
#include "chip.h"
#include "up_arch.h"
#include "up_internal.h"
#include "stm32_internal.h"
#include "stm32.h"
#include "stm32f4discovery-internal.h"
#ifdef CONFIG_ARCH_LEDS

View file

@ -84,8 +84,8 @@ void stm32_boardinitialize(void)
/* Initialize USB if the 1) OTG FS controller is in the configuration and 2)
* disabled, and 3) the weak function stm32_usbinitialize() has been brought
* the weak function stm32_usbinitialize() has been brought into the build.
* Presumeably either CONFIG_USBDEV or CONFIG_USBHOST is also selected.
* into the build. Presumeably either CONFIG_USBDEV or CONFIG_USBHOST is also
* selected.
*/
#ifdef CONFIG_STM32_OTGFS

View file

@ -51,7 +51,7 @@
#include "stm32_fsmc.h"
#include "stm32_gpio.h"
#include "stm32_internal.h"
#include "stm32.h"
#include "stm32f4discovery-internal.h"
/************************************************************************************

View file

@ -58,7 +58,7 @@
# include "stm32_usbhost.h"
#endif
#include "stm32_internal.h"
#include "stm32.h"
#include "stm32f4discovery-internal.h"
/****************************************************************************

View file

@ -50,7 +50,7 @@
#include "up_arch.h"
#include "chip.h"
#include "stm32_internal.h"
#include "stm32.h"
#include "stm32f4discovery-internal.h"
#if defined(CONFIG_STM32_SPI1) || defined(CONFIG_STM32_SPI2) || defined(CONFIG_STM32_SPI3)

Some files were not shown because too many files have changed in this diff Show more