diff --git a/arch/arm/src/stm32/Make.defs b/arch/arm/src/stm32/Make.defs
index f3aeed1ebdc1d33d2a27ad60ea0358676db1e301..d59363c3ed89eceec802238abd98e07c3a131db2 100644
--- a/arch/arm/src/stm32/Make.defs
+++ b/arch/arm/src/stm32/Make.defs
@@ -49,7 +49,7 @@ CMN_CSRCS	+= up_checkstack.c
 endif
 
 CHIP_ASRCS	= 
-CHIP_CSRCS	= stm32_start.c stm32_rcc.c stm32_gpio.c stm32_flash.c \
+CHIP_CSRCS	= stm32_start.c stm32_rcc.c stm32_gpio.c stm32_exti.c stm32_flash.c \
 		  stm32_irq.c stm32_timerisr.c stm32_dma.c stm32_lowputc.c \
 		  stm32_serial.c stm32_spi.c stm32_usbdev.c stm32_sdio.c \
 		  stm32_tim.c stm32_i2c.c stm32_pwr.c stm32_idle.c stm32_waste.c
@@ -61,3 +61,7 @@ endif
 ifeq ($(CONFIG_RTC),y)
 CHIP_CSRCS	+= stm32_rtc.c
 endif
+
+ifeq ($(CONFIG_DEBUG),y)
+CHIP_CSRCS	+= stm32_dumpgpio.c
+endif
diff --git a/arch/arm/src/stm32/stm32_dma.c b/arch/arm/src/stm32/stm32_dma.c
index 1fec07b2b529fcd0c3cf7df37b16be61f66c2b63..db492b6b83990366f025660ac69372eeaadc9dd4 100644
--- a/arch/arm/src/stm32/stm32_dma.c
+++ b/arch/arm/src/stm32/stm32_dma.c
@@ -56,6 +56,10 @@
 #include "stm32_dma.h"
 #include "stm32_internal.h"
 
+/* Only for the STM32F10xx family for now */
+
+#ifdef CONFIG_STM32_STM32F10XX
+
 /****************************************************************************
  * Pre-processor Definitions
  ****************************************************************************/
@@ -603,3 +607,4 @@ void stm32_dmadump(DMA_HANDLE handle, const struct stm32_dmaregs_s *regs,
 }
 #endif
 
+#endif /* CONFIG_STM32_STM32F10XX */
diff --git a/arch/arm/src/stm32/stm32_dumpgpio.c b/arch/arm/src/stm32/stm32_dumpgpio.c
new file mode 100644
index 0000000000000000000000000000000000000000..6f2f36fb4e6ab660227b511dc051fa49407e5753
--- /dev/null
+++ b/arch/arm/src/stm32/stm32_dumpgpio.c
@@ -0,0 +1,170 @@
+/****************************************************************************
+ * arch/arm/src/stm32/stm32_gpio.c
+ *
+ *   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.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <debug.h>
+
+#include "up_arch.h"
+
+#include "chip.h"
+#include "stm32_gpio.h"
+#include "stm32_rcc.h"
+
+#ifdef CONFIG_DEBUG
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+/* Port letters for prettier debug output */
+
+#ifdef CONFIG_DEBUG
+static const char g_portchar[STM32_NGPIO_PORTS] =
+{
+#if STM32_NGPIO_PORTS > 9
+#  error "Additional support required for this number of GPIOs"
+#elif STM32_NGPIO_PORTS > 8
+  'A', 'B', 'C', 'D', 'E', 'F', 'G', 'H', 'I'
+#elif STM32_NGPIO_PORTS > 7
+  'A', 'B', 'C', 'D', 'E', 'F', 'G', 'H' 
+#elif STM32_NGPIO_PORTS > 6
+  'A', 'B', 'C', 'D', 'E', 'F', 'G'
+#elif STM32_NGPIO_PORTS > 5
+  'A', 'B', 'C', 'D', 'E', 'F'
+#elif STM32_NGPIO_PORTS > 4
+  'A', 'B', 'C', 'D', 'E'
+#elif STM32_NGPIO_PORTS > 3
+  'A', 'B', 'C', 'D'
+#elif STM32_NGPIO_PORTS > 2
+  'A', 'B', 'C'
+#elif STM32_NGPIO_PORTS > 1
+  'A', 'B'
+#elif STM32_NGPIO_PORTS > 0
+  'A'
+#else
+#  error "Bad number of GPIOs"
+#endif
+};
+#endif
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function:  stm32_dumpgpio
+ *
+ * Description:
+ *   Dump all GPIO registers associated with the provided base address
+ *
+ ****************************************************************************/
+
+int stm32_dumpgpio(uint32_t pinset, const char *msg)
+{
+  irqstate_t   flags;
+  uint32_t     base;
+  unsigned int port;
+  unsigned int pin;
+
+  /* Get the base address associated with the GPIO port */
+
+  port = (pinset & GPIO_PORT_MASK) >> GPIO_PORT_SHIFT;
+  pin  = (pinset & GPIO_PIN_MASK) >> GPIO_PIN_SHIFT;
+  base = g_gpiobase[port];
+
+  /* The following requires exclusive access to the GPIO registers */
+
+  flags = irqsave();
+#if defined(CONFIG_STM32_STM32F10XX)
+  lldbg("GPIO%c pinset: %08x base: %08x -- %s\n",
+        g_portchar[port], pinset, base, msg);
+  if ((getreg32(STM32_RCC_APB2ENR) & RCC_APB2ENR_IOPEN(port)) != 0)
+    {
+      lldbg("  CR: %08x %08x IDR: %04x ODR: %04x LCKR: %04x\n",
+            getreg32(base + STM32_GPIO_CRH_OFFSET), getreg32(base + STM32_GPIO_CRL_OFFSET),
+            getreg32(base + STM32_GPIO_IDR_OFFSET), getreg32(base + STM32_GPIO_ODR_OFFSET),
+            getreg32(base + STM32_GPIO_LCKR_OFFSET));
+      lldbg("  EVCR: %02x MAPR: %08x CR: %04x %04x %04x %04x\n",
+            getreg32(STM32_AFIO_EVCR), getreg32(STM32_AFIO_MAPR),
+            getreg32(STM32_AFIO_EXTICR1), getreg32(STM32_AFIO_EXTICR2),
+            getreg32(STM32_AFIO_EXTICR3), getreg32(STM32_AFIO_EXTICR4));
+    }
+  else
+    {
+      lldbg("  GPIO%c not enabled: APB2ENR: %08x\n",
+            g_portchar[port], getreg32(STM32_RCC_APB2ENR));
+    }
+#elif defined(CONFIG_STM32_STM32F40XX)
+  DEBUGASSERT(port < STM32_NGPIO_PORTS);
+
+  lldbg("GPIO%c pinset: %08x base: %08x -- %s\n",
+        g_portchar[port], pinset, base, msg);
+  if ((getreg32(STM32_RCC_APB1ENR) & RCC_AH1BENR_GPIOEN(port)) != 0)
+    {
+      lldbg("  MODE: %08x OTYPE: %04x     OSPEED: %08x PUPDR: %08x\n",
+            getreg32(base + STM32_GPIO_MODER_OFFSET), getreg32(base + STM32_GPIO_OTYPER_OFFSET),
+            getreg32(base + STM32_GPIO_OSPEED_OFFSET), getreg32(base + STM32_GPIO_PUPDR_OFFSET));
+      lldbg("  IDR: %04x       ODR: %04x       BSRR: %08x   LCKR: %04x\n",
+            getreg32(STM32_GPIO_IDR_OFFSET), getreg32(STM32_GPIO_ODR_OFFSET),
+            getreg32(STM32_GPIO_BSRR_OFFSET), getreg32(STM32_GPIO_LCKR_OFFSET));
+      lldbg(" AFRH: %08x  AFRL: %08x\n",
+            getreg32(STM32_GPIO_ARFH_OFFSET), getreg32(STM32_GPIO_AFRL_OFFSET));
+    }
+  else
+    {
+      lldbg("  GPIO%c not enabled: APB1ENR: %08x\n",
+            g_portchar[port], getreg32(STM32_RCC_APB1ENR));
+    }
+#else
+# error "Unsupported STM32 chip"
+#endif
+  irqrestore(flags);
+  return OK;
+}
+
+#endif /* CONFIG_DEBUG */
diff --git a/arch/arm/src/stm32/stm32_exti.c b/arch/arm/src/stm32/stm32_exti.c
new file mode 100644
index 0000000000000000000000000000000000000000..711064cd678c8f15a57ab21d7a4d0b79ee562055
--- /dev/null
+++ b/arch/arm/src/stm32/stm32_exti.c
@@ -0,0 +1,316 @@
+/****************************************************************************
+ * arch/arm/src/stm32/stm32_exti.c
+ *
+ *   Copyright (C) 2009, 2011 Gregory Nutt. All rights reserved.
+ *   Copyright (C) 2011 Uros Platise. All rights reserved.
+ *   Author: Gregory Nutt <gnutt@nuttx.org>
+ *           Uros Platise <uros.platise@isotel.eu>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ *    notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ *    notice, this list of conditions and the following disclaimer in
+ *    the documentation and/or other materials provided with the
+ *    distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ *    used to endorse or promote products derived from this software
+ *    without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+#include <nuttx/irq.h>
+#include <nuttx/arch.h>
+
+#include <stdint.h>
+#include <stdbool.h>
+#include <errno.h>
+#include <debug.h>
+
+#include <arch/irq.h>
+
+#include "up_arch.h"
+#include "chip.h"
+#include "stm32_gpio.h"
+#include "stm32_exti.h"
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+/* Interrupt handlers attached to each EXTI */
+
+static xcpt_t stm32_exti_callbacks[16];
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+ /****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Interrupt Service Routines - Dispatchers
+ ****************************************************************************/
+
+static int stm32_exti0_isr(int irq, void *context)
+{
+  int ret = OK;
+
+  /* Clear the pending interrupt */
+
+  putreg32(0x0001, STM32_EXTI_PR);
+          
+  /* And dispatch the interrupt to the handler */
+          
+  if (stm32_exti_callbacks[0])
+    {
+      ret = stm32_exti_callbacks[0](irq, context);
+    }
+  return ret;
+}
+
+static int stm32_exti1_isr(int irq, void *context)
+{
+  int ret = OK;
+
+  /* Clear the pending interrupt */
+
+  putreg32(0x0002, STM32_EXTI_PR);
+          
+  /* And dispatch the interrupt to the handler */
+          
+  if (stm32_exti_callbacks[1])
+    {
+      ret = stm32_exti_callbacks[1](irq, context);
+    }
+  return ret;
+}
+
+static int stm32_exti2_isr(int irq, void *context)
+{
+  int ret = OK;
+
+  /* Clear the pending interrupt */
+
+  putreg32(0x0004, STM32_EXTI_PR);
+          
+  /* And dispatch the interrupt to the handler */
+          
+  if (stm32_exti_callbacks[2])
+    {
+      ret = stm32_exti_callbacks[2](irq, context);
+    }
+  return ret;
+}
+
+static int stm32_exti3_isr(int irq, void *context)
+{
+  int ret = OK;
+
+  /* Clear the pending interrupt */
+
+  putreg32(0x0008, STM32_EXTI_PR);
+          
+  /* And dispatch the interrupt to the handler */
+          
+  if (stm32_exti_callbacks[3])
+    {
+      ret = stm32_exti_callbacks[3](irq, context);
+    }
+  return ret;
+}
+
+static int stm32_exti4_isr(int irq, void *context)
+{
+  int ret = OK;
+
+  /* Clear the pending interrupt */
+
+  putreg32(0x0010, STM32_EXTI_PR);
+          
+  /* And dispatch the interrupt to the handler */
+          
+  if (stm32_exti_callbacks[4])
+    {
+      ret = stm32_exti_callbacks[4](irq, context);
+    }
+  return ret;
+}
+
+static int stm32_exti_multiisr(int irq, void *context, int first, int last)
+{
+  uint32_t pr;
+  int pin;
+  int ret = OK;
+
+  /* Examine the state of each pin in the group */
+
+  pr = getreg32(STM32_EXTI_PR);
+          
+  /* And dispatch the interrupt to the handler */
+          
+  for (pin = first; pin <= last; pin++)
+    {
+      /* Is an interrupt pending on this pin? */
+
+      uint32_t mask = (1 << pin);
+      if ((pr & mask) != 0)
+        {
+          /* Clear the pending interrupt */
+
+          putreg32(mask, STM32_EXTI_PR);
+          
+          /* And dispatch the interrupt to the handler */
+          
+          if (stm32_exti_callbacks[pin])
+            {
+              int tmp = stm32_exti_callbacks[pin](irq, context);
+              if (tmp != OK)
+                {
+                  ret = tmp;
+                }
+            }
+        }
+    }
+  return ret;
+}
+
+static int stm32_exti95_isr(int irq, void *context)
+{
+  return stm32_exti_multiisr(irq, context, 5, 9);
+}
+
+static int stm32_exti1510_isr(int irq, void *context)
+{
+  return stm32_exti_multiisr(irq, context, 10, 15);
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: stm32_gpiosetevent
+ *
+ * Description:
+ *   Sets/clears GPIO based event and interrupt triggers.
+ * 
+ * Parameters:
+ *  - pinset: gpio pin configuration
+ *  - rising/falling edge: enables
+ *  - event:  generate event when set
+ *  - func:   when non-NULL, generate interrupt
+ * 
+ * Returns: 
+ *  The previous value of the interrupt handler function pointer.  This value may,
+ *  for example, be used to restore the previous handler when multiple handlers are
+ *  used.
+ *
+ ****************************************************************************/
+
+xcpt_t stm32_gpiosetevent(uint32_t pinset, bool risingedge, bool fallingedge, 
+                          bool event, xcpt_t func)
+{
+  uint32_t pin = pinset & GPIO_PIN_MASK;
+  uint32_t exti = STM32_EXTI_BIT(pin);
+  int      irq;
+  xcpt_t   handler;
+  xcpt_t   oldhandler = NULL;
+    
+  /* Select the interrupt handler for this EXTI pin */
+    
+  if (pin < 5)
+    {
+      irq = pin + STM32_IRQ_EXTI0;
+      switch (pin)
+        {
+          case 0:
+            handler = stm32_exti0_isr;
+            break;
+          case 1:
+            handler = stm32_exti1_isr;
+            break;
+          case 2:
+            handler = stm32_exti2_isr;
+            break;
+          case 3:
+            handler = stm32_exti3_isr;
+            break;
+          default:
+            handler = stm32_exti4_isr;
+            break;
+        }
+    }
+  else if (pin < 10)
+    {
+      irq     = STM32_IRQ_EXTI95;
+      handler = stm32_exti95_isr;
+    }
+  else
+    {
+      irq     = STM32_IRQ_EXTI1510;
+      handler = stm32_exti1510_isr;
+    }
+    
+  /* Get the previous GPIO IRQ handler; Save the new IRQ handler. */
+
+  oldhandler = stm32_exti_callbacks[pin];
+  stm32_exti_callbacks[pin] = func;
+
+  /* Install external interrupt handlers */
+    
+  if (func)
+    {
+      irq_attach(irq, handler);
+      up_enable_irq(irq);
+    }
+  else
+    {
+      up_disable_irq(irq);
+    }
+
+  /* Configure GPIO, enable EXTI line enabled if event or interrupt is enabled */
+    
+  if (event || func) 
+    {
+      pinset |= GPIO_EXTI;
+    }
+   
+  stm32_configgpio(pinset);
+
+  /* Configure rising/falling edges */
+
+  modifyreg32(STM32_EXTI_RTSR, risingedge ? 0 : exti, risingedge ? exti : 0);
+  modifyreg32(STM32_EXTI_FTSR, fallingedge ? 0 : exti, fallingedge ? exti : 0);
+
+  /* Enable Events and Interrupts */
+
+  modifyreg32(STM32_EXTI_EMR, event ? 0 : exti, event ? exti : 0);
+  modifyreg32(STM32_EXTI_IMR, func ? 0 : exti, func ? exti : 0);
+
+  /* Return the old IRQ handler */
+
+  return oldhandler;
+}
diff --git a/arch/arm/src/stm32/stm32_flash.c b/arch/arm/src/stm32/stm32_flash.c
index 9648c5f51a1b98a6186a956e0f04115af27671cb..83fcc6172ee1001caa467f434b054f7ade33cc2b 100644
--- a/arch/arm/src/stm32/stm32_flash.c
+++ b/arch/arm/src/stm32/stm32_flash.c
@@ -55,6 +55,8 @@
 
 #include "up_arch.h"
 
+/* Only for the STM32F10xx family for now */
+
 #ifdef CONFIG_STM32_STM32F10XX
 
 /************************************************************************************
diff --git a/arch/arm/src/stm32/stm32_gpio.c b/arch/arm/src/stm32/stm32_gpio.c
index dc1d5dcccafe5d39e6acd37ac87b39f66cca9c52..75a893beecc660feb8976c3969ee828526a84bc8 100644
--- a/arch/arm/src/stm32/stm32_gpio.c
+++ b/arch/arm/src/stm32/stm32_gpio.c
@@ -40,29 +40,28 @@
  ****************************************************************************/
 
 #include <nuttx/config.h>
-#include <nuttx/irq.h>
-#include <nuttx/arch.h>
 
+#include <sys/types.h>
 #include <stdint.h>
 #include <stdbool.h>
 #include <errno.h>
 #include <debug.h>
 
-#include <arch/irq.h>
-
 #include "up_arch.h"
+
 #include "chip.h"
 #include "stm32_gpio.h"
-#include "stm32_exti.h"
-#include "stm32_rcc.h"
-#include "stm32_internal.h"
 
 /****************************************************************************
  * Private Data
  ****************************************************************************/
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
 /* Base addresses for each GPIO block */
 
-static const uint32_t g_gpiobase[STM32_NGPIO_PORTS] =
+const uint32_t g_gpiobase[STM32_NGPIO_PORTS] =
 {
 #if STM32_NGPIO_PORTS > 0
   STM32_GPIOA_BASE,
@@ -93,41 +92,6 @@ static const uint32_t g_gpiobase[STM32_NGPIO_PORTS] =
 #endif
 };
 
-/* Port letters for prettier debug output */
-
-#ifdef CONFIG_DEBUG
-static const char g_portchar[STM32_NGPIO_PORTS] =
-{
-#if STM32_NGPIO_PORTS > 9
-#  error "Additional support required for this number of GPIOs"
-#elif STM32_NGPIO_PORTS > 8
-  'A', 'B', 'C', 'D', 'E', 'F', 'G', 'H', 'I'
-#elif STM32_NGPIO_PORTS > 7
-  'A', 'B', 'C', 'D', 'E', 'F', 'G', 'H' 
-#elif STM32_NGPIO_PORTS > 6
-  'A', 'B', 'C', 'D', 'E', 'F', 'G'
-#elif STM32_NGPIO_PORTS > 5
-  'A', 'B', 'C', 'D', 'E', 'F'
-#elif STM32_NGPIO_PORTS > 4
-  'A', 'B', 'C', 'D', 'E'
-#elif STM32_NGPIO_PORTS > 3
-  'A', 'B', 'C', 'D'
-#elif STM32_NGPIO_PORTS > 2
-  'A', 'B', 'C'
-#elif STM32_NGPIO_PORTS > 1
-  'A', 'B'
-#elif STM32_NGPIO_PORTS > 0
-  'A'
-#else
-#  error "Bad number of GPIOs"
-#endif
-};
-#endif
-
-/* Interrupt handles attached to each EXTI */
-
-static xcpt_t stm32_exti_callbacks[16];
-
 /****************************************************************************
  * Private Functions
  ****************************************************************************/
@@ -305,143 +269,6 @@ static int stm32_gpio_configlock(uint32_t cfgset, bool altlock)
 }
 #endif
 
-/****************************************************************************
- * Interrupt Service Routines - Dispatchers
- ****************************************************************************/
-
-static int stm32_exti0_isr(int irq, void *context)
-{
-  int ret = OK;
-
-  /* Clear the pending interrupt */
-
-  putreg32(0x0001, STM32_EXTI_PR);
-          
-  /* And dispatch the interrupt to the handler */
-          
-  if (stm32_exti_callbacks[0])
-    {
-      ret = stm32_exti_callbacks[0](irq, context);
-    }
-  return ret;
-}
-
-static int stm32_exti1_isr(int irq, void *context)
-{
-  int ret = OK;
-
-  /* Clear the pending interrupt */
-
-  putreg32(0x0002, STM32_EXTI_PR);
-          
-  /* And dispatch the interrupt to the handler */
-          
-  if (stm32_exti_callbacks[1])
-    {
-      ret = stm32_exti_callbacks[1](irq, context);
-    }
-  return ret;
-}
-
-static int stm32_exti2_isr(int irq, void *context)
-{
-  int ret = OK;
-
-  /* Clear the pending interrupt */
-
-  putreg32(0x0004, STM32_EXTI_PR);
-          
-  /* And dispatch the interrupt to the handler */
-          
-  if (stm32_exti_callbacks[2])
-    {
-      ret = stm32_exti_callbacks[2](irq, context);
-    }
-  return ret;
-}
-
-static int stm32_exti3_isr(int irq, void *context)
-{
-  int ret = OK;
-
-  /* Clear the pending interrupt */
-
-  putreg32(0x0008, STM32_EXTI_PR);
-          
-  /* And dispatch the interrupt to the handler */
-          
-  if (stm32_exti_callbacks[3])
-    {
-      ret = stm32_exti_callbacks[3](irq, context);
-    }
-  return ret;
-}
-
-static int stm32_exti4_isr(int irq, void *context)
-{
-  int ret = OK;
-
-  /* Clear the pending interrupt */
-
-  putreg32(0x0010, STM32_EXTI_PR);
-          
-  /* And dispatch the interrupt to the handler */
-          
-  if (stm32_exti_callbacks[4])
-    {
-      ret = stm32_exti_callbacks[4](irq, context);
-    }
-  return ret;
-}
-
-static int stm32_exti_multiisr(int irq, void *context, int first, int last)
-{
-  uint32_t pr;
-  int pin;
-  int ret = OK;
-
-  /* Examine the state of each pin in the group */
-
-  pr = getreg32(STM32_EXTI_PR);
-          
-  /* And dispatch the interrupt to the handler */
-          
-  for (pin = first; pin <= last; pin++)
-    {
-      /* Is an interrupt pending on this pin? */
-
-      uint32_t mask = (1 << pin);
-      if ((pr & mask) != 0)
-        {
-          /* Clear the pending interrupt */
-
-          putreg32(mask, STM32_EXTI_PR);
-          
-          /* And dispatch the interrupt to the handler */
-          
-          if (stm32_exti_callbacks[pin])
-            {
-              int tmp = stm32_exti_callbacks[pin](irq, context);
-              if (tmp != OK)
-                {
-                  ret = tmp;
-                }
-            }
-        }
-    }
-  return ret;
-}
-
-static int stm32_exti95_isr(int irq, void *context)
-{
-  return stm32_exti_multiisr(irq, context, 5, 9);
-}
-
-static int stm32_exti1510_isr(int irq, void *context)
-{
-  return stm32_exti_multiisr(irq, context, 10, 15);
-}
-
 /****************************************************************************
  * Function:  stm32_gpioremap
  *
@@ -702,181 +529,3 @@ bool stm32_gpioread(uint32_t pinset)
     }
   return 0;
 }
-
-/****************************************************************************
- * Name: stm32_gpiosetevent
- *
- * Description:
- *   Sets/clears GPIO based event and interrupt triggers.
- * 
- * Parameters:
- *  - pinset: gpio pin configuration
- *  - rising/falling edge: enables
- *  - event:  generate event when set
- *  - func:   when non-NULL, generate interrupt
- * 
- * Returns: 
- *  The previous value of the interrupt handler function pointer.  This value may,
- *  for example, be used to restore the previous handler when multiple handlers are
- *  used.
- *
- ****************************************************************************/
-
-xcpt_t stm32_gpiosetevent(uint32_t pinset, bool risingedge, bool fallingedge, 
-                          bool event, xcpt_t func)
-{
-  uint32_t pin = pinset & GPIO_PIN_MASK;
-  uint32_t exti = STM32_EXTI_BIT(pin);
-  int      irq;
-  xcpt_t   handler;
-  xcpt_t   oldhandler = NULL;
-    
-  /* Select the interrupt handler for this EXTI pin */
-    
-  if (pin < 5)
-    {
-      irq = pin + STM32_IRQ_EXTI0;
-      switch (pin)
-        {
-          case 0:
-            handler = stm32_exti0_isr;
-            break;
-          case 1:
-            handler = stm32_exti1_isr;
-            break;
-          case 2:
-            handler = stm32_exti2_isr;
-            break;
-          case 3:
-            handler = stm32_exti3_isr;
-            break;
-          default:
-            handler = stm32_exti4_isr;
-            break;
-        }
-    }
-  else if (pin < 10)
-    {
-      irq     = STM32_IRQ_EXTI95;
-      handler = stm32_exti95_isr;
-    }
-  else
-    {
-      irq     = STM32_IRQ_EXTI1510;
-      handler = stm32_exti1510_isr;
-    }
-    
-  /* Get the previous GPIO IRQ handler; Save the new IRQ handler. */
-
-  oldhandler = stm32_exti_callbacks[pin];
-  stm32_exti_callbacks[pin] = func;
-
-  /* Install external interrupt handlers */
-    
-  if (func)
-    {
-      irq_attach(irq, handler);
-      up_enable_irq(irq);
-    }
-  else
-    {
-      up_disable_irq(irq);
-    }
-
-  /* Configure GPIO, enable EXTI line enabled if event or interrupt is enabled */
-    
-  if (event || func) 
-    {
-      pinset |= GPIO_EXTI;
-    }
-   
-  stm32_configgpio(pinset);
-
-  /* Configure rising/falling edges */
-
-  modifyreg32(STM32_EXTI_RTSR, risingedge ? 0 : exti, risingedge ? exti : 0);
-  modifyreg32(STM32_EXTI_FTSR, fallingedge ? 0 : exti, fallingedge ? exti : 0);
-
-  /* Enable Events and Interrupts */
-
-  modifyreg32(STM32_EXTI_EMR, event ? 0 : exti, event ? exti : 0);
-  modifyreg32(STM32_EXTI_IMR, func ? 0 : exti, func ? exti : 0);
-
-  /* Return the old IRQ handler */
-
-  return oldhandler;
-}
-
-/****************************************************************************
- * Function:  stm32_dumpgpio
- *
- * Description:
- *   Dump all GPIO registers associated with the provided base address
- *
- ****************************************************************************/
-
-#ifdef CONFIG_DEBUG
-int stm32_dumpgpio(uint32_t pinset, const char *msg)
-{
-  irqstate_t   flags;
-  uint32_t     base;
-  unsigned int port;
-  unsigned int pin;
-
-  /* Get the base address associated with the GPIO port */
-
-  port = (pinset & GPIO_PORT_MASK) >> GPIO_PORT_SHIFT;
-  pin  = (pinset & GPIO_PIN_MASK) >> GPIO_PIN_SHIFT;
-  base = g_gpiobase[port];
-
-  /* The following requires exclusive access to the GPIO registers */
-
-  flags = irqsave();
-#if defined(CONFIG_STM32_STM32F10XX)
-  lldbg("GPIO%c pinset: %08x base: %08x -- %s\n",
-        g_portchar[port], pinset, base, msg);
-  if ((getreg32(STM32_RCC_APB2ENR) & RCC_APB2ENR_IOPEN(port)) != 0)
-    {
-      lldbg("  CR: %08x %08x IDR: %04x ODR: %04x LCKR: %04x\n",
-            getreg32(base + STM32_GPIO_CRH_OFFSET), getreg32(base + STM32_GPIO_CRL_OFFSET),
-            getreg32(base + STM32_GPIO_IDR_OFFSET), getreg32(base + STM32_GPIO_ODR_OFFSET),
-            getreg32(base + STM32_GPIO_LCKR_OFFSET));
-      lldbg("  EVCR: %02x MAPR: %08x CR: %04x %04x %04x %04x\n",
-            getreg32(STM32_AFIO_EVCR), getreg32(STM32_AFIO_MAPR),
-            getreg32(STM32_AFIO_EXTICR1), getreg32(STM32_AFIO_EXTICR2),
-            getreg32(STM32_AFIO_EXTICR3), getreg32(STM32_AFIO_EXTICR4));
-    }
-  else
-    {
-      lldbg("  GPIO%c not enabled: APB2ENR: %08x\n",
-            g_portchar[port], getreg32(STM32_RCC_APB2ENR));
-    }
-#elif defined(CONFIG_STM32_STM32F40XX)
-  DEBUGASSERT(port < STM32_NGPIO_PORTS);
-
-  lldbg("GPIO%c pinset: %08x base: %08x -- %s\n",
-        g_portchar[port], pinset, base, msg);
-  if ((getreg32(STM32_RCC_APB1ENR) & RCC_AH1BENR_GPIOEN(port)) != 0)
-    {
-      lldbg("  MODE: %08x OTYPE: %04x     OSPEED: %08x PUPDR: %08x\n",
-            getreg32(base + STM32_GPIO_MODER_OFFSET), getreg32(base + STM32_GPIO_OTYPER_OFFSET),
-            getreg32(base + STM32_GPIO_OSPEED_OFFSET), getreg32(base + STM32_GPIO_PUPDR_OFFSET));
-      lldbg("  IDR: %04x       ODR: %04x       BSRR: %08x   LCKR: %04x\n",
-            getreg32(STM32_GPIO_IDR_OFFSET), getreg32(STM32_GPIO_ODR_OFFSET),
-            getreg32(STM32_GPIO_BSRR_OFFSET), getreg32(STM32_GPIO_LCKR_OFFSET));
-      lldbg(" AFRH: %08x  AFRL: %08x\n",
-            getreg32(STM32_GPIO_ARFH_OFFSET), getreg32(STM32_GPIO_AFRL_OFFSET));
-    }
-  else
-    {
-      lldbg("  GPIO%c not enabled: APB1ENR: %08x\n",
-            g_portchar[port], getreg32(STM32_RCC_APB1ENR));
-    }
-
-#else
-# error "Unsupported STM32 chip"
-#endif
-  irqrestore(flags);
-  return OK;
-}
-#endif
diff --git a/arch/arm/src/stm32/stm32_gpio.h b/arch/arm/src/stm32/stm32_gpio.h
index a93038ef0e649f3930bf1df224f9b8a4866cb45f..19e0adbe0d4d40d704bc745fd03ea76d03451469 100644
--- a/arch/arm/src/stm32/stm32_gpio.h
+++ b/arch/arm/src/stm32/stm32_gpio.h
@@ -384,6 +384,14 @@ extern "C" {
 #  error "Unrecognized STM32 chip"
 #endif
 
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/* Base addresses for each GPIO block */
+
+extern const uint32_t g_gpiobase[STM32_NGPIO_PORTS];
+
 /************************************************************************************
  * Public Function Prototypes
  ************************************************************************************/
diff --git a/arch/arm/src/stm32/stm32_lowputc.c b/arch/arm/src/stm32/stm32_lowputc.c
index 4d7527962538644a7bcf6657d23d8df787524c4e..fe10c7608a1c2d5d4cf888b4f860d6a8792fdbbb 100644
--- a/arch/arm/src/stm32/stm32_lowputc.c
+++ b/arch/arm/src/stm32/stm32_lowputc.c
@@ -47,6 +47,7 @@
 #include "up_arch.h"
 
 #include "chip.h"
+
 #include "stm32_rcc.h"
 #include "stm32_gpio.h"
 #include "stm32_uart.h"
@@ -55,27 +56,86 @@
 /**************************************************************************
  * Private Definitions
  **************************************************************************/
-
 /* Configuration **********************************************************/
+/* Make sure that we have not enabled more U[S]ARTs than are support by
+ * the device.
+ */
+
+#if STM32_NUSART < 6
+#  undef CONFIG_STM32_USART6
+#endif
+#if STM32_NUSART < 5
+#  undef CONFIG_STM32_UART5
+#endif
+#if STM32_NUSART < 4
+#  undef CONFIG_STM32_UART4
+#endif
+#if STM32_NUSART < 3
+#  undef CONFIG_STM32_USART3
+#endif
+#if STM32_NUSART < 2
+#  undef CONFIG_STM32_USART2
+#endif
+#if STM32_NUSART < 1
+#  undef CONFIG_STM32_USART1
+#endif
+
+#if defined(CONFIG_STM32_USART1) || defined (CONFIG_STM32_USART2) || defined(CONFIG_STM32_USART3) || \
+    defined(CONFIG_STM32_UART4)  || defined (CONFIG_STM32_UART5)  || defined(CONFIG_STM32_USART6)
+# define HAVE_UART
+#endif
 
 /* Is there a serial console? */
 
 #if defined(CONFIG_USART1_SERIAL_CONSOLE) && defined(CONFIG_STM32_USART1)
 #  undef CONFIG_USART2_SERIAL_CONSOLE
 #  undef CONFIG_USART3_SERIAL_CONSOLE
+#  undef CONFIG_UART4_SERIAL_CONSOLE
+#  undef CONFIG_UART5_SERIAL_CONSOLE
+#  undef CONFIG_USART6_SERIAL_CONSOLE
 #  define HAVE_CONSOLE 1
 #elif defined(CONFIG_USART2_SERIAL_CONSOLE) && defined(CONFIG_STM32_USART2)
 #  undef CONFIG_USART1_SERIAL_CONSOLE
 #  undef CONFIG_USART3_SERIAL_CONSOLE
+#  undef CONFIG_USART4_SERIAL_CONSOLE
+#  undef CONFIG_USART5_SERIAL_CONSOLE
+#  undef CONFIG_USART6_SERIAL_CONSOLE
 #  define HAVE_CONSOLE 1
 #elif defined(CONFIG_USART3_SERIAL_CONSOLE) && defined(CONFIG_STM32_USART3)
 #  undef CONFIG_USART1_SERIAL_CONSOLE
 #  undef CONFIG_USART2_SERIAL_CONSOLE
+#  undef CONFIG_UART4_SERIAL_CONSOLE
+#  undef CONFIG_UART5_SERIAL_CONSOLE
+#  undef CONFIG_USART6_SERIAL_CONSOLE
+#  define HAVE_CONSOLE 1
+#elif defined(CONFIG_UART4_SERIAL_CONSOLE) && defined(CONFIG_STM32_UART4)
+#  undef CONFIG_USART1_SERIAL_CONSOLE
+#  undef CONFIG_USART2_SERIAL_CONSOLE
+#  undef CONFIG_USART3_SERIAL_CONSOLE
+#  undef CONFIG_UART5_SERIAL_CONSOLE
+#  undef CONFIG_USART6_SERIAL_CONSOLE
+#  define HAVE_CONSOLE 1
+#elif defined(CONFIG_UART5_SERIAL_CONSOLE) && defined(CONFIG_STM32_UART5)
+#  undef CONFIG_USART1_SERIAL_CONSOLE
+#  undef CONFIG_USART2_SERIAL_CONSOLE
+#  undef CONFIG_USART3_SERIAL_CONSOLE
+#  undef CONFIG_UART4_SERIAL_CONSOLE
+#  undef CONFIG_USART6_SERIAL_CONSOLE
+#  define HAVE_CONSOLE 1
+#elif defined(CONFIG_USART6_SERIAL_CONSOLE) && defined(CONFIG_STM32_USART6)
+#  undef CONFIG_USART1_SERIAL_CONSOLE
+#  undef CONFIG_USART2_SERIAL_CONSOLE
+#  undef CONFIG_USART3_SERIAL_CONSOLE
+#  undef CONFIG_UART4_SERIAL_CONSOLE
+#  undef CONFIG_UART5_SERIAL_CONSOLE
 #  define HAVE_CONSOLE 1
 #else
 #  undef CONFIG_USART1_SERIAL_CONSOLE
 #  undef CONFIG_USART2_SERIAL_CONSOLE
 #  undef CONFIG_USART3_SERIAL_CONSOLE
+#  undef CONFIG_UART4_SERIAL_CONSOLE
+#  undef CONFIG_UART5_SERIAL_CONSOLE
+#  undef CONFIG_USART6_SERIAL_CONSOLE
 #  undef HAVE_CONSOLE
 #endif
 
@@ -102,6 +162,27 @@
 #  define STM32_CONSOLE_BITS     CONFIG_USART3_BITS
 #  define STM32_CONSOLE_PARITY   CONFIG_USART3_PARITY
 #  define STM32_CONSOLE_2STOP    CONFIG_USART3_2STOP
+#elif defined(CONFIG_UART4_SERIAL_CONSOLE)
+#  define STM32_CONSOLE_BASE     STM32_USART4_BASE
+#  define STM32_APBCLOCK         STM32_PCLK1_FREQUENCY
+#  define STM32_CONSOLE_BAUD     CONFIG_USART4_BAUD
+#  define STM32_CONSOLE_BITS     CONFIG_USART4_BITS
+#  define STM32_CONSOLE_PARITY   CONFIG_USART4_PARITY
+#  define STM32_CONSOLE_2STOP    CONFIG_USART4_2STOP
+#elif defined(CONFIG_UART5_SERIAL_CONSOLE)
+#  define STM32_CONSOLE_BASE     STM32_USART5_BASE
+#  define STM32_APBCLOCK         STM32_PCLK1_FREQUENCY
+#  define STM32_CONSOLE_BAUD     CONFIG_USART5_BAUD
+#  define STM32_CONSOLE_BITS     CONFIG_USART5_BITS
+#  define STM32_CONSOLE_PARITY   CONFIG_USART5_PARITY
+#  define STM32_CONSOLE_2STOP    CONFIG_USART5_2STOP
+#elif defined(CONFIG_USART6_SERIAL_CONSOLE)
+#  define STM32_CONSOLE_BASE     STM32_USART6_BASE
+#  define STM32_APBCLOCK         STM32_PCLK2_FREQUENCY
+#  define STM32_CONSOLE_BAUD     CONFIG_USART6_BAUD
+#  define STM32_CONSOLE_BITS     CONFIG_USART6_BITS
+#  define STM32_CONSOLE_PARITY   CONFIG_USART6_PARITY
+#  define STM32_CONSOLE_2STOP    CONFIG_USART6_2STOP
 #else
 #  error "No CONFIG_USARTn_SERIAL_CONSOLE Setting"
 #endif
@@ -239,9 +320,10 @@ void up_lowputc(char ch)
  *
  **************************************************************************/
 
+#if defined(CONFIG_STM32_STM32F10XX)
 void stm32_lowsetup(void)
 {
-#if defined(CONFIG_STM32_USART1) || defined(CONFIG_STM32_USART2) || defined(CONFIG_STM32_USART3)
+#if defined(HAVE_UART)
   uint32_t mapr;
 #if defined(HAVE_CONSOLE) && !defined(CONFIG_SUPPRESS_UART_CONFIG)
   uint32_t cr;
@@ -364,7 +446,107 @@ void stm32_lowsetup(void)
   cr |= (USART_CR1_UE|USART_CR1_TE|USART_CR1_RE);
   putreg32(cr, STM32_CONSOLE_BASE + STM32_USART_CR1_OFFSET);
 #endif
-#endif /* CONFIG_STM32_USART1 || CONFIG_STM32_USART2 || CONFIG_STM32_USART3 */
+#endif /* HAVE_UART */
+}
+#elif defined(CONFIG_STM32_STM32F40XX)
+void stm32_lowsetup(void)
+{
+#if defined(HAVE_UART)
+#if defined(HAVE_CONSOLE) && !defined(CONFIG_SUPPRESS_UART_CONFIG)
+  uint32_t cr;
+#endif
+
+  /* Enable the selected USARTs and configure GPIO pins need by the
+   * the selected USARTs.  NOTE: The serial driver later depends on
+   * this pin configuration -- whether or not a serial console is selected.
+   *
+   * NOTE: Clocking for USART1, USART2, and/or USART3 was already provided in stm32_rcc.c
+   */
+
+#ifdef CONFIG_STM32_USART1
+  stm32_configgpio(GPIO_USART1_TX);
+  stm32_configgpio(GPIO_USART1_RX);
+# ifdef GPIO_USART1_CTS
+  stm32_configgpio(GPIO_USART1_CTS);
+  stm32_configgpio(GPIO_USART1_RTS);
+# endif
+#endif
+
+#ifdef CONFIG_STM32_USART2
+  stm32_configgpio(GPIO_USART2_TX);
+  stm32_configgpio(GPIO_USART2_RX);
+# ifdef GPIO_USART2_CTS
+  stm32_configgpio(GPIO_USART2_CTS);
+  stm32_configgpio(GPIO_USART2_RTS);
+# endif
+#endif
+
+#ifdef CONFIG_STM32_USART3
+  stm32_configgpio(GPIO_USART3_TX);
+  stm32_configgpio(GPIO_USART3_RX);
+# ifdef GPIO_USART3_CTS
+  stm32_configgpio(GPIO_USART3_CTS);
+  stm32_configgpio(GPIO_USART3_RTS);
+# endif
+#endif
+
+#ifdef CONFIG_STM32_UART4
+  stm32_configgpio(GPIO_UART4_TX);
+  stm32_configgpio(GPIO_UART4_RX);
+#endif
+
+#ifdef CONFIG_STM32_UART5
+  stm32_configgpio(GPIO_UART5_TX);
+  stm32_configgpio(GPIO_UART5_RX);
+#endif
+
+#ifdef CONFIG_STM32_USART6
+  stm32_configgpio(GPIO_USART6_TX);
+  stm32_configgpio(GPIO_USART6_RX);
+# ifdef GPIO_USART6_CTS
+  stm32_configgpio(GPIO_USART6_CTS);
+  stm32_configgpio(GPIO_USART6_RTS);
+# endif
+#endif
+
+  /* Enable and configure the selected console device */
+
+#if defined(HAVE_CONSOLE) && !defined(CONFIG_SUPPRESS_UART_CONFIG)
+  /* Configure CR2 */
+
+  cr  = getreg32(STM32_CONSOLE_BASE + STM32_USART_CR2_OFFSET);
+  cr &= ~USART_CR2_CLRBITS;
+  cr |= USART_CR2_SETBITS;
+  putreg32(cr, STM32_CONSOLE_BASE + STM32_USART_CR2_OFFSET);
+
+  /* Configure CR1 */
+
+  cr  = getreg32(STM32_CONSOLE_BASE + STM32_USART_CR1_OFFSET);
+  cr &= ~USART_CR1_CLRBITS;
+  cr |= USART_CR1_SETBITS;
+  putreg32(cr, STM32_CONSOLE_BASE + STM32_USART_CR1_OFFSET);
+
+  /* Configure CR3 */
+
+  cr  = getreg32(STM32_CONSOLE_BASE + STM32_USART_CR3_OFFSET);
+  cr &= ~USART_CR3_CLRBITS;
+  cr |= USART_CR3_SETBITS;
+  putreg32(cr, STM32_CONSOLE_BASE + STM32_USART_CR3_OFFSET);
+
+  /* Configure the USART Baud Rate */
+
+  putreg32(STM32_BRR_VALUE, STM32_CONSOLE_BASE + STM32_USART_BRR_OFFSET);
+
+  /* Enable Rx, Tx, and the USART */
+
+  cr  = getreg32(STM32_CONSOLE_BASE + STM32_USART_CR1_OFFSET);
+  cr |= (USART_CR1_UE|USART_CR1_TE|USART_CR1_RE);
+  putreg32(cr, STM32_CONSOLE_BASE + STM32_USART_CR1_OFFSET);
+#endif
+#endif /* HAVE_UART */
 }
+#else
+#  error "Unsupported STM32 chip"
+#endif
 
 
diff --git a/configs/stm3240g-eval/include/board.h b/configs/stm3240g-eval/include/board.h
index 56a75a56fa0327dc1d9162aecaf6c1cf15715ea1..e3825551fd0c75d7430f460b4ce1dec436660b87 100755
--- a/configs/stm3240g-eval/include/board.h
+++ b/configs/stm3240g-eval/include/board.h
@@ -145,6 +145,16 @@
 
 #warning "Missing logic"
 
+/* Alternate function pin selections ************************************************/
+
+/* UART3:
+ * - PC11 is MicroSDCard_D3 & RS232/IrDA_RX (JP22 open)
+ * - PC10 is MicroSDCard_D2 & RSS232/IrDA_TX
+ */
+
+#define GPIO_USART3_RX GPIO_USART3_RX_2
+#define GPIO_USART3_TX GPIO_USART3_TX_2
+
 /************************************************************************************
  * Public Data
  ************************************************************************************/
diff --git a/configs/stm3240g-eval/ostest/defconfig b/configs/stm3240g-eval/ostest/defconfig
index bc8fcf94ffae0227e81c0d57e7475c9bba0d8e83..80a4ad45b05046c1f6327e7c570938c3c3a76613 100755
--- a/configs/stm3240g-eval/ostest/defconfig
+++ b/configs/stm3240g-eval/ostest/defconfig
@@ -149,7 +149,7 @@ CONFIG_STM32_WWDG=n
 CONFIG_STM32_SPI2=n
 CONFIG_STM32_SPI3=n
 CONFIG_STM32_USART2=n
-CONFIG_STM32_USART3=n
+CONFIG_STM32_USART3=y
 CONFIG_STM32_UART4=n
 CONFIG_STM32_UART5=n
 CONFIG_STM32_I2C1=n
@@ -162,7 +162,7 @@ CONFIG_STM32_DAC=n
 # APB2:
 CONFIG_STM32_TIM1=n
 CONFIG_STM32_TIM8=n
-CONFIG_STM32_USART1=y
+CONFIG_STM32_USART1=n
 CONFIG_STM32_USART6=n
 CONFIG_STM32_ADC1=n
 CONFIG_STM32_ADC2=n
@@ -193,23 +193,23 @@ CONFIG_STM32_TIM11=n
 # CONFIG_USARTn_PARTIY - 0=no parity, 1=odd parity, 2=even parity
 # CONFIG_USARTn_2STOP - Two stop bits
 #
-CONFIG_USART1_SERIAL_CONSOLE=y
+CONFIG_USART1_SERIAL_CONSOLE=n
 CONFIG_USART2_SERIAL_CONSOLE=n
-CONFIG_USART3_SERIAL_CONSOLE=n
+CONFIG_USART3_SERIAL_CONSOLE=y
 CONFIG_USART4_SERIAL_CONSOLE=n
 CONFIG_USART5_SERIAL_CONSOLE=n
 
-CONFIG_USART1_TXBUFSIZE=256
-CONFIG_USART2_TXBUFSIZE=256
-CONFIG_USART3_TXBUFSIZE=256
-CONFIG_USART4_TXBUFSIZE=256
-CONFIG_USART5_TXBUFSIZE=256
-
-CONFIG_USART1_RXBUFSIZE=256
-CONFIG_USART2_RXBUFSIZE=256
-CONFIG_USART3_RXBUFSIZE=256
-CONFIG_USART4_RXBUFSIZE=256
-CONFIG_USART5_RXBUFSIZE=256
+CONFIG_USART1_TXBUFSIZE=128
+CONFIG_USART2_TXBUFSIZE=128
+CONFIG_USART3_TXBUFSIZE=128
+CONFIG_USART4_TXBUFSIZE=128
+CONFIG_USART5_TXBUFSIZE=128
+
+CONFIG_USART1_RXBUFSIZE=128
+CONFIG_USART2_RXBUFSIZE=128
+CONFIG_USART3_RXBUFSIZE=128
+CONFIG_USART4_RXBUFSIZE=128
+CONFIG_USART5_RXBUFSIZE=128
 
 CONFIG_USART1_BAUD=115200
 CONFIG_USART2_BAUD=115200