summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_lowputc.c26
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_serial.c44
-rwxr-xr-xnuttx/configs/stm3210e-eval/README.txt2
-rwxr-xr-xnuttx/configs/stm3210e-eval/ostest/defconfig8
-rwxr-xr-xnuttx/configs/stm3210e-eval/src/stm3210e-internal.h13
-rwxr-xr-xnuttx/configs/stm3210e-eval/src/up_boot.c2
-rwxr-xr-xnuttx/configs/stm3210e-eval/src/up_spi.c8
7 files changed, 45 insertions, 58 deletions
diff --git a/nuttx/arch/arm/src/stm32/stm32_lowputc.c b/nuttx/arch/arm/src/stm32/stm32_lowputc.c
index 0c364022e..adbb29a27 100644
--- a/nuttx/arch/arm/src/stm32/stm32_lowputc.c
+++ b/nuttx/arch/arm/src/stm32/stm32_lowputc.c
@@ -59,15 +59,15 @@
/* Is there a serial console? */
-#if defined(CONFIG_USART1_SERIAL_CONSOLE) && !defined(CONFIG_USART1_DISABLE)
+#if defined(CONFIG_USART1_SERIAL_CONSOLE) && defined(CONFIG_STM32_USART1)
# undef CONFIG_USART2_SERIAL_CONSOLE
# undef CONFIG_USART3_SERIAL_CONSOLE
# define HAVE_CONSOLE 1
-#elif defined(CONFIG_USART2_SERIAL_CONSOLE) && !defined(CONFIG_USART2_DISABLE)
+#elif defined(CONFIG_USART2_SERIAL_CONSOLE) && defined(CONFIG_STM32_USART2)
# undef CONFIG_USART1_SERIAL_CONSOLE
# undef CONFIG_USART3_SERIAL_CONSOLE
# define HAVE_CONSOLE 1
-#elif defined(CONFIG_USART3_SERIAL_CONSOLE) && !defined(CONFIG_USART3_DISABLE)
+#elif defined(CONFIG_USART3_SERIAL_CONSOLE) && defined(CONFIG_STM32_USART3)
# undef CONFIG_USART1_SERIAL_CONSOLE
# undef CONFIG_USART2_SERIAL_CONSOLE
# define HAVE_CONSOLE 1
@@ -219,7 +219,7 @@ void up_lowputc(char ch)
void stm32_lowsetup(void)
{
-#if !defined(CONFIG_USART1_DISABLE) || !defined(CONFIG_USART2_DISABLE) || !defined(CONFIG_USART3_DISABLE)
+#if defined(CONFIG_STM32_USART1) || defined(CONFIG_STM32_USART2) || defined(CONFIG_STM32_USART3)
uint32 enr;
uint32 mapr;
#if defined(HAVE_CONSOLE) && !defined(CONFIG_SUPPRESS_USART_CONFIG)
@@ -233,7 +233,7 @@ void stm32_lowsetup(void)
mapr = getreg32(STM32_AFIO_MAPR);
-#ifndef CONFIG_USART1_DISABLE
+#ifdef CONFIG_STM32_USART1
/* Enable USART1 clocking */
enr = getreg32(STM32_RCC_APB2ENR_OFFSET);
@@ -251,12 +251,12 @@ void stm32_lowsetup(void)
mapr &= ~AFIO_MAPR_USART1_REMAP;
-#endif /* !CONFIG_USART1_DISABLE */
+#endif /* CONFIG_STM32_USART1 */
-#if !defined(CONFIG_USART2_DISABLE) && !defined(CONFIG_USART3_DISABLE)
+#if defined(CONFIG_STM32_USART2) || defined(CONFIG_STM32_USART3)
enr = getreg32(STM32_RCC_APB1ENR_OFFSET);
-#ifndef CONFIG_USART2_DISABLE
+#ifdef CONFIG_STM32_USART2
/* Enable USART2 clocking */
enr |= RCC_APB1ENR_USART2EN;
@@ -272,9 +272,9 @@ void stm32_lowsetup(void)
mapr &= ~AFIO_MAPR_USART2_REMAP;
-#endif /* !CONFIG_USART2_DISABLE */
+#endif /* CONFIG_STM32_USART2 */
-#ifndef CONFIG_USART3_DISABLE
+#ifdef CONFIG_STM32_USART3
/* Enable USART3 clocking */
enr |= RCC_APB1ENR_USART3EN;
@@ -291,11 +291,11 @@ void stm32_lowsetup(void)
mapr &= ~AFIO_MAPR_USART3_REMAP_MASK;
-#endif /* !CONFIG_USART3_DISABLE */
+#endif /* CONFIG_STM32_USART3 */
/* Save the UART enable settings */
putreg32(enr, STM32_RCC_APB1ENR_OFFSET);
-#endif /* !CONFIG_USART2_DISABLE && !CONFIG_USART3_DISABLE */
+#endif /* CONFIG_STM32_USART2 || CONFIG_STM32_USART3 */
/* Save the USART pin mappings */
putreg32(mapr, STM32_AFIO_MAPR);
@@ -334,7 +334,7 @@ void stm32_lowsetup(void)
cr |= (USART_CR1_UE|USART_CR1_TE|USART_CR1_RE);
putreg16(cr, STM32_CONSOLE_BASE + STM32_USART_CR2_OFFSET);
#endif
-#endif /* !CONFIG_USART1_DISABLE && !CONFIG_USART2_DISABLE && !CONFIG_USART3_DISABLE */
+#endif /* CONFIG_STM32_USART1 || CONFIG_STM32_USART2 || CONFIG_STM32_USART3 */
}
diff --git a/nuttx/arch/arm/src/stm32/stm32_serial.c b/nuttx/arch/arm/src/stm32/stm32_serial.c
index 30df74114..e56a8e7d0 100644
--- a/nuttx/arch/arm/src/stm32/stm32_serial.c
+++ b/nuttx/arch/arm/src/stm32/stm32_serial.c
@@ -65,21 +65,21 @@
/* Is there a USART enabled? */
-#if defined(CONFIG_USART1_DISABLE) && defined(CONFIG_USART2_DISABLE) && defined(CONFIG_USART3_DISABLE)
+#if !defined(CONFIG_STM32_USART1) && !defined(CONFIG_STM32_USART2) && !defined(CONFIG_STM32_USART3)
# error "No USARTs enabled"
#endif
/* Is there a serial console? */
-#if defined(CONFIG_USART1_SERIAL_CONSOLE) && !defined(CONFIG_USART1_DISABLE)
+#if defined(CONFIG_USART1_SERIAL_CONSOLE) && defined(CONFIG_STM32_USART1)
# undef CONFIG_USART2_SERIAL_CONSOLE
# undef CONFIG_USART3_SERIAL_CONSOLE
# define HAVE_CONSOLE 1
-#elif defined(CONFIG_USART2_SERIAL_CONSOLE) && !defined(CONFIG_USART2_DISABLE)
+#elif defined(CONFIG_USART2_SERIAL_CONSOLE) && defined(CONFIG_STM32_USART2)
# undef CONFIG_USART1_SERIAL_CONSOLE
# undef CONFIG_USART3_SERIAL_CONSOLE
# define HAVE_CONSOLE 1
-#elif defined(CONFIG_USART3_SERIAL_CONSOLE) && !defined(CONFIG_USART3_DISABLE)
+#elif defined(CONFIG_USART3_SERIAL_CONSOLE) && defined(CONFIG_STM32_USART3)
# undef CONFIG_USART1_SERIAL_CONSOLE
# undef CONFIG_USART3_SERIAL_CONSOLE
# define HAVE_CONSOLE 1
@@ -102,15 +102,15 @@
#if defined(CONFIG_USART1_SERIAL_CONSOLE)
# define CONSOLE_DEV g_usart1port /* USART1 is console */
# define TTYS0_DEV g_usart1port /* USART1 is ttyS0 */
-# ifndef CONFIG_USART2_DISABLE
+# ifdef CONFIG_STM32_USART2
# define TTYS1_DEV g_usart2port /* USART2 is ttyS1 */
-# ifndef CONFIG_USART3_DISABLE
+# ifdef CONFIG_STM32_USART3
# define TTYS2_DEV g_usart3port /* USART3 is ttyS2 */
# else
# undef TTYS1_DEV /* No ttyS2 */
# endif
# else
-# ifndef CONFIG_USART3_DISABLE
+# ifdef CONFIG_STM32_USART3
# define TTYS1_DEV g_usart3port /* USART3 is ttyS1 */
# else
# undef TTYS1_DEV /* No ttyS1 */
@@ -120,15 +120,15 @@
#elif defined(CONFIG_USART2_SERIAL_CONSOLE)
# define CONSOLE_DEV g_usart2port /* USART2 is console */
# define TTYS0_DEV g_usart2port /* USART2 is ttyS0 */
-# ifndef CONFIG_USART1_DISABLE
+# ifdef CONFIG_STM32_USART1
# define TTYS1_DEV g_usart1port /* USART1 is ttyS1 */
-# ifndef CONFIG_USART3_DISABLE
+# ifdef CONFIG_STM32_USART3
# define TTYS2_DEV g_usart3port /* USART3 is ttyS2 */
# else
# undef TTYS1_DEV /* No ttyS2 */
# endif
# else
-# ifndef CONFIG_USART3_DISABLE
+# ifdef CONFIG_STM32_USART3
# define TTYS1_DEV g_usart3port /* USART3 is ttyS1 */
# else
# undef TTYS1_DEV /* No ttyS1 */
@@ -138,15 +138,15 @@
#elif defined(CONFIG_USART3_SERIAL_CONSOLE)
# define CONSOLE_DEV g_usart3port /* USART3 is console */
# define TTYS0_DEV g_usart3port /* USART3 is ttyS0 */
-# ifndef CONFIG_USART1_DISABLE
+# ifdef CONFIG_STM32_USART1
# define TTYS1_DEV g_usart1port /* USART1 is ttyS1 */
-# ifndef CONFIG_USART2_DISABLE
+# ifdef CONFIG_STM32_USART2
# define TTYS2_DEV g_usart2port /* USART2 is ttyS2 */
# else
# undef TTYS1_DEV /* No ttyS2 */
# endif
# else
-# ifndef CONFIG_USART2_DISABLE
+# ifdef CONFIG_STM32_USART2
# define TTYS1_DEV g_usart2port /* USART2 is ttyS1 */
# else
# undef TTYS1_DEV /* No ttyS1 */
@@ -211,22 +211,22 @@ struct uart_ops_s g_uart_ops =
/* I/O buffers */
-#ifndef CONFIG_USART1_DISABLE
+#ifdef CONFIG_STM32_USART1
static char g_usart1rxbuffer[CONFIG_USART1_RXBUFSIZE];
static char g_usart1txbuffer[CONFIG_USART1_TXBUFSIZE];
#endif
-#ifndef CONFIG_USART2_DISABLE
+#ifdef CONFIG_STM32_USART2
static char g_usart2rxbuffer[CONFIG_USART2_RXBUFSIZE];
static char g_usart2txbuffer[CONFIG_USART2_TXBUFSIZE];
#endif
-#ifndef CONFIG_USART3_DISABLE
+#ifdef CONFIG_STM32_USART3
static char g_usart3rxbuffer[CONFIG_USART3_RXBUFSIZE];
static char g_usart3txbuffer[CONFIG_USART3_TXBUFSIZE];
#endif
/* This describes the state of the STM32 USART1 ports. */
-#ifndef CONFIG_USART1_DISABLE
+#ifdef CONFIG_STM32_USART1
static struct up_dev_s g_usart1priv =
{
.usartbase = STM32_USART1_BASE,
@@ -257,7 +257,7 @@ static uart_dev_t g_usart1port =
/* This describes the state of the STM32 USART2 port. */
-#ifndef CONFIG_USART2_DISABLE
+#ifdef CONFIG_STM32_USART2
static struct up_dev_s g_usart2priv =
{
.usartbase = STM32_USART2_BASE,
@@ -288,7 +288,7 @@ static uart_dev_t g_usart2port =
/* This describes the state of the STM32 USART3 port. */
-#ifndef CONFIG_USART3_DISABLE
+#ifdef CONFIG_STM32_USART3
static struct up_dev_s g_usart3priv =
{
.usartbase = STM32_USART3_BASE,
@@ -627,21 +627,21 @@ static int up_interrupt(int irq, void *context)
int passes;
boolean handled;
-#ifndef CONFIG_USART1_DISABLE
+#ifdef CONFIG_STM32_USART1
if (g_usart1priv.irq == irq)
{
dev = &g_usart1port;
}
else
#endif
-#ifndef CONFIG_USART2_DISABLE
+#ifdef CONFIG_STM32_USART2
if (g_usart2priv.irq == irq)
{
dev = &g_usart2port;
}
else
#endif
-#ifndef CONFIG_USART3_DISABLE
+#ifdef CONFIG_STM32_USART3
if (g_usart3priv.irq == irq)
{
dev = &g_usart3port;
diff --git a/nuttx/configs/stm3210e-eval/README.txt b/nuttx/configs/stm3210e-eval/README.txt
index 023055130..51e86d619 100755
--- a/nuttx/configs/stm3210e-eval/README.txt
+++ b/nuttx/configs/stm3210e-eval/README.txt
@@ -237,8 +237,6 @@ STM3210E-EVAL-specific Configuration Options
CONFIG_U[S]ARTn_PARTIY - 0=no parity, 1=odd parity, 2=even parity
CONFIG_U[S]ARTn_2STOP - Two stop bits
- CONFIG_SPI1_DISABLE - Select to disable support for SPI1
- CONFIG_SPI2_DISABLE - Select to disable support for SPI2
CONFIG_SPI_POLLWAIT - Select to disable interrupt driven SPI support.
Poll-waiting is recommended if the interrupt rate would be to
high in the interrupt driven case.
diff --git a/nuttx/configs/stm3210e-eval/ostest/defconfig b/nuttx/configs/stm3210e-eval/ostest/defconfig
index a511d4eb4..d73d0d983 100755
--- a/nuttx/configs/stm3210e-eval/ostest/defconfig
+++ b/nuttx/configs/stm3210e-eval/ostest/defconfig
@@ -126,8 +126,6 @@ CONFIG_STM32_ADC3=n
#
# STM32F103Z specific serial device driver settings
#
-# CONFIG_USARTn_DISABLE - select to disable all support for
-# the UART
# CONFIG_USARTn_SERIAL_CONSOLE - selects the USARTn for the
# console and ttys0 (default is the USART1).
# CONFIG_USARTn_RXBUFSIZE - Characters are buffered as received.
@@ -139,12 +137,6 @@ CONFIG_STM32_ADC3=n
# CONFIG_USARTn_PARTIY - 0=no parity, 1=odd parity, 2=even parity
# CONFIG_USARTn_2STOP - Two stop bits
#
-CONFIG_USART1_DISABLE=n
-CONFIG_USART2_DISABLE=y
-CONFIG_USART3_DISABLE=y
-CONFIG_USART4_DISABLE=y
-CONFIG_USART5_DISABLE=y
-
CONFIG_USART1_SERIAL_CONSOLE=y
CONFIG_USART2_SERIAL_CONSOLE=n
CONFIG_USART3_SERIAL_CONSOLE=n
diff --git a/nuttx/configs/stm3210e-eval/src/stm3210e-internal.h b/nuttx/configs/stm3210e-eval/src/stm3210e-internal.h
index 3e5018c26..683aa1054 100755
--- a/nuttx/configs/stm3210e-eval/src/stm3210e-internal.h
+++ b/nuttx/configs/stm3210e-eval/src/stm3210e-internal.h
@@ -54,14 +54,11 @@
* expanded).
*/
-#if STM32_NSPI == 0
-# undef CONFIG_SPI1_DISABLE
-# define CONFIG_SPI1_DISABLE 1
-# undef CONFIG_SPI2_DISABLE
-# define CONFIG_SPI2_DISABLE 1
-#elif STM32_NSPI == 1
-# undef CONFIG_SPI2_DISABLE
-# define CONFIG_SPI2_DISABLE 1
+#if STM32_NSPI < 1
+# undef CONFIG_STM32_SPI1
+# undef CONFIG_STM32_SPI2
+#elif STM32_NSPI < 2
+# undef CONFIG_STM32_SPI2
#endif
/* STM3210E-EVAL GPIOs **************************************************************/
diff --git a/nuttx/configs/stm3210e-eval/src/up_boot.c b/nuttx/configs/stm3210e-eval/src/up_boot.c
index cfc02062d..aef793520 100755
--- a/nuttx/configs/stm3210e-eval/src/up_boot.c
+++ b/nuttx/configs/stm3210e-eval/src/up_boot.c
@@ -76,7 +76,7 @@ void stm32_boardinitialize(void)
* stm32_spiinitialize() has been brought into the link.
*/
-#if !defined(CONFIG_SPI1_DISABLE) || !defined(CONFIG_SPI2_DISABLE)
+#if defined(CONFIG_STM32_SPI1) || defined(CONFIG_STM32_SPI2)
if (stm32_spiinitialize)
{
stm32_spiinitialize();
diff --git a/nuttx/configs/stm3210e-eval/src/up_spi.c b/nuttx/configs/stm3210e-eval/src/up_spi.c
index 852c4faec..c652a6eb2 100755
--- a/nuttx/configs/stm3210e-eval/src/up_spi.c
+++ b/nuttx/configs/stm3210e-eval/src/up_spi.c
@@ -51,7 +51,7 @@
#include "stm32_internal.h"
#include "stm3210e-internal.h"
-#if !defined(CONFIG_SPI1_DISABLE) || !defined(CONFIG_SPI2_DISABLE)
+#if defined(CONFIG_STM32_SPI1) || defined(CONFIG_STM32_SPI2)
/************************************************************************************
* Definitions
@@ -115,7 +115,7 @@ void weak_function stm32_spiinitialize(void)
*
****************************************************************************/
-#ifndef CONFIG_SPI1_DISABLE
+#ifdef CONFIG_STM32_SPI1
void stm32_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, boolean selected)
{
spidbg("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert");
@@ -127,7 +127,7 @@ ubyte stm32_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
}
#endif
-#ifndef CONFIG_SPI2_DISABLE
+#ifdef CONFIG_STM32_SPI2
void stm32_spi2select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, boolean selected)
{
spidbg("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert");
@@ -139,4 +139,4 @@ ubyte stm32_spi2status(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
}
#endif
-#endif /* !CONFIG_SPI1_DISABLE || !CONFIG_SPI2_DISABLE */
+#endif /* CONFIG_STM32_SPI1 || CONFIG_STM32_SPI2 */