aboutsummaryrefslogtreecommitdiff
path: root/nuttx/arch
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2013-02-17 15:29:31 +0100
committerLorenz Meier <lm@inf.ethz.ch>2013-02-17 15:29:31 +0100
commit8f8e30052bc6fb9a833b53570e8e836ea6686f1f (patch)
treee1b75b27fdb3c4a8942ead12a17b054d36cb0a7b /nuttx/arch
parent6bd18e46bb3b250213bb64d9b0da2e71ddc912ab (diff)
parentcaa11f0bbb7f30679c5c01a64e1d0f6d8627db9d (diff)
downloadpx4-firmware-8f8e30052bc6fb9a833b53570e8e836ea6686f1f.tar.gz
px4-firmware-8f8e30052bc6fb9a833b53570e8e836ea6686f1f.tar.bz2
px4-firmware-8f8e30052bc6fb9a833b53570e8e836ea6686f1f.zip
Merged
Diffstat (limited to 'nuttx/arch')
-rw-r--r--nuttx/arch/arm/src/armv7-m/Toolchain.defs42
-rw-r--r--nuttx/arch/arm/src/armv7-m/up_assert.c7
-rw-r--r--nuttx/arch/arm/src/armv7-m/up_reprioritizertr.c13
-rw-r--r--nuttx/arch/arm/src/common/up_exit.c46
-rw-r--r--nuttx/arch/arm/src/common/up_initialize.c14
-rw-r--r--nuttx/arch/arm/src/common/up_internal.h17
-rw-r--r--nuttx/arch/arm/src/stm32/chip/stm32_spi.h8
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_adc.c315
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_adc.h6
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_i2c.c89
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_otgfsdev.c129
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_serial.c12
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_spi.c51
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_usbdev.c14
14 files changed, 312 insertions, 451 deletions
diff --git a/nuttx/arch/arm/src/armv7-m/Toolchain.defs b/nuttx/arch/arm/src/armv7-m/Toolchain.defs
index 45ee9e36c..4de5b49f4 100644
--- a/nuttx/arch/arm/src/armv7-m/Toolchain.defs
+++ b/nuttx/arch/arm/src/armv7-m/Toolchain.defs
@@ -1,7 +1,7 @@
############################################################################
# arch/arm/src/armv7-m/Toolchain.defs
#
-# Copyright (C) 2012 Gregory Nutt. All rights reserved.
+# Copyright (C) 2012-2013 Gregory Nutt. All rights reserved.
# Author: Gregory Nutt <gnutt@nuttx.org>
#
# Redistribution and use in source and binary forms, with or without
@@ -141,8 +141,8 @@ endif
# Atollic toolchain under Windows
ifeq ($(CONFIG_ARMV7M_TOOLCHAIN),ATOLLIC)
- CROSSDEV = arm-atollic-eabi-
- ARCROSSDEV = arm-atollic-eabi-
+ CROSSDEV ?= arm-atollic-eabi-
+ ARCROSSDEV ?= arm-atollic-eabi-
ifneq ($(CONFIG_WINDOWS_NATIVE),y)
WINTOOL = y
endif
@@ -161,12 +161,12 @@ endif
ifeq ($(CONFIG_ARMV7M_TOOLCHAIN),BUILDROOT)
ifeq ($(CONFIG_ARMV7M_OABI_TOOLCHAIN),y)
- CROSSDEV = arm-nuttx-elf-
- ARCROSSDEV = arm-nuttx-elf-
+ CROSSDEV ?= arm-nuttx-elf-
+ ARCROSSDEV ?= arm-nuttx-elf-
ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft
else
- CROSSDEV = arm-nuttx-eabi-
- ARCROSSDEV = arm-nuttx-eabi-
+ CROSSDEV ?= arm-nuttx-eabi-
+ ARCROSSDEV ?= arm-nuttx-eabi-
ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft
endif
MAXOPTIMIZATION = -Os
@@ -175,8 +175,8 @@ endif
# Code Red RedSuite under Linux
ifeq ($(CONFIG_ARMV7M_TOOLCHAIN),CODEREDL)
- CROSSDEV = arm-none-eabi-
- ARCROSSDEV = arm-none-eabi-
+ CROSSDEV ?= arm-none-eabi-
+ ARCROSSDEV ?= arm-none-eabi-
ifeq ($(CONFIG_ARCH_CORTEXM4),y)
ifeq ($(CONFIG_ARCH_FPU),y)
ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -march=armv7e-m -mfpu=fpv4-sp-d16 -mfloat-abi=hard
@@ -191,8 +191,8 @@ endif
# Code Red RedSuite under Windows
ifeq ($(CONFIG_ARMV7M_TOOLCHAIN),CODEREDW)
- CROSSDEV = arm-none-eabi-
- ARCROSSDEV = arm-none-eabi-
+ CROSSDEV ?= arm-none-eabi-
+ ARCROSSDEV ?= arm-none-eabi-
ifneq ($(CONFIG_WINDOWS_NATIVE),y)
WINTOOL = y
endif
@@ -210,8 +210,8 @@ endif
# CodeSourcery under Linux
ifeq ($(CONFIG_ARMV7M_TOOLCHAIN),CODESOURCERYL)
- CROSSDEV = arm-none-eabi-
- ARCROSSDEV = arm-none-eabi-
+ CROSSDEV ?= arm-none-eabi-
+ ARCROSSDEV ?= arm-none-eabi-
ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft
MAXOPTIMIZATION = -O2
endif
@@ -219,8 +219,8 @@ endif
# CodeSourcery under Windows
ifeq ($(CONFIG_ARMV7M_TOOLCHAIN),CODESOURCERYW)
- CROSSDEV = arm-none-eabi-
- ARCROSSDEV = arm-none-eabi-
+ CROSSDEV ?= arm-none-eabi-
+ ARCROSSDEV ?= arm-none-eabi-
ifneq ($(CONFIG_WINDOWS_NATIVE),y)
WINTOOL = y
endif
@@ -230,8 +230,8 @@ endif
# devkitARM under Windows
ifeq ($(CONFIG_ARMV7M_TOOLCHAIN),DEVKITARM)
- CROSSDEV = arm-eabi-
- ARCROSSDEV = arm-eabi-
+ CROSSDEV ?= arm-eabi-
+ ARCROSSDEV ?= arm-eabi-
ifneq ($(CONFIG_WINDOWS_NATIVE),y)
WINTOOL = y
endif
@@ -241,8 +241,8 @@ endif
# Generic GNU EABI toolchain on OS X, Linux or any typical Posix system
ifeq ($(CONFIG_ARMV7M_TOOLCHAIN),GNU_EABI)
- CROSSDEV = arm-none-eabi-
- ARCROSSDEV = arm-none-eabi-
+ CROSSDEV ?= arm-none-eabi-
+ ARCROSSDEV ?= arm-none-eabi-
MAXOPTIMIZATION = -O3
ifeq ($(CONFIG_ARCH_CORTEXM4),y)
ifeq ($(CONFIG_ARCH_FPU),y)
@@ -258,8 +258,8 @@ endif
# Raisonance RIDE7 under Windows
ifeq ($(CONFIG_ARMV7M_TOOLCHAIN),RAISONANCE)
- CROSSDEV = arm-none-eabi-
- ARCROSSDEV = arm-none-eabi-
+ CROSSDEV ?= arm-none-eabi-
+ ARCROSSDEV ?= arm-none-eabi-
ifneq ($(CONFIG_WINDOWS_NATIVE),y)
WINTOOL = y
endif
diff --git a/nuttx/arch/arm/src/armv7-m/up_assert.c b/nuttx/arch/arm/src/armv7-m/up_assert.c
index ab30b09f3..b40b1090c 100644
--- a/nuttx/arch/arm/src/armv7-m/up_assert.c
+++ b/nuttx/arch/arm/src/armv7-m/up_assert.c
@@ -62,7 +62,7 @@
#ifdef CONFIG_ARCH_STACKDUMP
# undef lldbg
-# define lldbg lib_lowprintf
+# define lldbg lowsyslog
#endif
/* The following is just intended to keep some ugliness out of the mainline
@@ -70,7 +70,7 @@
*
* CONFIG_TASK_NAME_SIZE > 0 && <-- The task has a name
* (defined(CONFIG_DEBUG) || <-- And the debug is enabled (lldbg used)
- * defined(CONFIG_ARCH_STACKDUMP) <-- Or lib_lowprintf() is used
+ * defined(CONFIG_ARCH_STACKDUMP) <-- Or lowsyslog() is used
*/
#undef CONFIG_PRINT_TASKNAME
@@ -267,7 +267,8 @@ static void up_dumpstate(void)
* Name: _up_assert
****************************************************************************/
-static void _up_assert(int errorcode) /* noreturn_function */
+static void _up_assert(int errorcode) noreturn_function;
+static void _up_assert(int errorcode)
{
/* Are we in an interrupt handler or the idle task? */
diff --git a/nuttx/arch/arm/src/armv7-m/up_reprioritizertr.c b/nuttx/arch/arm/src/armv7-m/up_reprioritizertr.c
index f1c961b15..9a971f064 100644
--- a/nuttx/arch/arm/src/armv7-m/up_reprioritizertr.c
+++ b/nuttx/arch/arm/src/armv7-m/up_reprioritizertr.c
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/arm/src/armv7-m/up_reprioritizertr.c
*
- * Copyright (C) 2007-2009, 2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2009, 2012-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -89,9 +89,14 @@ void up_reprioritize_rtr(_TCB *tcb, uint8_t priority)
/* Verify that the caller is sane */
if (tcb->task_state < FIRST_READY_TO_RUN_STATE ||
- tcb->task_state > LAST_READY_TO_RUN_STATE ||
- priority < SCHED_PRIORITY_MIN ||
- priority > SCHED_PRIORITY_MAX)
+ tcb->task_state > LAST_READY_TO_RUN_STATE
+#if SCHED_PRIORITY_MIN > 0
+ || priority < SCHED_PRIORITY_MIN
+#endif
+#if SCHED_PRIORITY_MAX < UINT8_MAX
+ || priority > SCHED_PRIORITY_MAX
+#endif
+ )
{
PANIC(OSERR_BADREPRIORITIZESTATE);
}
diff --git a/nuttx/arch/arm/src/common/up_exit.c b/nuttx/arch/arm/src/common/up_exit.c
index 6f6d54f76..16f5c4442 100644
--- a/nuttx/arch/arm/src/common/up_exit.c
+++ b/nuttx/arch/arm/src/common/up_exit.c
@@ -1,7 +1,7 @@
/****************************************************************************
* common/up_exit.c
*
- * Copyright (C) 2007-2009, 2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2009, 201-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -75,7 +75,11 @@
#if defined(CONFIG_DUMP_ON_EXIT) && defined(CONFIG_DEBUG)
static void _up_dumponexit(FAR _TCB *tcb, FAR void *arg)
{
-#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NFILE_STREAMS > 0
+#if CONFIG_NFILE_DESCRIPTORS > 0
+ FAR struct filelist *filelist;
+#if CONFIG_NFILE_STREAMS > 0
+ FAR struct streamlist *streamlist;
+#endif
int i;
#endif
@@ -83,42 +87,32 @@ static void _up_dumponexit(FAR _TCB *tcb, FAR void *arg)
sdbg(" priority=%d state=%d\n", tcb->sched_priority, tcb->task_state);
#if CONFIG_NFILE_DESCRIPTORS > 0
- if (tcb->filelist)
+ filelist = tcb->group->tg_filelist;
+ for (i = 0; i < CONFIG_NFILE_DESCRIPTORS; i++)
{
- sdbg(" filelist refcount=%d\n",
- tcb->filelist->fl_crefs);
-
- for (i = 0; i < CONFIG_NFILE_DESCRIPTORS; i++)
+ struct inode *inode = filelist->fl_files[i].f_inode;
+ if (inode)
{
- struct inode *inode = tcb->filelist->fl_files[i].f_inode;
- if (inode)
- {
- sdbg(" fd=%d refcount=%d\n",
- i, inode->i_crefs);
- }
+ sdbg(" fd=%d refcount=%d\n",
+ i, inode->i_crefs);
}
}
#endif
#if CONFIG_NFILE_STREAMS > 0
- if (tcb->streams)
+ streamlist = tcb->group->tg_streamlist;
+ for (i = 0; i < CONFIG_NFILE_STREAMS; i++)
{
- sdbg(" streamlist refcount=%d\n",
- tcb->streams->sl_crefs);
-
- for (i = 0; i < CONFIG_NFILE_STREAMS; i++)
+ struct file_struct *filep = &streamlist->sl_streams[i];
+ if (filep->fs_filedes >= 0)
{
- struct file_struct *filep = &tcb->streams->sl_streams[i];
- if (filep->fs_filedes >= 0)
- {
#if CONFIG_STDIO_BUFFER_SIZE > 0
- sdbg(" fd=%d nbytes=%d\n",
- filep->fs_filedes,
- filep->fs_bufpos - filep->fs_bufstart);
+ sdbg(" fd=%d nbytes=%d\n",
+ filep->fs_filedes,
+ filep->fs_bufpos - filep->fs_bufstart);
#else
- sdbg(" fd=%d\n", filep->fs_filedes);
+ sdbg(" fd=%d\n", filep->fs_filedes);
#endif
- }
}
}
#endif
diff --git a/nuttx/arch/arm/src/common/up_initialize.c b/nuttx/arch/arm/src/common/up_initialize.c
index 80f9b1193..0ea3fcd35 100644
--- a/nuttx/arch/arm/src/common/up_initialize.c
+++ b/nuttx/arch/arm/src/common/up_initialize.c
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/arm/src/common/up_initialize.c
*
- * Copyright (C) 2007-2010, 2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2010, 2012-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -161,11 +161,17 @@ void up_initialize(void)
devnull_register(); /* Standard /dev/null */
#endif
- /* Initialize the console device driver */
+ /* Initialize the serial device driver */
-#if defined(USE_SERIALDRIVER)
+#ifdef USE_SERIALDRIVER
up_serialinit();
-#elif defined(CONFIG_DEV_LOWCONSOLE)
+#endif
+
+ /* Initialize the console device driver (if it is other than the standard
+ * serial driver).
+ */
+
+#if defined(CONFIG_DEV_LOWCONSOLE)
lowconsole_init();
#elif defined(CONFIG_RAMLOG_CONSOLE)
ramlog_consoleinit();
diff --git a/nuttx/arch/arm/src/common/up_internal.h b/nuttx/arch/arm/src/common/up_internal.h
index 55071345f..8a24f003e 100644
--- a/nuttx/arch/arm/src/common/up_internal.h
+++ b/nuttx/arch/arm/src/common/up_internal.h
@@ -1,7 +1,7 @@
/****************************************************************************
* common/up_internal.h
*
- * Copyright (C) 2007-2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -63,7 +63,10 @@
#undef CONFIG_SUPPRESS_UART_CONFIG /* DEFINED: Do not reconfig UART */
#undef CONFIG_DUMP_ON_EXIT /* DEFINED: Dump task state on exit */
-/* Determine which (if any) console driver to use */
+/* Determine which (if any) console driver to use. If a console is enabled
+ * and no other console device is specified, then a serial console is
+ * assumed.
+ */
#if !defined(CONFIG_DEV_CONSOLE) || CONFIG_NFILE_DESCRIPTORS == 0
# undef USE_SERIALDRIVER
@@ -84,6 +87,16 @@
# endif
#endif
+/* If some other device is used as the console, then the serial driver may
+ * still be needed. Let's assume that if the upper half serial driver is
+ * built, then the lower half will also be needed. There is no need for
+ * the early serial initialization in this case.
+ */
+
+#if !defined(USE_SERIALDRIVER) && defined(CONFIG_STANDARD_SERIAL)
+# define USE_SERIALDRIVER 1
+#endif
+
/* Determine which device to use as the system logging device */
#ifndef CONFIG_SYSLOG
diff --git a/nuttx/arch/arm/src/stm32/chip/stm32_spi.h b/nuttx/arch/arm/src/stm32/chip/stm32_spi.h
index d80c447bb..7731d03b0 100644
--- a/nuttx/arch/arm/src/stm32/chip/stm32_spi.h
+++ b/nuttx/arch/arm/src/stm32/chip/stm32_spi.h
@@ -47,7 +47,13 @@
* Pre-processor Definitions
************************************************************************************/
-#define STM32_SPI_CLK_MAX 18000000UL /* Maximum allowed speed as per specifications for all SPIs */
+/* Maximum allowed speed as per specifications for all SPIs */
+
+#if defined(CONFIG_STM32_STM32F40XX)
+# define STM32_SPI_CLK_MAX 37500000UL
+#else
+# define STM32_SPI_CLK_MAX 18000000UL
+#endif
/* Register Offsets *****************************************************************/
diff --git a/nuttx/arch/arm/src/stm32/stm32_adc.c b/nuttx/arch/arm/src/stm32/stm32_adc.c
index 844f1fd0f..b5033b057 100644
--- a/nuttx/arch/arm/src/stm32/stm32_adc.c
+++ b/nuttx/arch/arm/src/stm32/stm32_adc.c
@@ -118,25 +118,12 @@ struct stm32_dev_s
uint32_t freq; /* The desired frequency of conversions */
#endif
uint8_t chanlist[ADC_MAX_SAMPLES];
-#ifdef CONFIG_ADC_DMA
- const unsigned int rxdma_channel; /* DMA channel assigned */
- DMA_HANDLE rxdma; /* currently-open receive DMA stream */
- bool rxenable; /* DMA-based reception en/disable */
- uint32_t rxdmanext; /* Next byte in the DMA buffer to be read */
- int32_t *const rxfifo; /* Receive DMA buffer */
-#endif
};
/****************************************************************************
* Private Function Prototypes
****************************************************************************/
-# ifdef CONFIG_ADC_DMA
-static int16_t g_adc3dmarxfifo[ADC_MAX_SAMPLES];
-# endif
-
-
-
/* ADC Register access */
static uint32_t adc_getreg(struct stm32_dev_s *priv, int offset);
@@ -179,15 +166,6 @@ static int adc_timinit(FAR struct stm32_dev_s *priv);
static void adc_startconv(FAR struct stm32_dev_s *priv, bool enable);
#endif
-#ifdef CONFIG_ADC_DMA
-static int up_dma_setup(struct adc_dev_s *dev);
-static void up_dma_shutdown(struct adc_dev_s *dev);
-//static int up_dma_receive(struct uart_dev_s *dev, uint32_t *status);
-//static void up_dma_rxint(struct uart_dev_s *dev, bool enable);
-//static bool up_dma_rxavailable(struct uart_dev_s *dev);
-static void up_dma_rxcallback(DMA_HANDLE handle, uint8_t status, FAR struct adc_dev_s *dev);
-#endif
-
/****************************************************************************
* Private Data
****************************************************************************/
@@ -284,10 +262,6 @@ static struct stm32_dev_s g_adcpriv3 =
.pclck = ADC3_TIMER_PCLK_FREQUENCY,
.freq = CONFIG_STM32_ADC3_SAMPLE_FREQUENCY,
#endif
-#ifdef CONFIG_ADC_DMA
- .rxdma_channel = DMAMAP_ADC3_2,
- .rxfifo = g_adc3dmarxfifo,
-#endif
};
static struct adc_dev_s g_adcdev3 =
@@ -569,7 +543,7 @@ static int adc_timinit(FAR struct stm32_dev_s *priv)
* So ( prescaler = pclck / 65535 / freq ) would be optimal.
*/
- prescaler = 128;//(priv->pclck / priv->freq + 65534) / 65535;
+ prescaler = (priv->pclck / priv->freq + 65534) / 65535;
/* We need to decrement the prescaler value by one, but only, the value does
* not underflow.
@@ -591,7 +565,7 @@ static int adc_timinit(FAR struct stm32_dev_s *priv)
timclk = priv->pclck / prescaler;
- reload = priv->freq;//timclk / priv->freq;
+ reload = timclk / priv->freq;
if (reload < 1)
{
adbg("WARNING: Reload value underflowed.\n");
@@ -720,10 +694,10 @@ static int adc_timinit(FAR struct stm32_dev_s *priv)
case 4: /* TimerX TRGO event */
{
-#warning "TRGO support not yet implemented"
-
+ /* TODO: TRGO support not yet implemented */
/* Set the event TRGO */
+ ccenable = 0;
egr = GTIM_EGR_TG;
/* Set the duty cycle by writing to the CCR register for this channel */
@@ -936,139 +910,6 @@ static void adc_rccreset(struct stm32_dev_s *priv, bool reset)
irqrestore(flags);
}
-/****************************************************************************
- * Name: up_dma_setup
- *
- * Description:
- *
- ****************************************************************************/
-
-#ifdef CONFIG_ADC_DMA
-static int up_dma_setup(FAR struct adc_dev_s *dev)
-{
-
- FAR struct stm32_dev_s *priv = (FAR struct stm32_dev_s *)dev->ad_priv;
- int result;
- uint32_t regval;
-
-//
-// result = up_setup(dev);
-// if (result != OK)
-// {
-// return result;
-// }
-
- /* Acquire the DMA channel. This should always succeed. */
-
- priv->rxdma = stm32_dmachannel(priv->rxdma_channel);
-
- /* Configure for circular DMA reception into the RX fifo */
-
- stm32_dmasetup(priv->rxdma,
- priv->base + STM32_ADC_DR_OFFSET,
- (uint32_t)priv->rxfifo,
- 4,//buffersize
- DMA_SCR_DIR_P2M |
- DMA_SCR_CIRC |
- DMA_SCR_MINC |
- DMA_SCR_PSIZE_16BITS |
- DMA_SCR_MSIZE_16BITS |
- DMA_SCR_PBURST_SINGLE |
- DMA_SCR_MBURST_SINGLE);
-
- /* Reset our DMA shadow pointer to match the address just
- * programmed above.
- */
-
- //priv->rxdmanext = 0;
-
- /* Enable DMA for the ADC */
-
- /* Start the DMA channel, and arrange for callbacks at the half and
- * full points in the FIFO. This ensures that we have half a FIFO
- * worth of time to claim bytes before they are overwritten.
- */
-
- stm32_dmastart(priv->rxdma, up_dma_rxcallback, (void *)dev, false);
-
- return OK;
-}
-#endif
-/****************************************************************************
- * Name: up_dma_rxcallback
- *
- * Description:
-
- *
- ****************************************************************************/
-
-#ifdef CONFIG_ADC_DMA
-static void up_dma_rxcallback(DMA_HANDLE handle, uint8_t status, FAR struct adc_dev_s *dev)
-{
- //struct up_dev_s *priv = (struct up_dev_s*)arg;
- //uint32_t regval;
- FAR struct stm32_dev_s *priv = (FAR struct stm32_dev_s *)dev->ad_priv;
- //struct stm32_dma_s *dmast = (struct stm32_dma_s *)handle;
-
- //if (priv->rxenable && up_dma_rxavailable(&priv->dev))
- {
- /* Give the ADC data to the ADC driver. adc_receive accepts 3 parameters:
- *
- * 1) The first is the ADC device instance for this ADC block.
- * 2) The second is the channel number for the data, and
- * 3) The third is the converted data for the channel.
- */
-
-
- adc_receive(dev, 10, (int32_t)g_adc3dmarxfifo[1]);
- adc_receive(dev, 11, (int32_t)g_adc3dmarxfifo[2]);
- adc_receive(dev, 12, (int32_t)g_adc3dmarxfifo[3]);
- adc_receive(dev, 13, (int32_t)g_adc3dmarxfifo[0]);
-
-
- /* Set the channel number of the next channel that will complete conversion */
-
- priv->current++;
-
- if (priv->current >= priv->nchannels)
- {
- /* Restart the conversion sequence from the beginning */
-
- priv->current = 0;
- }
-
-
- }
-}
-#endif
-
-/****************************************************************************
- * Name: up_dma_shutdown
- *
- * Description:
- * Disable the DMA
- *
- ****************************************************************************/
-
-#ifdef CONFIG_ADC_DMA
-static void up_dma_shutdown(struct adc_dev_s *dev)
-{
-
- FAR struct stm32_dev_s *priv = (FAR struct stm32_dev_s *)dev->ad_priv;
-
-
- /* Stop the DMA channel */
-
- stm32_dmastop(priv->rxdma);
-
- /* Release the DMA channel */
-
- stm32_dmafree(priv->rxdma);
- priv->rxdma = NULL;
-}
-#endif
-
-
/*******************************************************************************
* Name: adc_enable
*
@@ -1089,7 +930,7 @@ static void adc_enable(FAR struct stm32_dev_s *priv, bool enable)
{
uint32_t regval;
- // avdbg("enable: %d\n", enable);
+ avdbg("enable: %d\n", enable);
regval = adc_getreg(priv, STM32_ADC_CR2_OFFSET);
if (enable)
@@ -1123,12 +964,14 @@ static void adc_reset(FAR struct adc_dev_s *dev)
uint32_t regval;
int offset;
int i;
+#ifdef ADC_HAVE_TIMER
int ret;
+#endif
avdbg("intf: ADC%d\n", priv->intf);
flags = irqsave();
- /* Enable ADC reset state */
+ /* Enable ADC reset state */
adc_rccreset(priv, true);
@@ -1146,7 +989,6 @@ static void adc_reset(FAR struct adc_dev_s *dev)
adc_putreg(priv, STM32_ADC_LTR_OFFSET, 0x00000000);
-
/* Initialize the same sample time for each ADC 55.5 cycles
*
* During sample cycles channel selection bits must remain unchanged.
@@ -1179,8 +1021,16 @@ static void adc_reset(FAR struct adc_dev_s *dev)
regval |= ADC_CR1_AWDEN;
regval |= (priv->chanlist[0] << ADC_CR1_AWDCH_SHIFT);
+ /* Enable interrupt flags */
+
+ regval |= ADC_CR1_ALLINTS;
+
#if defined(CONFIG_STM32_STM32F20XX) || defined(CONFIG_STM32_STM32F40XX)
+ /* Enable or disable Overrun interrupt */
+
+ regval &= ~ADC_CR1_OVRIE;
+
/* Set the resolution of the conversion */
regval |= ACD_CR1_RES_12BIT;
@@ -1229,12 +1079,6 @@ static void adc_reset(FAR struct adc_dev_s *dev)
{
regval |= (uint32_t)priv->chanlist[i] << offset;
}
- /* Set the number of conversions */
-
- DEBUGASSERT(priv->nchannels <= ADC_MAX_SAMPLES);
-
- regval |= (((uint32_t)priv->nchannels-1) << ADC_SQR1_L_SHIFT);
- adc_putreg(priv, STM32_ADC_SQR1_OFFSET, regval);
/* ADC CCR configuration */
@@ -1246,7 +1090,12 @@ static void adc_reset(FAR struct adc_dev_s *dev)
putreg32(regval, STM32_ADC_CCR);
#endif
+ /* Set the number of conversions */
+ DEBUGASSERT(priv->nchannels <= ADC_MAX_SAMPLES);
+
+ regval |= (((uint32_t)priv->nchannels-1) << ADC_SQR1_L_SHIFT);
+ adc_putreg(priv, STM32_ADC_SQR1_OFFSET, regval);
/* Set the channel index of the first conversion */
@@ -1270,29 +1119,24 @@ static void adc_reset(FAR struct adc_dev_s *dev)
adc_enable(priv, true);
#else
-#ifdef CONFIG_ADC_DMA
- //nothing
-#else
adc_startconv(priv, true);
-#endif
#endif /* CONFIG_STM32_STM32F10XX */
#endif /* ADC_HAVE_TIMER */
-
irqrestore(flags);
-// avdbg("SR: 0x%08x CR1: 0x%08x CR2: 0x%08x\n",
-// adc_getreg(priv, STM32_ADC_SR_OFFSET),
-// adc_getreg(priv, STM32_ADC_CR1_OFFSET),
-// adc_getreg(priv, STM32_ADC_CR2_OFFSET));
-// avdbg("SQR1: 0x%08x SQR2: 0x%08x SQR3: 0x%08x\n",
-// adc_getreg(priv, STM32_ADC_SQR1_OFFSET),
-// adc_getreg(priv, STM32_ADC_SQR2_OFFSET),
-// adc_getreg(priv, STM32_ADC_SQR3_OFFSET));
-//#if defined(CONFIG_STM32_STM32F20XX) || defined(CONFIG_STM32_STM32F40XX)
-// avdbg("CCR: 0x%08x\n",
-// getreg32(STM32_ADC_CCR));
-//#endif
+ avdbg("SR: 0x%08x CR1: 0x%08x CR2: 0x%08x\n",
+ adc_getreg(priv, STM32_ADC_SR_OFFSET),
+ adc_getreg(priv, STM32_ADC_CR1_OFFSET),
+ adc_getreg(priv, STM32_ADC_CR2_OFFSET));
+ avdbg("SQR1: 0x%08x SQR2: 0x%08x SQR3: 0x%08x\n",
+ adc_getreg(priv, STM32_ADC_SQR1_OFFSET),
+ adc_getreg(priv, STM32_ADC_SQR2_OFFSET),
+ adc_getreg(priv, STM32_ADC_SQR3_OFFSET));
+#if defined(CONFIG_STM32_STM32F20XX) || defined(CONFIG_STM32_STM32F40XX)
+ avdbg("CCR: 0x%08x\n",
+ getreg32(STM32_ADC_CCR));
+#endif
}
/****************************************************************************
@@ -1314,86 +1158,21 @@ static int adc_setup(FAR struct adc_dev_s *dev)
{
FAR struct stm32_dev_s *priv = (FAR struct stm32_dev_s *)dev->ad_priv;
int ret;
- uint32_t regval;
-
-
- /* the adc seems to need a full reset to be enabled correctly */
- adc_reset(dev);
-#ifndef CONFIG_ADC_DMA
/* Attach the ADC interrupt */
ret = irq_attach(priv->irq, priv->isr);
if (ret == OK)
{
+ /* Make sure that the ADC device is in the powered up, reset state */
+
+ adc_reset(dev);
+
/* Enable the ADC interrupt */
avdbg("Enable the ADC interrupt: irq=%d\n", priv->irq);
up_enable_irq(priv->irq);
}
-#endif
-
-#ifdef CONFIG_ADC_DMA
- up_dma_setup(dev);
-
-
-//#ifndef ADC_HAVE_TIMER
-// /*disable external trigger*/
-// regval = adc_getreg(priv, STM32_ADC_CR2_OFFSET);
-// regval |= ACD_CR2_EXTEN_NONE;
-// //regval |= ADC_CR1_DISCEN;
-// adc_putreg(priv, STM32_ADC_CR2_OFFSET, regval);
-//#else
-// /*enable external trigger*/
-// regval = adc_getreg(priv, STM32_ADC_CR2_OFFSET);
-// regval |=ADC_CR2_EXTSEL_T4CC4;
-// regval |=ACD_CR2_EXTEN_BOTH;
-// //regval |= ADC_CR2_CONT;
-// adc_putreg(priv, STM32_ADC_CR2_OFFSET, regval);
-//#endif
-
-
- /*enable scan mode*/
- regval = adc_getreg(priv, STM32_ADC_CR1_OFFSET);
- regval |= ADC_CR1_SCAN;
- //regval |= ADC_CR1_DISCEN;
- adc_putreg(priv, STM32_ADC_CR1_OFFSET, regval);
-
- /* Enable DMA request after last transfer (Single-ADC mode) */
- //ADC_DMARequestAfterLastTransferCmd(ADC3, ENABLE);
- regval = adc_getreg(priv, STM32_ADC_CR2_OFFSET);
- regval |= ADC_CR2_DDS;
- adc_putreg(priv, STM32_ADC_CR2_OFFSET, regval);
-
- /* Enable ADC3 DMA */
- // ADC_DMACmd(ADC3, ENABLE);
- regval = adc_getreg(priv, STM32_ADC_CR2_OFFSET);
- regval |= ADC_CR2_DMA;
- adc_putreg(priv, STM32_ADC_CR2_OFFSET, regval);
-#endif
-
-
-#ifndef ADC_HAVE_TIMER
- /*set continuous conversion */
- regval = adc_getreg(priv, STM32_ADC_CR2_OFFSET);
- regval |= ADC_CR2_CONT;
- adc_putreg(priv, STM32_ADC_CR2_OFFSET, regval);
-#endif
-
- /* Enable ADC3 */
- //ADC_Cmd(ADC3, ENABLE);
- regval = adc_getreg(priv, STM32_ADC_CR2_OFFSET);
- regval |= ADC_CR2_ADON;
- adc_putreg(priv, STM32_ADC_CR2_OFFSET, regval);
-
-//// /*start conversion*/
-// regval = adc_getreg(priv, STM32_ADC_CR2_OFFSET);
-// regval |= ADC_CR2_SWSTART;
-// adc_putreg(priv, STM32_ADC_CR2_OFFSET, regval);
-
-
-
-
return ret;
}
@@ -1415,24 +1194,14 @@ static void adc_shutdown(FAR struct adc_dev_s *dev)
{
FAR struct stm32_dev_s *priv = (FAR struct stm32_dev_s *)dev->ad_priv;
-#ifdef CONFIG_ADC_DMA
- up_dma_shutdown(dev);
-#endif
-
-#ifdef ADC_HAVE_TIMER
- /* stop adc timer */
- adc_timstart(priv, false);
-#endif
+ /* Disable ADC interrupts and detach the ADC interrupt handler */
- /* power down ADC */
- adc_enable(priv, false);
+ up_disable_irq(priv->irq);
+ irq_detach(priv->irq);
- adc_rxint(dev, false);
+ /* Disable and reset the ADC module */
- /* Disable ADC interrupts and detach the ADC interrupt handler */
- up_disable_irq(priv->irq);
-// irq_detach(priv->irq);
- // XXX Why is irq_detach here commented out?
+ adc_rccreset(priv, true);
}
/****************************************************************************
diff --git a/nuttx/arch/arm/src/stm32/stm32_adc.h b/nuttx/arch/arm/src/stm32/stm32_adc.h
index 7b6c13b33..060fcdfb9 100644
--- a/nuttx/arch/arm/src/stm32/stm32_adc.h
+++ b/nuttx/arch/arm/src/stm32/stm32_adc.h
@@ -161,6 +161,12 @@
#if defined(CONFIG_STM32_ADC1) || defined(CONFIG_STM32_ADC2) || defined(CONFIG_STM32_ADC3)
+/* DMA support is not yet implemented for this driver */
+
+#ifdef CONFIG_ADC_DMA
+# warning "DMA is not supported by the current driver"
+#endif
+
/* Timer configuration: If a timer trigger is specified, then get information
* about the timer.
*/
diff --git a/nuttx/arch/arm/src/stm32/stm32_i2c.c b/nuttx/arch/arm/src/stm32/stm32_i2c.c
index 633275906..05c3f7095 100644
--- a/nuttx/arch/arm/src/stm32/stm32_i2c.c
+++ b/nuttx/arch/arm/src/stm32/stm32_i2c.c
@@ -107,11 +107,11 @@
#if !defined(CONFIG_STM32_I2CTIMEOSEC) && !defined(CONFIG_STM32_I2CTIMEOMS)
# define CONFIG_STM32_I2CTIMEOSEC 0
-# define CONFIG_STM32_I2CTIMEOMS 500 /* Default is 500 milliseconds */
+# define CONFIG_STM32_I2CTIMEOMS 500 /* Default is 500 milliseconds */
#elif !defined(CONFIG_STM32_I2CTIMEOSEC)
# define CONFIG_STM32_I2CTIMEOSEC 0 /* User provided milliseconds */
#elif !defined(CONFIG_STM32_I2CTIMEOMS)
-# define CONFIG_STM32_I2CTIMEOMS 0 /* User provided seconds */
+# define CONFIG_STM32_I2CTIMEOMS 0 /* User provided seconds */
#endif
/* Interrupt wait time timeout in system timer ticks */
@@ -141,7 +141,7 @@
#endif
/* I2C event trace logic. NOTE: trace uses the internal, non-standard, low-level
- * debug interface lib_rawprintf() but does not require that any other debug
+ * debug interface syslog() but does not require that any other debug
* is enabled.
*/
@@ -235,31 +235,31 @@ struct stm32_i2c_config_s
struct stm32_i2c_priv_s
{
const struct stm32_i2c_config_s *config; /* Port configuration */
- int refs; /* Referernce count */
- sem_t sem_excl; /* Mutual exclusion semaphore */
+ int refs; /* Referernce count */
+ sem_t sem_excl; /* Mutual exclusion semaphore */
#ifndef CONFIG_I2C_POLLED
- sem_t sem_isr; /* Interrupt wait semaphore */
+ sem_t sem_isr; /* Interrupt wait semaphore */
#endif
- volatile uint8_t intstate; /* Interrupt handshake (see enum stm32_intstate_e) */
+ volatile uint8_t intstate; /* Interrupt handshake (see enum stm32_intstate_e) */
- uint8_t msgc; /* Message count */
- struct i2c_msg_s *msgv; /* Message list */
- uint8_t *ptr; /* Current message buffer */
- int dcnt; /* Current message length */
- uint16_t flags; /* Current message flags */
+ uint8_t msgc; /* Message count */
+ struct i2c_msg_s *msgv; /* Message list */
+ uint8_t *ptr; /* Current message buffer */
+ int dcnt; /* Current message length */
+ uint16_t flags; /* Current message flags */
/* I2C trace support */
#ifdef CONFIG_I2C_TRACE
- int tndx; /* Trace array index */
- uint32_t start_time; /* Time when the trace was started */
+ int tndx; /* Trace array index */
+ uint32_t start_time; /* Time when the trace was started */
/* The actual trace data */
struct stm32_trace_s trace[CONFIG_I2C_NTRACE];
#endif
- uint32_t status; /* End of transfer SR2|SR1 status */
+ uint32_t status; /* End of transfer SR2|SR1 status */
};
/* I2C Device, Instance */
@@ -297,7 +297,7 @@ static void stm32_i2c_tracenew(FAR struct stm32_i2c_priv_s *priv, uint32_t statu
static void stm32_i2c_traceevent(FAR struct stm32_i2c_priv_s *priv,
enum stm32_trace_e event, uint32_t parm);
static void stm32_i2c_tracedump(FAR struct stm32_i2c_priv_s *priv);
-#endif
+#endif /* CONFIG_I2C_TRACE */
static void stm32_i2c_setclock(FAR struct stm32_i2c_priv_s *priv,
uint32_t frequency);
static inline void stm32_i2c_sendstart(FAR struct stm32_i2c_priv_s *priv);
@@ -307,7 +307,7 @@ static inline uint32_t stm32_i2c_getstatus(FAR struct stm32_i2c_priv_s *priv);
#ifdef I2C1_FSMC_CONFLICT
static inline uint32_t stm32_i2c_disablefsmc(FAR struct stm32_i2c_priv_s *priv);
static inline void stm32_i2c_enablefsmc(uint32_t ahbenr);
-#endif
+#endif /* I2C1_FSMC_CONFLICT */
static int stm32_i2c_isr(struct stm32_i2c_priv_s * priv);
#ifndef CONFIG_I2C_POLLED
#ifdef CONFIG_STM32_I2C1
@@ -598,15 +598,14 @@ static inline int stm32_i2c_sem_waitdone(FAR struct stm32_i2c_priv_s *priv, int
abstime.tv_sec++;
abstime.tv_nsec -= 1000 * 1000 * 1000;
}
-#else
- #if CONFIG_STM32_I2CTIMEOMS > 0
- abstime.tv_nsec += CONFIG_STM32_I2CTIMEOMS * 1000 * 1000;
- if (abstime.tv_nsec > 1000 * 1000 * 1000)
- {
- abstime.tv_sec++;
- abstime.tv_nsec -= 1000 * 1000 * 1000;
- }
- #endif
+
+#elif CONFIG_STM32_I2CTIMEOMS > 0
+ abstime.tv_nsec += CONFIG_STM32_I2CTIMEOMS * 1000 * 1000;
+ if (abstime.tv_nsec > 1000 * 1000 * 1000)
+ {
+ abstime.tv_sec++;
+ abstime.tv_nsec -= 1000 * 1000 * 1000;
+ }
#endif
/* Wait until either the transfer is complete or the timeout expires */
@@ -883,11 +882,11 @@ static void stm32_i2c_tracedump(FAR struct stm32_i2c_priv_s *priv)
struct stm32_trace_s *trace;
int i;
- lib_rawprintf("Elapsed time: %d\n", clock_systimer() - priv->start_time);
+ syslog("Elapsed time: %d\n", clock_systimer() - priv->start_time);
for (i = 0; i <= priv->tndx; i++)
{
trace = &priv->trace[i];
- lib_rawprintf("%2d. STATUS: %08x COUNT: %3d EVENT: %s PARM: %08x TIME: %d\n",
+ syslog("%2d. STATUS: %08x COUNT: %3d EVENT: %s PARM: %08x TIME: %d\n",
i+1, trace->status, trace->count, stm32_trace_names[trace->event], trace->parm,
trace->time - priv->start_time);
}
@@ -949,7 +948,7 @@ static void stm32_i2c_setclock(FAR struct stm32_i2c_priv_s *priv, uint32_t frequ
{
/* Fast mode speed calculation with Tlow/Thigh = 16/9 */
-#ifdef CONFIG_I2C_DUTY16_9
+#ifdef CONFIG_STM32_I2C_DUTY16_9
speed = (uint16_t)(STM32_PCLK1_FREQUENCY / (frequency * 25));
/* Set DUTY and fast speed bits */
@@ -1088,7 +1087,7 @@ static inline uint32_t stm32_i2c_disablefsmc(FAR struct stm32_i2c_priv_s *priv)
/* Is this I2C1 */
-#ifdef CONFIG_STM32_I2C2
+#if defined(CONFIG_STM32_I2C2) || defined(CONFIG_STM32_I2C3)
if (priv->config->base == STM32_I2C1_BASE)
#endif
{
@@ -1215,10 +1214,14 @@ static int stm32_i2c_isr(struct stm32_i2c_priv_s *priv)
{
stm32_i2c_traceevent(priv, I2CEVENT_RCVBYTE, priv->dcnt);
+ /* No interrupts or context switches may occur in the following
+ * sequence. Otherwise, additional bytes may be sent by the
+ * device.
+ */
+
#ifdef CONFIG_I2C_POLLED
irqstate_t state = irqsave();
#endif
-
/* Receive a byte */
*priv->ptr++ = stm32_i2c_getreg(priv, STM32_I2C_DR_OFFSET);
@@ -1234,7 +1237,6 @@ static int stm32_i2c_isr(struct stm32_i2c_priv_s *priv)
#ifdef CONFIG_I2C_POLLED
irqrestore(state);
#endif
-
}
}
@@ -1425,7 +1427,6 @@ static int stm32_i2c_init(FAR struct stm32_i2c_priv_s *priv)
/* Enable power and reset the peripheral */
modifyreg32(STM32_RCC_APB1ENR, 0, priv->config->clk_bit);
-
modifyreg32(STM32_RCC_APB1RSTR, 0, priv->config->reset_bit);
modifyreg32(STM32_RCC_APB1RSTR, priv->config->reset_bit, 0);
@@ -1445,10 +1446,10 @@ static int stm32_i2c_init(FAR struct stm32_i2c_priv_s *priv)
/* Attach ISRs */
#ifndef CONFIG_I2C_POLLED
- irq_attach(priv->config->ev_irq, priv->config->isr);
- irq_attach(priv->config->er_irq, priv->config->isr);
- up_enable_irq(priv->config->ev_irq);
- up_enable_irq(priv->config->er_irq);
+ irq_attach(priv->config->ev_irq, priv->config->isr);
+ irq_attach(priv->config->er_irq, priv->config->isr);
+ up_enable_irq(priv->config->ev_irq);
+ up_enable_irq(priv->config->er_irq);
#endif
/* Set peripheral frequency, where it must be at least 2 MHz for 100 kHz
@@ -1478,17 +1479,23 @@ static int stm32_i2c_deinit(FAR struct stm32_i2c_priv_s *priv)
stm32_i2c_putreg(priv, STM32_I2C_CR1_OFFSET, 0);
+ /* Unconfigure GPIO pins */
+
stm32_unconfiggpio(priv->config->scl_pin);
stm32_unconfiggpio(priv->config->sda_pin);
+ /* Disable and detach interrupts */
+
#ifndef CONFIG_I2C_POLLED
up_disable_irq(priv->config->ev_irq);
up_disable_irq(priv->config->er_irq);
irq_detach(priv->config->ev_irq);
irq_detach(priv->config->er_irq);
#endif
- modifyreg32(STM32_RCC_APB1ENR, priv->config->clk_bit, 0);
+ /* Disable clocking */
+
+ modifyreg32(STM32_RCC_APB1ENR, priv->config->clk_bit, 0);
return OK;
}
@@ -1640,7 +1647,9 @@ static int stm32_i2c_process(FAR struct i2c_dev_s *dev, FAR struct i2c_msg_s *ms
*/
stm32_i2c_clrstart(priv);
- // XXX also clear busy flag in case of timeout
+
+ /* Clear busy flag in case of timeout */
+
status = priv->status & 0xffff;
}
else
@@ -2087,4 +2096,4 @@ out:
return ret;
}
-#endif /* defined(CONFIG_STM32_I2C1) || defined(CONFIG_STM32_I2C2) || defined(CONFIG_STM32_I2C3) */
+#endif /* CONFIG_STM32_I2C1 || CONFIG_STM32_I2C2 || CONFIG_STM32_I2C3 */
diff --git a/nuttx/arch/arm/src/stm32/stm32_otgfsdev.c b/nuttx/arch/arm/src/stm32/stm32_otgfsdev.c
index 94772b693..bcce3ce60 100644
--- a/nuttx/arch/arm/src/stm32/stm32_otgfsdev.c
+++ b/nuttx/arch/arm/src/stm32/stm32_otgfsdev.c
@@ -146,15 +146,6 @@
# error "CONFIG_USBDEV_EP3_TXFIFO_SIZE is out of range"
#endif
-/* REVISIT! This forces a hack that polls DTXFSTS for space in the Tx FIFO.
- * Enabling this option is a BAD thing. It will cause inline waits inside
- * of the USB interrupt handler. The correct way to handle this is to
- * enable the correct TxFIFO interrupt and wait until the Tx FIFO is empty.
- * Unfortunately, the interrupt driven logic is not working... Please fix!
- */
-
-#define ENABLE_DTXFSTS_POLLHACK 1
-
/* Debug ***********************************************************************/
/* Trace error codes */
@@ -184,8 +175,9 @@
#define STM32_TRACEERR_NOEP 0x18
#define STM32_TRACEERR_NOTCONFIGURED 0x19
#define STM32_TRACEERR_EPOUTQEMPTY 0x1a
-#define STM32_TRACEERR_EPINQEMPTY 0x1b
+#define STM32_TRACEERR_EPINREQEMPTY 0x1b
#define STM32_TRACEERR_NOOUTSETUP 0x1c
+#define STM32_TRACEERR_POLLTIMEOUT 0x1d
/* Trace interrupt codes */
@@ -432,7 +424,6 @@ struct stm32_usbdev_s
uint8_t stalled:1; /* 1: Protocol stalled */
uint8_t selfpowered:1; /* 1: Device is self powered */
- uint8_t connected:1; /* 1: Host connected */
uint8_t addressed:1; /* 1: Peripheral address has been set */
uint8_t configured:1; /* 1: Class driver has been configured */
uint8_t wakeup:1; /* 1: Device remote wake-up */
@@ -508,7 +499,7 @@ static void stm32_ep0out_ctrlsetup(FAR struct stm32_usbdev_s *priv);
static void stm32_txfifo_write(FAR struct stm32_ep_s *privep,
FAR uint8_t *buf, int nbytes);
static void stm32_epin_transfer(FAR struct stm32_ep_s *privep,
- FAR uint8_t *buf, int nbytes);
+ FAR uint8_t *buf, int nbytes);
static void stm32_epin_request(FAR struct stm32_usbdev_s *priv,
FAR struct stm32_ep_s *privep);
@@ -962,7 +953,7 @@ static void stm32_txfifo_write(FAR struct stm32_ep_s *privep,
regval |= ((uint32_t)*buf++) << 16;
regval |= ((uint32_t)*buf++) << 24;
- /* Then write the packed data to the TxFIFO */
+ /* Then write the packet data to the TxFIFO */
stm32_putreg(regval, regaddr);
}
@@ -1082,9 +1073,6 @@ static void stm32_epin_request(FAR struct stm32_usbdev_s *priv,
struct stm32_req_s *privreq;
uint32_t regaddr;
uint32_t regval;
-#ifdef ENABLE_DTXFSTS_POLLHACK
- int32_t timeout;
-#endif
uint8_t *buf;
int nbytes;
int nwords;
@@ -1113,7 +1101,7 @@ static void stm32_epin_request(FAR struct stm32_usbdev_s *priv,
privreq = stm32_rqpeek(privep);
if (!privreq)
{
- usbtrace(TRACE_DEVERROR(STM32_TRACEERR_EPINQEMPTY), privep->epphy);
+ usbtrace(TRACE_DEVERROR(STM32_TRACEERR_EPINREQEMPTY), privep->epphy);
/* There is no TX transfer in progress and no new pending TX
* requests to send. To stop transmitting any data on a particular
@@ -1151,13 +1139,20 @@ static void stm32_epin_request(FAR struct stm32_usbdev_s *priv,
privep->zlp = true;
}
- /* Loop while there are still bytes to be transferred (or a zero-length-
- * packet, ZLP, to be sent). The loop will also be terminated if there
- * is insufficient space remaining in the TxFIFO to send a complete
- * packet.
+ /* Add one more packet to the TxFIFO. We will wait for the transfer
+ * complete event before we add the next packet (or part of a packet
+ * to the TxFIFO).
+ *
+ * The documentation says that we can can multiple packets to the TxFIFO,
+ * but it seems that we need to get the transfer complete event before
+ * we can add the next (or maybe I have got something wrong?)
*/
+#if 0
while (privreq->req.xfrd < privreq->req.len || privep->zlp)
+#else
+ if (privreq->req.xfrd < privreq->req.len || privep->zlp)
+#endif
{
/* Get the number of bytes left to be sent in the request */
@@ -1219,25 +1214,9 @@ static void stm32_epin_request(FAR struct stm32_usbdev_s *priv,
regaddr = STM32_OTGFS_DTXFSTS(privep->epphy);
-#ifdef ENABLE_DTXFSTS_POLLHACK
- /* If ENABLE_DTXFSTS_POLLHACK is enabled , then poll DTXFSTS until
- * space in the TxFIFO is available. If it doesn't become available,
- * in a reasonable amount of time, then just pretend that it is.
- */
-
- for (timeout = 250000; timeout > 0; timeout--)
- {
- regval = stm32_getreg(regaddr);
- if ((regval & OTGFS_DTXFSTS_MASK) >= nwords)
- {
- break;
- }
- }
-#else
- /* If ENABLE_DTXFSTS_POLLHACK is not enabled, then check once for
- * space in the TxFIFO. If space in the TxFIFO is not available,
- * then set up an interrupt to resume the transfer when the TxFIFO
- * is empty.
+ /* Check for space in the TxFIFO. If space in the TxFIFO is not
+ * available, then set up an interrupt to resume the transfer when
+ * the TxFIFO is empty.
*/
regval = stm32_getreg(regaddr);
@@ -1253,11 +1232,12 @@ static void stm32_epin_request(FAR struct stm32_usbdev_s *priv,
empmsk |= OTGFS_DIEPEMPMSK(privep->epphy);
stm32_putreg(empmsk, STM32_OTGFS_DIEPEMPMSK);
- /* Terminate the transfer loop */
+ /* Terminate the transfer. We will try again when the TxFIFO empty
+ * interrupt is received.
+ */
- break;
+ return;
}
-#endif
/* Transfer data to the TxFIFO */
@@ -1290,11 +1270,12 @@ static void stm32_epin_request(FAR struct stm32_usbdev_s *priv,
if (privreq->req.xfrd >= privreq->req.len && !privep->zlp)
{
usbtrace(TRACE_COMPLETE(privep->epphy), privreq->req.xfrd);
- stm32_req_complete(privep, OK);
- /* The endpoint is no longer transferring data */
+ /* We are finished with the request (although the transfer has not
+ * yet completed).
+ */
- privep->active = false;
+ stm32_req_complete(privep, OK);
}
}
@@ -2690,7 +2671,7 @@ static inline void stm32_epin_txfifoempty(FAR struct stm32_usbdev_s *priv, int e
FAR struct stm32_ep_s *privep = &priv->epin[epno];
/* Continue processing the write request queue. This may mean sending
- * more dat from the exisiting request or terminating the current requests
+ * more data from the exisiting request or terminating the current requests
* and (perhaps) starting the IN transfer from the next write request.
*/
@@ -2741,9 +2722,11 @@ static inline void stm32_epin_interrupt(FAR struct stm32_usbdev_s *priv)
mask = stm32_getreg(STM32_OTGFS_DIEPMSK);
- /* Check for FIFO not empty. Bits n corresponds to endpoint n.
- * That condition corresponds to bit 7 of the DIEPINT interrupt
- * status register.
+ /* Check if the TxFIFO not empty interrupt is enabled for this
+ * endpoint in the DIEPMSK register. Bits n corresponds to
+ * endpoint n in the register. That condition corresponds to
+ * bit 7 of the DIEPINT interrupt status register. There is
+ * no TXFE bit in the mask register, so we fake one here.
*/
empty = stm32_getreg(STM32_OTGFS_DIEPEMPMSK);
@@ -2763,11 +2746,13 @@ static inline void stm32_epin_interrupt(FAR struct stm32_usbdev_s *priv)
if ((diepint & OTGFS_DIEPINT_XFRC) != 0)
{
- usbtrace(TRACE_INTDECODE(STM32_TRACEINTID_EPIN_XFRC), (uint16_t)diepint);
+ usbtrace(TRACE_INTDECODE(STM32_TRACEINTID_EPIN_XFRC),
+ (uint16_t)diepint);
- /* It is possible that logic may be waiting for a the TxFIFO to become
- * empty. We disable the TxFIFO empty interrupt here; it will be
- * re-enabled if there is still insufficient space in the TxFIFO.
+ /* It is possible that logic may be waiting for a the
+ * TxFIFO to become empty. We disable the TxFIFO empty
+ * interrupt here; it will be re-enabled if there is still
+ * insufficient space in the TxFIFO.
*/
empty &= ~OTGFS_DIEPEMPMSK(epno);
@@ -2828,7 +2813,7 @@ static inline void stm32_epin_interrupt(FAR struct stm32_usbdev_s *priv)
usbtrace(TRACE_INTDECODE(STM32_TRACEINTID_EPIN_TXFE), (uint16_t)diepint);
/* If we were waiting for TxFIFO to become empty, the we might have both
- * XFRC and TXFE interrups pending. Since we do the same thing for both
+ * XFRC and TXFE interrupts pending. Since we do the same thing for both
* cases, ignore the TXFE if we have already processed the XFRC.
*/
@@ -2886,6 +2871,13 @@ static inline void stm32_resumeinterrupt(FAR struct stm32_usbdev_s *priv)
/* Restore full power -- whatever that means for this particular board */
stm32_usbsuspend((struct usbdev_s *)priv, true);
+
+ /* Notify the class driver of the resume event */
+
+ if (priv->driver)
+ {
+ CLASS_RESUME(priv->driver, &priv->usbdev);
+ }
}
/*******************************************************************************
@@ -2900,7 +2892,16 @@ static inline void stm32_suspendinterrupt(FAR struct stm32_usbdev_s *priv)
{
#ifdef CONFIG_USBDEV_LOWPOWER
uint32_t regval;
+#endif
+
+ /* Notify the class driver of the suspend event */
+
+ if (priv->driver)
+ {
+ CLASS_SUSPEND(priv->driver, &priv->usbdev);
+ }
+#ifdef CONFIG_USBDEV_LOWPOWER
/* OTGFS_DSTS_SUSPSTS is set as long as the suspend condition is detected
* on USB. Check if we are still have the suspend condition, that we are
* connected to the host, and that we have been configured.
@@ -2908,9 +2909,7 @@ static inline void stm32_suspendinterrupt(FAR struct stm32_usbdev_s *priv)
regval = stm32_getreg(STM32_OTGFS_DSTS);
- if ((regval & OTGFS_DSTS_SUSPSTS) != 0 &&
- priv->connected &&
- devstate == DEVSTATE_CONFIGURED)
+ if ((regval & OTGFS_DSTS_SUSPSTS) != 0 && devstate == DEVSTATE_CONFIGURED)
{
/* Switch off OTG FS clocking. Setting OTGFS_PCGCCTL_STPPCLK stops the
* PHY clock.
@@ -4957,8 +4956,9 @@ static void stm32_hwinitialize(FAR struct stm32_usbdev_s *priv)
/* At startup the core is in FS mode. */
- /* Disable the USB global interrupt by clearing GINTMSK in the global OTG
- * FS AHB configuration register.
+ /* Disable global interrupts by clearing the GINTMASK bit in the GAHBCFG
+ * register; Set the TXFELVL bit in the GAHBCFG register so that TxFIFO
+ * interrupts will occur when the TxFIFO is truly empty (not just half full).
*/
stm32_putreg(OTGFS_GAHBCFG_TXFELVL, STM32_OTGFS_GAHBCFG);
@@ -5074,6 +5074,7 @@ static void stm32_hwinitialize(FAR struct stm32_usbdev_s *priv)
stm32_putreg(0, STM32_OTGFS_DIEPMSK);
stm32_putreg(0, STM32_OTGFS_DOEPMSK);
+ stm32_putreg(0, STM32_OTGFS_DIEPEMPMSK);
stm32_putreg(0xffffffff, STM32_OTGFS_DAINT);
stm32_putreg(0, STM32_OTGFS_DAINTMSK);
@@ -5155,10 +5156,13 @@ static void stm32_hwinitialize(FAR struct stm32_usbdev_s *priv)
stm32_putreg(regval, STM32_OTGFS_GINTMSK);
/* Enable the USB global interrupt by setting GINTMSK in the global OTG
- * FS AHB configuration register.
+ * FS AHB configuration register; Set the TXFELVL bit in the GAHBCFG
+ * register so that TxFIFO interrupts will occur when the TxFIFO is truly
+ * empty (not just half full).
*/
- stm32_putreg(OTGFS_GAHBCFG_GINTMSK | OTGFS_GAHBCFG_TXFELVL, STM32_OTGFS_GAHBCFG);
+ stm32_putreg(OTGFS_GAHBCFG_GINTMSK | OTGFS_GAHBCFG_TXFELVL,
+ STM32_OTGFS_GAHBCFG);
}
/*******************************************************************************
@@ -5314,6 +5318,7 @@ void up_usbuninitialize(void)
stm32_putreg(0, STM32_OTGFS_DIEPMSK);
stm32_putreg(0, STM32_OTGFS_DOEPMSK);
+ stm32_putreg(0, STM32_OTGFS_DIEPEMPMSK);
stm32_putreg(0, STM32_OTGFS_DAINTMSK);
stm32_putreg(0xffffffff, STM32_OTGFS_DAINT);
diff --git a/nuttx/arch/arm/src/stm32/stm32_serial.c b/nuttx/arch/arm/src/stm32/stm32_serial.c
index 6aaecb2d9..c91f6a6d7 100644
--- a/nuttx/arch/arm/src/stm32/stm32_serial.c
+++ b/nuttx/arch/arm/src/stm32/stm32_serial.c
@@ -2077,7 +2077,8 @@ void up_serialinit(void)
{
#ifdef HAVE_UART
char devname[16];
- unsigned i, j;
+ unsigned i;
+ unsigned minor = 0;
#ifdef CONFIG_PM
int ret;
#endif
@@ -2094,6 +2095,7 @@ void up_serialinit(void)
#if CONSOLE_UART > 0
(void)uart_register("/dev/console", &uart_devs[CONSOLE_UART - 1]->dev);
(void)uart_register("/dev/ttyS0", &uart_devs[CONSOLE_UART - 1]->dev);
+ minor = 1;
/* If we need to re-initialise the console to enable DMA do that here. */
@@ -2107,19 +2109,19 @@ void up_serialinit(void)
strcpy(devname, "/dev/ttySx");
- for (i = 0, j = 1; i < STM32_NUSART; i++)
+ for (i = 0; i < STM32_NUSART; i++)
{
- /* don't create a device for the console - we did that above */
+ /* Don't create a device for the console - we did that above */
if ((uart_devs[i] == 0) || (uart_devs[i]->dev.isconsole))
{
continue;
}
- /* register USARTs as devices in increasing order */
+ /* Register USARTs as devices in increasing order */
- devname[9] = '0' + j++;
+ devname[9] = '0' + minor++;
(void)uart_register(devname, &uart_devs[i]->dev);
}
#endif /* HAVE UART */
diff --git a/nuttx/arch/arm/src/stm32/stm32_spi.c b/nuttx/arch/arm/src/stm32/stm32_spi.c
index 8de698cd5..b4a4f36ab 100644
--- a/nuttx/arch/arm/src/stm32/stm32_spi.c
+++ b/nuttx/arch/arm/src/stm32/stm32_spi.c
@@ -130,14 +130,28 @@
/* DMA channel configuration */
-#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 )
-#define SPI_RXDMA8NULL_CONFIG (SPI_DMA_PRIO|DMA_CCR_MSIZE_8BITS |DMA_CCR_PSIZE_8BITS )
-#define SPI_TXDMA16_CONFIG (SPI_DMA_PRIO|DMA_CCR_MSIZE_16BITS|DMA_CCR_PSIZE_16BITS|DMA_CCR_MINC|DMA_CCR_DIR)
-#define SPI_TXDMA8_CONFIG (SPI_DMA_PRIO|DMA_CCR_MSIZE_8BITS |DMA_CCR_PSIZE_8BITS |DMA_CCR_MINC|DMA_CCR_DIR)
-#define SPI_TXDMA16NULL_CONFIG (SPI_DMA_PRIO|DMA_CCR_MSIZE_8BITS |DMA_CCR_PSIZE_16BITS |DMA_CCR_DIR)
-#define SPI_TXDMA8NULL_CONFIG (SPI_DMA_PRIO|DMA_CCR_MSIZE_8BITS |DMA_CCR_PSIZE_8BITS |DMA_CCR_DIR)
+#if defined(CONFIG_STM32_STM32F10XX)
+# 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 )
+# define SPI_RXDMA8NULL_CONFIG (SPI_DMA_PRIO|DMA_CCR_MSIZE_8BITS |DMA_CCR_PSIZE_8BITS )
+# define SPI_TXDMA16_CONFIG (SPI_DMA_PRIO|DMA_CCR_MSIZE_16BITS|DMA_CCR_PSIZE_16BITS|DMA_CCR_MINC|DMA_CCR_DIR)
+# define SPI_TXDMA8_CONFIG (SPI_DMA_PRIO|DMA_CCR_MSIZE_8BITS |DMA_CCR_PSIZE_8BITS |DMA_CCR_MINC|DMA_CCR_DIR)
+# define SPI_TXDMA16NULL_CONFIG (SPI_DMA_PRIO|DMA_CCR_MSIZE_8BITS |DMA_CCR_PSIZE_16BITS |DMA_CCR_DIR)
+# define SPI_TXDMA8NULL_CONFIG (SPI_DMA_PRIO|DMA_CCR_MSIZE_8BITS |DMA_CCR_PSIZE_8BITS |DMA_CCR_DIR)
+#elif defined(CONFIG_STM32_STM32F20XX) || defined(CONFIG_STM32_STM32F40XX)
+# define SPI_RXDMA16_CONFIG (SPI_DMA_PRIO|DMA_SCR_MSIZE_16BITS|DMA_SCR_PSIZE_16BITS|DMA_SCR_MINC|DMA_SCR_DIR_P2M)
+# define SPI_RXDMA8_CONFIG (SPI_DMA_PRIO|DMA_SCR_MSIZE_8BITS |DMA_SCR_PSIZE_8BITS |DMA_SCR_MINC|DMA_SCR_DIR_P2M)
+# define SPI_RXDMA16NULL_CONFIG (SPI_DMA_PRIO|DMA_SCR_MSIZE_8BITS |DMA_SCR_PSIZE_16BITS |DMA_SCR_DIR_P2M)
+# define SPI_RXDMA8NULL_CONFIG (SPI_DMA_PRIO|DMA_SCR_MSIZE_8BITS |DMA_SCR_PSIZE_8BITS |DMA_SCR_DIR_P2M)
+# define SPI_TXDMA16_CONFIG (SPI_DMA_PRIO|DMA_SCR_MSIZE_16BITS|DMA_SCR_PSIZE_16BITS|DMA_SCR_MINC|DMA_SCR_DIR_M2P)
+# define SPI_TXDMA8_CONFIG (SPI_DMA_PRIO|DMA_SCR_MSIZE_8BITS |DMA_SCR_PSIZE_8BITS |DMA_SCR_MINC|DMA_SCR_DIR_M2P)
+# define SPI_TXDMA16NULL_CONFIG (SPI_DMA_PRIO|DMA_SCR_MSIZE_8BITS |DMA_SCR_PSIZE_16BITS |DMA_SCR_DIR_M2P)
+# define SPI_TXDMA8NULL_CONFIG (SPI_DMA_PRIO|DMA_SCR_MSIZE_8BITS |DMA_SCR_PSIZE_8BITS |DMA_SCR_DIR_M2P)
+#else
+# error "Unknown STM32 DMA"
+#endif
+
/* Debug ****************************************************************************/
/* Check if (non-standard) SPI debug is enabled */
@@ -550,6 +564,21 @@ static inline void spi_dmarxwakeup(FAR struct stm32_spidev_s *priv)
#endif
/************************************************************************************
+ * Name: spi_dmatxwakeup
+ *
+ * Description:
+ * Signal that DMA is complete
+ *
+ ************************************************************************************/
+
+#ifdef CONFIG_STM32_SPI_DMA
+static inline void spi_dmatxwakeup(FAR struct stm32_spidev_s *priv)
+{
+ (void)sem_post(&priv->txsem);
+}
+#endif
+
+/************************************************************************************
* Name: spi_dmarxcallback
*
* Description:
@@ -1183,8 +1212,8 @@ static void spi_exchange(FAR struct spi_dev_s *dev, FAR const void *txbuffer,
FAR void *rxbuffer, size_t nwords)
{
FAR struct stm32_spidev_s *priv = (FAR struct stm32_spidev_s *)dev;
- uint16_t rxdummy = 0xffff;
- uint16_t txdummy;
+ static uint16_t rxdummy = 0xffff;
+ static const uint16_t txdummy = 0xffff;
spivdbg("txbuffer=%p rxbuffer=%p nwords=%d\n", txbuffer, rxbuffer, nwords);
DEBUGASSERT(priv && priv->spibase);
@@ -1330,6 +1359,8 @@ static void spi_portinitialize(FAR struct stm32_spidev_s *priv)
priv->rxdma = stm32_dmachannel(priv->rxch);
priv->txdma = stm32_dmachannel(priv->txch);
DEBUGASSERT(priv->rxdma && priv->txdma);
+
+ spi_putreg(priv, STM32_SPI_CR2_OFFSET, SPI_CR2_RXDMAEN | SPI_CR2_TXDMAEN);
#endif
/* Enable spi */
diff --git a/nuttx/arch/arm/src/stm32/stm32_usbdev.c b/nuttx/arch/arm/src/stm32/stm32_usbdev.c
index 602de3824..d13ac8f96 100644
--- a/nuttx/arch/arm/src/stm32/stm32_usbdev.c
+++ b/nuttx/arch/arm/src/stm32/stm32_usbdev.c
@@ -2346,6 +2346,13 @@ static void stm32_suspend(struct stm32_usbdev_s *priv)
{
uint16_t regval;
+ /* Notify the class driver of the suspend event */
+
+ if (priv->driver)
+ {
+ CLASS_SUSPEND(priv->driver, &priv->usbdev);
+ }
+
/* Disable ESOF polling, disable the SUSP interrupt, and enable the WKUP
* interrupt. Clear any pending WKUP interrupt.
*/
@@ -2411,6 +2418,13 @@ static void stm32_initresume(struct stm32_usbdev_s *priv)
/* Reset FSUSP bit and enable normal interrupt handling */
stm32_putreg(STM32_CNTR_SETUP, STM32_USB_CNTR);
+
+ /* Notify the class driver of the resume event */
+
+ if (priv->driver)
+ {
+ CLASS_RESUME(priv->driver, &priv->usbdev);
+ }
}
/****************************************************************************