diff --git a/Documentation/NuttxPortingGuide.html b/Documentation/NuttxPortingGuide.html
index 8ecbf7abc7..f1007f4992 100644
--- a/Documentation/NuttxPortingGuide.html
+++ b/Documentation/NuttxPortingGuide.html
@@ -1008,10 +1008,6 @@ drivers/
| |-- Kconfig
| |-- Make.defs
| `-- (Common sensor driver source files)
-|-- sercomm/
-| |-- Kconfig
-| |-- Make.defs
-| `-- (Files for the Calypso SERCOMM driver)
|-- serial/
| |-- Kconfig
| |-- Make.defs
@@ -1170,8 +1166,6 @@ include/
| | `-- (Power management header files)
| |-sensors/
| | `-- (Sensor device driver header files)
-| |-sercomm/
-| | `-- (SERCOMM driver header files)
| |-serial/
| | `-- (Serial driver header files)
| |-spi/
diff --git a/Documentation/README.html b/Documentation/README.html
index 6e0d32528e..b7d8330c10 100644
--- a/Documentation/README.html
+++ b/Documentation/README.html
@@ -320,8 +320,6 @@ nuttx/
| | `- README.txt
| |- sensors/
| | `- README.txt
- | |- sercomm/
- | | `- README.txt
| |- syslog/
| | `- README.txt
| `- README.txt
diff --git a/README.txt b/README.txt
index f09c6dff96..4ea0c51437 100644
--- a/README.txt
+++ b/README.txt
@@ -1536,8 +1536,6 @@ nuttx/
| | `- README.txt
| |- sensors/
| | `- README.txt
- | |- sercomm/
- | | `- README.txt
| |- syslog/
| | `- README.txt
| `- README.txt
diff --git a/arch/README.txt b/arch/README.txt
index 2e52e95ff0..a0f604e4af 100644
--- a/arch/README.txt
+++ b/arch/README.txt
@@ -158,7 +158,6 @@ arch/arm - ARM-based micro-controllers
MCU support
arch/arm/include/a1x and arch/arm/src/a1x
arch/arm/include/c5471 and arch/arm/src/c5471
- arch/arm/include/calypso and arch/arm/src/calypso
arch/arm/include/dm320 and arch/arm/src/dm320
arch/arm/include/efm32 and arch/arm/src/efm32
arch/arm/include/imx1 and arch/arm/src/imx1
diff --git a/arch/arm/Kconfig b/arch/arm/Kconfig
index 9b721e2a3e..d56e0a861e 100644
--- a/arch/arm/Kconfig
+++ b/arch/arm/Kconfig
@@ -31,16 +31,6 @@ config ARCH_CHIP_C5471
---help---
TI TMS320 C5471, A180, or DA180 (ARM7TDMI)
-config ARCH_CHIP_CALYPSO
- bool "Calypso"
- select ARCH_ARM7TDMI
- select ARCH_HAVE_HEAP2
- select ARCH_HAVE_LOWVECTORS
- select OTHER_UART_SERIALDRIVER
- select ARCH_HAVE_POWEROFF
- ---help---
- TI Calypso-based cell phones (ARM7TDMI)
-
config ARCH_CHIP_DM320
bool "TMS320 DM320"
select ARCH_ARM926EJS
@@ -409,7 +399,6 @@ config ARCH_CHIP
string
default "a1x" if ARCH_CHIP_A1X
default "c5471" if ARCH_CHIP_C5471
- default "calypso" if ARCH_CHIP_CALYPSO
default "dm320" if ARCH_CHIP_DM320
default "efm32" if ARCH_CHIP_EFM32
default "imx1" if ARCH_CHIP_IMX1
@@ -625,9 +614,6 @@ endif
if ARCH_CHIP_C5471
source arch/arm/src/c5471/Kconfig
endif
-if ARCH_CHIP_CALYPSO
-source arch/arm/src/calypso/Kconfig
-endif
if ARCH_CHIP_DM320
source arch/arm/src/dm320/Kconfig
endif
diff --git a/arch/arm/include/calypso/armio.h b/arch/arm/include/calypso/armio.h
deleted file mode 100644
index 2f232beb22..0000000000
--- a/arch/arm/include/calypso/armio.h
+++ /dev/null
@@ -1,49 +0,0 @@
-/****************************************************************************
- * Driver for Calypso ARMIO
- *
- * Copyright (C) 2011 Stefan Richter. All rights reserved.
- * Author: Stefan Richter
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
- *
- * 1. Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * 2. Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in
- * the documentation and/or other materials provided with the
- * distribution.
- * 3. Neither the name NuttX nor the names of its contributors may be
- * used to endorse or promote products derived from this software
- * without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
- * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
- * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- *
- ****************************************************************************/
-
-#include
-#include
-
-/****************************************************************************
- * Prototypes for interrupt handling
- ****************************************************************************/
-
-inline int calypso_kbd_irq(int irq, uint32_t *regs);
-
-/****************************************************************************
- * Initialize device, add /dev/... nodes
- ****************************************************************************/
-
-void calypso_armio(void);
diff --git a/arch/arm/include/calypso/clock.h b/arch/arm/include/calypso/clock.h
deleted file mode 100644
index a10a607a5d..0000000000
--- a/arch/arm/include/calypso/clock.h
+++ /dev/null
@@ -1,67 +0,0 @@
-#ifndef __ARCH_ARM_INCLUDE_CALYPSO_CLOCK_H
-#define __ARCH_ARM_INCLUDE_CALYPSO_CLOCK_H
-
-#include
-
-#define CALYPSO_PLL26_52_MHZ ((2 << 8) | 0)
-#define CALYPSO_PLL26_86_7_MHZ ((10 << 8) | 2)
-#define CALYPSO_PLL26_87_MHZ ((3 << 8) | 0)
-#define CALYPSO_PLL13_104_MHZ ((8 << 8) | 0)
-
-enum mclk_div {
- _ARM_MCLK_DIV_1 = 0,
- ARM_MCLK_DIV_1 = 1,
- ARM_MCLK_DIV_2 = 2,
- ARM_MCLK_DIV_3 = 3,
- ARM_MCLK_DIV_4 = 4,
- ARM_MCLK_DIV_5 = 5,
- ARM_MCLK_DIV_6 = 6,
- ARM_MCLK_DIV_7 = 7,
- ARM_MCLK_DIV_1_5 = 0x80 | 1,
- ARM_MCLK_DIV_2_5 = 0x80 | 2,
-};
-
-void calypso_clock_set(uint8_t vtcxo_div2, uint16_t inp, enum mclk_div mclk_div);
-void calypso_pll_set(uint16_t inp);
-void calypso_clk_dump(void);
-
-/* CNTL_RST */
-enum calypso_rst {
- RESET_DSP = (1 << 1),
- RESET_EXT = (1 << 2),
- RESET_WDOG = (1 << 3),
-};
-
-void calypso_reset_set(enum calypso_rst calypso_rst, int active);
-int calypso_reset_get(enum calypso_rst);
-
-enum calypso_bank {
- CALYPSO_nCS0 = 0,
- CALYPSO_nCS1 = 2,
- CALYPSO_nCS2 = 4,
- CALYPSO_nCS3 = 6,
- CALYPSO_nCS7 = 8,
- CALYPSO_CS4 = 0xa,
- CALYPSO_nCS6 = 0xc,
-};
-
-enum calypso_mem_width {
- CALYPSO_MEM_8bit = 0,
- CALYPSO_MEM_16bit = 1,
- CALYPSO_MEM_32bit = 2,
-};
-
-void calypso_mem_cfg(enum calypso_bank bank, uint8_t ws,
- enum calypso_mem_width width, int we);
-
-/* Enable or disable the internal bootrom mapped to 0x0000'0000 */
-void calypso_bootrom(int enable);
-
-/* Enable or disable the debug unit */
-void calypso_debugunit(int enable);
-
-/* configure the RHEA bus bridge[s] */
-void calypso_rhea_cfg(uint8_t fac0, uint8_t fac1, uint8_t timeout,
- uint8_t ws_h, uint8_t ws_l, uint8_t w_en0, uint8_t w_en1);
-
-#endif /* __ARCH_ARM_INCLUDE_CALYPSO_CLOCK_H */
diff --git a/arch/arm/include/calypso/debug.h b/arch/arm/include/calypso/debug.h
deleted file mode 100644
index 9596946775..0000000000
--- a/arch/arm/include/calypso/debug.h
+++ /dev/null
@@ -1,31 +0,0 @@
-#ifndef __ARCH_ARM_INCLUDE_CALYPSO_DEBUG_H
-#define __ARCH_ARM_INCLUDE_CALYPSO_DEBUG_H
-
-#ifndef ARRAY_SIZE
-#define ARRAY_SIZE(x) (sizeof(x) / sizeof((x)[0]))
-#endif
-
-/*
- * Check at compile time that something is of a particular type.
- * Always evaluates to 1 so you may use it easily in comparisons.
- */
-#define typecheck(type,x) \
-({ type __dummy; \
- typeof(x) __dummy2; \
- (void)(&__dummy == &__dummy2); \
- 1; \
-})
-
-#ifdef DEBUG
-#define dputchar(x) putchar(x)
-#define dputs(x) puts(x)
-#define dphex(x,y) phex(x,y)
-#define printd(x, ...) printf(x, ##__VA_ARGS__)
-#else
-#define dputchar(x)
-#define dputs(x)
-#define dphex(x,y)
-#define printd(x, args ...)
-#endif
-
-#endif /* __ARCH_ARM_INCLUDE_CALYPSO_DEBUG_H */
diff --git a/arch/arm/include/calypso/defines.h b/arch/arm/include/calypso/defines.h
deleted file mode 100644
index 4f29560c83..0000000000
--- a/arch/arm/include/calypso/defines.h
+++ /dev/null
@@ -1,17 +0,0 @@
-#ifndef __ARCH_ARM_INCLUDE_CALYPSO_DEFINES_H
-#define __ARCH_ARM_INCLUDE_CALYPSO_DEFINES_H
-
-#define __attribute_const__ __attribute__((__const__))
-
-/* type properties */
-#define __packed __attribute__((packed))
-#define __aligned(alignment) __attribute__((aligned(alignment)))
-#define __unused __attribute__((unused))
-
-/* linkage */
-#define __section(name) __attribute__((section(name)))
-
-/* force placement in zero-waitstate memory */
-#define __ramtext __section(".ramtext")
-
-#endif /* !__ARCH_ARM_INCLUDE_CALYPSO_DEFINES_H */
diff --git a/arch/arm/include/calypso/irq.h b/arch/arm/include/calypso/irq.h
deleted file mode 100644
index 0dda3f312f..0000000000
--- a/arch/arm/include/calypso/irq.h
+++ /dev/null
@@ -1,81 +0,0 @@
-/****************************************************************************
- * arch/arm/include/calypso/irq.h
- * Driver for Calypso IRQ controller
- *
- * (C) 2010 by Harald Welte
- * (C) 2011 by Stefan Richter
- *
- * This source code is derivated from Osmocom-BB project and was
- * relicensed as BSD with permission from original authors.
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
- *
- * 1. Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * 2. Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in
- * the documentation and/or other materials provided with the
- * distribution.
- * 3. Neither the name NuttX nor the names of its contributors may be
- * used to endorse or promote products derived from this software
- * without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
- * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
- * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- *
- ****************************************************************************/
-
-#ifndef __INCLUDE_NUTTX_IRQ_H
-#error "This file should never be included directly! Use "
-#endif
-
-#ifndef __ARCH_ARM_INCLUDE_CALYPSO_IRQ_H
-#define __ARCH_ARM_INCLUDE_CALYPSO_IRQ_H
-
-#ifndef __ASSEMBLY__
-
-enum irq_nr {
- IRQ_WATCHDOG = 0,
- IRQ_TIMER1 = 1,
- IRQ_TIMER2 = 2,
- IRQ_TSP_RX = 3,
- IRQ_TPU_FRAME = 4,
- IRQ_TPU_PAGE = 5,
- IRQ_SIMCARD = 6,
- IRQ_UART_MODEM = 7,
- IRQ_KEYPAD_GPIO = 8,
- IRQ_RTC_TIMER = 9,
- IRQ_RTC_ALARM_I2C = 10,
- IRQ_ULPD_GAUGING = 11,
- IRQ_EXTERNAL = 12,
- IRQ_SPI = 13,
- IRQ_DMA = 14,
- IRQ_API = 15,
- IRQ_SIM_DETECT = 16,
- IRQ_EXTERNAL_FIQ = 17,
- IRQ_UART_IRDA = 18,
- IRQ_ULPD_GSM_TIMER = 19,
- IRQ_GEA = 20,
- _NR_IRQS
-};
-
-#endif /* __ASSEMBLY__ */
-
-/* Don't use _NR_IRQS!!! Won't work in preprocessor... */
-#define NR_IRQS 21
-
-#define IRQ_SYSTIMER IRQ_TIMER2
-
-#endif /* __ARCH_ARM_INCLUDE_CALYPSO_IRQ_H */
diff --git a/arch/arm/include/calypso/memory.h b/arch/arm/include/calypso/memory.h
deleted file mode 100644
index a4ce1e890e..0000000000
--- a/arch/arm/include/calypso/memory.h
+++ /dev/null
@@ -1,28 +0,0 @@
-#ifndef __ARCH_ARM_INCLUDE_CALYPSO_MEMORY_H
-#define __ARCH_ARM_INCLUDE_CALYPSO_MEMORY_H
-
-#define __arch_getb(a) (*(volatile unsigned char *)(a))
-#define __arch_getw(a) (*(volatile unsigned short *)(a))
-#define __arch_getl(a) (*(volatile unsigned int *)(a))
-
-#define __arch_putb(v,a) (*(volatile unsigned char *)(a) = (v))
-#define __arch_putw(v,a) (*(volatile unsigned short *)(a) = (v))
-#define __arch_putl(v,a) (*(volatile unsigned int *)(a) = (v))
-
-#define __raw_writeb(v,a) __arch_putb(v,a)
-#define __raw_writew(v,a) __arch_putw(v,a)
-#define __raw_writel(v,a) __arch_putl(v,a)
-
-#define __raw_readb(a) __arch_getb(a)
-#define __raw_readw(a) __arch_getw(a)
-#define __raw_readl(a) __arch_getl(a)
-
-#define writeb(v,a) __arch_putb(v,a)
-#define writew(v,a) __arch_putw(v,a)
-#define writel(v,a) __arch_putl(v,a)
-
-#define readb(a) __arch_getb(a)
-#define readw(a) __arch_getw(a)
-#define readl(a) __arch_getl(a)
-
-#endif /* __ARCH_ARM_INCLUDE_CALYPSO_MEMORY_H */
diff --git a/arch/arm/include/calypso/timer.h b/arch/arm/include/calypso/timer.h
deleted file mode 100644
index 93a1bd1492..0000000000
--- a/arch/arm/include/calypso/timer.h
+++ /dev/null
@@ -1,25 +0,0 @@
-#ifndef __ARCH_ARM_INCLUDE_CALYPSO_TIMER_H
-#define __ARCH_ARM_INCLUDE_CALYPSO_TIMER_H
-
-/* Enable or Disable a timer */
-void hwtimer_enable(int num, int on);
-
-/* Configure pre-scaler and if timer is auto-reload */
-void hwtimer_config(int num, uint8_t pre_scale, int auto_reload);
-
-/* Load a timer with the given value */
-void hwtimer_load(int num, uint16_t val);
-
-/* Read the current timer value */
-uint16_t hwtimer_read(int num);
-
-/* Enable or disable the watchdog */
-void wdog_enable(int on);
-
-/* Reset cpu using watchdog */
-void wdog_reset(void);
-
-/* power up the timers */
-void hwtimer_init(void);
-
-#endif /* __ARCH_ARM_INCLUDE_CALYPSO_TIMER_H */
diff --git a/arch/arm/include/calypso/uwire.h b/arch/arm/include/calypso/uwire.h
deleted file mode 100644
index 0ca6c376ca..0000000000
--- a/arch/arm/include/calypso/uwire.h
+++ /dev/null
@@ -1,6 +0,0 @@
-#ifndef __ARCH_ARM_INCLUDE_CALYPSO_UWIRE_H
-#define __ARCH_ARM_INCLUDE_CALYPSO_UWIRE_H
-void uwire_init(void);
-int uwire_xfer(int cs, int bitlen, const void *dout, void *din);
-#endif
-
diff --git a/arch/arm/src/calypso/Kconfig b/arch/arm/src/calypso/Kconfig
deleted file mode 100644
index e044280f62..0000000000
--- a/arch/arm/src/calypso/Kconfig
+++ /dev/null
@@ -1,115 +0,0 @@
-#
-# For a description of the syntax of this configuration file,
-# see the file kconfig-language.txt in the NuttX tools repository.
-#
-
-comment "Calypso Configuration Options"
-
-menu "Modem UART Configuration"
-
-config UART_MODEM_BAUD
- int "Modem UART BAUD"
- default 115200
-
-config UART_MODEM_PARITY
- int "Modem UART parity"
- default 0
- ---help---
- Modem UART parity. 0=None, 1=Odd, 2=Even. Default: None
-
-config UART_MODEM_BITS
- int "Modem UART number of bits"
- default 8
- ---help---
- Modem UART number of bits. Default: 8
-
-config UART_MODEM_2STOP
- int "Modem UART two stop bits"
- default 0
- ---help---
- 0=1 stop bit, 1=Two stop bits. Default: 1 stop bit
-
-config UART_MODEM_RXBUFSIZE
- int "Modem UART Rx buffer size"
- default 256
- ---help---
- Modem UART Rx buffer size. Default: 256
-
-config UART_MODEM_TXBUFSIZE
- int "Modem UART Tx buffer size"
- default 256
- ---help---
- Modem UART Tx buffer size. Default: 256
-
-config UART_MODEM_HWFLOWCONTROL
- bool "Hardware flow control"
- default n
- ---help---
- Enabled Modem UART hardware flow control. Default: n
-
-endmenu
-
-menu "IrDA UART Configuration"
-
-config UART_IRDA_BAUD
- int "IrDA UART BAUD"
- default 115200
-
-config UART_IRDA_PARITY
- int "IrDA UART parity"
- default 0
- ---help---
- IrDA UART parity. 0=None, 1=Odd, 2=Even. Default: None
-
-config UART_IRDA_BITS
- int "IrDA UART number of bits"
- default 8
- ---help---
- IrDA UART number of bits. Default: 8
-
-config UART_IRDA_2STOP
- int "IrDA UART two stop bits"
- default 0
- ---help---
- 0=1 stop bit, 1=Two stop bits. Default: 1 stop bit
-
-config UART_IRDA_RXBUFSIZE
- int "IrDA UART Rx buffer size"
- default 256
- ---help---
- IrDA UART Rx buffer size. Default: 256
-
-config UART_IRDA_TXBUFSIZE
- int "IrDA UART Tx buffer size"
- default 256
- ---help---
- IrDA UART Tx buffer size. Default: 256
-
-config UART_IRDA_HWFLOWCONTROL
- bool "Hardware flow control"
- default n
- ---help---
- Enabled IrDA UART hardware flow control. Default: n
-
-endmenu
-
-choice
- prompt "Serial Console Selection"
- default SERIAL_CONSOLE_NONE
- depends on DEV_CONSOLE
-
-# See drivers/Kconfig
-config USE_SERCOMM_CONSOLE
- bool "SERCOMM console"
- select SERCOMM_CONSOLE
-
-config SERIAL_MODEM_CONSOLE
- bool "Serial console on modem UART"
-
-config SERIAL_IRDA_CONSOLE
- bool "Serial console on IrDA UART"
-
-config SERIAL_CONSOLE_NONE
- bool "No serial console"
-
-endchoice
diff --git a/arch/arm/src/calypso/Make.defs b/arch/arm/src/calypso/Make.defs
deleted file mode 100644
index c3d6b6b0bb..0000000000
--- a/arch/arm/src/calypso/Make.defs
+++ /dev/null
@@ -1,71 +0,0 @@
-############################################################################
-# calypso/Make.defs
-#
-# Copyright (C) 2007, 2013-2015 Gregory Nutt. All rights reserved.
-# Author: Gregory Nutt
-#
-# Copyright (C) 2011 Stefan Richter. All rights reserved.
-# Author: Stefan Richter
-#
-# 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 Gregory Nutt 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.
-#
-############################################################################
-
-HEAD_ASRC = calypso_head.S
-
-CMN_ASRCS = up_saveusercontext.S up_fullcontextrestore.S up_vectors.S
-CMN_ASRCS += up_nommuhead.S vfork.S
-CMN_CSRCS = up_allocateheap.c up_assert.c up_blocktask.c up_copyfullstate.c
-CMN_CSRCS += up_createstack.c up_dataabort.c up_mdelay.c up_udelay.c
-CMN_CSRCS += up_doirq.c up_exit.c up_idle.c up_initialstate.c up_initialize.c
-CMN_CSRCS += up_interruptcontext.c up_prefetchabort.c up_releasepending.c
-CMN_CSRCS += up_releasestack.c up_reprioritizertr.c up_schedulesigaction.c
-CMN_CSRCS += up_sigdeliver.c up_stackframe.c up_syscall.c up_unblocktask.c
-CMN_CSRCS += up_undefinedinsn.c up_usestack.c calypso_power.c up_vfork.c
-
-ifeq ($(CONFIG_ELF),y)
-CMN_CSRCS += up_elf.c
-else ifeq ($(CONFIG_MODULE),y)
-CMN_CSRCS += up_elf.c
-endif
-
-ifeq ($(CONFIG_STACK_COLORATION),y)
-CMN_CSRCS += up_checkstack.c
-endif
-
-CHIP_ASRCS = calypso_lowputc.S
-CHIP_CSRCS = calypso_irq.c calypso_heap.c calypso_serial.c clock.c
-CHIP_CSRCS += calypso_uwire.c calypso_armio.c calypso_keypad.c
-
-ifeq ($(CONFIG_SPI),y)
-CHIP_CSRCS += calypso_spi.c
-endif
-
-ifneq ($(CONFIG_SCHED_TICKLESS),y)
-CHIP_CSRCS += calypso_timer.c
-endif
diff --git a/arch/arm/src/calypso/calypso_armio.c b/arch/arm/src/calypso/calypso_armio.c
deleted file mode 100644
index c210fa34dc..0000000000
--- a/arch/arm/src/calypso/calypso_armio.c
+++ /dev/null
@@ -1,103 +0,0 @@
-/****************************************************************************
- * Driver for shared features of ARMIO modules
- *
- * Copyright (C) 2011 Stefan Richter. All rights reserved.
- * Author: Stefan Richter
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
- *
- * 1. Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * 2. Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in
- * the documentation and/or other materials provided with the
- * distribution.
- * 3. Neither the name NuttX nor the names of its contributors may be
- * used to endorse or promote products derived from this software
- * without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
- * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
- * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- *
- ****************************************************************************/
-
-#include
-
-#include
-#include
-
-#include
-#include
-
-#include "up_arch.h"
-
-/****************************************************************************
- * HW access
- ****************************************************************************/
-
-#define BASE_ADDR_ARMIO 0xfffe4800
-#define ARMIO_REG(x) (BASE_ADDR_ARMIO + (x))
-
-enum armio_reg {
- LATCH_IN = 0x00,
- LATCH_OUT = 0x02,
- IO_CNTL = 0x04,
- CNTL_REG = 0x06,
- LOAD_TIM = 0x08,
- KBR_LATCH_REG = 0x0a,
- KBC_REG = 0x0c,
- BUZZ_LIGHT_REG = 0x0e,
- LIGHT_LEVEL = 0x10,
- BUZZER_LEVEL = 0x12,
- GPIO_EVENT_MODE = 0x14,
- KBD_GPIO_INT = 0x16,
- KBD_GPIO_MASKIT = 0x18,
- GPIO_DEBOUNCING = 0x1a,
- GPIO_LATCH = 0x1c,
-};
-
-#define KBD_INT (1 << 0)
-#define GPIO_INT (1 << 1)
-
-/****************************************************************************
- * ARMIO interrupt handler
- * forward keypad events
- * forward GPIO events
- ****************************************************************************/
-
-static int kbd_gpio_irq(int irq, uint32_t *regs)
-{
- return calypso_kbd_irq(irq, regs);
-}
-
-/****************************************************************************
- * Initialize ARMIO
- ****************************************************************************/
-
-void calypso_armio(void)
-{
- /* Enable ARMIO clock */
-
- putreg16(1 << 5, ARMIO_REG(CNTL_REG));
-
- /* Mask GPIO interrupt and keypad interrupt */
-
- putreg16(KBD_INT | GPIO_INT, ARMIO_REG(KBD_GPIO_MASKIT));
-
- /* Attach and enable the interrupt */
-
- irq_attach(IRQ_KEYPAD_GPIO, (xcpt_t)kbd_gpio_irq);
- up_enable_irq(IRQ_KEYPAD_GPIO);
-}
diff --git a/arch/arm/src/calypso/calypso_head.S b/arch/arm/src/calypso/calypso_head.S
deleted file mode 100644
index eb83b68516..0000000000
--- a/arch/arm/src/calypso/calypso_head.S
+++ /dev/null
@@ -1,23 +0,0 @@
-/* Place a branch to the real head at the entry point */
-.section .text.start
- b __start
-
-
-/* Exception Vectors like they are needed for the exception vector
- indirection of the internal boot ROM. The following section must
- be liked to appear at 0x80001c */
-.section .text.exceptions
-_undef_instr:
- b up_vectorundefinsn
-_sw_interr:
- b up_vectorswi
-_prefetch_abort:
- b up_vectorprefetch
-_data_abort:
- b up_vectordata
-_reserved:
- b _reserved
-_irq:
- b up_vectorirq
-_fiq:
- b up_vectorfiq
diff --git a/arch/arm/src/calypso/calypso_heap.c b/arch/arm/src/calypso/calypso_heap.c
deleted file mode 100644
index 697e05a8f5..0000000000
--- a/arch/arm/src/calypso/calypso_heap.c
+++ /dev/null
@@ -1,101 +0,0 @@
-/****************************************************************************
- * arch/arm/src/calypso/calypso_heap.c
- * Initialize memory interfaces of Calypso MCU
- *
- * (C) 2010 by Harald Welte
- * (C) 2011 Stefan Richter
- *
- * This source code is derivated from Osmocom-BB project and was
- * relicensed as BSD with permission from original authors.
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
- *
- * 1. Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * 2. Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in
- * the documentation and/or other materials provided with the
- * distribution.
- * 3. Neither the name NuttX nor the names of its contributors may be
- * used to endorse or promote products derived from this software
- * without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
- * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
- * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- *
- ****************************************************************************/
-
-/****************************************************************************
- * Included Files
- ****************************************************************************/
-
-#include
-#include
-
-#include
-#include
-
-#include
-#include
-
-#include
-#include
-
-#include "up_arch.h"
-#include "up_internal.h"
-
-/****************************************************************************
- * Pre-processor Definitions
- ****************************************************************************/
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: up_addregion
- *
- * Description:
- * This function is called right after basics are initialized and right
- * before IRQ system setup.
- *
- ****************************************************************************/
-
-#if CONFIG_MM_REGIONS > 1
-void up_addregion(void)
-{
-#ifdef CONFIG_ARCH_BOARD_COMPALE99
- /* Disable watchdog in first non-common function */
- wdog_enable(0);
-#endif
- /* XXX: change to initialization of extern memory with save defaults */
- /* Configure memory interface */
- calypso_mem_cfg(CALYPSO_nCS0, 3, CALYPSO_MEM_16bit, 1);
- calypso_mem_cfg(CALYPSO_nCS1, 3, CALYPSO_MEM_16bit, 1);
- calypso_mem_cfg(CALYPSO_nCS2, 5, CALYPSO_MEM_16bit, 1);
- calypso_mem_cfg(CALYPSO_nCS3, 5, CALYPSO_MEM_16bit, 1);
- calypso_mem_cfg(CALYPSO_CS4, 0, CALYPSO_MEM_8bit, 1);
- calypso_mem_cfg(CALYPSO_nCS6, 0, CALYPSO_MEM_32bit, 1);
- calypso_mem_cfg(CALYPSO_nCS7, 0, CALYPSO_MEM_32bit, 0);
-
- /* Set VTCXO_DIV2 = 1, configure PLL for 104 MHz and give ARM half of that */
- calypso_clock_set(2, CALYPSO_PLL13_104_MHZ, ARM_MCLK_DIV_2);
-
- /* Configure the RHEA bridge with some sane default values */
- calypso_rhea_cfg(0, 0, 0xff, 0, 1, 0, 0);
-
- kmm_addregion((FAR void *)CONFIG_HEAP2_BASE, CONFIG_HEAP2_SIZE);
-}
-#endif
diff --git a/arch/arm/src/calypso/calypso_irq.c b/arch/arm/src/calypso/calypso_irq.c
deleted file mode 100644
index 85f4f08458..0000000000
--- a/arch/arm/src/calypso/calypso_irq.c
+++ /dev/null
@@ -1,357 +0,0 @@
-/****************************************************************************
- * arch/arm/src/calypso/calypso_irq.c
- * Driver for Calypso IRQ controller
- *
- * (C) 2010 by Harald Welte
- * (C) 2011 by Stefan Richter
- *
- * This source code is derivated from Osmocom-BB project and was
- * relicensed as BSD with permission from original authors.
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
- *
- * 1. Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * 2. Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in
- * the documentation and/or other materials provided with the
- * distribution.
- * 3. Neither the name NuttX nor the names of its contributors may be
- * used to endorse or promote products derived from this software
- * without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
- * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
- * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- *
- ****************************************************************************/
-
-/****************************************************************************
- * Included Files
- ****************************************************************************/
-
-#include
-
-#include
-#include
-
-#include
-#include
-
-#include
-#include
-
-#include "arm.h"
-#include "up_internal.h"
-#include "up_arch.h"
-
-/****************************************************************************
- * Pre-processor Definitions
- ****************************************************************************/
-
-#define BASE_ADDR_IRQ 0xfffffa00
-#define BASE_ADDR_IBOOT_EXC 0x0080001C
-
-enum irq_reg
-{
- IT_REG1 = 0x00,
- IT_REG2 = 0x02,
- MASK_IT_REG1 = 0x08,
- MASK_IT_REG2 = 0x0a,
- IRQ_NUM = 0x10,
- FIQ_NUM = 0x12,
- IRQ_CTRL = 0x14,
-};
-
-#define ILR_IRQ(x) (0x20 + (x*2))
-#define IRQ_REG(x) (BASE_ADDR_IRQ + (x))
-
-#ifndef ARRAY_SIZE
-#define ARRAY_SIZE(x) (sizeof(x) / sizeof((x)[0]))
-#endif
-
-/****************************************************************************
- * Public Data
- ****************************************************************************/
-
-/* g_current_regs[] holds a references to the current interrupt level
- * register storage structure. If is non-NULL only during interrupt
- * processing. Access to g_current_regs[] must be through the macro
- * CURRENT_REGS for portability.
- */
-
-volatile uint32_t *g_current_regs[1];
-extern uint32_t _exceptions;
-
-/****************************************************************************
- * Private Data
- ****************************************************************************/
-
-static uint8_t default_irq_prio[] =
-{
- [IRQ_WATCHDOG] = 0xff,
- [IRQ_TIMER1] = 0xff,
- [IRQ_TIMER2] = 0xff,
- [IRQ_TSP_RX] = 0,
- [IRQ_TPU_FRAME] = 3,
- [IRQ_TPU_PAGE] = 0xff,
- [IRQ_SIMCARD] = 0xff,
- [IRQ_UART_MODEM] = 8,
- [IRQ_KEYPAD_GPIO] = 4,
- [IRQ_RTC_TIMER] = 9,
- [IRQ_RTC_ALARM_I2C] = 10,
- [IRQ_ULPD_GAUGING] = 2,
- [IRQ_EXTERNAL] = 12,
- [IRQ_SPI] = 0xff,
- [IRQ_DMA] = 0xff,
- [IRQ_API] = 0xff,
- [IRQ_SIM_DETECT] = 0,
- [IRQ_EXTERNAL_FIQ] = 7,
- [IRQ_UART_IRDA] = 2,
- [IRQ_ULPD_GSM_TIMER] = 1,
- [IRQ_GEA] = 0xff,
-};
-
-/****************************************************************************
- * Private Functions
- ****************************************************************************/
-
-static void _irq_enable(enum irq_nr nr, int enable)
-{
- uintptr_t reg = IRQ_REG(MASK_IT_REG1);
- uint16_t val;
-
- if (nr > 15)
- {
- reg = IRQ_REG(MASK_IT_REG2);
- nr -= 16;
- }
-
- val = getreg16(reg);
- if (enable)
- {
- val &= ~(1 << nr);
- }
- else
- {
- val |= (1 << nr);
- }
-
- putreg16(val, reg);
-}
-
-static void set_default_priorities(void)
-{
- unsigned int i;
-
- for (i = 0; i < ARRAY_SIZE(default_irq_prio); i++)
- {
- uint16_t val;
- uint8_t prio = default_irq_prio[i];
-
- if (prio > 31)
- {
- prio = 31;
- }
-
- val = getreg16(IRQ_REG(ILR_IRQ(i)));
- val &= ~(0x1f << 2);
- val |= prio << 2;
-
- /* Make edge mode default. Hopefully causes less trouble */
-
- val |= 0x02;
-
- putreg16(val, IRQ_REG(ILR_IRQ(i)));
- }
-}
-
-/* Install the exception handlers to where the ROM loader jumps */
-
-static void calypso_exceptions_install(void)
-{
- uint32_t *exceptions_dst = (uint32_t *) BASE_ADDR_IBOOT_EXC;
- uint32_t *exceptions_src = &_exceptions;
- int i;
-
- for (i = 0; i < 7; i++)
- {
- *exceptions_dst++ = *exceptions_src++;
- }
-}
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: up_irqinitialize
- *
- * Description:
- * Setup the IRQ and FIQ controllers
- *
- ****************************************************************************/
-
-void up_irqinitialize(void)
-{
- /* Prepare hardware */
-
- calypso_exceptions_install();
- CURRENT_REGS = NULL;
-
- /* Switch to internal ROM */
-
- calypso_bootrom(1);
-
- /* Set default priorities */
-
- set_default_priorities();
-
- /* Mask all interrupts off */
-
- putreg16(0xffff, IRQ_REG(MASK_IT_REG1));
- putreg16(0xffff, IRQ_REG(MASK_IT_REG2));
-
- /* clear all pending interrupts */
- putreg16(0, IRQ_REG(IT_REG1));
- putreg16(0, IRQ_REG(IT_REG2));
-
- /* Enable interrupts globally to the ARM core */
-
-#ifndef CONFIG_SUPPRESS_INTERRUPTS
- up_irq_restore(SVC_MODE | PSR_F_BIT);
-#endif
-}
-
-/****************************************************************************
- * Name: up_disable_irq
- *
- * Description:
- * Disable the IRQ specified by 'irq'
- *
- ****************************************************************************/
-
-void up_disable_irq(int irq)
-{
- if ((unsigned)irq < NR_IRQS)
- {
- _irq_enable(irq, 0);
- }
-}
-
-/****************************************************************************
- * Name: up_enable_irq
- *
- * Description:
- * Enable the IRQ specified by 'irq'
- *
- ****************************************************************************/
-
-void up_enable_irq(int irq)
-{
- if ((unsigned)irq < NR_IRQS)
- {
- _irq_enable(irq, 1);
- }
-}
-
-/****************************************************************************
- * Name: up_prioritize_irq
- *
- * Description:
- * Set the priority of an IRQ.
- *
- ****************************************************************************/
-
-#ifndef CONFIG_ARCH_IRQPRIO
-int up_prioritize_irq(int nr, int prio)
-{
- uint16_t val;
-
- if (prio == -1)
- {
- prio = default_irq_prio[nr];
- }
-
- if (prio > 31)
- {
- prio = 31;
- }
-
- val = prio << 2;
- putreg16(val, IRQ_REG(ILR_IRQ(nr)));
-
- return 0;
-}
-#endif
-
-/****************************************************************************
- * Entry point for interrupts
- ****************************************************************************/
-
-void up_decodeirq(uint32_t *regs)
-{
- uint8_t num, tmp;
- uint32_t *saved_regs;
-
- /* XXX: What is this???
- * Passed to but ignored in IRQ handlers
- * Only valid meaning is apparently non-NULL == IRQ context */
-
- saved_regs = (uint32_t *)CURRENT_REGS;
- CURRENT_REGS = regs;
-
- /* Detect & deliver the IRQ */
-
- num = getreg8(IRQ_REG(IRQ_NUM)) & 0x1f;
- irq_dispatch(num, regs);
-
- /* Start new IRQ agreement */
-
- tmp = getreg8(IRQ_REG(IRQ_CTRL));
- tmp |= 0x01;
- putreg8(tmp, IRQ_REG(IRQ_CTRL));
-
- CURRENT_REGS = saved_regs;
-}
-
-/****************************************************************************
- * Entry point for FIQs
- ****************************************************************************/
-
-void calypso_fiq(void)
-{
- uint8_t num, tmp;
- uint32_t *regs;
-
- /* XXX: What is this???
- * Passed to but ignored in IRQ handlers
- * Only valid meaning is apparently non-NULL == IRQ context */
-
- regs = (uint32_t *)CURRENT_REGS;
- CURRENT_REGS = (uint32_t *)#
-
- /* Detect & deliver like an IRQ but we are in FIQ context */
-
- num = getreg8(IRQ_REG(FIQ_NUM)) & 0x1f;
- irq_dispatch(num, regs);
-
- /* Start new FIQ agreement */
-
- tmp = getreg8(IRQ_REG(IRQ_CTRL));
- tmp |= 0x02;
- putreg8(tmp, IRQ_REG(IRQ_CTRL));
-
- CURRENT_REGS = regs;
-}
diff --git a/arch/arm/src/calypso/calypso_keypad.c b/arch/arm/src/calypso/calypso_keypad.c
deleted file mode 100644
index 1d9b11b98a..0000000000
--- a/arch/arm/src/calypso/calypso_keypad.c
+++ /dev/null
@@ -1,385 +0,0 @@
-/****************************************************************************
- * Driver for Calypso keypad hardware
- *
- * Copyright (C) 2011 Stefan Richter. All rights reserved.
- * Author: Stefan Richter
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
- *
- * 1. Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * 2. Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in
- * the documentation and/or other materials provided with the
- * distribution.
- * 3. Neither the name NuttX nor the names of its contributors may be
- * used to endorse or promote products derived from this software
- * without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
- * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
- * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- *
- ****************************************************************************/
-
-#include
-
-#include
-#include
-#include
-#include
-
-#include
-#include
-#include
-#include
-#include
-
-#include
-#include
-#include
-#include
-
-/****************************************************************************
- * HW access
- ****************************************************************************/
-
-#define BASE_ADDR_ARMIO 0xfffe4800
-#define ARMIO_REG(x) ((void *)BASE_ADDR_ARMIO + (x))
-
-enum armio_reg
-{
- LATCH_IN = 0x00,
- LATCH_OUT = 0x02,
- IO_CNTL = 0x04,
- CNTL_REG = 0x06,
- LOAD_TIM = 0x08,
- KBR_LATCH_REG = 0x0a,
- KBC_REG = 0x0c,
- BUZZ_LIGHT_REG = 0x0e,
- LIGHT_LEVEL = 0x10,
- BUZZER_LEVEL = 0x12,
- GPIO_EVENT_MODE = 0x14,
- KBD_GPIO_INT = 0x16,
- KBD_GPIO_MASKIT = 0x18,
- GPIO_DEBOUNCING = 0x1a,
- GPIO_LATCH = 0x1c,
-};
-
-#define KBD_INT (1 << 0)
-#define GPIO_INT (1 << 1)
-
-/****************************************************************************
- * Decoder functions for matrix and power button
- ****************************************************************************/
-
-static int btn_dec(uint32_t * btn_state, uint8_t col, uint8_t reg,
- char *buf, size_t buflen, size_t * len)
-{
- uint8_t diff = (*btn_state ^ reg) & 0x1f;
-
- while (diff)
- {
- uint8_t val = diff & ~(diff - 1);
- uint8_t sc = val >> 1;
- sc |= sc << 2;
- sc += col;
- sc += (sc & 0x20) ? 0x26 : 0x3f;
-
- if (reg & val)
- {
- sc |= 0x20;
- }
-
- /* Check for space in buffer and dispatch */
-
- if (*len < buflen)
- {
- buf[(*len)++] = sc;
- }
- else
- {
- break;
- }
-
- /* Only change diff if dispatched/buffer not full */
-
- diff ^= val;
- }
-
- /* Store new state of the buttons (but only if they where dispatch) */
-
- *btn_state >>= 5;
-#ifdef INCLUDE_ALL_COLS
- *btn_state |= (reg ^ diff) << 20;
-#else
- *btn_state |= (reg ^ diff) << 15;
-#endif
- return diff;
-}
-
-static int pwr_btn_dec(uint32_t * state, uint8_t reg, char *buf, size_t * len)
-{
- if (reg)
- {
- /* Check for pressed power button. If pressed, ignore other
- * buttons since it collides with an entire row.
- */
-
- if (~*state & 0x80000000)
- {
- buf[0] = 'z';
- *len = 1;
- *state |= 0x80000000;
- }
-
- return 1; /* break loop in caller */
- }
- else
- {
- /* Check for released power button. */
-
- if (*state & 0x80000000)
- {
- buf[0] = 'Z';
- *len = 1;
-
- *state &= 0x7fffffff;
-
- /* Don't scan others when released; might trigger
- * false keystrokes otherwise
- */
-
- return 1;
- }
- }
-
- return 0; /* Continue with other columns */
-}
-
-/****************************************************************************
- * Keypad: Fileops Prototypes and Structures
- ****************************************************************************/
-
-typedef FAR struct file file_t;
-
-static int keypad_open(file_t * filep);
-static int keypad_close(file_t * filep);
-static ssize_t keypad_read(file_t * filep, FAR char *buffer, size_t buflen);
-#ifndef CONFIG_DISABLE_POLL
-static int keypad_poll(file_t * filep, FAR struct pollfd *fds, bool setup);
-#endif
-
-static const struct file_operations keypad_ops =
-{
- keypad_open, /* open */
- keypad_close, /* close */
- keypad_read, /* read */
- 0, /* write */
- 0, /* seek */
- 0, /* ioctl */
-#ifndef CONFIG_DISABLE_POLL
- keypad_poll /* poll */
-#endif
-};
-
-static sem_t kbdsem;
-
-/****************************************************************************
- * Keypad: Fileops
- ****************************************************************************/
-
-static int keypad_open(file_t * filep)
-{
- register uint16_t reg;
-
- /* Unmask keypad interrupt */
-
- reg = readw(ARMIO_REG(KBD_GPIO_MASKIT));
- writew(reg & ~KBD_INT, ARMIO_REG(KBD_GPIO_MASKIT));
-
- return OK;
-}
-
-static int keypad_close(file_t * filep)
-{
- register uint16_t reg;
-
- /* Mask keypad interrupt */
-
- reg = readw(ARMIO_REG(KBD_GPIO_MASKIT));
- writew(reg | KBD_INT, ARMIO_REG(KBD_GPIO_MASKIT));
-
- return OK;
-}
-
-static ssize_t keypad_read(file_t * filep, FAR char *buf, size_t buflen)
-{
- static uint32_t btn_state = 0;
- register uint16_t reg;
- uint16_t col, col_mask;
- size_t len = 0;
-
- if (buf == NULL || buflen < 1)
- {
- /* Well... nothing to do */
-
- return -EINVAL;
- }
-
-retry:
- col = 1;
- col_mask = 0x1e;
-
- if (!btn_state)
- {
- /* Drive all cols low such that all buttons cause events */
-
- writew(0, ARMIO_REG(KBC_REG));
-
- /* No button currently pressed, use IRQ */
-
- reg = readw(ARMIO_REG(KBD_GPIO_MASKIT));
- writew(reg & ~KBD_INT, ARMIO_REG(KBD_GPIO_MASKIT));
- sem_wait(&kbdsem);
- }
- else
- {
- writew(0x1f, ARMIO_REG(KBC_REG));
- usleep(80000);
- }
-
- /* Scan columns */
-
-#ifdef INCLUDE_ALL_COLS
- while (col <= 6)
- {
-#else
- while (col <= 5)
- {
-#endif
- /* Read keypad latch and immediately set new column since
- * synchronization takes about 5usec. For the 1st round, the
- * interrupt has prepared this and the context switch takes
- * long enough to serve as a delay.
- */
-
- reg = readw(ARMIO_REG(KBR_LATCH_REG));
- writew(col_mask, ARMIO_REG(KBC_REG));
-
- /* Turn pressed buttons into 1s */
-
- reg = 0x1f & ~reg;
-
- if (col == 1)
- {
- /* Power/End switch */
-
- if (pwr_btn_dec(&btn_state, reg, buf, &len))
- {
- break;
- }
- }
- else
- {
- /* Non-power switches */
-
- if (btn_dec(&btn_state, col, reg, buf, buflen, &len))
- {
- break;
- }
- }
-
- /* Select next column and respective mask */
-
- col_mask = 0x1f & ~(1 << col++);
-
- /* We have to wait for synchronization of the inputs. The
- * processing is too fast if no/few buttons are processed.
- */
-
- usleep(5);
-
- /* XXX: usleep seems to suffer hugh overhead. Better this!?
- * If nothing else can be done, it's overhead still wastes
- * time 'usefully'.
- */
- /* sched_yield(); up_udelay(2); */
- }
-
- /* If we don't have anything to return, retry to avoid EOF */
-
- if (!len)
- {
- goto retry;
- }
-
- return len;
-}
-
-/****************************************************************************
- * Keypad interrupt handler
- * mask interrupts
- * prepare column drivers for scan
- * posts keypad semaphore
- ****************************************************************************/
-
-int calypso_kbd_irq(int irq, uint32_t * regs)
-{
- register uint16_t reg;
-
- /* Mask keypad interrupt */
-
- reg = readw(ARMIO_REG(KBD_GPIO_MASKIT));
- writew(reg | KBD_INT, ARMIO_REG(KBD_GPIO_MASKIT));
-
- /* Turn off column drivers */
-
- writew(0x1f, ARMIO_REG(KBC_REG));
-
- /* Let the userspace know */
-
- sem_post(&kbdsem);
-
- return 0;
-}
-
-/****************************************************************************
- * Initialize device, add /dev/... nodes
- ****************************************************************************/
-
-void up_keypad(void)
-{
- /* kbssem semaphore helps leaving IRQ ctx as soon as possible. This
- * semaphore is used for signaling and, hence, should not have priority
- * inheritance enabled.
- */
-
- sem_init(&kbdsem, 0, 0);
- sem_setprotocol(&kbdsem, SEM_PRIO_NONE);
-
- /* Drive cols low in idle state such that all buttons cause events */
-
- writew(0, ARMIO_REG(KBC_REG));
-
- (void)register_driver("/dev/keypad", &keypad_ops, 0444, NULL);
-}
-
-int keypad_kbdinit(void)
-{
- calypso_armio();
- up_keypad();
-
- return OK;
-}
diff --git a/arch/arm/src/calypso/calypso_lowputc.S b/arch/arm/src/calypso/calypso_lowputc.S
deleted file mode 100644
index 5556b3baca..0000000000
--- a/arch/arm/src/calypso/calypso_lowputc.S
+++ /dev/null
@@ -1,133 +0,0 @@
-/**************************************************************************
- * calypso/calypso_lowputc.S
- *
- * Copyright (C) 2011 Stefan Richter. All rights reserved.
- * Author: Stefan Richter
- *
- * based on: c5471/c5471_lowputc.S
- * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
- *
- * 1. Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * 2. Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in
- * the documentation and/or other materials provided with the
- * distribution.
- * 3. Neither the name NuttX nor the names of its contributors may be
- * used to endorse or promote products derived from this software
- * without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
- * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
- * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- *
- **************************************************************************/
-
-/**************************************************************************
- * Included Files
- **************************************************************************/
-
-#include
-
-#include "chip.h"
-#include "up_arch.h"
-#include "up_internal.h"
-
-/**************************************************************************
- * Pre-processor Definitions
- **************************************************************************/
-
-/**************************************************************************
- * Private Types
- **************************************************************************/
-
-/**************************************************************************
- * Private Function Prototypes
- **************************************************************************/
-
-/**************************************************************************
- * Public Data
- **************************************************************************/
-
-/**************************************************************************
- * Private Data
- **************************************************************************/
-
-/**************************************************************************
- * Private Functions
- **************************************************************************/
-
-/**************************************************************************
- * Public Functions
- **************************************************************************/
-
-/**************************************************************************
- * Name: up_lowputc
- **************************************************************************/
-
-/* This assembly language version has the advantage that it can does not
- * require a C stack and uses only r0-r1. Hence it can be used during
- * early boot phases.
- */
-
- .text
- .global up_lowputc
- .type up_lowputc, function
-up_lowputc:
- /* On entry, r0 holds the character to be printed */
-
-#ifdef CONFIG_SERIAL_IRDA_CONSOLE
- ldr r2, =UART_IRDA_BASE /* r2=IRDA UART base */
-#else
- ldr r2, =UART_MODEM_BASE /* r2=Modem UART base */
-#endif
-
- /* Poll bit 0 of the UART_SSR register. When the bit
- * is clear, the TX FIFO is no longer full
- */
-
-1: ldrb r1, [r2, #UART_SSR_OFFS]
- tst r1, #UART_SSR_TXFULL
- bne 1b
-
- /* Send the character by writing it into the UART_THR
- * register.
- */
-
- strb r0, [r2, #UART_THR_OFFS]
-
- /* Wait for the tranmsit holding regiser (THR) to be
- * emptied. This is detemined when bit 6 of the LSR
- * is set.
- */
-
-2: ldrb r1, [r2, #UART_LSR_OFFS]
- tst r1, #0x00000020
- beq 2b
-
- /* If the character that we just sent was a linefeed,
- * then send a carriage return as well.
- */
-
- teq r0, #'\n'
- moveq r0, #'\r'
- beq 1b
-
- /* And return */
-
- mov pc, lr
-
diff --git a/arch/arm/src/calypso/calypso_power.c b/arch/arm/src/calypso/calypso_power.c
deleted file mode 100644
index 11b51a629b..0000000000
--- a/arch/arm/src/calypso/calypso_power.c
+++ /dev/null
@@ -1,50 +0,0 @@
-/****************************************************************************
- * Included Files
- ****************************************************************************/
-
-#include
-
-#include
-
-#include
-#include
-
-#include "calypso_spi.h"
-
-/****************************************************************************
- * Name: board_power_off
- *
- * Description:
- * Power off the board.
- *
- * If this function returns, then it was not possible to power-off the
- * board due to some other constraints.
- *
- * Input Parameters:
- * status - Status information provided with the power off event.
- *
- * Returned Value:
- * If this function returns, then it was not possible to power-off the
- * board due to some constraints. The return value int this case is a
- * board-specific reason for the failure to shutdown.
- *
- ****************************************************************************/
-
-#ifdef CONFIG_BOARDCTL_POWEROFF
-int board_power_off(int status)
-{
- struct spi_dev_s *spi = calypso_spibus_initialize(0);
- uint16_t tx;
-
- SPI_SETBITS(spi, 16);
- (void)SPI_HWFEATURES(spi, 0);
-
- tx = (1 << 6) | (1 << 1);
- SPI_SNDBLOCK(spi, &tx, 1);
-
- tx = (1 << 6) | (30 << 1);
- SPI_SNDBLOCK(spi, &tx, 1);
-
- return 0;
-}
-#endif
diff --git a/arch/arm/src/calypso/calypso_serial.c b/arch/arm/src/calypso/calypso_serial.c
deleted file mode 100644
index 0c4a44c0c1..0000000000
--- a/arch/arm/src/calypso/calypso_serial.c
+++ /dev/null
@@ -1,968 +0,0 @@
-/****************************************************************************
- * arch/arm/src/calypso/calypso_serial.c
- *
- * Copyright (C) 2011 Stefan Richter. All rights reserved.
- * Author: Stefan Richter
- *
- * based on c5471/c5471_serial.c
- * Copyright (C) 2007-2009, 2013 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
- *
- * 1. Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * 2. Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in
- * the documentation and/or other materials provided with the
- * distribution.
- * 3. Neither the name NuttX nor the names of its contributors may be
- * used to endorse or promote products derived from this software
- * without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
- * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
- * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- *
- ****************************************************************************/
-
-/****************************************************************************
- * Included Files
- ****************************************************************************/
-
-#include
-
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-
-#include
-#include
-#include
-#include
-
-#include "chip.h"
-#include "up_arch.h"
-#include "up_internal.h"
-
-/****************************************************************************
- * Pre-processor Definitions
- ****************************************************************************/
-
-#define BASE_BAUD 115200
-
-#if defined(CONFIG_UART_IRDA_HWFLOWCONTROL) || defined(CONFIG_UART_MODEM_HWFLOWCONTROL)
-# define CONFIG_UART_HWFLOWCONTROL
-#endif
-
-#if UART_FCR_OFFS == UART_EFR_OFFS
-# define UART_MULTIPLEX_REGS
-
-/* HW flow control not supported yet */
-
-# undef CONFIG_UART_HWFLOWCONTROL
-#endif
-
-/****************************************************************************
- * Private Types
- ****************************************************************************/
-
-struct uart_regs_s
-{
- uint32_t ier;
- uint32_t lcr;
- uint32_t fcr;
-#ifdef CONFIG_UART_HWFLOWCONTROL
- uint32_t efr;
- uint32_t tcr;
-#endif
-};
-
-struct up_dev_s
-{
- unsigned int uartbase; /* Base address of UART registers */
- unsigned int baud_base; /* Base baud for conversions */
- unsigned int baud; /* Configured baud */
- uint8_t xmit_fifo_size; /* Size of transmit FIFO */
- uint8_t irq; /* IRQ associated with this UART */
- uint8_t parity; /* 0=none, 1=odd, 2=even */
- uint8_t bits; /* Number of bits (7 or 8) */
-#ifdef CONFIG_UART_HWFLOWCONTROL
- bool flowcontrol; /* true: Hardware flow control
- * is enabled. */
-#endif
- bool stopbits2; /* true: Configure with 2
- * stop bits instead of 1 */
- struct uart_regs_s regs; /* Shadow copy of readonly regs */
-
-#ifdef CONFIG_SERCOMM_CONSOLE
- bool sercomm; /* Call sercomm in interrupt if true */
-#endif
-};
-
-/****************************************************************************
- * Private Function Prototypes
- ****************************************************************************/
-
-static int up_setup(struct uart_dev_s *dev);
-static void up_shutdown(struct uart_dev_s *dev);
-static int up_attach(struct uart_dev_s *dev);
-static void up_detach(struct uart_dev_s *dev);
-static int up_interrupt(int irq, void *context);
-static int up_ioctl(struct file *filep, int cmd, unsigned long arg);
-static int up_receive(struct uart_dev_s *dev, unsigned int *status);
-static void up_rxint(struct uart_dev_s *dev, bool enable);
-static bool up_rxavailable(struct uart_dev_s *dev);
-static void up_send(struct uart_dev_s *dev, int ch);
-static void up_txint(struct uart_dev_s *dev, bool enable);
-static bool up_txready(struct uart_dev_s *dev);
-static bool up_txempty(struct uart_dev_s *dev);
-
-/****************************************************************************
- * Private Data
- ****************************************************************************/
-
-static const struct uart_ops_s g_uart_ops =
-{
- .setup = up_setup,
- .shutdown = up_shutdown,
- .attach = up_attach,
- .detach = up_detach,
- .ioctl = up_ioctl,
- .receive = up_receive,
- .rxint = up_rxint,
- .rxavailable = up_rxavailable,
-#ifdef CONFIG_SERIAL_IFLOWCONTROL
- .rxflowcontrol = NULL,
-#endif
- .send = up_send,
- .txint = up_txint,
- .txready = up_txready,
- .txempty = up_txempty,
-};
-
-/* I/O buffers */
-
-static char g_irdarxbuffer[CONFIG_UART_IRDA_RXBUFSIZE];
-static char g_irdatxbuffer[CONFIG_UART_IRDA_TXBUFSIZE];
-static char g_modemrxbuffer[CONFIG_UART_MODEM_RXBUFSIZE];
-static char g_modemtxbuffer[CONFIG_UART_MODEM_TXBUFSIZE];
-
-/* This describes the state of the C5471 serial IRDA port. */
-
-static struct up_dev_s g_irdapriv =
-{
- .xmit_fifo_size = UART_IRDA_XMIT_FIFO_SIZE,
- .baud_base = BASE_BAUD,
- .uartbase = UART_IRDA_BASE,
- .baud = CONFIG_UART_IRDA_BAUD,
- .irq = UART_IRQ_IRDA,
- .parity = CONFIG_UART_IRDA_PARITY,
- .bits = CONFIG_UART_IRDA_BITS,
-#ifdef CONFIG_UART_IRDA_HWFLOWCONTROL
- .flowcontrol = true,
-#endif
- .stopbits2 = CONFIG_UART_IRDA_2STOP,
-
-#ifdef CONFIG_SERCOMM_CONSOLE
- .sercomm = false,
-#endif
-};
-
-static uart_dev_t g_irdaport =
-{
- .recv =
- {
- .size = CONFIG_UART_IRDA_RXBUFSIZE,
- .buffer = g_irdarxbuffer,
- },
- .xmit =
- {
- .size = CONFIG_UART_IRDA_TXBUFSIZE,
- .buffer = g_irdatxbuffer,
- },
- .ops = &g_uart_ops,
- .priv = &g_irdapriv,
-};
-
-/* This describes the state of the C5471 serial Modem port. */
-
-static struct up_dev_s g_modempriv =
-{
- .xmit_fifo_size = UART_XMIT_FIFO_SIZE,
- .baud_base = BASE_BAUD,
- .uartbase = UART_MODEM_BASE,
- .baud = CONFIG_UART_MODEM_BAUD,
- .irq = UART_IRQ_MODEM,
- .parity = CONFIG_UART_MODEM_PARITY,
- .bits = CONFIG_UART_MODEM_BITS,
-#ifdef CONFIG_UART_MODEM_HWFLOWCONTROL
- .flowcontrol = true,
-#endif
- .stopbits2 = CONFIG_UART_MODEM_2STOP,
-
-#ifdef CONFIG_SERCOMM_CONSOLE
- .sercomm = false,
-#endif
-};
-
-static uart_dev_t g_modemport =
-{
- .recv =
- {
- .size = CONFIG_UART_MODEM_RXBUFSIZE,
- .buffer = g_modemrxbuffer,
- },
- .xmit =
- {
- .size = CONFIG_UART_MODEM_TXBUFSIZE,
- .buffer = g_modemtxbuffer,
- },
- .ops = &g_uart_ops,
- .priv = &g_modempriv,
-};
-
-/* Now, which one with be tty0/console and which tty1? */
-
-#ifdef CONFIG_SERIAL_IRDA_CONSOLE
-# define CONSOLE_DEV g_irdaport
-# define TTYS0_DEV g_irdaport
-# define TTYS1_DEV g_modemport
-#else
-# define CONSOLE_DEV g_modemport
-# define TTYS0_DEV g_modemport
-# define TTYS1_DEV g_irdaport
-#endif
-
-/****************************************************************************
- * Private Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: up_inserial
- ****************************************************************************/
-
-static inline uint32_t up_inserial(struct up_dev_s *priv, uint32_t offset)
-{
-#if UART_REGISTER_BITS == 8
- return getreg8(priv->uartbase + offset);
-#elif UART_REGISTER_BITS == 32
- return getreg32(priv->uartbase + offset);
-#else
-#error Unsupported number of bits set in UART_REGISTER_BITS
-#endif
-}
-
-/****************************************************************************
- * Name: up_serialout
- ****************************************************************************/
-
-static inline void up_serialout(struct up_dev_s *priv, uint32_t offset, uint32_t value)
-{
-#if UART_REGISTER_BITS == 8
- putreg8(value & 0xff, priv->uartbase + offset);
-#elif UART_REGISTER_BITS == 32
- putreg32(value, priv->uartbase + offset);
-#endif
-}
-
-/****************************************************************************
- * Name: up_disableuartint
- ****************************************************************************/
-
-static inline void up_disableuartint(struct up_dev_s *priv, uint16_t *ier)
-{
- if (ier)
- {
- *ier = priv->regs.ier & UART_IER_INTMASK;
- }
- priv->regs.ier &= ~UART_IER_INTMASK;
- up_serialout(priv, UART_IER_OFFS, priv->regs.ier);
-}
-
-/****************************************************************************
- * Name: up_restoreuartint
- ****************************************************************************/
-
-static inline void up_restoreuartint(struct up_dev_s *priv, uint16_t ier)
-{
- priv->regs.ier |= ier & (UART_IER_RECVINT | UART_IER_XMITINT);
- up_serialout(priv, UART_IER_OFFS, priv->regs.ier);
-}
-
-/****************************************************************************
- * Name: up_waittxready
- ****************************************************************************/
-
-static inline void up_waittxready(struct up_dev_s *priv)
-{
- int tmp;
-
- for (tmp = 1000 ; tmp > 0 ; tmp--)
- {
- if ((up_inserial(priv, UART_SSR_OFFS) & UART_SSR_TXFULL) == 0)
- {
- break;
- }
- }
-}
-/****************************************************************************
- * Name: up_disablebreaks
- ****************************************************************************/
-
-static inline void up_disablebreaks(struct up_dev_s *priv)
-{
- priv->regs.lcr &= ~UART_LCR_BOC;
- up_serialout(priv, UART_LCR_OFFS, priv->regs.lcr);
-}
-
-/****************************************************************************
- * Name: up_enablebreaks
- ****************************************************************************/
-
-static inline void up_enablebreaks(struct up_dev_s *priv)
-{
- priv->regs.lcr |= UART_LCR_BOC;
- up_serialout(priv, UART_LCR_OFFS, priv->regs.lcr);
-}
-
-/****************************************************************************
- * Name: up_setrate
- ****************************************************************************/
-
-static inline void up_setrate(struct up_dev_s *priv, unsigned int rate)
-{
- uint32_t div_bit_rate;
-
- switch (rate)
- {
- case 115200:
- div_bit_rate = BAUD_115200;
- break;
- case 57600:
- div_bit_rate = BAUD_57600;
- break;
- case 38400:
- div_bit_rate = BAUD_38400;
- break;
- case 19200:
- div_bit_rate = BAUD_19200;
- break;
- case 4800:
- div_bit_rate = BAUD_4800;
- break;
- case 2400:
- div_bit_rate = BAUD_2400;
- break;
- case 1200:
- div_bit_rate = BAUD_1200;
- break;
- case 9600:
- default:
- div_bit_rate = BAUD_9600;
- break;
- }
-
-#ifdef UART_DIV_BIT_RATE_OFFS
- up_serialout(priv, UART_DIV_BIT_RATE_OFFS, div_bit_rate);
-#else
- up_serialout(priv, UART_DIV_LOW_OFFS, div_bit_rate);
- up_serialout(priv, UART_DIV_HIGH_OFFS, div_bit_rate >> 8);
-#endif
-}
-
-/****************************************************************************
- * Name: up_setup
- *
- * Description:
- * Configure the UART baud, bits, parity, fifos, etc. This
- * method is called the first time that the serial port is
- * opened.
- *
- ****************************************************************************/
-#include
-static int up_setup(struct uart_dev_s *dev)
-{
-#ifndef CONFIG_SUPPRESS_UART_CONFIG
- struct up_dev_s *priv = dev->priv;
- unsigned int cval;
-
- if (priv->bits == 7)
- {
- cval = UART_LCR_7BITS;
- }
- else
- {
- cval = UART_LCR_8BITS;
- }
-
- if (priv->stopbits2)
- {
- cval |= UART_LCR_2STOP;
- }
-
- if (priv->parity == 1) /* Odd parity */
- {
- cval |= (UART_LCR_PAREN | UART_LCR_PARODD);
- }
- else if (priv->parity == 2) /* Even parity */
- {
- cval |= (UART_LCR_PAREN | UART_LCR_PAREVEN);
- }
-
- /* Both the IrDA and MODEM UARTs support RESET and UART mode. */
-
- up_serialout(priv, UART_MDR_OFFS, MDR_RESET_MODE);
- up_serialout(priv, UART_LCR_OFFS, 0xbf);
- up_serialout(priv, UART_XON1_OFFS, 0x00);
- up_serialout(priv, UART_XON2_OFFS, 0x00);
- up_serialout(priv, UART_XOFF1_OFFS, 0x00);
- up_serialout(priv, UART_XOFF2_OFFS, 0x00);
- up_serialout(priv, UART_EFR_OFFS, 0x00);
- up_serialout(priv, UART_LCR_OFFS, 0x00);
- up_mdelay(5);
-
- up_serialout(priv, UART_MDR_OFFS, MDR_UART_MODE);
- up_mdelay(5);
-
- priv->regs.ier = up_inserial(priv, UART_IER_OFFS);
- priv->regs.lcr = up_inserial(priv, UART_LCR_OFFS);
-#ifdef CONFIG_UART_HWFLOWCONTROL
- if (priv->flowcontrol)
- {
- priv->regs.efr = up_inserial(priv, UART_EFR_OFFS);
- priv->regs.tcr = up_inserial(priv, UART_TCR_OFFS);
- }
-#endif
-
- up_disableuartint(priv, NULL);
-
-#ifdef UART_MULTIPLEX_REGS
- up_serialout(priv, UART_LCR_OFFS, 0x00bf);
-#endif
-
- up_serialout(priv, UART_EFR_OFFS, 0x0010); /* Unprotect enhanced control */
-
-#ifdef UART_MULTIPLEX_REGS
- priv->regs.lcr = 0x80;
- up_serialout(priv, UART_LCR_OFFS, priv->regs.lcr);
- //up_serialout(priv, UART_MCR_OFFS, 1 << 4); /* loopback */
-#endif
-
- up_serialout(priv, UART_TFCR_OFFS, 0); /* Reset to 0 */
- up_serialout(priv, UART_RFCR_OFFS, UART_FCR_RX_CLR); /* Clear RX fifo */
- up_serialout(priv, UART_TFCR_OFFS, UART_FCR_TX_CLR); /* Clear TX fifo */
- priv->regs.fcr = UART_FCR_FIFO_EN;
- up_serialout(priv, UART_TFCR_OFFS, priv->regs.fcr); /* Enable RX/TX fifos */
-
- up_disablebreaks(priv);
-
- /* Set the RX and TX trigger levels to the minimum */
-
- priv->regs.fcr = (priv->regs.fcr & 0xffffff0f) | UART_FCR_FTL;
- up_serialout(priv, UART_RFCR_OFFS, priv->regs.fcr);
-
- up_setrate(priv, priv->baud);
-
-#ifdef UART_MULTIPLEX_REGS
- up_serialout(priv, UART_SCR_OFFS, 1); /* Disable DMA */
- priv->regs.lcr = (uint32_t)cval; /* Configure mode, return to THR/RHR */
-#else
- priv->regs.lcr &= 0xffffffe0; /* clear original field, and... */
- priv->regs.lcr |= (uint32_t)cval; /* Set new bits in that field. */
-#endif
- up_serialout(priv, UART_LCR_OFFS, priv->regs.lcr);
-
-#ifdef CONFIG_UART_HWFLOWCONTROL
- if (priv->flowcontrol)
- {
- /* Set the FIFO level triggers for flow control
- * Halt = 48 bytes, resume = 12 bytes
- */
-
- priv->regs.tcr = (priv->regs.tcr & 0xffffff00) | 0x0000003c;
- up_serialout(priv, UART_TCR_OFFS, priv->regs.tcr);
-
- /* Enable RTS/CTS flow control */
-
- priv->regs.efr |= 0x000000c0;
- up_serialout(priv, UART_EFR_OFFS, priv->regs.efr);
- }
- else
- {
- /* Disable RTS/CTS flow control */
-
- priv->regs.efr &= 0xffffff3f;
- up_serialout(priv, UART_EFR_OFFS, priv->regs.efr);
- }
-#endif
-#endif
- return OK;
-}
-
-/****************************************************************************
- * Name: up_shutdown
- *
- * Description:
- * Disable the UART. This method is called when the serial port is closed
- *
- ****************************************************************************/
-
-static void up_shutdown(struct uart_dev_s *dev)
-{
- struct up_dev_s *priv = (struct up_dev_s *)CONSOLE_DEV.priv;
- up_disableuartint(priv, NULL);
-}
-
-/****************************************************************************
- * Name: up_attach
- *
- * Description:
- * Configure the UART to operation in interrupt driven mode. This method is
- * called when the serial port is opened. Normally, this is just after the
- * the setup() method is called, however, the serial console may operate in
- * a non-interrupt driven mode during the boot phase.
- *
- * RX and TX interrupts are not enabled when by the attach method (unless the
- * hardware supports multiple levels of interrupt enabling). The RX and TX
- * interrupts are not enabled until the txint() and rxint() methods are called.
- *
- ****************************************************************************/
-
-static int up_attach(struct uart_dev_s *dev)
-{
- struct up_dev_s *priv = (struct up_dev_s *)dev->priv;
- int ret;
-
- /* Attach and enable the IRQ */
-
- ret = irq_attach(priv->irq, up_interrupt);
- if (ret == OK)
- {
- /* Enable the interrupt (RX and TX interrupts are still disabled
- * in the UART
- */
-
- up_enable_irq(priv->irq);
- }
-
- return ret;
-}
-
-/****************************************************************************
- * Name: up_detach
- *
- * Description:
- * Detach UART interrupts. This method is called when the serial port is
- * closed normally just before the shutdown method is called. The exception is
- * the serial console which is never shutdown.
- *
- ****************************************************************************/
-
-static void up_detach(struct uart_dev_s *dev)
-{
- struct up_dev_s *priv = (struct up_dev_s *)dev->priv;
- up_disable_irq(priv->irq);
- irq_detach(priv->irq);
-}
-
-/****************************************************************************
- * Name: up_interrupt
- *
- * Description:
- * This is the UART interrupt handler. It will be invoked
- * when an interrupt received on the 'irq' It should call
- * uart_transmitchars or uart_receivechar to perform the
- * appropriate data transfers. The interrupt handling logic\
- * must be able to map the 'irq' number into the approprite
- * uart_dev_s structure in order to call these functions.
- *
- ****************************************************************************/
-
-static int up_interrupt(int irq, void *context)
-{
- struct uart_dev_s *dev = NULL;
- struct up_dev_s *priv;
- volatile uint32_t cause;
-
- if (g_irdapriv.irq == irq)
- {
- dev = &g_irdaport;
- }
- else if (g_modempriv.irq == irq)
- {
- dev = &g_modemport;
- }
- else
- {
- PANIC();
- }
- priv = (struct up_dev_s *)dev->priv;
-
- cause = up_inserial(priv, UART_ISR_OFFS) & 0x0000003f;
-
- if ((cause & 0x0000000c) == 0x0000000c)
- {
- uint32_t ier_val = 0;
-
- /* Is this an interrupt from the IrDA UART? */
-
- if (irq == UART_IRQ_IRDA)
- {
- /* Save the currently enabled IrDA UART interrupts
- * so that we can restore the IrDA interrupt state
- * below.
- */
-
- ier_val = up_inserial(priv, UART_IER_OFFS);
-
- /* Then disable all IrDA UART interrupts */
-
- up_serialout(priv, UART_IER_OFFS, 0);
- }
-
- /* Receive characters from the RX fifo */
-
-#ifdef CONFIG_SERCOMM_CONSOLE
- if (priv->sercomm)
- {
- sercomm_recvchars(dev);
- }
- else
-#endif
- {
- uart_recvchars(dev);
- }
-
- /* read UART_RHR to clear int condition
- * toss = up_inserialchar(priv,&status);
- */
-
- /* Is this an interrupt from the IrDA UART? */
-
- if (irq == UART_IRQ_IRDA)
- {
- /* Restore the IrDA UART interrupt enables */
-
- up_serialout(priv, UART_IER_OFFS, ier_val);
- }
- }
- else if ((cause & 0x0000000c) == 0x00000004)
- {
-#ifdef CONFIG_SERCOMM_CONSOLE
- if (priv->sercomm)
- {
- sercomm_recvchars(dev);
- }
- else
-#endif
- {
- uart_recvchars(dev);
- }
- }
-
- if ((cause & 0x00000002) != 0)
- {
-#ifdef CONFIG_SERCOMM_CONSOLE
- if (priv->sercomm)
- {
- sercomm_xmitchars(dev);
- }
- else
-#endif
- {
- uart_xmitchars(dev);
- }
- }
-
- return OK;
-}
-
-/****************************************************************************
- * Name: up_ioctl
- *
- * Description:
- * All ioctl calls will be routed through this method
- *
- ****************************************************************************/
-
-static int up_ioctl(struct file *filep, int cmd, unsigned long arg)
-{
- struct inode *inode = filep->f_inode;
- struct uart_dev_s *dev = inode->i_private;
- struct up_dev_s *priv = (struct up_dev_s *)dev->priv;
- int ret = OK;
-
- switch (cmd)
- {
-#ifdef CONFIG_SERIAL_TIOCSERGSTRUCT
- case TIOCSERGSTRUCT:
- {
- struct up_dev_s *user = (struct up_dev_s *)arg;
- if (!user)
- {
- ret = -EINVAL;
- }
- else
- {
- memcpy(user, dev, sizeof(struct up_dev_s));
- }
- }
- break;
-#endif
-
- case TIOCSBRK: /* BSD compatibility: Turn break on, unconditionally */
- {
- irqstate_t flags = enter_critical_section();
- up_enablebreaks(priv);
- leave_critical_section(flags);
- }
- break;
-
- case TIOCCBRK: /* BSD compatibility: Turn break off, unconditionally */
- {
- irqstate_t flags;
- flags = enter_critical_section();
- up_disablebreaks(priv);
- leave_critical_section(flags);
- }
- break;
-
- default:
- ret = -ENOTTY;
- break;
- }
-
- return ret;
-}
-
-/****************************************************************************
- * Name: up_receive
- *
- * Description:
- * Called (usually) from the interrupt level to receive one character from
- * the UART. Error bits associated with the receipt are provided in the
- * the return 'status'.
- *
- ****************************************************************************/
-
-static int up_receive(struct uart_dev_s *dev, unsigned int *status)
-{
- struct up_dev_s *priv = (struct up_dev_s *)dev->priv;
- uint32_t rhr;
- uint32_t lsr;
-
- /* Construct a 16bit status word that uses the high byte to
- * hold the status bits associated with framing,parity,break
- * and a low byte that holds error bits of LSR for
- * conditions such as overflow, etc.
- */
-
- rhr = up_inserial(priv, UART_RHR_OFFS);
- lsr = up_inserial(priv, UART_LSR_OFFS);
-
- *status = (unsigned int)((rhr & 0x0000ff00) | (lsr & 0x000000ff));
-
- return rhr & 0x000000ff;
-}
-
-/****************************************************************************
- * Name: up_rxint
- *
- * Description:
- * Call to enable or disable RX interrupts
- *
- ****************************************************************************/
-
-static void up_rxint(struct uart_dev_s *dev, bool enable)
-{
- struct up_dev_s *priv = (struct up_dev_s *)dev->priv;
- if (enable)
- {
-#ifndef CONFIG_SUPPRESS_SERIAL_INTS
- priv->regs.ier |= UART_IER_RECVINT;
- up_serialout(priv, UART_IER_OFFS, priv->regs.ier);
-#endif
- }
- else
- {
- priv->regs.ier &= ~UART_IER_RECVINT;
- up_serialout(priv, UART_IER_OFFS, priv->regs.ier);
- }
-}
-
-/****************************************************************************
- * Name: up_rxavailable
- *
- * Description:
- * Return true if the receive fifo is not empty
- *
- ****************************************************************************/
-
-static bool up_rxavailable(struct uart_dev_s *dev)
-{
- struct up_dev_s *priv = (struct up_dev_s *)dev->priv;
- return up_inserial(priv, UART_LSR_OFFS) & UART_RX_FIFO_NOEMPTY;
-}
-
-/****************************************************************************
- * Name: up_send
- *
- * Description:
- * This method will send one byte on the UART
- *
- ****************************************************************************/
-
-static void up_send(struct uart_dev_s *dev, int ch)
-{
- struct up_dev_s *priv = (struct up_dev_s *)dev->priv;
- up_serialout(priv, UART_THR_OFFS, (uint8_t)ch);
-}
-
-/****************************************************************************
- * Name: up_txint
- *
- * Description:
- * Call to enable or disable TX interrupts
- *
- ****************************************************************************/
-
-static void up_txint(struct uart_dev_s *dev, bool enable)
-{
- struct up_dev_s *priv = (struct up_dev_s *)dev->priv;
- if (enable)
- {
-#ifndef CONFIG_SUPPRESS_SERIAL_INTS
- priv->regs.ier |= UART_IER_XMITINT;
- up_serialout(priv, UART_IER_OFFS, priv->regs.ier);
-#endif
- }
- else
- {
- priv->regs.ier &= ~UART_IER_XMITINT;
- up_serialout(priv, UART_IER_OFFS, priv->regs.ier);
- }
-}
-
-/****************************************************************************
- * Name: up_txready
- *
- * Description:
- * Return true if the tranmsit fifo is not full
- *
- ****************************************************************************/
-
-static bool up_txready(struct uart_dev_s *dev)
-{
- struct up_dev_s *priv = (struct up_dev_s *)dev->priv;
- return (up_inserial(priv, UART_SSR_OFFS) & UART_SSR_TXFULL) == 0;
-}
-
-/****************************************************************************
- * Name: up_txempty
- *
- * Description:
- * Return true if the transmit fifo is empty
- *
- ****************************************************************************/
-
-static bool up_txempty(struct uart_dev_s *dev)
-{
- struct up_dev_s *priv = (struct up_dev_s *)dev->priv;
- return (up_inserial(priv, UART_LSR_OFFS) & UART_LSR_TREF) != 0;
-}
-
-/****************************************************************************
- * Public Funtions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: up_earlyserialinit
- *
- * Description:
- * Performs the low level UART initialization early in
- * debug so that the serial console will be available
- * during bootup. This must be called before up_serialinit.
- *
- ****************************************************************************/
-
-void up_earlyserialinit(void)
-{
- up_disableuartint(TTYS0_DEV.priv, NULL);
- up_disableuartint(TTYS1_DEV.priv, NULL);
-
- CONSOLE_DEV.isconsole = true;
- up_setup(&CONSOLE_DEV);
-}
-
-/****************************************************************************
- * Name: up_serialinit
- *
- * Description:
- * Register serial console and serial ports. This assumes
- * that up_earlyserialinit was called previously.
- *
- ****************************************************************************/
-
-void up_serialinit(void)
-{
-#ifdef CONFIG_SERCOMM_CONSOLE
- ((struct up_dev_s *)TTYS0_DEV.priv)->sercomm = true;
- (void)sercomm_register("/dev/console", &TTYS0_DEV);
- (void)uart_register("/dev/ttyS0", &TTYS1_DEV);
-#else
- (void)uart_register("/dev/console", &CONSOLE_DEV);
- (void)uart_register("/dev/ttyS0", &TTYS0_DEV);
- (void)uart_register("/dev/ttyS1", &TTYS1_DEV);
-#endif
-}
-
-/****************************************************************************
- * Name: up_putc
- *
- * Description:
- * Provide priority, low-level access to support OS debug
- * writes
- *
- ****************************************************************************/
-
-int up_putc(int ch)
-{
- struct up_dev_s *priv = (struct up_dev_s *)CONSOLE_DEV.priv;
- uint16_t ier;
-
- up_disableuartint(priv, &ier);
- up_waittxready(priv);
- up_serialout(priv, UART_THR_OFFS, (uint8_t)ch);
-
- /* Check for LF */
-
- if (ch == '\n')
- {
- /* Add CR */
-
- up_waittxready(priv);
- up_serialout(priv, UART_THR_OFFS, '\r');
- }
-
- up_waittxready(priv);
- up_restoreuartint(priv, ier);
- return ch;
-}
-
diff --git a/arch/arm/src/calypso/calypso_spi.c b/arch/arm/src/calypso/calypso_spi.c
deleted file mode 100644
index 36727927c4..0000000000
--- a/arch/arm/src/calypso/calypso_spi.c
+++ /dev/null
@@ -1,314 +0,0 @@
-/****************************************************************************
- * arch/arm/src/calypso/calypso_spi.c
- * SPI driver for TI Calypso
- *
- * Copyright (C) 2010 Harald Welte
- * Copyright (C) 2011 Stefan Richter
- *
- * Part of this source code is derivated from Osmocom-BB project and was
- * relicensed as BSD with permission from original authors.
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
- *
- * 1. Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * 2. Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in
- * the documentation and/or other materials provided with the
- * distribution.
- * 3. Neither the name NuttX nor the names of its contributors may be
- * used to endorse or promote products derived from this software
- * without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
- * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
- * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- *
- ****************************************************************************/
-
-#include
-#include
-
-#include
-#include
-#include
-#include
-#include
-
-#include "up_arch.h"
-#include "calypso_spi.h"
-
-#warning "MOST OF SPI API IS INCOMPLETE! (Wrapper around Osmocom driver)"
-extern void spi_init(void);
-extern int spi_xfer(uint8_t dev_idx, uint8_t bitlen, const void *dout, void *din);
-
-#ifndef CONFIG_SPI_EXCHANGE
-#error "Calypso HW only supports exchange. Enable CONFIG_SPI_EXCHANGE!"
-#endif
-
-struct calypso_spidev_s
-{
- struct spi_dev_s spidev; /* External driver interface */
- int nbits; /* Number of transfered bits */
- sem_t exclsem; /* Supports mutually exclusive access */
-};
-
-static int spi_lock(FAR struct spi_dev_s *dev, bool lock)
-{
- struct calypso_spidev_s *priv = (struct calypso_spidev_s *)dev;
-
- if (lock)
- {
- /* Take the semaphore (perhaps waiting) */
-
- while (sem_wait(&priv->exclsem) != 0)
- {
- /* The only case that an error should occur here is if the wait
- * was awakened by a signal.
- */
-
- DEBUGASSERT(errno == EINTR);
- }
- }
- else
- {
- (void)sem_post(&priv->exclsem);
- }
-
- return OK;
-}
-
-/* STUBS! */
-
-static void spi_select(FAR struct spi_dev_s *dev, enum spi_dev_e devid,
- bool selected)
-{
-}
-
-static uint32_t spi_setfrequency(FAR struct spi_dev_s *dev, uint32_t frequency)
-{
- return frequency;
-}
-
-static void spi_setmode(FAR struct spi_dev_s *dev, enum spi_mode_e mode)
-{
-}
-
-/* Osmocom wrapper */
-
-static void spi_setbits(FAR struct spi_dev_s *dev, int nbits)
-{
- ((FAR struct calypso_spidev_s *)dev)->nbits = nbits;
-}
-
-static void spi_exchange(FAR struct spi_dev_s *dev, FAR const void *txbuffer,
- FAR void *rxbuffer, size_t nwords)
-{
- FAR struct calypso_spidev_s *priv = (FAR struct calypso_spidev_s *)dev;
- size_t i;
-
- for (i = 0; i < nwords; i++)
- {
- spi_xfer(0, priv->nbits, txbuffer + i, rxbuffer + i);
- }
-}
-
-static uint16_t spi_send(FAR struct spi_dev_s *dev, uint16_t wd)
-{
- uint16_t buf = wd;
- spi_exchange(dev, &buf, &buf, 1);
- return buf;
-}
-
-static const struct spi_ops_s g_spiops =
-{
- .lock = spi_lock,
- .select = spi_select,
- .setfrequency = spi_setfrequency,
- .setmode = spi_setmode,
- .setbits = spi_setbits,
-#ifdef CONFIG_SPI_HWFEATURES
- .hwfeatures = 0,
-#endif
- .status = 0,
-#ifdef CONFIG_SPI_CMDDATA
- .cmddata = 0,
-#endif
- .send = spi_send,
-#ifdef CONFIG_SPI_EXCHANGE
- .exchange = spi_exchange,
-#else
- .sndblock = spi_sndblock,
- .recvblock = spi_recvblock,
-#endif
- .registercallback = 0,
-};
-
-static struct calypso_spidev_s g_spidev =
-{
- .spidev = { &g_spiops },
- .nbits = 0,
- .exclsem = SEM_INITIALIZER(1)
-};
-
-void spi_init(void)
-{
- putreg16(SPI_SET1_EN_CLK | SPI_SET1_WR_IRQ_DIS | SPI_SET1_RDWR_IRQ_DIS,
- SPI_REG(REG_SET1));
-
- putreg16(0x0001, SPI_REG(REG_SET2));
-}
-
-int spi_xfer(uint8_t dev_idx, uint8_t bitlen, const void *dout, void *din)
-{
- uint8_t bytes_per_xfer;
- uint8_t reg_status, reg_ctrl = 0;
- uint32_t tmp;
-
- if (bitlen == 0)
- {
- return 0;
- }
-
- if (bitlen > 32)
- {
- return -1;
- }
-
- if (dev_idx > 4)
- {
- return -1;
- }
-
- bytes_per_xfer = bitlen / 8;
- if (bitlen % 8)
- {
- bytes_per_xfer ++;
- }
-
- reg_ctrl |= (bitlen - 1) << SPI_CTRL_NB_SHIFT;
- reg_ctrl |= (dev_idx & 0x7) << SPI_CTRL_AD_SHIFT;
-
- if (bitlen <= 8)
- {
- tmp = *(uint8_t *)dout;
- tmp <<= 24 + (8-bitlen); /* align to MSB */
- }
- else if (bitlen <= 16)
- {
- tmp = *(uint16_t *)dout;
- tmp <<= 16 + (16-bitlen); /* align to MSB */
- }
- else
- {
- tmp = *(uint32_t *)dout;
- tmp <<= (32-bitlen); /* align to MSB */
- }
-
- spiinfo("spi_xfer(dev_idx=%u, bitlen=%u, data_out=0x%08x): ",
- dev_idx, bitlen, tmp);
-
- /* fill transmit registers */
-
- putreg16(tmp >> 16, SPI_REG(REG_TX_MSB));
- putreg16(tmp & 0xffff, SPI_REG(REG_TX_LSB));
-
- /* initiate transfer */
-
- if (din)
- {
- reg_ctrl |= SPI_CTRL_RDWR;
- }
- else
- {
- reg_ctrl |= SPI_CTRL_WR;
- }
-
- putreg16(reg_ctrl, SPI_REG(REG_CTRL));
- spiinfo("reg_ctrl=0x%04x ", reg_ctrl);
-
- /* wait until the transfer is complete */
-
- while (1)
- {
- reg_status = getreg16(SPI_REG(REG_STATUS));
- spiinfo("status=0x%04x ", reg_status);
- if (din && (reg_status & SPI_STATUS_RE))
- {
- break;
- }
- else if (reg_status & SPI_STATUS_WE)
- {
- break;
- }
- }
-
- /* FIXME: calibrate how much delay we really need (seven 13MHz cycles) */
-
- usleep(1000);
-
- if (din)
- {
- tmp = getreg16(SPI_REG(REG_RX_MSB)) << 16;
- tmp |= getreg16(SPI_REG(REG_RX_LSB));
- spiinfo("data_in=0x%08x ", tmp);
-
- if (bitlen <= 8)
- {
- *(uint8_t *)din = tmp & 0xff;
- }
- else if (bitlen <= 16)
- {
- *(uint16_t *)din = tmp & 0xffff;
- }
- else
- {
- *(uint32_t *)din = tmp;
- }
- }
-
- spiinfo("\n");
-
- return 0;
-}
-
-/****************************************************************************
- * Name: calypso_spibus_initialize
- *
- * Description:
- * Initialize the selected SPI port
- *
- * Input Parameter:
- * Port number (for hardware that has mutiple SPI interfaces)
- *
- * Returned Value:
- * Valid SPI device structure reference on succcess; a NULL on failure
- *
- ****************************************************************************/
-
-FAR struct spi_dev_s *calypso_spibus_initialize(int port)
-{
- switch (port)
- {
- case 0: /* SPI master device */
- spi_init();
- return (FAR struct spi_dev_s *)&g_spidev;
-
- case 1: /* uWire device */
- return NULL;
-
- default:
- return NULL;
- }
-}
diff --git a/arch/arm/src/calypso/calypso_spi.h b/arch/arm/src/calypso/calypso_spi.h
deleted file mode 100644
index 70ca2ad9d0..0000000000
--- a/arch/arm/src/calypso/calypso_spi.h
+++ /dev/null
@@ -1,59 +0,0 @@
-#ifndef ___ARCH_ARM_SRC_CALYPSO_CALYPSO_SPI_H
-#define ___ARCH_ARM_SRC_CALYPSO_CALYPSO_SPI_H
-
-/****************************************************************************
- * Pre-processor Definitions
- ****************************************************************************/
-
-#define BASE_ADDR_SPI 0xfffe3000
-#define SPI_REG(n) (BASE_ADDR_SPI+(n))
-
-#define SPI_SET1_EN_CLK (1 << 0)
-#define SPI_SET1_WR_IRQ_DIS (1 << 4)
-#define SPI_SET1_RDWR_IRQ_DIS (1 << 5)
-
-#define SPI_CTRL_RDWR (1 << 0)
-#define SPI_CTRL_WR (1 << 1)
-#define SPI_CTRL_NB_SHIFT 2
-#define SPI_CTRL_AD_SHIFT 7
-
-#define SPI_STATUS_RE (1 << 0) /* Read End */
-#define SPI_STATUS_WE (1 << 1) /* Write End */
-
-/****************************************************************************
- * Public Types
- ****************************************************************************/
-
-enum spi_regs
-{
- REG_SET1 = 0x00,
- REG_SET2 = 0x02,
- REG_CTRL = 0x04,
- REG_STATUS = 0x06,
- REG_TX_LSB = 0x08,
- REG_TX_MSB = 0x0a,
- REG_RX_LSB = 0x0c,
- REG_RX_MSB = 0x0e,
-};
-
-/****************************************************************************
- * Public Function Prototypes
- ****************************************************************************/
-
-/****************************************************************************
- * Name: calypso_spibus_initialize
- *
- * Description:
- * Initialize the selected SPI port
- *
- * Input Parameter:
- * Port number (for hardware that has mutiple SPI interfaces)
- *
- * Returned Value:
- * Valid SPI device structure reference on succcess; a NULL on failure
- *
- ****************************************************************************/
-
-FAR struct spi_dev_s *calypso_spibus_initialize(int port);
-
-#endif /* ___ARCH_ARM_SRC_CALYPSO_CALYPSO_SPI_H */
diff --git a/arch/arm/src/calypso/calypso_timer.c b/arch/arm/src/calypso/calypso_timer.c
deleted file mode 100644
index 86626c5de6..0000000000
--- a/arch/arm/src/calypso/calypso_timer.c
+++ /dev/null
@@ -1,227 +0,0 @@
-/****************************************************************************
- * arch/arm/src/calypso/calypso_timer.c
- * Calypso DBB internal Timer Driver
- *
- * (C) 2010 by Harald Welte
- * (C) 2011 by Stefan Richter
- *
- * This source code is derivated from Osmocom-BB project and was
- * relicensed as BSD with permission from original authors.
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
- *
- * 1. Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * 2. Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in
- * the documentation and/or other materials provided with the
- * distribution.
- * 3. Neither the name NuttX nor the names of its contributors may be
- * used to endorse or promote products derived from this software
- * without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
- * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
- * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- *
- ****************************************************************************/
-
-#include
-#include
-#include
-
-#include
-#include
-#include
-
-#include "up_arch.h"
-
-#define BASE_ADDR_TIMER 0xfffe3800
-#define TIMER2_OFFSET 0x3000
-
-#define TIMER_REG(n, m) (((n)-1) ? (BASE_ADDR_TIMER + TIMER2_OFFSET + (m)) : (BASE_ADDR_TIMER + (m)))
-
-enum timer_reg
-{
- CNTL_TIMER = 0x00,
- LOAD_TIMER = 0x02,
- READ_TIMER = 0x04,
-};
-
-enum timer_ctl
-{
- CNTL_START = (1 << 0),
- CNTL_AUTO_RELOAD = (1 << 1),
- CNTL_CLOCK_ENABLE = (1 << 5),
-};
-
-/* Regular Timers (1 and 2) */
-
-void hwtimer_enable(int num, int on)
-{
- uint8_t ctl;
-
- if (num < 1 || num > 2)
- {
- printf("Unknown timer %d\n", num);
- return;
- }
-
- ctl = getreg8(TIMER_REG(num, CNTL_TIMER));
- if (on)
- {
- ctl |= CNTL_START | CNTL_CLOCK_ENABLE;
- }
- else
- {
- ctl &= ~CNTL_START;
- }
-
- putreg8(ctl, TIMER_REG(num, CNTL_TIMER));
-}
-
-void hwtimer_config(int num, uint8_t pre_scale, int auto_reload)
-{
- uint8_t ctl;
-
- ctl = (pre_scale & 0x7) << 2;
- if (auto_reload)
- ctl |= CNTL_AUTO_RELOAD;
-
- putreg8(ctl, TIMER_REG(num, CNTL_TIMER));
-}
-
-void hwtimer_load(int num, uint16_t val)
-{
- putreg16(val, TIMER_REG(num, LOAD_TIMER));
-}
-
-uint16_t hwtimer_read(int num)
-{
- uint8_t ctl = getreg8(TIMER_REG(num, CNTL_TIMER));
-
- /* Somehow a read results in an abort */
-
- if ((ctl & (CNTL_START | CNTL_CLOCK_ENABLE)) != (CNTL_START | CNTL_CLOCK_ENABLE))
- {
- return 0xffff;
- }
-
- return getreg16(TIMER_REG(num, READ_TIMER));
-}
-
-/****************************************************************************
- * Watchdog Timer
- ****************************************************************************/
-
-#define BASE_ADDR_WDOG 0xfffff800
-#define WDOG_REG(m) (BASE_ADDR_WDOG + m)
-
-enum wdog_reg
-{
- WD_CNTL_TIMER = CNTL_TIMER,
- WD_LOAD_TIMER = LOAD_TIMER,
- WD_READ_TIMER = 0x02,
- WD_MODE = 0x04,
-};
-
-enum wdog_ctl
-{
- WD_CTL_START = (1 << 7),
- WD_CTL_AUTO_RELOAD = (1 << 8)
-};
-
-enum wdog_mode
-{
- WD_MODE_DIS_ARM = 0xF5,
- WD_MODE_DIS_CONFIRM = 0xA0,
- WD_MODE_ENABLE = (1 << 15)
-};
-
-#define WD_CTL_PRESCALE(value) (((value)&0x07) << 9)
-
-static void wdog_irq(__unused enum irq_nr nr)
-{
- puts("=> WATCHDOG\n");
-}
-
-void wdog_enable(int on)
-{
- if (!on)
- {
- putreg16(WD_MODE_DIS_ARM, WDOG_REG(WD_MODE));
- putreg16(WD_MODE_DIS_CONFIRM, WDOG_REG(WD_MODE));
- }
-}
-
-void wdog_reset(void)
-{
- /* Enable watchdog */
-
- putreg16(WD_MODE_ENABLE, WDOG_REG(WD_MODE));
-
- /* Force expiration */
-
- putreg16(0x0000, WDOG_REG(WD_LOAD_TIMER));
- putreg16(0x0000, WDOG_REG(WD_LOAD_TIMER));
-}
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Function: up_timerisr
- *
- * Description:
- * The timer ISR will perform a variety of services for
- * various portions of the systems.
- *
- ****************************************************************************/
-
-int up_timerisr(int irq, uint32_t *regs)
-{
- /* Process timer interrupt */
-
- sched_process_timer();
- return 0;
-}
-
-/****************************************************************************
- * Function: up_timer_initialize
- *
- * Description:
- * Setup Calypso HW timer 2 to cause system ticks.
- *
- * This function is called during start-up to initialize
- * the timer interrupt.
- *
- ****************************************************************************/
-
-void up_timer_initialize(void)
-{
- up_disable_irq(IRQ_SYSTIMER);
-
- /* The timer runs at 13MHz / 32, i.e. 406.25kHz */
- /* 4062 ticks until expiry yields 100Hz interrupt */
-
- hwtimer_load(2, 4062);
- hwtimer_config(2, 0, 1);
- hwtimer_enable(2, 1);
-
- /* Attach and enable the timer interrupt */
-
- irq_attach(IRQ_SYSTIMER, (xcpt_t)up_timerisr);
- up_enable_irq(IRQ_SYSTIMER);
-}
diff --git a/arch/arm/src/calypso/calypso_uwire.c b/arch/arm/src/calypso/calypso_uwire.c
deleted file mode 100644
index fe2c33b7cc..0000000000
--- a/arch/arm/src/calypso/calypso_uwire.c
+++ /dev/null
@@ -1,161 +0,0 @@
-/****************************************************************************
- * arch/arm/src/calypso/calypso_uwire.c
- * Driver for Calypso uWire Master Controller
- *
- * (C) 2010 by Sylvain Munaut
- *
- * This source code is derivated from Osmocom-BB project and was
- * relicensed as BSD with permission from original authors.
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
- *
- * 1. Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * 2. Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in
- * the documentation and/or other materials provided with the
- * distribution.
- * 3. Neither the name NuttX nor the names of its contributors may be
- * used to endorse or promote products derived from this software
- * without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
- * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
- * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- *
- ****************************************************************************/
-
-/****************************************************************************
- * Included Files
- ****************************************************************************/
-
-#include
-#include
-#include
-
-#include "up_arch.h"
-
-#define BASE_ADDR_UWIRE 0xfffe4000
-#define UWIRE_REG(n) (BASE_ADDR_UWIRE+(n))
-
-enum uwire_regs
-{
- REG_DATA = 0x00,
- REG_CSR = 0x02,
- REG_SR1 = 0x04,
- REG_SR2 = 0x06,
- REG_SR3 = 0x08,
-};
-
-#define UWIRE_CSR_BITS_RD(n) (((n) & 0x1f) << 0)
-#define UWIRE_CSR_BITS_WR(n) (((n) & 0x1f) << 5)
-#define UWIRE_CSR_IDX(n) (((n) & 3) << 10)
-#define UWIRE_CSR_CS_CMD (1 << 12)
-#define UWIRE_CSR_START (1 << 13)
-#define UWIRE_CSR_CSRB (1 << 14)
-#define UWIRE_CSR_RDRB (1 << 15)
-
-#define UWIRE_CSn_EDGE_RD (1 << 0) /* 1=falling 0=rising */
-#define UWIRE_CSn_EDGE_WR (1 << 1) /* 1=falling 0=rising */
-#define UWIRE_CSn_CS_LVL (1 << 2)
-#define UWIRE_CSn_FRQ_DIV2 (0 << 3)
-#define UWIRE_CSn_FRQ_DIV4 (1 << 3)
-#define UWIRE_CSn_FRQ_DIV8 (2 << 3)
-#define UWIRE_CSn_CKH
-
-#define UWIRE_CSn_SHIFT(n) (((n) & 1) ? 6 : 0)
-#define UWIRE_CSn_REG(n) (((n) & 2) ? REG_SR2 : REG_SR1)
-
-#define UWIRE_SR3_CLK_EN (1 << 0)
-#define UWIRE_SR3_CLK_DIV2 (0 << 1)
-#define UWIRE_SR3_CLK_DIV4 (1 << 1)
-#define UWIRE_SR3_CLK_DIV7 (2 << 1)
-#define UWIRE_SR3_CLK_DIV10 (3 << 1)
-
-static inline void _uwire_wait(int mask, int val)
-{
- while ((getreg16(UWIRE_REG(REG_CSR)) & mask) != val);
-}
-
-void uwire_init(void)
-{
- putreg16(UWIRE_SR3_CLK_EN | UWIRE_SR3_CLK_DIV2, UWIRE_REG(REG_SR3));
-
- /* FIXME only init CS0 for now */
-
- putreg16(((UWIRE_CSn_CS_LVL | UWIRE_CSn_FRQ_DIV2) << UWIRE_CSn_SHIFT(0)),
- UWIRE_REG(UWIRE_CSn_REG(0)));
- putreg16(UWIRE_CSR_IDX(0) | UWIRE_CSR_CS_CMD, UWIRE_REG(REG_CSR));
- _uwire_wait(UWIRE_CSR_CSRB, 0);
-}
-
-int uwire_xfer(int cs, int bitlen, const void *dout, void *din)
-{
- uint16_t tmp = 0;
-
- if (bitlen <= 0 || bitlen > 16)
- return -1;
-
- if (cs < 0 || cs > 4)
- return -1;
-
- /* FIXME uwire_init always selects CS0 for now */
-
- _info("uwire_xfer(dev_idx=%u, bitlen=%u\n", cs, bitlen);
-
- /* select the chip */
-
- putreg16(UWIRE_CSR_IDX(0) | UWIRE_CSR_CS_CMD, UWIRE_REG(REG_CSR));
- _uwire_wait(UWIRE_CSR_CSRB, 0);
-
- if (dout)
- {
- if (bitlen <= 8)
- tmp = *(uint8_t *)dout;
- else if (bitlen <= 16)
- tmp = *(uint16_t *)dout;
-
- tmp <<= 16 - bitlen; /* align to MSB */
- putreg16(tmp, UWIRE_REG(REG_DATA));
- _info(", data_out=0x%04hx", tmp);
- }
-
- tmp = (dout ? UWIRE_CSR_BITS_WR(bitlen) : 0) |
- (din ? UWIRE_CSR_BITS_RD(bitlen) : 0) |
- UWIRE_CSR_START;
- putreg16(tmp, UWIRE_REG(REG_CSR));
- _uwire_wait(UWIRE_CSR_CSRB, 0);
-
- if (din)
- {
- _uwire_wait(UWIRE_CSR_RDRB, UWIRE_CSR_RDRB);
-
- tmp = getreg16(UWIRE_REG(REG_DATA));
- _info(", data_in=0x%08x", tmp);
-
- if (bitlen <= 8)
- *(uint8_t *)din = tmp & 0xff;
- else if (bitlen <= 16)
- *(uint16_t *)din = tmp & 0xffff;
- }
-
- /* unselect the chip */
-
- putreg16(UWIRE_CSR_IDX(0) | 0, UWIRE_REG(REG_CSR));
- _uwire_wait(UWIRE_CSR_CSRB, 0);
-
- _info(")\n");
-
- return 0;
-}
diff --git a/arch/arm/src/calypso/chip.h b/arch/arm/src/calypso/chip.h
deleted file mode 100644
index bea381cc38..0000000000
--- a/arch/arm/src/calypso/chip.h
+++ /dev/null
@@ -1,211 +0,0 @@
-/****************************************************************************
- * calypso/chip.h
- *
- * Copyright (C) 2011 Stefan Richter. All rights reserved.
- * Author: Stefan Richter
- *
- * based on: c5471/chip.h
- * Copyright (C) 2007 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
- *
- * 1. Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * 2. Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in
- * the documentation and/or other materials provided with the
- * distribution.
- * 3. Neither the name Gregory Nutt nor the names of its contributors may be
- * used to endorse or promote products derived from this software
- * without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
- * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
- * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- *
- ****************************************************************************/
-
-#ifndef __ARCH_ARM_SRC_CALYPSO_CHIP_H
-#define __ARCH_ARM_SRC_CALYPSO_CHIP_H
-
-/****************************************************************************
- * Included Files
- ****************************************************************************/
-
-/****************************************************************************
- * Pre-processor Definitions
- ****************************************************************************/
-
-/* UARTs ********************************************************************/
-
-#define UART_IRDA_BASE 0xffff5000
-#define UART_MODEM_BASE 0xffff5800
-#define UART_UIR 0xffff6000
-#define UARTn_IO_RANGE 0x00000800
-
-/* Common UART Registers. Expressed as offsets from the BASE address */
-
-#define UART_RHR_OFFS 0x00000000 /* Rcv Holding Register */
-#define UART_THR_OFFS 0x00000000 /* Xmit Holding Register */
-#define UART_FCR_OFFS 0x00000002 /* FIFO Control Register */
-#define UART_RFCR_OFFS 0x00000002 /* Rcv FIFO Control Register */
-#define UART_TFCR_OFFS 0x00000002 /* Xmit FIFO Control Register */
-#define UART_SCR_OFFS 0x00000010 /* Status Control Register */
-#define UART_LCR_OFFS 0x00000003 /* Line Control Register */
-#define UART_LSR_OFFS 0x00000005 /* Line Status Register */
-#define UART_SSR_OFFS 0x00000011 /* Supplementary Status Register */
-#define UART_MCR_OFFS 0x00000004 /* Modem Control Register */
-#define UART_MSR_OFFS 0x00000006 /* Modem Status Register */
-#define UART_IER_OFFS 0x00000001 /* Interrupt Enable Register */
-#define UART_ISR_OFFS 0x00000002 /* Interrupt Status Register */
-#define UART_EFR_OFFS 0x00000002 /* Enhanced Feature Register */
-#define UART_XON1_OFFS 0x00000004 /* XON1 Character Register */
-#define UART_XON2_OFFS 0x00000005 /* XON2 Character Register */
-#define UART_XOFF1_OFFS 0x00000006 /* XOFF1 Character Register */
-#define UART_XOFF2_OFFS 0x00000007 /* XOFF2 Character Register */
-#define UART_SPR_OFFS 0x00000007 /* Scratch-pad Register */
-#define UART_DIV_LOW_OFFS 0x00000000 /* Divisor for baud generation */
-#define UART_DIV_HIGH_OFFS 0x00000001
-#define UART_TCR_OFFS 0x00000006 /* Transmission Control Register */
-#define UART_TLR_OFFS 0x00000007 /* Trigger Level Register */
-#define UART_MDR_OFFS 0x00000008 /* Mode Definition Register */
-
-/* UART Settings ************************************************************/
-
-/* Miscellaneous UART settings. */
-
-#define UART_REGISTER_BITS 8
-#define UART_IRQ_MODEM IRQ_UART_MODEM
-#define UART_IRQ_IRDA IRQ_UART_IRDA
-
-#define UART_RX_FIFO_NOEMPTY 0x00000001
-#define UART_SSR_TXFULL 0x00000001
-#define UART_LSR_TREF 0x00000020
-
-#define UART_XMIT_FIFO_SIZE 64
-#define UART_IRDA_XMIT_FIFO_SIZE 64
-
-/* UART_LCR Register */
- /* Bits 31-7: Reserved */
-#define UART_LCR_BOC 0x00000040 /* Bit 6: Break Control */
- /* Bit 5: Parity Type 2 */
-#define UART_LCR_PAREVEN 0x00000010 /* Bit 4: Parity Type 1 */
-#define UART_LCR_PARODD 0x00000000
-#define UART_LCR_PARMARK 0x00000010
-#define UART_LCR_PARSPACE 0x00000011
-#define UART_LCR_PAREN 0x00000008 /* Bit 3: Paity Enable */
-#define UART_LCR_PARDIS 0x00000000
-#define UART_LCR_2STOP 0x00000004 /* Bit 2: Number of stop bits */
-#define UART_LCR_1STOP 0x00000000
-#define UART_LCR_5BITS 0x00000000 /* Bits 0-1: Word-length */
-#define UART_LCR_6BITS 0x00000001
-#define UART_LCR_7BITS 0x00000002
-#define UART_LCR_8BITS 0x00000003
-
-#define UART_FCR_FTL 0x000000f0
-#define UART_FCR_FIFO_EN 0x00000001
-#define UART_FCR_TX_CLR 0x00000002
-#define UART_FCR_RX_CLR 0x00000004
-
-#define UART_IER_RECVINT 0x00000001
-#define UART_IER_XMITINT 0x00000002
-#define UART_IER_LINESTSINT 0x00000004
-#define UART_IER_MODEMSTSINT 0x00000008 /* IrDA UART only */
-#define UART_IER_XOFFINT 0x00000020
-#define UART_IER_RTSINT 0x00000040 /* IrDA UART only */
-#define UART_IER_CTSINT 0x00000080 /* IrDA UART only */
-#define UART_IER_INTMASK 0x000000ff
-
-#define BAUD_115200 0x00000007
-#define BAUD_57600 0x00000014
-#define BAUD_38400 0x00000021
-#define BAUD_19200 0x00000006
-#define BAUD_9600 0x0000000C
-#define BAUD_4800 0x00000018
-#define BAUD_2400 0x00000030
-#define BAUD_1200 0x00000060
-
-#define MDR_UART_MODE 0x00000000 /* Both IrDA and Modem UARTs */
-#define MDR_SIR_MODE 0x00000001 /* IrDA UART only */
-#define MDR_AUTOBAUDING_MODE 0x00000002 /* Modem UART only */
-#define MDR_RESET_MODE 0x00000007 /* Both IrDA and Modem UARTs */
-
-/* SPI **********************************************************************/
-
-#define MAX_SPI 3
-
-#define SPI_REGISTER_BASE 0xffff2000
-
-/* ARMIO ********************************************************************/
-/* Timers / Watchdog ********************************************************/
-
-#define C5471_TIMER0_CTRL 0xffff2a00
-#define C5471_TIMER0_CNT 0xffff2a04
-#define C5471_TIMER1_CTRL 0xffff2b00
-#define C5471_TIMER1_CNT 0xffff2b04
-#define C5471_TIMER2_CTRL 0xffff2c00
-#define C5471_TIMER2_CNT 0xffff2c04
-
-/* Interrupts ***************************************************************/
-
-#define HAVE_SRC_IRQ_BIN_REG 0
-
-#define INT_FIRST_IO 0xffff2d00
-#define INT_IO_RANGE 0x5C
-
-#define IT_REG 0xffff2d00
-#define MASK_IT_REG 0xffff2d04
-#define SRC_IRQ_REG 0xffff2d08
-#define SRC_FIQ_REG 0xffff2d0c
-#define SRC_IRQ_BIN_REG 0xffff2d10
-#define INT_CTRL_REG 0xffff2d18
-
-#define ILR_IRQ0_REG 0xffff2d1C /* 0-Timer 0 */
-#define ILR_IRQ1_REG 0xffff2d20 /* 1-Timer 1 */
-#define ILR_IRQ2_REG 0xffff2d24 /* 2-Timer 2 */
-#define ILR_IRQ3_REG 0xffff2d28 /* 3-GPIO0 */
-#define ILR_IRQ4_REG 0xffff2d2c /* 4-Ethernet */
-#define ILR_IRQ5_REG 0xffff2d30 /* 5-KBGPIO[7:0] */
-#define ILR_IRQ6_REG 0xffff2d34 /* 6-Uart serial */
-#define ILR_IRQ7_REG 0xffff2d38 /* 7-Uart IRDA */
-#define ILR_IRQ8_REG 0xffff2d3c /* 8-KBGPIO[15:8] */
-#define ILR_IRQ9_REG 0xffff2d40 /* 9-GPIO3 */
-#define ILR_IRQ10_REG 0xffff2d44 /* 10-GPIO2 */
-#define ILR_IRQ11_REG 0xffff2d48 /* 11-I2C */
-#define ILR_IRQ12_REG 0xffff2d4c /* 12-GPIO1 */
-#define ILR_IRQ13_REG 0xffff2d50 /* 13-SPI */
-#define ILR_IRQ14_REG 0xffff2d54 /* 14-GPIO[19:4] */
-#define ILR_IRQ15_REG 0xffff2d58 /* 15-API */
-
-/* CLKM *********************************************************************/
-
-#define CLKM 0xffff2f00
-#define CLKM_CTL_RST 0xffff2f10
-#define CLKM_RESET 0xffff2f18
-
-#define CLKM_RESET_EIM 0x00000008
-#define CLKM_EIM_CLK_STOP 0x00000010
-#define CLKM_CTL_RST_LEAD_RESET 0x00000000
-#define CLKM_CTL_RST_EXT_RESET 0x00000002
-
-/****************************************************************************
- * Inline Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Public Function Prototypes
- ****************************************************************************/
-
-#endif /* __ARCH_ARM_SRC_CALYPSO_CHIP_H */
diff --git a/arch/arm/src/calypso/clock.c b/arch/arm/src/calypso/clock.c
deleted file mode 100644
index 29dc2f8273..0000000000
--- a/arch/arm/src/calypso/clock.c
+++ /dev/null
@@ -1,230 +0,0 @@
-/****************************************************************************
- * arch/arm/src/calypso/clock.c
- * Driver for Calypso clock management
- *
- * (C) 2010 by Harald Welte
- *
- * This source code is derivated from Osmocom-BB project and was
- * relicensed as BSD with permission from original authors.
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
- *
- * 1. Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * 2. Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in
- * the documentation and/or other materials provided with the
- * distribution.
- * 3. Neither the name NuttX nor the names of its contributors may be
- * used to endorse or promote products derived from this software
- * without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
- * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
- * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- *
- ****************************************************************************/
-
-#include
-
-#include
-#include
-
-//#define DEBUG
-#include
-
-#include
-#include
-
-#include "up_arch.h"
-
-#define REG_DPLL 0xffff9800
-#define DPLL_LOCK (1 << 0)
-#define DPLL_BREAKLN (1 << 1)
-#define DPLL_BYPASS_DIV_SHIFT 2 /* 2 bits */
-#define DPLL_PLL_ENABLE (1 << 4)
-#define DPLL_PLL_DIV_SHIFT 5 /* 2 bits */
-#define DPLL_PLL_MULT_SHIFT 7 /* 5 bits */
-#define DPLL_TEST (1 << 12)
-#define DPLL_IOB (1 << 13) /* Initialize on break */
-#define DPLL_IAI (1 << 14) /* Initialize after Idle */
-
-#define BASE_ADDR_CLKM 0xfffffd00
-#define CLKM_REG(m) (BASE_ADDR_CLKM+(m))
-
-enum clkm_reg
-{
- CNTL_ARM_CLK = 0,
- CNTL_CLK = 2,
- CNTL_RST = 4,
- CNTL_ARM_DIV = 8,
-};
-
-/* CNTL_ARM_CLK */
-
-#define ARM_CLK_BIG_SLEEP (1 << 0) /* MCU Master Clock enabled? */
-#define ARM_CLK_CLKIN_SEL0 (1 << 1) /* MCU source clock (0 = DPLL output, 1 = VTCXO or CLKIN */
-#define ARM_CLK_CLKIN_SEL (1 << 2) /* 0 = VTCXO or 1 = CLKIN */
-#define ARM_CLK_MCLK_DIV5 (1 << 3) /* enable 1.5 or 2.5 division factor */
-#define ARM_CLK_MCLK_DIV_SHIFT 4 /* 3 bits */
-#define ARM_CLK_DEEP_POWER_SHIFT 8
-#define ARM_CLK_DEEP_SLEEP 12
-
-/* CNTL_CLK */
-#define CLK_IRQ_CLK_DIS (1 << 0) /* IRQ clock control (0 always, 1 according ARM_MCLK_EN) */
-#define CLK_BRIDGE_CLK_DIS (1 << 1)
-#define CLK_TIMER_CLK_DIS (1 << 2)
-#define CLK_DPLL_DIS (1 << 3) /* 0: DPLL is not stopped during SLEEP */
-#define CLK_CLKOUT_EN (1 << 4) /* Enable CLKOUT output pins */
-#define CLK_EN_IDLE3_FLG (1 << 5) /* DSP idle flag control (1 =
- * SAM/HOM register forced to HOM when DSP IDLE3) */
-#define CLK_VCLKOUT_DIV2 (1 << 6) /* 1: VCLKOUT-FR is divided by 2 */
-#define CLK_VTCXO_DIV2 (1 << 7) /* 1: VTCXO is dividied by 2 */
-
-#define BASE_ADDR_MEMIF 0xfffffb00
-#define MEMIF_REG(x) (BASE_ADDR_MEMIF+(x))
-
-enum memif_reg
-{
- API_RHEA_CTL = 0x0e,
- EXTRA_CONF = 0x10,
-};
-
-static void dump_reg16(uint32_t addr, char *name)
-{
- printf("%s=0x%04x\n", name, getreg16(addr));
-}
-
-void calypso_clk_dump(void)
-{
- dump_reg16(REG_DPLL, "REG_DPLL");
- dump_reg16(CLKM_REG(CNTL_ARM_CLK), "CNTL_ARM_CLK");
- dump_reg16(CLKM_REG(CNTL_CLK), "CNTL_CLK");
- dump_reg16(CLKM_REG(CNTL_RST), "CNTL_RST");
- dump_reg16(CLKM_REG(CNTL_ARM_DIV), "CNTL_ARM_DIV");
-}
-
-void calypso_pll_set(uint16_t inp)
-{
- uint8_t mult = inp >> 8;
- uint8_t div = inp & 0xff;
- uint16_t reg = getreg16(REG_DPLL);
-
- reg &= ~0x0fe0;
- reg |= (div & 0x3) << DPLL_PLL_DIV_SHIFT;
- reg |= (mult & 0x1f) << DPLL_PLL_MULT_SHIFT;
- reg |= DPLL_PLL_ENABLE;
-
- putreg16(reg, REG_DPLL);
-}
-
-void calypso_reset_set(enum calypso_rst calypso_rst, int active)
-{
- uint8_t reg = getreg8(CLKM_REG(CNTL_RST));
-
- if (active)
- reg |= calypso_rst;
- else
- reg &= ~calypso_rst;
-
- putreg8(reg, CLKM_REG(CNTL_RST));
-}
-
-int calypso_reset_get(enum calypso_rst calypso_rst)
-{
- uint8_t reg = getreg8(CLKM_REG(CNTL_RST));
-
- if (reg & calypso_rst)
- return 1;
- else
- return 0;
-}
-
-void calypso_clock_set(uint8_t vtcxo_div2, uint16_t inp, enum mclk_div mclk_div)
-{
- uint16_t cntl_clock = getreg16(CLKM_REG(CNTL_CLK));
- uint16_t cntl_arm_clk = getreg16(CLKM_REG(CNTL_ARM_CLK));
-
- /* First set the vtcxo_div2 */
-
- cntl_clock &= ~CLK_VCLKOUT_DIV2;
- if (vtcxo_div2)
- cntl_clock |= CLK_VTCXO_DIV2;
- else
- cntl_clock &= ~CLK_VTCXO_DIV2;
-
- putreg16(cntl_clock, CLKM_REG(CNTL_CLK));
-
- /* Then configure the MCLK divider */
-
- cntl_arm_clk &= ~ARM_CLK_CLKIN_SEL0;
- if (mclk_div & 0x80)
- {
- mclk_div &= ~0x80;
- cntl_arm_clk |= ARM_CLK_MCLK_DIV5;
- }
- else
- cntl_arm_clk &= ~ARM_CLK_MCLK_DIV5;
-
- cntl_arm_clk &= ~(0x7 << ARM_CLK_MCLK_DIV_SHIFT);
- cntl_arm_clk |= (mclk_div << ARM_CLK_MCLK_DIV_SHIFT);
- putreg16(cntl_arm_clk, CLKM_REG(CNTL_ARM_CLK));
-
- /* Then finally set the PLL */
-
- calypso_pll_set(inp);
-}
-
-void calypso_mem_cfg(enum calypso_bank bank, uint8_t ws,
- enum calypso_mem_width width, int we)
-{
- putreg16((ws & 0x1f) | ((width & 3) << 5) | ((we & 1) << 7),
- BASE_ADDR_MEMIF + bank);
-}
-
-void calypso_bootrom(int enable)
-{
- uint16_t conf = getreg16(MEMIF_REG(EXTRA_CONF));
-
- conf |= (3 << 8);
-
- if (enable)
- conf &= ~(1 << 9);
-
- putreg16(conf, MEMIF_REG(EXTRA_CONF));
-}
-
-void calypso_debugunit(int enable)
-{
- uint16_t conf = getreg16(MEMIF_REG(EXTRA_CONF));
-
- if (enable)
- conf &= ~(1 << 11);
- else
- conf |= (1 << 11);
-
- putreg16(conf, MEMIF_REG(EXTRA_CONF));
-}
-
-#define REG_RHEA_CNTL 0xfffff900
-#define REG_API_CNTL 0xfffff902
-#define REG_ARM_RHEA 0xfffff904
-
-void calypso_rhea_cfg(uint8_t fac0, uint8_t fac1, uint8_t timeout,
- uint8_t ws_h, uint8_t ws_l, uint8_t w_en0, uint8_t w_en1)
-{
- putreg16(fac0 | (fac1 << 4) | (timeout << 8), REG_RHEA_CNTL);
- putreg16(ws_h | (ws_l << 5), REG_API_CNTL);
- putreg16(w_en0 | (w_en1 << 1), REG_ARM_RHEA);
-}
diff --git a/configs/amber/hello/defconfig b/configs/amber/hello/defconfig
index 7292bfeb9d..2dc6a34254 100644
--- a/configs/amber/hello/defconfig
+++ b/configs/amber/hello/defconfig
@@ -233,7 +233,6 @@ CONFIG_DEV_NULL=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
CONFIG_DEV_LOWCONSOLE=y
# CONFIG_16550_UART is not set
diff --git a/configs/arduino-due/nsh/defconfig b/configs/arduino-due/nsh/defconfig
index 1d50abd7e9..bc43e12c28 100644
--- a/configs/arduino-due/nsh/defconfig
+++ b/configs/arduino-due/nsh/defconfig
@@ -500,7 +500,6 @@ CONFIG_DEV_NULL=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/arduino-mega2560/hello/defconfig b/configs/arduino-mega2560/hello/defconfig
index 8907161516..95e74bd6c9 100644
--- a/configs/arduino-mega2560/hello/defconfig
+++ b/configs/arduino-mega2560/hello/defconfig
@@ -296,7 +296,6 @@ CONFIG_DEV_NULL=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
CONFIG_DEV_LOWCONSOLE=y
# CONFIG_16550_UART is not set
diff --git a/configs/arduino-mega2560/nsh/defconfig b/configs/arduino-mega2560/nsh/defconfig
index 6636c1d8ff..40cfb5458a 100644
--- a/configs/arduino-mega2560/nsh/defconfig
+++ b/configs/arduino-mega2560/nsh/defconfig
@@ -304,7 +304,6 @@ CONFIG_DEV_NULL=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_16550_UART is not set
diff --git a/configs/avr32dev1/nsh/defconfig b/configs/avr32dev1/nsh/defconfig
index cbd3aa7c1a..5e2bffbca8 100644
--- a/configs/avr32dev1/nsh/defconfig
+++ b/configs/avr32dev1/nsh/defconfig
@@ -271,7 +271,6 @@ CONFIG_DEV_NULL=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_16550_UART is not set
diff --git a/configs/avr32dev1/ostest/defconfig b/configs/avr32dev1/ostest/defconfig
index ea66ee4723..600c0191aa 100644
--- a/configs/avr32dev1/ostest/defconfig
+++ b/configs/avr32dev1/ostest/defconfig
@@ -270,7 +270,6 @@ CONFIG_DEV_NULL=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
CONFIG_DEV_LOWCONSOLE=y
# CONFIG_16550_UART is not set
diff --git a/configs/bambino-200e/nsh/defconfig b/configs/bambino-200e/nsh/defconfig
index 405b666585..729e7fdc65 100644
--- a/configs/bambino-200e/nsh/defconfig
+++ b/configs/bambino-200e/nsh/defconfig
@@ -501,7 +501,6 @@ CONFIG_TIMER=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
CONFIG_SERIAL_REMOVABLE=y
diff --git a/configs/c5471evm/httpd/defconfig b/configs/c5471evm/httpd/defconfig
index 2816583ae1..c388a368c8 100644
--- a/configs/c5471evm/httpd/defconfig
+++ b/configs/c5471evm/httpd/defconfig
@@ -413,7 +413,6 @@ CONFIG_WATCHDOG_DEVPATH="/dev/watchdog0"
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/c5471evm/nettest/defconfig b/configs/c5471evm/nettest/defconfig
index 989d3be0e8..729f8df76e 100644
--- a/configs/c5471evm/nettest/defconfig
+++ b/configs/c5471evm/nettest/defconfig
@@ -406,7 +406,6 @@ CONFIG_WATCHDOG_DEVPATH="/dev/watchdog0"
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/c5471evm/nsh/defconfig b/configs/c5471evm/nsh/defconfig
index eae7f1f095..a7d595285f 100644
--- a/configs/c5471evm/nsh/defconfig
+++ b/configs/c5471evm/nsh/defconfig
@@ -414,7 +414,6 @@ CONFIG_NETDEV_TELNET=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/cc3200-launchpad/nsh/defconfig b/configs/cc3200-launchpad/nsh/defconfig
index c0b7945bc2..1de3eee3e2 100644
--- a/configs/cc3200-launchpad/nsh/defconfig
+++ b/configs/cc3200-launchpad/nsh/defconfig
@@ -461,7 +461,6 @@ CONFIG_DEV_NULL=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/cloudctrl/nsh/defconfig b/configs/cloudctrl/nsh/defconfig
index a558bd84c1..6da8937d15 100644
--- a/configs/cloudctrl/nsh/defconfig
+++ b/configs/cloudctrl/nsh/defconfig
@@ -834,7 +834,6 @@ CONFIG_ETH0_PHY_DM9161=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/demo9s12ne64/ostest/defconfig b/configs/demo9s12ne64/ostest/defconfig
index b571cf62e8..c5f77d58a5 100644
--- a/configs/demo9s12ne64/ostest/defconfig
+++ b/configs/demo9s12ne64/ostest/defconfig
@@ -242,7 +242,6 @@ CONFIG_DEV_NULL=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_16550_UART is not set
diff --git a/configs/dk-tm4c129x/ipv6/defconfig b/configs/dk-tm4c129x/ipv6/defconfig
index 2cdd072895..83644a89c4 100644
--- a/configs/dk-tm4c129x/ipv6/defconfig
+++ b/configs/dk-tm4c129x/ipv6/defconfig
@@ -596,7 +596,6 @@ CONFIG_LM75_I2C_FREQUENCY=100000
# CONFIG_VEML6070 is not set
# CONFIG_XEN1210 is not set
# CONFIG_ZEROCROSS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/dk-tm4c129x/nsh/defconfig b/configs/dk-tm4c129x/nsh/defconfig
index 085a598e1f..c9a9edac93 100644
--- a/configs/dk-tm4c129x/nsh/defconfig
+++ b/configs/dk-tm4c129x/nsh/defconfig
@@ -598,7 +598,6 @@ CONFIG_LM75_I2C_FREQUENCY=100000
# CONFIG_VEML6070 is not set
# CONFIG_XEN1210 is not set
# CONFIG_ZEROCROSS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/ea3131/nsh/defconfig b/configs/ea3131/nsh/defconfig
index 3250e05da7..b98a0b0c96 100644
--- a/configs/ea3131/nsh/defconfig
+++ b/configs/ea3131/nsh/defconfig
@@ -418,7 +418,6 @@ CONFIG_DEV_NULL=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/ea3131/pgnsh/defconfig b/configs/ea3131/pgnsh/defconfig
index 8d53362269..8bb8ce2903 100644
--- a/configs/ea3131/pgnsh/defconfig
+++ b/configs/ea3131/pgnsh/defconfig
@@ -494,7 +494,6 @@ CONFIG_M25P_MEMORY_TYPE=0x20
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/ea3131/usbserial/defconfig b/configs/ea3131/usbserial/defconfig
index 6c2c68e5db..cf79f1ff54 100644
--- a/configs/ea3131/usbserial/defconfig
+++ b/configs/ea3131/usbserial/defconfig
@@ -431,7 +431,6 @@ CONFIG_DEV_NULL=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
CONFIG_DEV_LOWCONSOLE=y
CONFIG_SERIAL_REMOVABLE=y
diff --git a/configs/ea3152/ostest/defconfig b/configs/ea3152/ostest/defconfig
index 96961e4204..5222be557c 100644
--- a/configs/ea3152/ostest/defconfig
+++ b/configs/ea3152/ostest/defconfig
@@ -413,7 +413,6 @@ CONFIG_DEV_NULL=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
CONFIG_DEV_LOWCONSOLE=y
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/eagle100/httpd/defconfig b/configs/eagle100/httpd/defconfig
index b2fbabd77c..10e1481b20 100644
--- a/configs/eagle100/httpd/defconfig
+++ b/configs/eagle100/httpd/defconfig
@@ -532,7 +532,6 @@ CONFIG_ARCH_HAVE_NETDEV_STATISTICS=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
CONFIG_DEV_LOWCONSOLE=y
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/eagle100/nettest/defconfig b/configs/eagle100/nettest/defconfig
index a0c3b49b98..2b2d08c871 100644
--- a/configs/eagle100/nettest/defconfig
+++ b/configs/eagle100/nettest/defconfig
@@ -524,7 +524,6 @@ CONFIG_ARCH_HAVE_NETDEV_STATISTICS=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
CONFIG_DEV_LOWCONSOLE=y
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/eagle100/nsh/defconfig b/configs/eagle100/nsh/defconfig
index 2a90032891..31736a4493 100644
--- a/configs/eagle100/nsh/defconfig
+++ b/configs/eagle100/nsh/defconfig
@@ -563,7 +563,6 @@ CONFIG_ARCH_HAVE_NETDEV_STATISTICS=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/eagle100/nxflat/defconfig b/configs/eagle100/nxflat/defconfig
index d28067ad94..1d55be1648 100644
--- a/configs/eagle100/nxflat/defconfig
+++ b/configs/eagle100/nxflat/defconfig
@@ -483,7 +483,6 @@ CONFIG_DEV_NULL=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
CONFIG_DEV_LOWCONSOLE=y
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/eagle100/thttpd/defconfig b/configs/eagle100/thttpd/defconfig
index 579c652513..e0e7a25e9f 100644
--- a/configs/eagle100/thttpd/defconfig
+++ b/configs/eagle100/thttpd/defconfig
@@ -520,7 +520,6 @@ CONFIG_DEV_FIFO_SIZE=1024
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
CONFIG_DEV_LOWCONSOLE=y
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/efm32-g8xx-stk/nsh/defconfig b/configs/efm32-g8xx-stk/nsh/defconfig
index d97369ecf9..4c7b62ce8b 100644
--- a/configs/efm32-g8xx-stk/nsh/defconfig
+++ b/configs/efm32-g8xx-stk/nsh/defconfig
@@ -457,7 +457,6 @@ CONFIG_ARCH_HAVE_SPI_BITORDER=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/efm32gg-stk3700/nsh/defconfig b/configs/efm32gg-stk3700/nsh/defconfig
index aef89ed858..db3dbf7aa9 100644
--- a/configs/efm32gg-stk3700/nsh/defconfig
+++ b/configs/efm32gg-stk3700/nsh/defconfig
@@ -457,7 +457,6 @@ CONFIG_ARCH_HAVE_SPI_BITORDER=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/ekk-lm3s9b96/nsh/defconfig b/configs/ekk-lm3s9b96/nsh/defconfig
index 9870858ce1..cca7bc60c5 100644
--- a/configs/ekk-lm3s9b96/nsh/defconfig
+++ b/configs/ekk-lm3s9b96/nsh/defconfig
@@ -552,7 +552,6 @@ CONFIG_ARCH_HAVE_NETDEV_STATISTICS=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/esp32-core/nsh/defconfig b/configs/esp32-core/nsh/defconfig
index 5c75b76887..ce5088bb99 100644
--- a/configs/esp32-core/nsh/defconfig
+++ b/configs/esp32-core/nsh/defconfig
@@ -354,7 +354,6 @@ CONFIG_SPI_EXCHANGE=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/esp32-core/smp/defconfig b/configs/esp32-core/smp/defconfig
index 9db1561de7..620896ec4f 100644
--- a/configs/esp32-core/smp/defconfig
+++ b/configs/esp32-core/smp/defconfig
@@ -357,7 +357,6 @@ CONFIG_SPI_EXCHANGE=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/ez80f910200kitg/ostest/defconfig b/configs/ez80f910200kitg/ostest/defconfig
index fcfe07a33b..4a79e9765a 100644
--- a/configs/ez80f910200kitg/ostest/defconfig
+++ b/configs/ez80f910200kitg/ostest/defconfig
@@ -369,7 +369,6 @@ CONFIG_MMCSD_HAVECARDDETECT=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
CONFIG_DEV_LOWCONSOLE=y
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/ez80f910200zco/dhcpd/defconfig b/configs/ez80f910200zco/dhcpd/defconfig
index 72dcc5ecfa..d48a15c6f2 100644
--- a/configs/ez80f910200zco/dhcpd/defconfig
+++ b/configs/ez80f910200zco/dhcpd/defconfig
@@ -424,7 +424,6 @@ CONFIG_ETH0_PHY_AM79C874=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
CONFIG_DEV_LOWCONSOLE=y
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/ez80f910200zco/httpd/defconfig b/configs/ez80f910200zco/httpd/defconfig
index b74d62ba78..7ef42bdffa 100644
--- a/configs/ez80f910200zco/httpd/defconfig
+++ b/configs/ez80f910200zco/httpd/defconfig
@@ -433,7 +433,6 @@ CONFIG_ETH0_PHY_AM79C874=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
CONFIG_DEV_LOWCONSOLE=y
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/ez80f910200zco/nettest/defconfig b/configs/ez80f910200zco/nettest/defconfig
index e4fe5af40f..e9b3d8c54f 100644
--- a/configs/ez80f910200zco/nettest/defconfig
+++ b/configs/ez80f910200zco/nettest/defconfig
@@ -425,7 +425,6 @@ CONFIG_ETH0_PHY_AM79C874=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
CONFIG_DEV_LOWCONSOLE=y
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/ez80f910200zco/nsh/defconfig b/configs/ez80f910200zco/nsh/defconfig
index 2b23512921..72a9774dd9 100644
--- a/configs/ez80f910200zco/nsh/defconfig
+++ b/configs/ez80f910200zco/nsh/defconfig
@@ -435,7 +435,6 @@ CONFIG_ETH0_PHY_AM79C874=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/ez80f910200zco/poll/defconfig b/configs/ez80f910200zco/poll/defconfig
index a7b22914de..b806a20f74 100644
--- a/configs/ez80f910200zco/poll/defconfig
+++ b/configs/ez80f910200zco/poll/defconfig
@@ -435,7 +435,6 @@ CONFIG_DEV_FIFO_SIZE=1024
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
CONFIG_DEV_LOWCONSOLE=y
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/fire-stm32v2/nsh/defconfig b/configs/fire-stm32v2/nsh/defconfig
index 50cae46c40..4abebec236 100644
--- a/configs/fire-stm32v2/nsh/defconfig
+++ b/configs/fire-stm32v2/nsh/defconfig
@@ -842,7 +842,6 @@ CONFIG_ENC28J60_HPWORK=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/freedom-k64f/netnsh/defconfig b/configs/freedom-k64f/netnsh/defconfig
index 02ec9f3d77..a16d6eae3f 100644
--- a/configs/freedom-k64f/netnsh/defconfig
+++ b/configs/freedom-k64f/netnsh/defconfig
@@ -564,7 +564,6 @@ CONFIG_ETH0_PHY_KSZ8081=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/freedom-k64f/nsh/defconfig b/configs/freedom-k64f/nsh/defconfig
index 32c412eff7..d32846b642 100644
--- a/configs/freedom-k64f/nsh/defconfig
+++ b/configs/freedom-k64f/nsh/defconfig
@@ -512,7 +512,6 @@ CONFIG_SDIO_BLOCKSETUP=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/freedom-kl25z/nsh/defconfig b/configs/freedom-kl25z/nsh/defconfig
index 7e8e1e499c..4ce766e4e7 100644
--- a/configs/freedom-kl25z/nsh/defconfig
+++ b/configs/freedom-kl25z/nsh/defconfig
@@ -428,7 +428,6 @@ CONFIG_PWM=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/freedom-kl26z/nsh/defconfig b/configs/freedom-kl26z/nsh/defconfig
index 47dd2b666c..34ecf77745 100644
--- a/configs/freedom-kl26z/nsh/defconfig
+++ b/configs/freedom-kl26z/nsh/defconfig
@@ -422,7 +422,6 @@ CONFIG_PWM=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/hymini-stm32v/nsh/defconfig b/configs/hymini-stm32v/nsh/defconfig
index 47f1611dde..54662444e9 100644
--- a/configs/hymini-stm32v/nsh/defconfig
+++ b/configs/hymini-stm32v/nsh/defconfig
@@ -740,7 +740,6 @@ CONFIG_SDIO_PREFLIGHT=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/hymini-stm32v/nsh2/defconfig b/configs/hymini-stm32v/nsh2/defconfig
index 7bc35a4917..6998b185dc 100644
--- a/configs/hymini-stm32v/nsh2/defconfig
+++ b/configs/hymini-stm32v/nsh2/defconfig
@@ -837,7 +837,6 @@ CONFIG_SDIO_PREFLIGHT=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/hymini-stm32v/usbmsc/defconfig b/configs/hymini-stm32v/usbmsc/defconfig
index 504e368db2..9d5759bf6c 100644
--- a/configs/hymini-stm32v/usbmsc/defconfig
+++ b/configs/hymini-stm32v/usbmsc/defconfig
@@ -746,7 +746,6 @@ CONFIG_SDIO_PREFLIGHT=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/hymini-stm32v/usbnsh/defconfig b/configs/hymini-stm32v/usbnsh/defconfig
index 32e61c43d6..2d2497ca47 100644
--- a/configs/hymini-stm32v/usbnsh/defconfig
+++ b/configs/hymini-stm32v/usbnsh/defconfig
@@ -733,7 +733,6 @@ CONFIG_ARCH_HAVE_SPI_BITORDER=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
CONFIG_SERIAL_REMOVABLE=y
diff --git a/configs/hymini-stm32v/usbserial/defconfig b/configs/hymini-stm32v/usbserial/defconfig
index e60be704c7..13be18558c 100644
--- a/configs/hymini-stm32v/usbserial/defconfig
+++ b/configs/hymini-stm32v/usbserial/defconfig
@@ -720,7 +720,6 @@ CONFIG_ARCH_HAVE_SPI_BITORDER=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
CONFIG_SERIAL_REMOVABLE=y
diff --git a/configs/kwikstik-k40/ostest/defconfig b/configs/kwikstik-k40/ostest/defconfig
index 3aa09462c5..4ea31a1c0f 100644
--- a/configs/kwikstik-k40/ostest/defconfig
+++ b/configs/kwikstik-k40/ostest/defconfig
@@ -463,7 +463,6 @@ CONFIG_DEV_NULL=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
CONFIG_DEV_LOWCONSOLE=y
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/launchxl-tms57004/nsh/defconfig b/configs/launchxl-tms57004/nsh/defconfig
index d80732cc89..d59a2f60f5 100644
--- a/configs/launchxl-tms57004/nsh/defconfig
+++ b/configs/launchxl-tms57004/nsh/defconfig
@@ -433,7 +433,6 @@ CONFIG_SPI_EXCHANGE=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/lincoln60/netnsh/defconfig b/configs/lincoln60/netnsh/defconfig
index d441e274ba..8e9cdf53c6 100644
--- a/configs/lincoln60/netnsh/defconfig
+++ b/configs/lincoln60/netnsh/defconfig
@@ -543,7 +543,6 @@ CONFIG_ETH0_PHY_KSZ8041=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/lincoln60/nsh/defconfig b/configs/lincoln60/nsh/defconfig
index 3fcf92ddc8..31e8eae34a 100644
--- a/configs/lincoln60/nsh/defconfig
+++ b/configs/lincoln60/nsh/defconfig
@@ -462,7 +462,6 @@ CONFIG_DEV_NULL=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/lincoln60/thttpd-binfs/defconfig b/configs/lincoln60/thttpd-binfs/defconfig
index 2ca94f7fa3..f1d8ab9bbf 100644
--- a/configs/lincoln60/thttpd-binfs/defconfig
+++ b/configs/lincoln60/thttpd-binfs/defconfig
@@ -525,7 +525,6 @@ CONFIG_DEV_FIFO_SIZE=1024
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
CONFIG_DEV_LOWCONSOLE=y
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/lm3s6432-s2e/nsh/defconfig b/configs/lm3s6432-s2e/nsh/defconfig
index a18a57d4c2..6212b42fab 100644
--- a/configs/lm3s6432-s2e/nsh/defconfig
+++ b/configs/lm3s6432-s2e/nsh/defconfig
@@ -529,7 +529,6 @@ CONFIG_ARCH_HAVE_NETDEV_STATISTICS=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/lm3s6965-ek/discover/defconfig b/configs/lm3s6965-ek/discover/defconfig
index 8d96db5491..265299c608 100644
--- a/configs/lm3s6965-ek/discover/defconfig
+++ b/configs/lm3s6965-ek/discover/defconfig
@@ -557,7 +557,6 @@ CONFIG_ARCH_HAVE_NETDEV_STATISTICS=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/lm3s6965-ek/nsh/defconfig b/configs/lm3s6965-ek/nsh/defconfig
index 8d96db5491..265299c608 100644
--- a/configs/lm3s6965-ek/nsh/defconfig
+++ b/configs/lm3s6965-ek/nsh/defconfig
@@ -557,7 +557,6 @@ CONFIG_ARCH_HAVE_NETDEV_STATISTICS=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/lm3s6965-ek/nx/defconfig b/configs/lm3s6965-ek/nx/defconfig
index 496b2737ea..fdc5c9c632 100644
--- a/configs/lm3s6965-ek/nx/defconfig
+++ b/configs/lm3s6965-ek/nx/defconfig
@@ -541,7 +541,6 @@ CONFIG_LCD_LANDSCAPE=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/lm3s6965-ek/tcpecho/defconfig b/configs/lm3s6965-ek/tcpecho/defconfig
index d080e57f55..96af39bd22 100644
--- a/configs/lm3s6965-ek/tcpecho/defconfig
+++ b/configs/lm3s6965-ek/tcpecho/defconfig
@@ -528,7 +528,6 @@ CONFIG_ARCH_HAVE_NETDEV_STATISTICS=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/lm3s8962-ek/nsh/defconfig b/configs/lm3s8962-ek/nsh/defconfig
index d707ebe974..d834d65af4 100644
--- a/configs/lm3s8962-ek/nsh/defconfig
+++ b/configs/lm3s8962-ek/nsh/defconfig
@@ -567,7 +567,6 @@ CONFIG_ARCH_HAVE_NETDEV_STATISTICS=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/lm3s8962-ek/nx/defconfig b/configs/lm3s8962-ek/nx/defconfig
index 7cfe420286..92d68b951c 100644
--- a/configs/lm3s8962-ek/nx/defconfig
+++ b/configs/lm3s8962-ek/nx/defconfig
@@ -551,7 +551,6 @@ CONFIG_LCD_LANDSCAPE=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/lm4f120-launchpad/nsh/defconfig b/configs/lm4f120-launchpad/nsh/defconfig
index 2dd6e821ae..759d63075b 100644
--- a/configs/lm4f120-launchpad/nsh/defconfig
+++ b/configs/lm4f120-launchpad/nsh/defconfig
@@ -492,7 +492,6 @@ CONFIG_DEV_NULL=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/lpc4330-xplorer/nsh/defconfig b/configs/lpc4330-xplorer/nsh/defconfig
index ded2899940..6d0df578a2 100644
--- a/configs/lpc4330-xplorer/nsh/defconfig
+++ b/configs/lpc4330-xplorer/nsh/defconfig
@@ -480,7 +480,6 @@ CONFIG_DEV_NULL=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/lpc4337-ws/nsh/defconfig b/configs/lpc4337-ws/nsh/defconfig
index f4f3a256a3..a462d6a1e4 100644
--- a/configs/lpc4337-ws/nsh/defconfig
+++ b/configs/lpc4337-ws/nsh/defconfig
@@ -499,7 +499,6 @@ CONFIG_ADC_FIFOSIZE=8
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
CONFIG_SERIAL_REMOVABLE=y
diff --git a/configs/lpc4357-evb/nsh/defconfig b/configs/lpc4357-evb/nsh/defconfig
index a4aeb12c63..fda9ffd04c 100644
--- a/configs/lpc4357-evb/nsh/defconfig
+++ b/configs/lpc4357-evb/nsh/defconfig
@@ -472,7 +472,6 @@ CONFIG_DEV_NULL=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/lpc4370-link2/nsh/defconfig b/configs/lpc4370-link2/nsh/defconfig
index e6705f3f53..605c816885 100644
--- a/configs/lpc4370-link2/nsh/defconfig
+++ b/configs/lpc4370-link2/nsh/defconfig
@@ -496,7 +496,6 @@ CONFIG_SPI=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
CONFIG_SERIAL_REMOVABLE=y
diff --git a/configs/lpcxpresso-lpc1115/nsh/defconfig b/configs/lpcxpresso-lpc1115/nsh/defconfig
index 9f84ad4089..8a66a48cc7 100644
--- a/configs/lpcxpresso-lpc1115/nsh/defconfig
+++ b/configs/lpcxpresso-lpc1115/nsh/defconfig
@@ -394,7 +394,6 @@ CONFIG_DEV_NULL=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/lpcxpresso-lpc1768/dhcpd/defconfig b/configs/lpcxpresso-lpc1768/dhcpd/defconfig
index bba536eb45..380604febf 100644
--- a/configs/lpcxpresso-lpc1768/dhcpd/defconfig
+++ b/configs/lpcxpresso-lpc1768/dhcpd/defconfig
@@ -513,7 +513,6 @@ CONFIG_ETH0_PHY_LAN8720=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/lpcxpresso-lpc1768/nsh/defconfig b/configs/lpcxpresso-lpc1768/nsh/defconfig
index 711a813f12..fdbc186bc7 100644
--- a/configs/lpcxpresso-lpc1768/nsh/defconfig
+++ b/configs/lpcxpresso-lpc1768/nsh/defconfig
@@ -583,7 +583,6 @@ CONFIG_ETH0_PHY_LAN8720=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/lpcxpresso-lpc1768/nx/defconfig b/configs/lpcxpresso-lpc1768/nx/defconfig
index fbfd01860b..bb99255c2d 100644
--- a/configs/lpcxpresso-lpc1768/nx/defconfig
+++ b/configs/lpcxpresso-lpc1768/nx/defconfig
@@ -519,7 +519,6 @@ CONFIG_LCD_LANDSCAPE=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/lpcxpresso-lpc1768/thttpd/defconfig b/configs/lpcxpresso-lpc1768/thttpd/defconfig
index 9b6d1f1642..0020d90dbf 100644
--- a/configs/lpcxpresso-lpc1768/thttpd/defconfig
+++ b/configs/lpcxpresso-lpc1768/thttpd/defconfig
@@ -517,7 +517,6 @@ CONFIG_DEV_FIFO_SIZE=1024
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
CONFIG_DEV_LOWCONSOLE=y
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/lpcxpresso-lpc1768/usbmsc/defconfig b/configs/lpcxpresso-lpc1768/usbmsc/defconfig
index b320318150..608efd1c81 100644
--- a/configs/lpcxpresso-lpc1768/usbmsc/defconfig
+++ b/configs/lpcxpresso-lpc1768/usbmsc/defconfig
@@ -492,7 +492,6 @@ CONFIG_MMCSD_SPIMODE=0
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/maple/nsh/defconfig b/configs/maple/nsh/defconfig
index 1b7e1f5ac7..3a9c485155 100644
--- a/configs/maple/nsh/defconfig
+++ b/configs/maple/nsh/defconfig
@@ -704,7 +704,6 @@ CONFIG_ARCH_HAVE_SPI_BITORDER=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/maple/nx/defconfig b/configs/maple/nx/defconfig
index 3906da6970..9936c99c3d 100644
--- a/configs/maple/nx/defconfig
+++ b/configs/maple/nx/defconfig
@@ -799,7 +799,6 @@ CONFIG_LCD_LANDSCAPE=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
CONFIG_SERIAL_REMOVABLE=y
CONFIG_SERIAL_CONSOLE=y
diff --git a/configs/maple/usbnsh/defconfig b/configs/maple/usbnsh/defconfig
index 03c4bdf963..1a0485d7dc 100644
--- a/configs/maple/usbnsh/defconfig
+++ b/configs/maple/usbnsh/defconfig
@@ -716,7 +716,6 @@ CONFIG_ARCH_HAVE_SPI_BITORDER=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
CONFIG_SERIAL_REMOVABLE=y
CONFIG_SERIAL_CONSOLE=y
diff --git a/configs/mbed/hidkbd/defconfig b/configs/mbed/hidkbd/defconfig
index 1543135095..749e51ef04 100644
--- a/configs/mbed/hidkbd/defconfig
+++ b/configs/mbed/hidkbd/defconfig
@@ -476,7 +476,6 @@ CONFIG_DEV_NULL=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/mbed/nsh/defconfig b/configs/mbed/nsh/defconfig
index 094452f385..e58d828f5e 100644
--- a/configs/mbed/nsh/defconfig
+++ b/configs/mbed/nsh/defconfig
@@ -514,7 +514,6 @@ CONFIG_MTD=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/mcu123-lpc214x/composite/defconfig b/configs/mcu123-lpc214x/composite/defconfig
index c201531c3e..cffe65a216 100644
--- a/configs/mcu123-lpc214x/composite/defconfig
+++ b/configs/mcu123-lpc214x/composite/defconfig
@@ -429,7 +429,6 @@ CONFIG_MMCSD_SPIMODE=0
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
CONFIG_SERIAL_REMOVABLE=y
diff --git a/configs/mcu123-lpc214x/nsh/defconfig b/configs/mcu123-lpc214x/nsh/defconfig
index ecf4525145..16148fb70a 100644
--- a/configs/mcu123-lpc214x/nsh/defconfig
+++ b/configs/mcu123-lpc214x/nsh/defconfig
@@ -422,7 +422,6 @@ CONFIG_MMCSD_SPIMODE=0
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/mcu123-lpc214x/usbmsc/defconfig b/configs/mcu123-lpc214x/usbmsc/defconfig
index 6aa0970854..902c2e9593 100644
--- a/configs/mcu123-lpc214x/usbmsc/defconfig
+++ b/configs/mcu123-lpc214x/usbmsc/defconfig
@@ -429,7 +429,6 @@ CONFIG_MMCSD_SPIMODE=0
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/mcu123-lpc214x/usbserial/defconfig b/configs/mcu123-lpc214x/usbserial/defconfig
index c2717e3634..d6293bc0cc 100644
--- a/configs/mcu123-lpc214x/usbserial/defconfig
+++ b/configs/mcu123-lpc214x/usbserial/defconfig
@@ -409,7 +409,6 @@ CONFIG_DEV_NULL=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
CONFIG_SERIAL_REMOVABLE=y
diff --git a/configs/micropendous3/hello/defconfig b/configs/micropendous3/hello/defconfig
index 46d64c660c..c11817790b 100644
--- a/configs/micropendous3/hello/defconfig
+++ b/configs/micropendous3/hello/defconfig
@@ -241,7 +241,6 @@ CONFIG_DEV_NULL=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
CONFIG_DEV_LOWCONSOLE=y
# CONFIG_16550_UART is not set
diff --git a/configs/mikroe-stm32f4/fulldemo/defconfig b/configs/mikroe-stm32f4/fulldemo/defconfig
index 3588440c91..ec1f44da76 100644
--- a/configs/mikroe-stm32f4/fulldemo/defconfig
+++ b/configs/mikroe-stm32f4/fulldemo/defconfig
@@ -901,7 +901,6 @@ CONFIG_MTD_SMART_WEAR_LEVEL=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
CONFIG_SERIAL_REMOVABLE=y
# CONFIG_SERIAL_CONSOLE is not set
diff --git a/configs/mikroe-stm32f4/kostest/defconfig b/configs/mikroe-stm32f4/kostest/defconfig
index 5baa0d7129..e8740c395b 100644
--- a/configs/mikroe-stm32f4/kostest/defconfig
+++ b/configs/mikroe-stm32f4/kostest/defconfig
@@ -845,7 +845,6 @@ CONFIG_MTD_SMART_WEAR_LEVEL=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
CONFIG_SERIAL_REMOVABLE=y
# CONFIG_SERIAL_CONSOLE is not set
diff --git a/configs/mikroe-stm32f4/nsh/defconfig b/configs/mikroe-stm32f4/nsh/defconfig
index 88f1e50141..bd189e13d9 100644
--- a/configs/mikroe-stm32f4/nsh/defconfig
+++ b/configs/mikroe-stm32f4/nsh/defconfig
@@ -812,7 +812,6 @@ CONFIG_MTD_SMART_WEAR_LEVEL=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_SERIAL_REMOVABLE is not set
CONFIG_SERIAL_CONSOLE=y
diff --git a/configs/mikroe-stm32f4/nx/defconfig b/configs/mikroe-stm32f4/nx/defconfig
index 141f06a3f2..51f178871d 100644
--- a/configs/mikroe-stm32f4/nx/defconfig
+++ b/configs/mikroe-stm32f4/nx/defconfig
@@ -758,7 +758,6 @@ CONFIG_LCD_LANDSCAPE=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
# CONFIG_SERIAL is not set
# CONFIG_USBDEV is not set
# CONFIG_USBHOST is not set
diff --git a/configs/mikroe-stm32f4/nxlines/defconfig b/configs/mikroe-stm32f4/nxlines/defconfig
index 96e58d2a0e..f0c6adcfea 100644
--- a/configs/mikroe-stm32f4/nxlines/defconfig
+++ b/configs/mikroe-stm32f4/nxlines/defconfig
@@ -745,7 +745,6 @@ CONFIG_LCD_LANDSCAPE=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
# CONFIG_SERIAL is not set
# CONFIG_USBDEV is not set
# CONFIG_USBHOST is not set
diff --git a/configs/mikroe-stm32f4/nxtext/defconfig b/configs/mikroe-stm32f4/nxtext/defconfig
index 511b951270..52933714d6 100644
--- a/configs/mikroe-stm32f4/nxtext/defconfig
+++ b/configs/mikroe-stm32f4/nxtext/defconfig
@@ -758,7 +758,6 @@ CONFIG_LCD_LANDSCAPE=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
# CONFIG_SERIAL is not set
# CONFIG_USBDEV is not set
# CONFIG_USBHOST is not set
diff --git a/configs/mikroe-stm32f4/usbnsh/defconfig b/configs/mikroe-stm32f4/usbnsh/defconfig
index 5e53200ce8..6ebceb9c45 100644
--- a/configs/mikroe-stm32f4/usbnsh/defconfig
+++ b/configs/mikroe-stm32f4/usbnsh/defconfig
@@ -820,7 +820,6 @@ CONFIG_MTD_SMART_WEAR_LEVEL=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
CONFIG_SERIAL_REMOVABLE=y
# CONFIG_SERIAL_CONSOLE is not set
diff --git a/configs/mirtoo/nsh/defconfig b/configs/mirtoo/nsh/defconfig
index 8c8743a9ce..3630f0f223 100644
--- a/configs/mirtoo/nsh/defconfig
+++ b/configs/mirtoo/nsh/defconfig
@@ -499,7 +499,6 @@ CONFIG_DEV_NULL=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/mirtoo/nxffs/defconfig b/configs/mirtoo/nxffs/defconfig
index 6dbc62ca2b..627d0b9e7a 100644
--- a/configs/mirtoo/nxffs/defconfig
+++ b/configs/mirtoo/nxffs/defconfig
@@ -540,7 +540,6 @@ CONFIG_SST25_SPIFREQUENCY=20000000
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/misoc/hello/defconfig b/configs/misoc/hello/defconfig
index 3aef6631d1..a9a5dfc138 100644
--- a/configs/misoc/hello/defconfig
+++ b/configs/misoc/hello/defconfig
@@ -407,7 +407,6 @@ CONFIG_ETH0_PHY_NONE=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/misoc/nsh/defconfig b/configs/misoc/nsh/defconfig
index 438198545a..75cf732f67 100644
--- a/configs/misoc/nsh/defconfig
+++ b/configs/misoc/nsh/defconfig
@@ -334,7 +334,6 @@ CONFIG_DEV_NULL=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/moteino-mega/hello/defconfig b/configs/moteino-mega/hello/defconfig
index 973aac4a8d..ffadd04745 100644
--- a/configs/moteino-mega/hello/defconfig
+++ b/configs/moteino-mega/hello/defconfig
@@ -269,7 +269,6 @@ CONFIG_DEV_NULL=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
CONFIG_DEV_LOWCONSOLE=y
# CONFIG_16550_UART is not set
diff --git a/configs/moteino-mega/nsh/defconfig b/configs/moteino-mega/nsh/defconfig
index 97bf0cf3e0..c3021fcbf7 100644
--- a/configs/moteino-mega/nsh/defconfig
+++ b/configs/moteino-mega/nsh/defconfig
@@ -277,7 +277,6 @@ CONFIG_DEV_NULL=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_16550_UART is not set
diff --git a/configs/moxa/nsh/defconfig b/configs/moxa/nsh/defconfig
index f1fdbfbda3..fd951b047a 100644
--- a/configs/moxa/nsh/defconfig
+++ b/configs/moxa/nsh/defconfig
@@ -427,7 +427,6 @@ CONFIG_FTMAC100_HPWORK=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/mx1ads/ostest/defconfig b/configs/mx1ads/ostest/defconfig
index 6f911c5a48..04225dad73 100644
--- a/configs/mx1ads/ostest/defconfig
+++ b/configs/mx1ads/ostest/defconfig
@@ -390,7 +390,6 @@ CONFIG_SPI=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/ne64badge/ostest/defconfig b/configs/ne64badge/ostest/defconfig
index 94d4e981c3..2986223f0c 100644
--- a/configs/ne64badge/ostest/defconfig
+++ b/configs/ne64badge/ostest/defconfig
@@ -242,7 +242,6 @@ CONFIG_DEV_NULL=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_16550_UART is not set
diff --git a/configs/nr5m100-nexys4/nsh/defconfig b/configs/nr5m100-nexys4/nsh/defconfig
index eacb815a02..e2b6c7f66d 100644
--- a/configs/nr5m100-nexys4/nsh/defconfig
+++ b/configs/nr5m100-nexys4/nsh/defconfig
@@ -348,7 +348,6 @@ CONFIG_DEV_ZERO=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/ntosd-dm320/nettest/defconfig b/configs/ntosd-dm320/nettest/defconfig
index 8621bd1cba..e1f95fe831 100644
--- a/configs/ntosd-dm320/nettest/defconfig
+++ b/configs/ntosd-dm320/nettest/defconfig
@@ -417,7 +417,6 @@ CONFIG_DM9X_HPWORK=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/ntosd-dm320/nsh/defconfig b/configs/ntosd-dm320/nsh/defconfig
index 13fba2e95f..39868b6085 100644
--- a/configs/ntosd-dm320/nsh/defconfig
+++ b/configs/ntosd-dm320/nsh/defconfig
@@ -433,7 +433,6 @@ CONFIG_DM9X_HPWORK=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/ntosd-dm320/poll/defconfig b/configs/ntosd-dm320/poll/defconfig
index 504fe1fd77..16cd6306ee 100644
--- a/configs/ntosd-dm320/poll/defconfig
+++ b/configs/ntosd-dm320/poll/defconfig
@@ -427,7 +427,6 @@ CONFIG_DEV_FIFO_SIZE=1024
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/ntosd-dm320/thttpd/defconfig b/configs/ntosd-dm320/thttpd/defconfig
index e0b5074661..5b9439f577 100644
--- a/configs/ntosd-dm320/thttpd/defconfig
+++ b/configs/ntosd-dm320/thttpd/defconfig
@@ -420,7 +420,6 @@ CONFIG_DEV_FIFO_SIZE=1024
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/ntosd-dm320/udp/defconfig b/configs/ntosd-dm320/udp/defconfig
index a9713516f4..430d9c3d54 100644
--- a/configs/ntosd-dm320/udp/defconfig
+++ b/configs/ntosd-dm320/udp/defconfig
@@ -416,7 +416,6 @@ CONFIG_DM9X_HPWORK=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/ntosd-dm320/webserver/defconfig b/configs/ntosd-dm320/webserver/defconfig
index 8cb5e5715c..5b9e96f8f2 100644
--- a/configs/ntosd-dm320/webserver/defconfig
+++ b/configs/ntosd-dm320/webserver/defconfig
@@ -424,7 +424,6 @@ CONFIG_DM9X_HPWORK=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/nucleo-144/f746-evalos/defconfig b/configs/nucleo-144/f746-evalos/defconfig
index 8dd40aa090..3372db8d00 100644
--- a/configs/nucleo-144/f746-evalos/defconfig
+++ b/configs/nucleo-144/f746-evalos/defconfig
@@ -628,7 +628,6 @@ CONFIG_USERLED_LOWER=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/nucleo-144/f746-nsh/defconfig b/configs/nucleo-144/f746-nsh/defconfig
index 91cc088605..d034bff8ac 100644
--- a/configs/nucleo-144/f746-nsh/defconfig
+++ b/configs/nucleo-144/f746-nsh/defconfig
@@ -616,7 +616,6 @@ CONFIG_ARCH_HAVE_SPI_BITORDER=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/nucleo-144/f767-evalos/defconfig b/configs/nucleo-144/f767-evalos/defconfig
index 90f0a2fa63..bae0a8f84b 100644
--- a/configs/nucleo-144/f767-evalos/defconfig
+++ b/configs/nucleo-144/f767-evalos/defconfig
@@ -632,7 +632,6 @@ CONFIG_USERLED_LOWER=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/nucleo-144/f767-nsh/defconfig b/configs/nucleo-144/f767-nsh/defconfig
index 30ea41719a..36e14b0093 100644
--- a/configs/nucleo-144/f767-nsh/defconfig
+++ b/configs/nucleo-144/f767-nsh/defconfig
@@ -620,7 +620,6 @@ CONFIG_ARCH_HAVE_SPI_BITORDER=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/nucleo-f303re/adc/defconfig b/configs/nucleo-f303re/adc/defconfig
index 6bd903c7b8..4fb368517a 100644
--- a/configs/nucleo-f303re/adc/defconfig
+++ b/configs/nucleo-f303re/adc/defconfig
@@ -723,7 +723,6 @@ CONFIG_ADC_FIFOSIZE=8
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
# CONFIG_SERIAL is not set
# CONFIG_USBDEV is not set
# CONFIG_USBHOST is not set
diff --git a/configs/nucleo-f303re/can/defconfig b/configs/nucleo-f303re/can/defconfig
index 957b4d9412..883c9c3668 100644
--- a/configs/nucleo-f303re/can/defconfig
+++ b/configs/nucleo-f303re/can/defconfig
@@ -724,7 +724,6 @@ CONFIG_ARCH_HAVE_SPI_BITORDER=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
# CONFIG_SERIAL is not set
# CONFIG_USBDEV is not set
# CONFIG_USBHOST is not set
diff --git a/configs/nucleo-f303re/hello/defconfig b/configs/nucleo-f303re/hello/defconfig
index 46e78f3399..dffa050525 100644
--- a/configs/nucleo-f303re/hello/defconfig
+++ b/configs/nucleo-f303re/hello/defconfig
@@ -726,7 +726,6 @@ CONFIG_ARCH_HAVE_SPI_BITORDER=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/nucleo-f303re/nxlines/defconfig b/configs/nucleo-f303re/nxlines/defconfig
index da112c4350..84d948c102 100644
--- a/configs/nucleo-f303re/nxlines/defconfig
+++ b/configs/nucleo-f303re/nxlines/defconfig
@@ -788,7 +788,6 @@ CONFIG_LCD_LANDSCAPE=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
# CONFIG_SERIAL is not set
# CONFIG_USBDEV is not set
# CONFIG_USBHOST is not set
diff --git a/configs/nucleo-f303re/pwm/defconfig b/configs/nucleo-f303re/pwm/defconfig
index ba86073959..ca70a10f72 100644
--- a/configs/nucleo-f303re/pwm/defconfig
+++ b/configs/nucleo-f303re/pwm/defconfig
@@ -723,7 +723,6 @@ CONFIG_ARCH_HAVE_SPI_BITORDER=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
# CONFIG_SERIAL is not set
# CONFIG_USBDEV is not set
# CONFIG_USBHOST is not set
diff --git a/configs/nucleo-f303re/serialrx/defconfig b/configs/nucleo-f303re/serialrx/defconfig
index 0cbb86fdbf..17f8c5f5e2 100644
--- a/configs/nucleo-f303re/serialrx/defconfig
+++ b/configs/nucleo-f303re/serialrx/defconfig
@@ -727,7 +727,6 @@ CONFIG_ADC_FIFOSIZE=8
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_SERIAL_REMOVABLE is not set
# CONFIG_SERIAL_CONSOLE is not set
diff --git a/configs/nucleo-f303re/uavcan/defconfig b/configs/nucleo-f303re/uavcan/defconfig
index 0d6b7a805a..21ffa46165 100644
--- a/configs/nucleo-f303re/uavcan/defconfig
+++ b/configs/nucleo-f303re/uavcan/defconfig
@@ -704,7 +704,6 @@ CONFIG_ARCH_HAVE_SPI_BITORDER=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
# CONFIG_SERIAL is not set
# CONFIG_USBDEV is not set
# CONFIG_USBHOST is not set
diff --git a/configs/nucleo-f4x1re/f401-nsh/defconfig b/configs/nucleo-f4x1re/f401-nsh/defconfig
index bd6347ccf4..5973a284e1 100644
--- a/configs/nucleo-f4x1re/f401-nsh/defconfig
+++ b/configs/nucleo-f4x1re/f401-nsh/defconfig
@@ -723,7 +723,6 @@ CONFIG_ARCH_HAVE_SPI_BITORDER=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/nucleo-f4x1re/f411-nsh/defconfig b/configs/nucleo-f4x1re/f411-nsh/defconfig
index 93f29a8058..a1fafd77d5 100644
--- a/configs/nucleo-f4x1re/f411-nsh/defconfig
+++ b/configs/nucleo-f4x1re/f411-nsh/defconfig
@@ -725,7 +725,6 @@ CONFIG_ARCH_HAVE_SPI_BITORDER=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/nucleo-l476rg/nsh/defconfig b/configs/nucleo-l476rg/nsh/defconfig
index 293d43a01e..c8b4ec6900 100644
--- a/configs/nucleo-l476rg/nsh/defconfig
+++ b/configs/nucleo-l476rg/nsh/defconfig
@@ -556,7 +556,6 @@ CONFIG_RTC_IOCTL=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/nutiny-nuc120/nsh/defconfig b/configs/nutiny-nuc120/nsh/defconfig
index 52cd0aa73d..a8d566fcc0 100644
--- a/configs/nutiny-nuc120/nsh/defconfig
+++ b/configs/nutiny-nuc120/nsh/defconfig
@@ -444,7 +444,6 @@ CONFIG_DEV_NULL=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/olimex-efm32g880f128-stk/nsh/defconfig b/configs/olimex-efm32g880f128-stk/nsh/defconfig
index 325b4d39c6..284ccdf97a 100644
--- a/configs/olimex-efm32g880f128-stk/nsh/defconfig
+++ b/configs/olimex-efm32g880f128-stk/nsh/defconfig
@@ -450,7 +450,6 @@ CONFIG_ARCH_HAVE_SPI_BITORDER=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/olimex-lpc-h3131/nsh/defconfig b/configs/olimex-lpc-h3131/nsh/defconfig
index aa99aad41a..589cbe3c03 100644
--- a/configs/olimex-lpc-h3131/nsh/defconfig
+++ b/configs/olimex-lpc-h3131/nsh/defconfig
@@ -416,7 +416,6 @@ CONFIG_DEV_NULL=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/olimex-lpc1766stk/ftpc/defconfig b/configs/olimex-lpc1766stk/ftpc/defconfig
index 6e4257fabf..fc0d118c62 100644
--- a/configs/olimex-lpc1766stk/ftpc/defconfig
+++ b/configs/olimex-lpc1766stk/ftpc/defconfig
@@ -549,7 +549,6 @@ CONFIG_ETH0_PHY_KS8721=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/olimex-lpc1766stk/hidkbd/defconfig b/configs/olimex-lpc1766stk/hidkbd/defconfig
index 91339c8034..f052dbade6 100644
--- a/configs/olimex-lpc1766stk/hidkbd/defconfig
+++ b/configs/olimex-lpc1766stk/hidkbd/defconfig
@@ -501,7 +501,6 @@ CONFIG_MMCSD_NSLOTS=1
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/olimex-lpc1766stk/hidmouse/defconfig b/configs/olimex-lpc1766stk/hidmouse/defconfig
index 779627451c..a87a47d09e 100644
--- a/configs/olimex-lpc1766stk/hidmouse/defconfig
+++ b/configs/olimex-lpc1766stk/hidmouse/defconfig
@@ -518,7 +518,6 @@ CONFIG_NETDEV_TELNET=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/olimex-lpc1766stk/nettest/defconfig b/configs/olimex-lpc1766stk/nettest/defconfig
index 3b16844a41..187301717f 100644
--- a/configs/olimex-lpc1766stk/nettest/defconfig
+++ b/configs/olimex-lpc1766stk/nettest/defconfig
@@ -515,7 +515,6 @@ CONFIG_ETH0_PHY_KS8721=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
CONFIG_DEV_LOWCONSOLE=y
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/olimex-lpc1766stk/nsh/defconfig b/configs/olimex-lpc1766stk/nsh/defconfig
index 7f6d655492..061eb4cd36 100644
--- a/configs/olimex-lpc1766stk/nsh/defconfig
+++ b/configs/olimex-lpc1766stk/nsh/defconfig
@@ -551,7 +551,6 @@ CONFIG_ETH0_PHY_KS8721=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/olimex-lpc1766stk/nx/defconfig b/configs/olimex-lpc1766stk/nx/defconfig
index 9eab58ddbb..498cc7c004 100644
--- a/configs/olimex-lpc1766stk/nx/defconfig
+++ b/configs/olimex-lpc1766stk/nx/defconfig
@@ -529,7 +529,6 @@ CONFIG_LCD_LANDSCAPE=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/olimex-lpc1766stk/slip-httpd/defconfig b/configs/olimex-lpc1766stk/slip-httpd/defconfig
index 0d5615bac1..6ccd8a93a4 100644
--- a/configs/olimex-lpc1766stk/slip-httpd/defconfig
+++ b/configs/olimex-lpc1766stk/slip-httpd/defconfig
@@ -465,7 +465,6 @@ CONFIG_DEV_FIFO_SIZE=1024
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/olimex-lpc1766stk/thttpd-binfs/defconfig b/configs/olimex-lpc1766stk/thttpd-binfs/defconfig
index 0e6f02065b..ee3023b507 100644
--- a/configs/olimex-lpc1766stk/thttpd-binfs/defconfig
+++ b/configs/olimex-lpc1766stk/thttpd-binfs/defconfig
@@ -525,7 +525,6 @@ CONFIG_DEV_FIFO_SIZE=1024
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
CONFIG_DEV_LOWCONSOLE=y
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/olimex-lpc1766stk/thttpd-nxflat/defconfig b/configs/olimex-lpc1766stk/thttpd-nxflat/defconfig
index 048d75917e..9a9f869082 100644
--- a/configs/olimex-lpc1766stk/thttpd-nxflat/defconfig
+++ b/configs/olimex-lpc1766stk/thttpd-nxflat/defconfig
@@ -518,7 +518,6 @@ CONFIG_DEV_FIFO_SIZE=1024
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
CONFIG_DEV_LOWCONSOLE=y
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/olimex-lpc1766stk/usbmsc/defconfig b/configs/olimex-lpc1766stk/usbmsc/defconfig
index cac5beabd4..be389ce940 100644
--- a/configs/olimex-lpc1766stk/usbmsc/defconfig
+++ b/configs/olimex-lpc1766stk/usbmsc/defconfig
@@ -493,7 +493,6 @@ CONFIG_MMCSD_SPIMODE=0
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/olimex-lpc1766stk/usbserial/defconfig b/configs/olimex-lpc1766stk/usbserial/defconfig
index 82a00f158d..3941c38d2c 100644
--- a/configs/olimex-lpc1766stk/usbserial/defconfig
+++ b/configs/olimex-lpc1766stk/usbserial/defconfig
@@ -474,7 +474,6 @@ CONFIG_DEV_NULL=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
CONFIG_SERIAL_REMOVABLE=y
diff --git a/configs/olimex-lpc1766stk/zmodem/defconfig b/configs/olimex-lpc1766stk/zmodem/defconfig
index 4bb500d149..7eca8a61a9 100644
--- a/configs/olimex-lpc1766stk/zmodem/defconfig
+++ b/configs/olimex-lpc1766stk/zmodem/defconfig
@@ -553,7 +553,6 @@ CONFIG_ETH0_PHY_KS8721=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/olimex-lpc2378/nsh/defconfig b/configs/olimex-lpc2378/nsh/defconfig
index 0217cd1a89..f5592ef7c9 100644
--- a/configs/olimex-lpc2378/nsh/defconfig
+++ b/configs/olimex-lpc2378/nsh/defconfig
@@ -388,7 +388,6 @@ CONFIG_DEV_NULL=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/olimex-stm32-e407/discover/defconfig b/configs/olimex-stm32-e407/discover/defconfig
index a10f5196cb..d4f6b116be 100644
--- a/configs/olimex-stm32-e407/discover/defconfig
+++ b/configs/olimex-stm32-e407/discover/defconfig
@@ -823,7 +823,6 @@ CONFIG_ETH0_PHY_LAN8720=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/olimex-stm32-e407/netnsh/defconfig b/configs/olimex-stm32-e407/netnsh/defconfig
index 2053901804..5d71e695ec 100644
--- a/configs/olimex-stm32-e407/netnsh/defconfig
+++ b/configs/olimex-stm32-e407/netnsh/defconfig
@@ -825,7 +825,6 @@ CONFIG_ETH0_PHY_LAN8720=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/olimex-stm32-e407/nsh/defconfig b/configs/olimex-stm32-e407/nsh/defconfig
index cc1f9c936c..e65e883811 100644
--- a/configs/olimex-stm32-e407/nsh/defconfig
+++ b/configs/olimex-stm32-e407/nsh/defconfig
@@ -737,7 +737,6 @@ CONFIG_ARCH_HAVE_SPI_BITORDER=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/olimex-stm32-e407/telnetd/defconfig b/configs/olimex-stm32-e407/telnetd/defconfig
index 4867ca74cd..f5410d6391 100644
--- a/configs/olimex-stm32-e407/telnetd/defconfig
+++ b/configs/olimex-stm32-e407/telnetd/defconfig
@@ -825,7 +825,6 @@ CONFIG_ETH0_PHY_LAN8720=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/olimex-stm32-e407/usbnsh/defconfig b/configs/olimex-stm32-e407/usbnsh/defconfig
index 937cdcdf9d..2f62bb2803 100644
--- a/configs/olimex-stm32-e407/usbnsh/defconfig
+++ b/configs/olimex-stm32-e407/usbnsh/defconfig
@@ -754,7 +754,6 @@ CONFIG_ARCH_HAVE_SPI_BITORDER=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
CONFIG_SERIAL_REMOVABLE=y
# CONFIG_SERIAL_CONSOLE is not set
diff --git a/configs/olimex-stm32-e407/webserver/defconfig b/configs/olimex-stm32-e407/webserver/defconfig
index 7da7262f19..5066117e88 100644
--- a/configs/olimex-stm32-e407/webserver/defconfig
+++ b/configs/olimex-stm32-e407/webserver/defconfig
@@ -823,7 +823,6 @@ CONFIG_ETH0_PHY_LAN8720=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/olimex-stm32-h405/usbnsh/defconfig b/configs/olimex-stm32-h405/usbnsh/defconfig
index 4054b5aaa8..623dc403e6 100644
--- a/configs/olimex-stm32-h405/usbnsh/defconfig
+++ b/configs/olimex-stm32-h405/usbnsh/defconfig
@@ -792,7 +792,6 @@ CONFIG_ADC_FIFOSIZE=8
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
CONFIG_SERIAL_REMOVABLE=y
# CONFIG_SERIAL_CONSOLE is not set
diff --git a/configs/olimex-stm32-h407/nsh/defconfig b/configs/olimex-stm32-h407/nsh/defconfig
index 91f089efaa..f6134cc73c 100644
--- a/configs/olimex-stm32-h407/nsh/defconfig
+++ b/configs/olimex-stm32-h407/nsh/defconfig
@@ -747,7 +747,6 @@ CONFIG_ARCH_HAVE_SPI_BITORDER=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/olimex-stm32-p107/nsh/defconfig b/configs/olimex-stm32-p107/nsh/defconfig
index e93ce79019..a35f6c8abd 100644
--- a/configs/olimex-stm32-p107/nsh/defconfig
+++ b/configs/olimex-stm32-p107/nsh/defconfig
@@ -826,7 +826,6 @@ CONFIG_ETH0_PHY_KS8721=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/olimex-stm32-p207/nsh/defconfig b/configs/olimex-stm32-p207/nsh/defconfig
index 79ffb43b17..5bb065a98b 100644
--- a/configs/olimex-stm32-p207/nsh/defconfig
+++ b/configs/olimex-stm32-p207/nsh/defconfig
@@ -857,7 +857,6 @@ CONFIG_ETH0_PHY_KS8721=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/olimex-strp711/nettest/defconfig b/configs/olimex-strp711/nettest/defconfig
index 3d25b1799d..838239291f 100644
--- a/configs/olimex-strp711/nettest/defconfig
+++ b/configs/olimex-strp711/nettest/defconfig
@@ -460,7 +460,6 @@ CONFIG_ENC28J60_HPWORK=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
CONFIG_DEV_LOWCONSOLE=y
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/olimex-strp711/nsh/defconfig b/configs/olimex-strp711/nsh/defconfig
index 1a5d097977..d889a22c2e 100644
--- a/configs/olimex-strp711/nsh/defconfig
+++ b/configs/olimex-strp711/nsh/defconfig
@@ -432,7 +432,6 @@ CONFIG_MMCSD_SPIMODE=0
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/olimexino-stm32/can/defconfig b/configs/olimexino-stm32/can/defconfig
index b2e0ce9159..93c56baffe 100644
--- a/configs/olimexino-stm32/can/defconfig
+++ b/configs/olimexino-stm32/can/defconfig
@@ -782,7 +782,6 @@ CONFIG_ANALOG=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/olimexino-stm32/composite/defconfig b/configs/olimexino-stm32/composite/defconfig
index bd5fb70be0..8bf9ffffa7 100644
--- a/configs/olimexino-stm32/composite/defconfig
+++ b/configs/olimexino-stm32/composite/defconfig
@@ -793,7 +793,6 @@ CONFIG_MMCSD_SPIMODE=0
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
CONFIG_SERIAL_REMOVABLE=y
diff --git a/configs/olimexino-stm32/nsh/defconfig b/configs/olimexino-stm32/nsh/defconfig
index c00722b831..10da4dcdbd 100644
--- a/configs/olimexino-stm32/nsh/defconfig
+++ b/configs/olimexino-stm32/nsh/defconfig
@@ -792,7 +792,6 @@ CONFIG_MMCSD_SPIMODE=0
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/olimexino-stm32/smallnsh/defconfig b/configs/olimexino-stm32/smallnsh/defconfig
index 6edc98d077..fd206bba45 100644
--- a/configs/olimexino-stm32/smallnsh/defconfig
+++ b/configs/olimexino-stm32/smallnsh/defconfig
@@ -760,7 +760,6 @@ CONFIG_ARCH_HAVE_SPI_BITORDER=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/olimexino-stm32/tiny/defconfig b/configs/olimexino-stm32/tiny/defconfig
index 60ea1b64a7..5940eb260c 100644
--- a/configs/olimexino-stm32/tiny/defconfig
+++ b/configs/olimexino-stm32/tiny/defconfig
@@ -765,7 +765,6 @@ CONFIG_ARCH_HAVE_SPI_BITORDER=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
CONFIG_DEV_LOWCONSOLE=y
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/open1788/knsh/defconfig b/configs/open1788/knsh/defconfig
index 42f45c7b05..c304ff0464 100644
--- a/configs/open1788/knsh/defconfig
+++ b/configs/open1788/knsh/defconfig
@@ -494,7 +494,6 @@ CONFIG_PIPES=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/open1788/nsh/defconfig b/configs/open1788/nsh/defconfig
index 97b91ad2eb..2f155a49d0 100644
--- a/configs/open1788/nsh/defconfig
+++ b/configs/open1788/nsh/defconfig
@@ -490,7 +490,6 @@ CONFIG_PIPES=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/open1788/nxlines/defconfig b/configs/open1788/nxlines/defconfig
index 4fe9369eff..5abe3e6aa0 100644
--- a/configs/open1788/nxlines/defconfig
+++ b/configs/open1788/nxlines/defconfig
@@ -522,7 +522,6 @@ CONFIG_PIPES=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/p112/ostest/defconfig b/configs/p112/ostest/defconfig
index 7c5b119941..56ea350bf4 100644
--- a/configs/p112/ostest/defconfig
+++ b/configs/p112/ostest/defconfig
@@ -271,7 +271,6 @@ CONFIG_DEV_NULL=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
CONFIG_DEV_LOWCONSOLE=y
# CONFIG_16550_UART is not set
diff --git a/configs/pcblogic-pic32mx/nsh/defconfig b/configs/pcblogic-pic32mx/nsh/defconfig
index 32b0908358..8b93eb5cc4 100644
--- a/configs/pcblogic-pic32mx/nsh/defconfig
+++ b/configs/pcblogic-pic32mx/nsh/defconfig
@@ -495,7 +495,6 @@ CONFIG_DEV_NULL=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/pcduino-a10/nsh/defconfig b/configs/pcduino-a10/nsh/defconfig
index c2bcbc0772..db630aab6d 100644
--- a/configs/pcduino-a10/nsh/defconfig
+++ b/configs/pcduino-a10/nsh/defconfig
@@ -474,7 +474,6 @@ CONFIG_DEV_NULL=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/pic32mx-starterkit/nsh/defconfig b/configs/pic32mx-starterkit/nsh/defconfig
index 7281f362e7..780f215091 100644
--- a/configs/pic32mx-starterkit/nsh/defconfig
+++ b/configs/pic32mx-starterkit/nsh/defconfig
@@ -539,7 +539,6 @@ CONFIG_MTD=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/pic32mx-starterkit/nsh2/defconfig b/configs/pic32mx-starterkit/nsh2/defconfig
index c28f915d1c..1de3487770 100644
--- a/configs/pic32mx-starterkit/nsh2/defconfig
+++ b/configs/pic32mx-starterkit/nsh2/defconfig
@@ -603,7 +603,6 @@ CONFIG_ETH0_PHY_DP83848C=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/pic32mx7mmb/nsh/defconfig b/configs/pic32mx7mmb/nsh/defconfig
index 75ff18d6d0..7b0660e986 100644
--- a/configs/pic32mx7mmb/nsh/defconfig
+++ b/configs/pic32mx7mmb/nsh/defconfig
@@ -622,7 +622,6 @@ CONFIG_ETH0_PHY_LAN8720=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/pic32mz-starterkit/nsh/defconfig b/configs/pic32mz-starterkit/nsh/defconfig
index 9368fa716d..b64f33c262 100644
--- a/configs/pic32mz-starterkit/nsh/defconfig
+++ b/configs/pic32mz-starterkit/nsh/defconfig
@@ -466,7 +466,6 @@ CONFIG_MTD=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/qemu-i486/nsh/defconfig b/configs/qemu-i486/nsh/defconfig
index 36683c23fb..dc240aa19a 100644
--- a/configs/qemu-i486/nsh/defconfig
+++ b/configs/qemu-i486/nsh/defconfig
@@ -238,7 +238,6 @@ CONFIG_DEV_NULL=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
CONFIG_16550_UART=y
diff --git a/configs/qemu-i486/ostest/defconfig b/configs/qemu-i486/ostest/defconfig
index bddc708e7d..b205650b6c 100644
--- a/configs/qemu-i486/ostest/defconfig
+++ b/configs/qemu-i486/ostest/defconfig
@@ -237,7 +237,6 @@ CONFIG_DEV_NULL=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
CONFIG_DEV_LOWCONSOLE=y
# CONFIG_16550_UART is not set
diff --git a/configs/sabre-6quad/nsh/defconfig b/configs/sabre-6quad/nsh/defconfig
index daa1d8b791..41a976f714 100644
--- a/configs/sabre-6quad/nsh/defconfig
+++ b/configs/sabre-6quad/nsh/defconfig
@@ -448,7 +448,6 @@ CONFIG_DEV_ZERO=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/sabre-6quad/smp/defconfig b/configs/sabre-6quad/smp/defconfig
index 3ddf587c09..e9e22fc45f 100644
--- a/configs/sabre-6quad/smp/defconfig
+++ b/configs/sabre-6quad/smp/defconfig
@@ -454,7 +454,6 @@ CONFIG_DEV_ZERO=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/sam3u-ek/knsh/defconfig b/configs/sam3u-ek/knsh/defconfig
index 53f3338fcf..23349ef9a8 100644
--- a/configs/sam3u-ek/knsh/defconfig
+++ b/configs/sam3u-ek/knsh/defconfig
@@ -511,7 +511,6 @@ CONFIG_MMCSD_NSLOTS=1
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/sam3u-ek/nsh/defconfig b/configs/sam3u-ek/nsh/defconfig
index 424d740a73..0de7635260 100644
--- a/configs/sam3u-ek/nsh/defconfig
+++ b/configs/sam3u-ek/nsh/defconfig
@@ -496,7 +496,6 @@ CONFIG_DEV_NULL=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/sam3u-ek/nx/defconfig b/configs/sam3u-ek/nx/defconfig
index 1cdcce9d1c..87b7722e88 100644
--- a/configs/sam3u-ek/nx/defconfig
+++ b/configs/sam3u-ek/nx/defconfig
@@ -536,7 +536,6 @@ CONFIG_LCD_PORTRAIT=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/sam3u-ek/nxwm/defconfig b/configs/sam3u-ek/nxwm/defconfig
index 8002fb2885..c0e70052c1 100644
--- a/configs/sam3u-ek/nxwm/defconfig
+++ b/configs/sam3u-ek/nxwm/defconfig
@@ -580,7 +580,6 @@ CONFIG_LCD_LANDSCAPE=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/sam4cmp-db/nsh/defconfig b/configs/sam4cmp-db/nsh/defconfig
index 9175b32a13..118b123cef 100644
--- a/configs/sam4cmp-db/nsh/defconfig
+++ b/configs/sam4cmp-db/nsh/defconfig
@@ -522,7 +522,6 @@ CONFIG_DEV_NULL=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/sam4e-ek/nsh/defconfig b/configs/sam4e-ek/nsh/defconfig
index 264bd8063b..fa0dcfdf16 100644
--- a/configs/sam4e-ek/nsh/defconfig
+++ b/configs/sam4e-ek/nsh/defconfig
@@ -642,7 +642,6 @@ CONFIG_ETH0_PHY_KSZ8051=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/sam4e-ek/nxwm/defconfig b/configs/sam4e-ek/nxwm/defconfig
index e5bf010054..e4a4a5a664 100644
--- a/configs/sam4e-ek/nxwm/defconfig
+++ b/configs/sam4e-ek/nxwm/defconfig
@@ -701,7 +701,6 @@ CONFIG_ETH0_PHY_KSZ8051=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/sam4e-ek/usbnsh/defconfig b/configs/sam4e-ek/usbnsh/defconfig
index 717b13c4d2..4a65eb790b 100644
--- a/configs/sam4e-ek/usbnsh/defconfig
+++ b/configs/sam4e-ek/usbnsh/defconfig
@@ -647,7 +647,6 @@ CONFIG_ETH0_PHY_KSZ8051=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
CONFIG_SERIAL_REMOVABLE=y
# CONFIG_SERIAL_CONSOLE is not set
diff --git a/configs/sam4l-xplained/nsh/defconfig b/configs/sam4l-xplained/nsh/defconfig
index e08bac68fd..a4d744bbf5 100644
--- a/configs/sam4l-xplained/nsh/defconfig
+++ b/configs/sam4l-xplained/nsh/defconfig
@@ -514,7 +514,6 @@ CONFIG_DEV_NULL=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/sam4s-xplained-pro/nsh/defconfig b/configs/sam4s-xplained-pro/nsh/defconfig
index d81f101294..bd98575c00 100644
--- a/configs/sam4s-xplained-pro/nsh/defconfig
+++ b/configs/sam4s-xplained-pro/nsh/defconfig
@@ -580,7 +580,6 @@ CONFIG_DEV_FIFO_SIZE=1024
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
CONFIG_SERIAL_REMOVABLE=y
diff --git a/configs/sam4s-xplained/nsh/defconfig b/configs/sam4s-xplained/nsh/defconfig
index 87f20e61a7..5120854680 100644
--- a/configs/sam4s-xplained/nsh/defconfig
+++ b/configs/sam4s-xplained/nsh/defconfig
@@ -494,7 +494,6 @@ CONFIG_DEV_NULL=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/sama5d2-xult/nsh/defconfig b/configs/sama5d2-xult/nsh/defconfig
index 424cc780d1..bfd5cf964a 100644
--- a/configs/sama5d2-xult/nsh/defconfig
+++ b/configs/sama5d2-xult/nsh/defconfig
@@ -577,7 +577,6 @@ CONFIG_RTC_DATETIME=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/sama5d3-xplained/bridge/defconfig b/configs/sama5d3-xplained/bridge/defconfig
index 5fdf2964d7..ca9a6b5b22 100644
--- a/configs/sama5d3-xplained/bridge/defconfig
+++ b/configs/sama5d3-xplained/bridge/defconfig
@@ -633,7 +633,6 @@ CONFIG_ETH1_PHY_KSZ8081=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/sama5d3-xplained/nsh/defconfig b/configs/sama5d3-xplained/nsh/defconfig
index 930ffa3db4..8646ca8b03 100644
--- a/configs/sama5d3-xplained/nsh/defconfig
+++ b/configs/sama5d3-xplained/nsh/defconfig
@@ -532,7 +532,6 @@ CONFIG_ARCH_HAVE_I2CRESET=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/sama5d3x-ek/demo/defconfig b/configs/sama5d3x-ek/demo/defconfig
index 761e7ae57c..b0e5384d27 100644
--- a/configs/sama5d3x-ek/demo/defconfig
+++ b/configs/sama5d3x-ek/demo/defconfig
@@ -658,7 +658,6 @@ CONFIG_AT25_SPIFREQUENCY=10000000
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/sama5d3x-ek/hello/defconfig b/configs/sama5d3x-ek/hello/defconfig
index b5127834f8..d4ab562020 100644
--- a/configs/sama5d3x-ek/hello/defconfig
+++ b/configs/sama5d3x-ek/hello/defconfig
@@ -513,7 +513,6 @@ CONFIG_ARCH_HAVE_I2CRESET=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
CONFIG_DEV_LOWCONSOLE=y
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/sama5d3x-ek/norboot/defconfig b/configs/sama5d3x-ek/norboot/defconfig
index 29022a34d3..11eedfe99a 100644
--- a/configs/sama5d3x-ek/norboot/defconfig
+++ b/configs/sama5d3x-ek/norboot/defconfig
@@ -527,7 +527,6 @@ CONFIG_ARCH_HAVE_I2CRESET=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
CONFIG_DEV_LOWCONSOLE=y
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/sama5d3x-ek/nsh/defconfig b/configs/sama5d3x-ek/nsh/defconfig
index dbace7c89c..b3140774af 100644
--- a/configs/sama5d3x-ek/nsh/defconfig
+++ b/configs/sama5d3x-ek/nsh/defconfig
@@ -531,7 +531,6 @@ CONFIG_ARCH_HAVE_I2CRESET=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/sama5d3x-ek/nx/defconfig b/configs/sama5d3x-ek/nx/defconfig
index 3532962812..b67a145dfc 100644
--- a/configs/sama5d3x-ek/nx/defconfig
+++ b/configs/sama5d3x-ek/nx/defconfig
@@ -587,7 +587,6 @@ CONFIG_ARCH_HAVE_I2CRESET=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/sama5d3x-ek/nxplayer/defconfig b/configs/sama5d3x-ek/nxplayer/defconfig
index c9c7526992..00b2d5479d 100644
--- a/configs/sama5d3x-ek/nxplayer/defconfig
+++ b/configs/sama5d3x-ek/nxplayer/defconfig
@@ -628,7 +628,6 @@ CONFIG_SDIO_BLOCKSETUP=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/sama5d3x-ek/nxwm/defconfig b/configs/sama5d3x-ek/nxwm/defconfig
index a0abcb828d..5c873be148 100644
--- a/configs/sama5d3x-ek/nxwm/defconfig
+++ b/configs/sama5d3x-ek/nxwm/defconfig
@@ -642,7 +642,6 @@ CONFIG_INPUT=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/sama5d3x-ek/ov2640/defconfig b/configs/sama5d3x-ek/ov2640/defconfig
index 95ea0ac9ad..c0d64cc771 100644
--- a/configs/sama5d3x-ek/ov2640/defconfig
+++ b/configs/sama5d3x-ek/ov2640/defconfig
@@ -598,7 +598,6 @@ CONFIG_OV2640_SVGA_RESOLUTION=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
CONFIG_DEV_LOWCONSOLE=y
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/sama5d4-ek/at25boot/defconfig b/configs/sama5d4-ek/at25boot/defconfig
index d7290202de..57b32544cd 100644
--- a/configs/sama5d4-ek/at25boot/defconfig
+++ b/configs/sama5d4-ek/at25boot/defconfig
@@ -597,7 +597,6 @@ CONFIG_AT25_SPIFREQUENCY=20000000
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/sama5d4-ek/bridge/defconfig b/configs/sama5d4-ek/bridge/defconfig
index ca94b121e1..d723f24150 100644
--- a/configs/sama5d4-ek/bridge/defconfig
+++ b/configs/sama5d4-ek/bridge/defconfig
@@ -651,7 +651,6 @@ CONFIG_ETH1_PHY_KSZ8081=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/sama5d4-ek/dramboot/defconfig b/configs/sama5d4-ek/dramboot/defconfig
index 2fadab3a1c..8ca250d5d3 100644
--- a/configs/sama5d4-ek/dramboot/defconfig
+++ b/configs/sama5d4-ek/dramboot/defconfig
@@ -549,7 +549,6 @@ CONFIG_ARCH_HAVE_I2CRESET=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/sama5d4-ek/elf/defconfig b/configs/sama5d4-ek/elf/defconfig
index 0c51be98ea..7382750412 100644
--- a/configs/sama5d4-ek/elf/defconfig
+++ b/configs/sama5d4-ek/elf/defconfig
@@ -576,7 +576,6 @@ CONFIG_AUDIO_DEVICES=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/sama5d4-ek/ipv6/defconfig b/configs/sama5d4-ek/ipv6/defconfig
index 7d2d826b28..434147e369 100644
--- a/configs/sama5d4-ek/ipv6/defconfig
+++ b/configs/sama5d4-ek/ipv6/defconfig
@@ -787,7 +787,6 @@ CONFIG_ETH0_PHY_KSZ8081=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/sama5d4-ek/knsh/defconfig b/configs/sama5d4-ek/knsh/defconfig
index b0fd035fad..feeeb88157 100644
--- a/configs/sama5d4-ek/knsh/defconfig
+++ b/configs/sama5d4-ek/knsh/defconfig
@@ -605,7 +605,6 @@ CONFIG_SDIO_BLOCKSETUP=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/sama5d4-ek/knsh/defconfig.ROMFS b/configs/sama5d4-ek/knsh/defconfig.ROMFS
index 91d49d841b..047303d132 100644
--- a/configs/sama5d4-ek/knsh/defconfig.ROMFS
+++ b/configs/sama5d4-ek/knsh/defconfig.ROMFS
@@ -481,7 +481,6 @@ CONFIG_RTC_DATETIME=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_16550_UART is not set
diff --git a/configs/sama5d4-ek/nsh/defconfig b/configs/sama5d4-ek/nsh/defconfig
index 22b8c8931e..a169aa669c 100644
--- a/configs/sama5d4-ek/nsh/defconfig
+++ b/configs/sama5d4-ek/nsh/defconfig
@@ -789,7 +789,6 @@ CONFIG_ETH0_PHY_KSZ8081=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/sama5d4-ek/nxwm/defconfig b/configs/sama5d4-ek/nxwm/defconfig
index 4f3a2904f7..a6987f8f8b 100644
--- a/configs/sama5d4-ek/nxwm/defconfig
+++ b/configs/sama5d4-ek/nxwm/defconfig
@@ -758,7 +758,6 @@ CONFIG_ETH0_PHY_KSZ8081=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/sama5d4-ek/ramtest/defconfig b/configs/sama5d4-ek/ramtest/defconfig
index e17821e104..e76da62faa 100644
--- a/configs/sama5d4-ek/ramtest/defconfig
+++ b/configs/sama5d4-ek/ramtest/defconfig
@@ -549,7 +549,6 @@ CONFIG_ARCH_HAVE_I2CRESET=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/samd20-xplained/nsh/defconfig b/configs/samd20-xplained/nsh/defconfig
index ecb302a397..a91d464767 100644
--- a/configs/samd20-xplained/nsh/defconfig
+++ b/configs/samd20-xplained/nsh/defconfig
@@ -476,7 +476,6 @@ CONFIG_DEV_NULL=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/samd21-xplained/nsh/defconfig b/configs/samd21-xplained/nsh/defconfig
index 08e9d330ec..3181a18cfe 100644
--- a/configs/samd21-xplained/nsh/defconfig
+++ b/configs/samd21-xplained/nsh/defconfig
@@ -474,7 +474,6 @@ CONFIG_DEV_NULL=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/same70-xplained/netnsh/defconfig b/configs/same70-xplained/netnsh/defconfig
index 0069f726ac..c2d2a2401b 100644
--- a/configs/same70-xplained/netnsh/defconfig
+++ b/configs/same70-xplained/netnsh/defconfig
@@ -688,7 +688,6 @@ CONFIG_ETH0_PHY_KSZ8081=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/same70-xplained/nsh/defconfig b/configs/same70-xplained/nsh/defconfig
index 204304f086..c8dc02ad82 100644
--- a/configs/same70-xplained/nsh/defconfig
+++ b/configs/same70-xplained/nsh/defconfig
@@ -631,7 +631,6 @@ CONFIG_AT25_SPIFREQUENCY=20000000
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/saml21-xplained/nsh/defconfig b/configs/saml21-xplained/nsh/defconfig
index 17a9dca981..9d487c68b0 100644
--- a/configs/saml21-xplained/nsh/defconfig
+++ b/configs/saml21-xplained/nsh/defconfig
@@ -462,7 +462,6 @@ CONFIG_DEV_NULL=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/samv71-xult/knsh/defconfig b/configs/samv71-xult/knsh/defconfig
index a405803266..2c7189db7c 100644
--- a/configs/samv71-xult/knsh/defconfig
+++ b/configs/samv71-xult/knsh/defconfig
@@ -634,7 +634,6 @@ CONFIG_AT25_SPIFREQUENCY=20000000
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/samv71-xult/module/defconfig b/configs/samv71-xult/module/defconfig
index daea087771..f4e7afb959 100644
--- a/configs/samv71-xult/module/defconfig
+++ b/configs/samv71-xult/module/defconfig
@@ -542,7 +542,6 @@ CONFIG_ARCH_HAVE_SPI_CS_CONTROL=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/samv71-xult/mxtxplnd/defconfig b/configs/samv71-xult/mxtxplnd/defconfig
index e55210e0e6..49cbf5f29f 100644
--- a/configs/samv71-xult/mxtxplnd/defconfig
+++ b/configs/samv71-xult/mxtxplnd/defconfig
@@ -675,7 +675,6 @@ CONFIG_AT25_SPIFREQUENCY=20000000
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/samv71-xult/netnsh/defconfig b/configs/samv71-xult/netnsh/defconfig
index c533a146e1..37be93f688 100644
--- a/configs/samv71-xult/netnsh/defconfig
+++ b/configs/samv71-xult/netnsh/defconfig
@@ -691,7 +691,6 @@ CONFIG_ETH0_PHY_KSZ8061=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/samv71-xult/nsh/defconfig b/configs/samv71-xult/nsh/defconfig
index 4d49b5ca61..e10517c26c 100644
--- a/configs/samv71-xult/nsh/defconfig
+++ b/configs/samv71-xult/nsh/defconfig
@@ -634,7 +634,6 @@ CONFIG_AT25_SPIFREQUENCY=20000000
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/samv71-xult/nxwm/defconfig b/configs/samv71-xult/nxwm/defconfig
index e6d80b7d9a..5ea82c1a85 100644
--- a/configs/samv71-xult/nxwm/defconfig
+++ b/configs/samv71-xult/nxwm/defconfig
@@ -678,7 +678,6 @@ CONFIG_AT25_SPIFREQUENCY=20000000
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/samv71-xult/vnc/defconfig b/configs/samv71-xult/vnc/defconfig
index c6f2a7aa48..d01ad46b86 100644
--- a/configs/samv71-xult/vnc/defconfig
+++ b/configs/samv71-xult/vnc/defconfig
@@ -692,7 +692,6 @@ CONFIG_ETH0_PHY_KSZ8061=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/samv71-xult/vnxwm/defconfig b/configs/samv71-xult/vnxwm/defconfig
index e2eea5f424..87e57d38fb 100644
--- a/configs/samv71-xult/vnxwm/defconfig
+++ b/configs/samv71-xult/vnxwm/defconfig
@@ -695,7 +695,6 @@ CONFIG_ETH0_PHY_KSZ8061=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/shenzhou/nsh/defconfig b/configs/shenzhou/nsh/defconfig
index af69c7abfa..aa0359c9db 100644
--- a/configs/shenzhou/nsh/defconfig
+++ b/configs/shenzhou/nsh/defconfig
@@ -825,7 +825,6 @@ CONFIG_ETH0_PHY_DM9161=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/shenzhou/nxwm/defconfig b/configs/shenzhou/nxwm/defconfig
index e3b6e5d788..ecab569fe4 100644
--- a/configs/shenzhou/nxwm/defconfig
+++ b/configs/shenzhou/nxwm/defconfig
@@ -888,7 +888,6 @@ CONFIG_ETH0_PHY_DM9161=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/shenzhou/thttpd/defconfig b/configs/shenzhou/thttpd/defconfig
index f246239d2f..fcd1ac4074 100644
--- a/configs/shenzhou/thttpd/defconfig
+++ b/configs/shenzhou/thttpd/defconfig
@@ -855,7 +855,6 @@ CONFIG_DEV_FIFO_SIZE=1024
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/sim/bas/defconfig b/configs/sim/bas/defconfig
index 9b11ad5947..71c6bf6659 100644
--- a/configs/sim/bas/defconfig
+++ b/configs/sim/bas/defconfig
@@ -298,7 +298,6 @@ CONFIG_DEV_NULL=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_16550_UART is not set
diff --git a/configs/sim/configdata/defconfig b/configs/sim/configdata/defconfig
index 6a58a5c9e9..c46b145c61 100644
--- a/configs/sim/configdata/defconfig
+++ b/configs/sim/configdata/defconfig
@@ -327,7 +327,6 @@ CONFIG_RAMMTD_FLASHSIM=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/sim/cxxtest/defconfig b/configs/sim/cxxtest/defconfig
index 7ecdc39504..de26a571ac 100644
--- a/configs/sim/cxxtest/defconfig
+++ b/configs/sim/cxxtest/defconfig
@@ -315,7 +315,6 @@ CONFIG_DEV_NULL=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/sim/minibasic/defconfig b/configs/sim/minibasic/defconfig
index b7a6e11eae..edeba61d18 100644
--- a/configs/sim/minibasic/defconfig
+++ b/configs/sim/minibasic/defconfig
@@ -352,7 +352,6 @@ CONFIG_DEV_LOOP=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/sim/mount/defconfig b/configs/sim/mount/defconfig
index 14234058c0..9af8bfff48 100644
--- a/configs/sim/mount/defconfig
+++ b/configs/sim/mount/defconfig
@@ -314,7 +314,6 @@ CONFIG_DEV_NULL=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/sim/mtdpart/defconfig b/configs/sim/mtdpart/defconfig
index a9e8cb82f9..b594447333 100644
--- a/configs/sim/mtdpart/defconfig
+++ b/configs/sim/mtdpart/defconfig
@@ -325,7 +325,6 @@ CONFIG_RAMMTD_FLASHSIM=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/sim/mtdrwb/defconfig b/configs/sim/mtdrwb/defconfig
index 4a24af5075..3716ffcb22 100644
--- a/configs/sim/mtdrwb/defconfig
+++ b/configs/sim/mtdrwb/defconfig
@@ -357,7 +357,6 @@ CONFIG_RAMMTD_FLASHSIM=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/sim/nettest/defconfig b/configs/sim/nettest/defconfig
index 7bce3f6cb1..09df2684d6 100644
--- a/configs/sim/nettest/defconfig
+++ b/configs/sim/nettest/defconfig
@@ -327,7 +327,6 @@ CONFIG_DEV_NULL=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/sim/nsh/defconfig b/configs/sim/nsh/defconfig
index b7b881c136..26c5503422 100644
--- a/configs/sim/nsh/defconfig
+++ b/configs/sim/nsh/defconfig
@@ -334,7 +334,6 @@ CONFIG_DEV_LOOP=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/sim/nsh2/defconfig b/configs/sim/nsh2/defconfig
index 320355597b..3101ea4785 100644
--- a/configs/sim/nsh2/defconfig
+++ b/configs/sim/nsh2/defconfig
@@ -343,7 +343,6 @@ CONFIG_INPUT=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/sim/nx/defconfig b/configs/sim/nx/defconfig
index b205eadbdc..c596a93fa5 100644
--- a/configs/sim/nx/defconfig
+++ b/configs/sim/nx/defconfig
@@ -329,7 +329,6 @@ CONFIG_DEV_NULL=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/sim/nx11/defconfig b/configs/sim/nx11/defconfig
index d845ca9349..f6c56ac9ae 100644
--- a/configs/sim/nx11/defconfig
+++ b/configs/sim/nx11/defconfig
@@ -330,7 +330,6 @@ CONFIG_DEV_NULL=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/sim/nxffs/defconfig b/configs/sim/nxffs/defconfig
index fb1252ac6e..fb70a4df9b 100644
--- a/configs/sim/nxffs/defconfig
+++ b/configs/sim/nxffs/defconfig
@@ -296,7 +296,6 @@ CONFIG_RAMMTD_FLASHSIM=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_16550_UART is not set
diff --git a/configs/sim/nxlines/defconfig b/configs/sim/nxlines/defconfig
index 9b82cf3586..c80c0efaa9 100644
--- a/configs/sim/nxlines/defconfig
+++ b/configs/sim/nxlines/defconfig
@@ -305,7 +305,6 @@ CONFIG_DEV_NULL=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_16550_UART is not set
diff --git a/configs/sim/nxwm/defconfig b/configs/sim/nxwm/defconfig
index ab478684c3..0748c0164f 100644
--- a/configs/sim/nxwm/defconfig
+++ b/configs/sim/nxwm/defconfig
@@ -341,7 +341,6 @@ CONFIG_DEV_NULL=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/sim/ostest/defconfig b/configs/sim/ostest/defconfig
index 089a488da3..e3570e0481 100644
--- a/configs/sim/ostest/defconfig
+++ b/configs/sim/ostest/defconfig
@@ -327,7 +327,6 @@ CONFIG_DEV_NULL=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/sim/pashello/defconfig b/configs/sim/pashello/defconfig
index ad3b274ceb..b64438c27e 100644
--- a/configs/sim/pashello/defconfig
+++ b/configs/sim/pashello/defconfig
@@ -288,7 +288,6 @@ CONFIG_DEV_NULL=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_16550_UART is not set
diff --git a/configs/sim/touchscreen/defconfig b/configs/sim/touchscreen/defconfig
index e5427ff736..66e90503f5 100644
--- a/configs/sim/touchscreen/defconfig
+++ b/configs/sim/touchscreen/defconfig
@@ -338,7 +338,6 @@ CONFIG_INPUT=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/sim/traveler/defconfig b/configs/sim/traveler/defconfig
index 14f3aa4719..3a6a75c03c 100644
--- a/configs/sim/traveler/defconfig
+++ b/configs/sim/traveler/defconfig
@@ -344,7 +344,6 @@ CONFIG_AJOYSTICK=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/sim/udgram/defconfig b/configs/sim/udgram/defconfig
index 6a41938192..856d330290 100644
--- a/configs/sim/udgram/defconfig
+++ b/configs/sim/udgram/defconfig
@@ -339,7 +339,6 @@ CONFIG_DEV_FIFO_SIZE=1024
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/sim/unionfs/defconfig b/configs/sim/unionfs/defconfig
index 77da0ebc32..0fea09b8d3 100644
--- a/configs/sim/unionfs/defconfig
+++ b/configs/sim/unionfs/defconfig
@@ -298,7 +298,6 @@ CONFIG_DEV_NULL=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_16550_UART is not set
diff --git a/configs/sim/ustream/defconfig b/configs/sim/ustream/defconfig
index b61d8b04a7..e356f4bbac 100644
--- a/configs/sim/ustream/defconfig
+++ b/configs/sim/ustream/defconfig
@@ -339,7 +339,6 @@ CONFIG_DEV_FIFO_SIZE=1024
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/skp16c26/ostest/defconfig b/configs/skp16c26/ostest/defconfig
index b46a95b90d..61814e3a1c 100644
--- a/configs/skp16c26/ostest/defconfig
+++ b/configs/skp16c26/ostest/defconfig
@@ -253,7 +253,6 @@ CONFIG_LCD_LANDSCAPE=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
CONFIG_DEV_LOWCONSOLE=y
# CONFIG_16550_UART is not set
diff --git a/configs/spark/composite/defconfig b/configs/spark/composite/defconfig
index 99da95b423..d192166cef 100644
--- a/configs/spark/composite/defconfig
+++ b/configs/spark/composite/defconfig
@@ -773,7 +773,6 @@ CONFIG_SST25_SECTOR512=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
CONFIG_SERIAL_REMOVABLE=y
diff --git a/configs/spark/nsh/defconfig b/configs/spark/nsh/defconfig
index c86b4a81bb..5f8d3daac6 100644
--- a/configs/spark/nsh/defconfig
+++ b/configs/spark/nsh/defconfig
@@ -773,7 +773,6 @@ CONFIG_SST25_SECTOR512=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
CONFIG_SERIAL_REMOVABLE=y
diff --git a/configs/spark/usbmsc/defconfig b/configs/spark/usbmsc/defconfig
index aede0e5bd1..dfd2fda659 100644
--- a/configs/spark/usbmsc/defconfig
+++ b/configs/spark/usbmsc/defconfig
@@ -773,7 +773,6 @@ CONFIG_SST25_SECTOR512=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/spark/usbnsh/defconfig b/configs/spark/usbnsh/defconfig
index bd658acc0f..9af591a0f5 100644
--- a/configs/spark/usbnsh/defconfig
+++ b/configs/spark/usbnsh/defconfig
@@ -774,7 +774,6 @@ CONFIG_SST25_SPIFREQUENCY=20000000
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
CONFIG_SERIAL_REMOVABLE=y
# CONFIG_SERIAL_CONSOLE is not set
diff --git a/configs/spark/usbserial/defconfig b/configs/spark/usbserial/defconfig
index cf1548ef7d..2bbed930a3 100644
--- a/configs/spark/usbserial/defconfig
+++ b/configs/spark/usbserial/defconfig
@@ -778,7 +778,6 @@ CONFIG_SST25_SECTOR512=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
CONFIG_SERIAL_REMOVABLE=y
diff --git a/configs/stm3210e-eval/composite/defconfig b/configs/stm3210e-eval/composite/defconfig
index e86878eb0b..0d9c189726 100644
--- a/configs/stm3210e-eval/composite/defconfig
+++ b/configs/stm3210e-eval/composite/defconfig
@@ -801,7 +801,6 @@ CONFIG_MTD=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
CONFIG_SERIAL_REMOVABLE=y
diff --git a/configs/stm3210e-eval/nsh/defconfig b/configs/stm3210e-eval/nsh/defconfig
index 9cd76a6fcf..6e963ddd3d 100644
--- a/configs/stm3210e-eval/nsh/defconfig
+++ b/configs/stm3210e-eval/nsh/defconfig
@@ -802,7 +802,6 @@ CONFIG_MTD=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/stm3210e-eval/nsh2/defconfig b/configs/stm3210e-eval/nsh2/defconfig
index ed2f9de53a..22a4433f22 100644
--- a/configs/stm3210e-eval/nsh2/defconfig
+++ b/configs/stm3210e-eval/nsh2/defconfig
@@ -855,7 +855,6 @@ CONFIG_MTD=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/stm3210e-eval/nx/defconfig b/configs/stm3210e-eval/nx/defconfig
index 515abea738..d7eb099f52 100644
--- a/configs/stm3210e-eval/nx/defconfig
+++ b/configs/stm3210e-eval/nx/defconfig
@@ -793,7 +793,6 @@ CONFIG_LCD_RPORTRAIT=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
CONFIG_DEV_LOWCONSOLE=y
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/stm3210e-eval/nxterm/defconfig b/configs/stm3210e-eval/nxterm/defconfig
index f8b261f023..ffb7dc3e2d 100644
--- a/configs/stm3210e-eval/nxterm/defconfig
+++ b/configs/stm3210e-eval/nxterm/defconfig
@@ -786,7 +786,6 @@ CONFIG_LCD_LANDSCAPE=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/stm3210e-eval/pm/defconfig b/configs/stm3210e-eval/pm/defconfig
index 2ea8dc6299..aa84118fb7 100644
--- a/configs/stm3210e-eval/pm/defconfig
+++ b/configs/stm3210e-eval/pm/defconfig
@@ -828,7 +828,6 @@ CONFIG_PM_SLEEPEXIT_THRESH=2
CONFIG_PM_SLEEPENTER_COUNT=70
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/stm3210e-eval/usbmsc/defconfig b/configs/stm3210e-eval/usbmsc/defconfig
index 5afafd6fe6..988055ebab 100644
--- a/configs/stm3210e-eval/usbmsc/defconfig
+++ b/configs/stm3210e-eval/usbmsc/defconfig
@@ -763,7 +763,6 @@ CONFIG_SDIO_PREFLIGHT=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/stm3210e-eval/usbserial/defconfig b/configs/stm3210e-eval/usbserial/defconfig
index db0f50e033..d6cd26bde2 100644
--- a/configs/stm3210e-eval/usbserial/defconfig
+++ b/configs/stm3210e-eval/usbserial/defconfig
@@ -738,7 +738,6 @@ CONFIG_ARCH_HAVE_SPI_BITORDER=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
CONFIG_SERIAL_REMOVABLE=y
diff --git a/configs/stm3220g-eval/dhcpd/defconfig b/configs/stm3220g-eval/dhcpd/defconfig
index 6c75dfc4de..79a0512054 100644
--- a/configs/stm3220g-eval/dhcpd/defconfig
+++ b/configs/stm3220g-eval/dhcpd/defconfig
@@ -799,7 +799,6 @@ CONFIG_ETH0_PHY_DP83848C=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/stm3220g-eval/nettest/defconfig b/configs/stm3220g-eval/nettest/defconfig
index cd5e76b2e9..41df74c759 100644
--- a/configs/stm3220g-eval/nettest/defconfig
+++ b/configs/stm3220g-eval/nettest/defconfig
@@ -800,7 +800,6 @@ CONFIG_ETH0_PHY_DP83848C=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
CONFIG_DEV_LOWCONSOLE=y
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/stm3220g-eval/nsh/defconfig b/configs/stm3220g-eval/nsh/defconfig
index 0bf15bd471..29cbdf4d71 100644
--- a/configs/stm3220g-eval/nsh/defconfig
+++ b/configs/stm3220g-eval/nsh/defconfig
@@ -866,7 +866,6 @@ CONFIG_ETH0_PHY_DP83848C=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/stm3220g-eval/nsh2/defconfig b/configs/stm3220g-eval/nsh2/defconfig
index 756d46ec97..277d815547 100644
--- a/configs/stm3220g-eval/nsh2/defconfig
+++ b/configs/stm3220g-eval/nsh2/defconfig
@@ -873,7 +873,6 @@ CONFIG_ETH0_PHY_DP83848C=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_SERIAL_REMOVABLE is not set
# CONFIG_SERIAL_CONSOLE is not set
diff --git a/configs/stm3220g-eval/nxwm/defconfig b/configs/stm3220g-eval/nxwm/defconfig
index 00be7789aa..70f3be0871 100644
--- a/configs/stm3220g-eval/nxwm/defconfig
+++ b/configs/stm3220g-eval/nxwm/defconfig
@@ -909,7 +909,6 @@ CONFIG_ETH0_PHY_DP83848C=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/stm3220g-eval/telnetd/defconfig b/configs/stm3220g-eval/telnetd/defconfig
index 8087eefa4c..c096d97f0e 100644
--- a/configs/stm3220g-eval/telnetd/defconfig
+++ b/configs/stm3220g-eval/telnetd/defconfig
@@ -802,7 +802,6 @@ CONFIG_ETH0_PHY_DP83848C=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
CONFIG_DEV_LOWCONSOLE=y
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/stm3240g-eval/dhcpd/defconfig b/configs/stm3240g-eval/dhcpd/defconfig
index e853770ca0..9144444845 100644
--- a/configs/stm3240g-eval/dhcpd/defconfig
+++ b/configs/stm3240g-eval/dhcpd/defconfig
@@ -803,7 +803,6 @@ CONFIG_ETH0_PHY_DP83848C=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/stm3240g-eval/discover/defconfig b/configs/stm3240g-eval/discover/defconfig
index 3173ed20d7..f51ac02cc1 100644
--- a/configs/stm3240g-eval/discover/defconfig
+++ b/configs/stm3240g-eval/discover/defconfig
@@ -826,7 +826,6 @@ CONFIG_ETH0_PHY_DP83848C=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/stm3240g-eval/knxwm/defconfig b/configs/stm3240g-eval/knxwm/defconfig
index c5d466cc75..55af319147 100644
--- a/configs/stm3240g-eval/knxwm/defconfig
+++ b/configs/stm3240g-eval/knxwm/defconfig
@@ -857,7 +857,6 @@ CONFIG_LCD_LANDSCAPE=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/stm3240g-eval/nettest/defconfig b/configs/stm3240g-eval/nettest/defconfig
index ee8324e9d5..6ada351475 100644
--- a/configs/stm3240g-eval/nettest/defconfig
+++ b/configs/stm3240g-eval/nettest/defconfig
@@ -804,7 +804,6 @@ CONFIG_ETH0_PHY_DP83848C=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
CONFIG_DEV_LOWCONSOLE=y
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/stm3240g-eval/nsh/defconfig b/configs/stm3240g-eval/nsh/defconfig
index 0215da9426..52a2e2b6ae 100644
--- a/configs/stm3240g-eval/nsh/defconfig
+++ b/configs/stm3240g-eval/nsh/defconfig
@@ -844,7 +844,6 @@ CONFIG_ETH0_PHY_DP83848C=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/stm3240g-eval/nsh2/defconfig b/configs/stm3240g-eval/nsh2/defconfig
index 47b77ad25e..e9d10d9490 100644
--- a/configs/stm3240g-eval/nsh2/defconfig
+++ b/configs/stm3240g-eval/nsh2/defconfig
@@ -877,7 +877,6 @@ CONFIG_ETH0_PHY_DP83848C=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_SERIAL_REMOVABLE is not set
# CONFIG_SERIAL_CONSOLE is not set
diff --git a/configs/stm3240g-eval/nxterm/defconfig b/configs/stm3240g-eval/nxterm/defconfig
index c8fa345a86..a83753f652 100644
--- a/configs/stm3240g-eval/nxterm/defconfig
+++ b/configs/stm3240g-eval/nxterm/defconfig
@@ -883,7 +883,6 @@ CONFIG_ETH0_PHY_DP83848C=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/stm3240g-eval/nxwm/defconfig b/configs/stm3240g-eval/nxwm/defconfig
index c1e7c78384..f57abc9254 100644
--- a/configs/stm3240g-eval/nxwm/defconfig
+++ b/configs/stm3240g-eval/nxwm/defconfig
@@ -906,7 +906,6 @@ CONFIG_ETH0_PHY_NONE=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/stm3240g-eval/telnetd/defconfig b/configs/stm3240g-eval/telnetd/defconfig
index afccc0581a..23d37a3970 100644
--- a/configs/stm3240g-eval/telnetd/defconfig
+++ b/configs/stm3240g-eval/telnetd/defconfig
@@ -806,7 +806,6 @@ CONFIG_ETH0_PHY_DP83848C=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
CONFIG_DEV_LOWCONSOLE=y
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/stm3240g-eval/webserver/defconfig b/configs/stm3240g-eval/webserver/defconfig
index fc5f38129e..98c8514caf 100644
--- a/configs/stm3240g-eval/webserver/defconfig
+++ b/configs/stm3240g-eval/webserver/defconfig
@@ -865,7 +865,6 @@ CONFIG_ETH0_PHY_NONE=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/stm3240g-eval/xmlrpc/defconfig b/configs/stm3240g-eval/xmlrpc/defconfig
index 691149e1cd..c305c0cc18 100644
--- a/configs/stm3240g-eval/xmlrpc/defconfig
+++ b/configs/stm3240g-eval/xmlrpc/defconfig
@@ -821,7 +821,6 @@ CONFIG_ETH0_PHY_DP83848C=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/stm32_tiny/nsh/defconfig b/configs/stm32_tiny/nsh/defconfig
index 7c96533b6e..4c75ba7ed6 100644
--- a/configs/stm32_tiny/nsh/defconfig
+++ b/configs/stm32_tiny/nsh/defconfig
@@ -728,7 +728,6 @@ CONFIG_ARCH_HAVE_SPI_BITORDER=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/stm32_tiny/usbnsh/defconfig b/configs/stm32_tiny/usbnsh/defconfig
index 8a254501e2..ddc34f64d2 100644
--- a/configs/stm32_tiny/usbnsh/defconfig
+++ b/configs/stm32_tiny/usbnsh/defconfig
@@ -706,7 +706,6 @@ CONFIG_ARCH_HAVE_SPI_BITORDER=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
CONFIG_SERIAL_REMOVABLE=y
CONFIG_SERIAL_CONSOLE=y
diff --git a/configs/stm32butterfly2/nsh/defconfig b/configs/stm32butterfly2/nsh/defconfig
index c738c08de3..ed2275d4a7 100644
--- a/configs/stm32butterfly2/nsh/defconfig
+++ b/configs/stm32butterfly2/nsh/defconfig
@@ -777,7 +777,6 @@ CONFIG_MMCSD_SPIMODE=0
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/stm32butterfly2/nshnet/defconfig b/configs/stm32butterfly2/nshnet/defconfig
index 3804ac4ff0..43d0054ecd 100644
--- a/configs/stm32butterfly2/nshnet/defconfig
+++ b/configs/stm32butterfly2/nshnet/defconfig
@@ -827,7 +827,6 @@ CONFIG_DEV_FIFO_SIZE=1024
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
CONFIG_SERIAL_REMOVABLE=y
diff --git a/configs/stm32butterfly2/nshusbdev/defconfig b/configs/stm32butterfly2/nshusbdev/defconfig
index 2a27dfaed9..602e063375 100644
--- a/configs/stm32butterfly2/nshusbdev/defconfig
+++ b/configs/stm32butterfly2/nshusbdev/defconfig
@@ -770,7 +770,6 @@ CONFIG_MMCSD_SPIMODE=0
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
CONFIG_SERIAL_REMOVABLE=y
diff --git a/configs/stm32butterfly2/nshusbhost/defconfig b/configs/stm32butterfly2/nshusbhost/defconfig
index c738c08de3..ed2275d4a7 100644
--- a/configs/stm32butterfly2/nshusbhost/defconfig
+++ b/configs/stm32butterfly2/nshusbhost/defconfig
@@ -777,7 +777,6 @@ CONFIG_MMCSD_SPIMODE=0
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/stm32f103-minimum/audio_tone/defconfig b/configs/stm32f103-minimum/audio_tone/defconfig
index 086dad19f5..993a61286b 100644
--- a/configs/stm32f103-minimum/audio_tone/defconfig
+++ b/configs/stm32f103-minimum/audio_tone/defconfig
@@ -729,7 +729,6 @@ CONFIG_AUDIO_TONE=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/stm32f103-minimum/buttons/defconfig b/configs/stm32f103-minimum/buttons/defconfig
index e5fccea096..a37eab30f7 100644
--- a/configs/stm32f103-minimum/buttons/defconfig
+++ b/configs/stm32f103-minimum/buttons/defconfig
@@ -726,7 +726,6 @@ CONFIG_BUTTONS_NPOLLWAITERS=2
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/stm32f103-minimum/jlx12864g/defconfig b/configs/stm32f103-minimum/jlx12864g/defconfig
index 09a91ef88d..b9ff3e625f 100644
--- a/configs/stm32f103-minimum/jlx12864g/defconfig
+++ b/configs/stm32f103-minimum/jlx12864g/defconfig
@@ -815,7 +815,6 @@ CONFIG_LCD_LANDSCAPE=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/stm32f103-minimum/nsh/defconfig b/configs/stm32f103-minimum/nsh/defconfig
index f2ce954678..f7f96edde2 100644
--- a/configs/stm32f103-minimum/nsh/defconfig
+++ b/configs/stm32f103-minimum/nsh/defconfig
@@ -709,7 +709,6 @@ CONFIG_ARCH_HAVE_SPI_BITORDER=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/stm32f103-minimum/pwm/defconfig b/configs/stm32f103-minimum/pwm/defconfig
index 021a9fcbd3..5c851766af 100644
--- a/configs/stm32f103-minimum/pwm/defconfig
+++ b/configs/stm32f103-minimum/pwm/defconfig
@@ -723,7 +723,6 @@ CONFIG_ARCH_HAVE_SPI_BITORDER=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/stm32f103-minimum/rfid-rc522/defconfig b/configs/stm32f103-minimum/rfid-rc522/defconfig
index 03e471615c..13b50d89fc 100644
--- a/configs/stm32f103-minimum/rfid-rc522/defconfig
+++ b/configs/stm32f103-minimum/rfid-rc522/defconfig
@@ -729,7 +729,6 @@ CONFIG_ARCH_HAVE_SPI_BITORDER=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/stm32f103-minimum/rgbled/defconfig b/configs/stm32f103-minimum/rgbled/defconfig
index f236ee1a63..19ef7948ef 100644
--- a/configs/stm32f103-minimum/rgbled/defconfig
+++ b/configs/stm32f103-minimum/rgbled/defconfig
@@ -750,7 +750,6 @@ CONFIG_RGBLED=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/stm32f103-minimum/usbnsh/defconfig b/configs/stm32f103-minimum/usbnsh/defconfig
index 6015311697..5425732ae1 100644
--- a/configs/stm32f103-minimum/usbnsh/defconfig
+++ b/configs/stm32f103-minimum/usbnsh/defconfig
@@ -706,7 +706,6 @@ CONFIG_ARCH_HAVE_SPI_BITORDER=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
CONFIG_SERIAL_REMOVABLE=y
CONFIG_SERIAL_CONSOLE=y
diff --git a/configs/stm32f103-minimum/userled/defconfig b/configs/stm32f103-minimum/userled/defconfig
index fd0a0a857b..ba69602cc6 100644
--- a/configs/stm32f103-minimum/userled/defconfig
+++ b/configs/stm32f103-minimum/userled/defconfig
@@ -712,7 +712,6 @@ CONFIG_USERLED_LOWER=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/stm32f103-minimum/veml6070/defconfig b/configs/stm32f103-minimum/veml6070/defconfig
index 7ef17b58be..2c73508f80 100644
--- a/configs/stm32f103-minimum/veml6070/defconfig
+++ b/configs/stm32f103-minimum/veml6070/defconfig
@@ -768,7 +768,6 @@ CONFIG_MS58XX_VDD=30
CONFIG_VEML6070=y
# CONFIG_XEN1210 is not set
# CONFIG_ZEROCROSS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/stm32f3discovery/nsh/defconfig b/configs/stm32f3discovery/nsh/defconfig
index f0acc39483..0a4c3b350d 100644
--- a/configs/stm32f3discovery/nsh/defconfig
+++ b/configs/stm32f3discovery/nsh/defconfig
@@ -727,7 +727,6 @@ CONFIG_ARCH_HAVE_SPI_BITORDER=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
CONFIG_SERIAL_REMOVABLE=y
diff --git a/configs/stm32f3discovery/usbnsh/defconfig b/configs/stm32f3discovery/usbnsh/defconfig
index 9da62c72fd..265bb26eeb 100644
--- a/configs/stm32f3discovery/usbnsh/defconfig
+++ b/configs/stm32f3discovery/usbnsh/defconfig
@@ -745,7 +745,6 @@ CONFIG_ARCH_HAVE_SPI_BITORDER=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
CONFIG_SERIAL_REMOVABLE=y
# CONFIG_SERIAL_CONSOLE is not set
diff --git a/configs/stm32f411e-disco/nsh/defconfig b/configs/stm32f411e-disco/nsh/defconfig
index 6124f39735..16b329ad85 100644
--- a/configs/stm32f411e-disco/nsh/defconfig
+++ b/configs/stm32f411e-disco/nsh/defconfig
@@ -708,7 +708,6 @@ CONFIG_ARCH_HAVE_SPI_BITORDER=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/stm32f429i-disco/extflash/defconfig b/configs/stm32f429i-disco/extflash/defconfig
index b1661bf394..5d05d32227 100644
--- a/configs/stm32f429i-disco/extflash/defconfig
+++ b/configs/stm32f429i-disco/extflash/defconfig
@@ -826,7 +826,6 @@ CONFIG_SST25XX_MEMORY_TYPE=0x25
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/stm32f429i-disco/lcd/defconfig b/configs/stm32f429i-disco/lcd/defconfig
index b799f6048d..49d8da93fc 100644
--- a/configs/stm32f429i-disco/lcd/defconfig
+++ b/configs/stm32f429i-disco/lcd/defconfig
@@ -806,7 +806,6 @@ CONFIG_LCD_ILI9341_IFACE0_RGB565=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/stm32f429i-disco/ltdc/defconfig b/configs/stm32f429i-disco/ltdc/defconfig
index 2f398c0057..087b0b89ca 100644
--- a/configs/stm32f429i-disco/ltdc/defconfig
+++ b/configs/stm32f429i-disco/ltdc/defconfig
@@ -823,7 +823,6 @@ CONFIG_SPI_CMDDATA=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/stm32f429i-disco/nsh/defconfig b/configs/stm32f429i-disco/nsh/defconfig
index 2d15d01d64..90fa62e4f7 100644
--- a/configs/stm32f429i-disco/nsh/defconfig
+++ b/configs/stm32f429i-disco/nsh/defconfig
@@ -755,7 +755,6 @@ CONFIG_ARCH_HAVE_SPI_BITORDER=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/stm32f429i-disco/usbmsc/defconfig b/configs/stm32f429i-disco/usbmsc/defconfig
index 6ef99c00e0..8f1fbb5583 100644
--- a/configs/stm32f429i-disco/usbmsc/defconfig
+++ b/configs/stm32f429i-disco/usbmsc/defconfig
@@ -775,7 +775,6 @@ CONFIG_ARCH_HAVE_SPI_BITORDER=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/stm32f429i-disco/usbnsh/defconfig b/configs/stm32f429i-disco/usbnsh/defconfig
index aa93f546d1..99cfa1b985 100644
--- a/configs/stm32f429i-disco/usbnsh/defconfig
+++ b/configs/stm32f429i-disco/usbnsh/defconfig
@@ -761,7 +761,6 @@ CONFIG_ARCH_HAVE_SPI_BITORDER=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
CONFIG_SERIAL_REMOVABLE=y
# CONFIG_SERIAL_CONSOLE is not set
diff --git a/configs/stm32f4discovery/canard/defconfig b/configs/stm32f4discovery/canard/defconfig
index 339029f3dc..606f95268c 100644
--- a/configs/stm32f4discovery/canard/defconfig
+++ b/configs/stm32f4discovery/canard/defconfig
@@ -777,7 +777,6 @@ CONFIG_ARCH_HAVE_SPI_BITORDER=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/stm32f4discovery/cxxtest/defconfig b/configs/stm32f4discovery/cxxtest/defconfig
index fe76de0ff3..47aa9ad471 100644
--- a/configs/stm32f4discovery/cxxtest/defconfig
+++ b/configs/stm32f4discovery/cxxtest/defconfig
@@ -746,7 +746,6 @@ CONFIG_ARCH_HAVE_SPI_BITORDER=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/stm32f4discovery/elf/defconfig b/configs/stm32f4discovery/elf/defconfig
index e2152eff65..a7acd95315 100644
--- a/configs/stm32f4discovery/elf/defconfig
+++ b/configs/stm32f4discovery/elf/defconfig
@@ -746,7 +746,6 @@ CONFIG_ARCH_HAVE_SPI_BITORDER=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
CONFIG_DEV_LOWCONSOLE=y
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/stm32f4discovery/ipv6/defconfig b/configs/stm32f4discovery/ipv6/defconfig
index 6b6a5021fd..964ec83c84 100644
--- a/configs/stm32f4discovery/ipv6/defconfig
+++ b/configs/stm32f4discovery/ipv6/defconfig
@@ -866,7 +866,6 @@ CONFIG_ETH0_PHY_LAN8720=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/stm32f4discovery/kostest/defconfig b/configs/stm32f4discovery/kostest/defconfig
index d0568bac6c..e48549911f 100644
--- a/configs/stm32f4discovery/kostest/defconfig
+++ b/configs/stm32f4discovery/kostest/defconfig
@@ -754,7 +754,6 @@ CONFIG_ARCH_HAVE_SPI_BITORDER=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
CONFIG_DEV_LOWCONSOLE=y
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/stm32f4discovery/netnsh/defconfig b/configs/stm32f4discovery/netnsh/defconfig
index 93c015c220..7798def2d6 100644
--- a/configs/stm32f4discovery/netnsh/defconfig
+++ b/configs/stm32f4discovery/netnsh/defconfig
@@ -868,7 +868,6 @@ CONFIG_ETH0_PHY_LAN8720=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/stm32f4discovery/nsh/defconfig b/configs/stm32f4discovery/nsh/defconfig
index 45b4d516bd..ad989a0384 100644
--- a/configs/stm32f4discovery/nsh/defconfig
+++ b/configs/stm32f4discovery/nsh/defconfig
@@ -764,7 +764,6 @@ CONFIG_ARCH_HAVE_SPI_BITORDER=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/stm32f4discovery/nxlines/defconfig b/configs/stm32f4discovery/nxlines/defconfig
index 6d0afb67cf..3ea55af740 100644
--- a/configs/stm32f4discovery/nxlines/defconfig
+++ b/configs/stm32f4discovery/nxlines/defconfig
@@ -799,7 +799,6 @@ CONFIG_LCD_LANDSCAPE=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/stm32f4discovery/pm/defconfig b/configs/stm32f4discovery/pm/defconfig
index 23611818a5..9d31f4d16c 100644
--- a/configs/stm32f4discovery/pm/defconfig
+++ b/configs/stm32f4discovery/pm/defconfig
@@ -785,7 +785,6 @@ CONFIG_PM_SLEEPEXIT_THRESH=2
CONFIG_PM_SLEEPENTER_COUNT=70
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/stm32f4discovery/posix_spawn/defconfig b/configs/stm32f4discovery/posix_spawn/defconfig
index 0b50120eef..6244ecf5de 100644
--- a/configs/stm32f4discovery/posix_spawn/defconfig
+++ b/configs/stm32f4discovery/posix_spawn/defconfig
@@ -746,7 +746,6 @@ CONFIG_ARCH_HAVE_SPI_BITORDER=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
CONFIG_DEV_LOWCONSOLE=y
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/stm32f4discovery/pseudoterm/defconfig b/configs/stm32f4discovery/pseudoterm/defconfig
index bf893357b4..2e888aa40d 100644
--- a/configs/stm32f4discovery/pseudoterm/defconfig
+++ b/configs/stm32f4discovery/pseudoterm/defconfig
@@ -764,7 +764,6 @@ CONFIG_DEV_FIFO_SIZE=1024
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/stm32f4discovery/rgbled/defconfig b/configs/stm32f4discovery/rgbled/defconfig
index cbdcd8a62b..60d084552e 100644
--- a/configs/stm32f4discovery/rgbled/defconfig
+++ b/configs/stm32f4discovery/rgbled/defconfig
@@ -771,7 +771,6 @@ CONFIG_RGBLED=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/stm32f4discovery/uavcan/defconfig b/configs/stm32f4discovery/uavcan/defconfig
index 6b16317813..c80096bf72 100644
--- a/configs/stm32f4discovery/uavcan/defconfig
+++ b/configs/stm32f4discovery/uavcan/defconfig
@@ -716,7 +716,6 @@ CONFIG_ARCH_HAVE_SPI_BITORDER=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
# CONFIG_SERIAL is not set
# CONFIG_USBDEV is not set
# CONFIG_USBHOST is not set
diff --git a/configs/stm32f4discovery/usbnsh/defconfig b/configs/stm32f4discovery/usbnsh/defconfig
index f526a52b11..b6661f5d88 100644
--- a/configs/stm32f4discovery/usbnsh/defconfig
+++ b/configs/stm32f4discovery/usbnsh/defconfig
@@ -770,7 +770,6 @@ CONFIG_ARCH_HAVE_SPI_BITORDER=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
CONFIG_SERIAL_REMOVABLE=y
# CONFIG_SERIAL_CONSOLE is not set
diff --git a/configs/stm32f4discovery/winbuild/defconfig b/configs/stm32f4discovery/winbuild/defconfig
index 32a5be99c5..a5740592a5 100644
--- a/configs/stm32f4discovery/winbuild/defconfig
+++ b/configs/stm32f4discovery/winbuild/defconfig
@@ -652,7 +652,6 @@ CONFIG_ARCH_HAVE_I2CRESET=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
CONFIG_DEV_LOWCONSOLE=y
# CONFIG_16550_UART is not set
diff --git a/configs/stm32f4discovery/xen1210/defconfig b/configs/stm32f4discovery/xen1210/defconfig
index be43bc8716..076a4e5a03 100644
--- a/configs/stm32f4discovery/xen1210/defconfig
+++ b/configs/stm32f4discovery/xen1210/defconfig
@@ -801,7 +801,6 @@ CONFIG_MS58XX_VDD=30
# CONFIG_QENCODER is not set
CONFIG_XEN1210=y
# CONFIG_ZEROCROSS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/stm32f746-ws/nsh/defconfig b/configs/stm32f746-ws/nsh/defconfig
index c8b5d79c69..46aed04635 100644
--- a/configs/stm32f746-ws/nsh/defconfig
+++ b/configs/stm32f746-ws/nsh/defconfig
@@ -690,7 +690,6 @@ CONFIG_DEV_FIFO_SIZE=1024
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
CONFIG_SERIAL_REMOVABLE=y
diff --git a/configs/stm32f746g-disco/nsh/defconfig b/configs/stm32f746g-disco/nsh/defconfig
index aaf5ad642b..80155b308a 100644
--- a/configs/stm32f746g-disco/nsh/defconfig
+++ b/configs/stm32f746g-disco/nsh/defconfig
@@ -618,7 +618,6 @@ CONFIG_ARCH_HAVE_SPI_BITORDER=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/stm32l476-mdk/nsh/defconfig b/configs/stm32l476-mdk/nsh/defconfig
index bff1aace3e..57b5c9fd47 100644
--- a/configs/stm32l476-mdk/nsh/defconfig
+++ b/configs/stm32l476-mdk/nsh/defconfig
@@ -561,7 +561,6 @@ CONFIG_RTC_IOCTL=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/stm32l476vg-disco/nsh/defconfig b/configs/stm32l476vg-disco/nsh/defconfig
index a341d1ba39..a62de0776c 100644
--- a/configs/stm32l476vg-disco/nsh/defconfig
+++ b/configs/stm32l476vg-disco/nsh/defconfig
@@ -614,7 +614,6 @@ CONFIG_N25QXXX_SECTOR512=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/stm32ldiscovery/nsh/defconfig b/configs/stm32ldiscovery/nsh/defconfig
index ad496c0a98..af6dda6e9a 100644
--- a/configs/stm32ldiscovery/nsh/defconfig
+++ b/configs/stm32ldiscovery/nsh/defconfig
@@ -706,7 +706,6 @@ CONFIG_ARCH_HAVE_SPI_BITORDER=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/stm32vldiscovery/nsh/defconfig b/configs/stm32vldiscovery/nsh/defconfig
index ef516541c4..c7ca2ef2c5 100644
--- a/configs/stm32vldiscovery/nsh/defconfig
+++ b/configs/stm32vldiscovery/nsh/defconfig
@@ -724,7 +724,6 @@ CONFIG_RTC=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/sure-pic32mx/nsh/defconfig b/configs/sure-pic32mx/nsh/defconfig
index 6934ae6970..7cf509a7bf 100644
--- a/configs/sure-pic32mx/nsh/defconfig
+++ b/configs/sure-pic32mx/nsh/defconfig
@@ -506,7 +506,6 @@ CONFIG_DEV_NULL=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/sure-pic32mx/usbnsh/defconfig b/configs/sure-pic32mx/usbnsh/defconfig
index b5dd27d3ed..0a5838887e 100644
--- a/configs/sure-pic32mx/usbnsh/defconfig
+++ b/configs/sure-pic32mx/usbnsh/defconfig
@@ -508,7 +508,6 @@ CONFIG_DEV_NULL=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
CONFIG_SERIAL_REMOVABLE=y
# CONFIG_SERIAL_CONSOLE is not set
diff --git a/configs/teensy-2.0/hello/defconfig b/configs/teensy-2.0/hello/defconfig
index 410aba1b5c..cf6bd2ee38 100644
--- a/configs/teensy-2.0/hello/defconfig
+++ b/configs/teensy-2.0/hello/defconfig
@@ -300,7 +300,6 @@ CONFIG_DEV_NULL=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
CONFIG_DEV_LOWCONSOLE=y
# CONFIG_16550_UART is not set
diff --git a/configs/teensy-2.0/nsh/defconfig b/configs/teensy-2.0/nsh/defconfig
index 80afdf009b..a947d314ee 100644
--- a/configs/teensy-2.0/nsh/defconfig
+++ b/configs/teensy-2.0/nsh/defconfig
@@ -311,7 +311,6 @@ CONFIG_DEV_NULL=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_16550_UART is not set
diff --git a/configs/teensy-2.0/usbmsc/defconfig b/configs/teensy-2.0/usbmsc/defconfig
index 821868dc61..ed35a4ece2 100644
--- a/configs/teensy-2.0/usbmsc/defconfig
+++ b/configs/teensy-2.0/usbmsc/defconfig
@@ -333,7 +333,6 @@ CONFIG_MMCSD_SPIMODE=0
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
CONFIG_DEV_LOWCONSOLE=y
# CONFIG_16550_UART is not set
diff --git a/configs/teensy-3.x/nsh/defconfig b/configs/teensy-3.x/nsh/defconfig
index 2297c163a2..4712175377 100644
--- a/configs/teensy-3.x/nsh/defconfig
+++ b/configs/teensy-3.x/nsh/defconfig
@@ -478,7 +478,6 @@ CONFIG_SPI_EXCHANGE=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/teensy-3.x/usbnsh/defconfig b/configs/teensy-3.x/usbnsh/defconfig
index 55c2e4509b..8b71905cff 100644
--- a/configs/teensy-3.x/usbnsh/defconfig
+++ b/configs/teensy-3.x/usbnsh/defconfig
@@ -478,7 +478,6 @@ CONFIG_SPI_EXCHANGE=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
CONFIG_SERIAL_REMOVABLE=y
diff --git a/configs/teensy-lc/nsh/defconfig b/configs/teensy-lc/nsh/defconfig
index 0b235d0dee..e3e77e208a 100644
--- a/configs/teensy-lc/nsh/defconfig
+++ b/configs/teensy-lc/nsh/defconfig
@@ -441,7 +441,6 @@ CONFIG_SPI_EXCHANGE=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/tm4c123g-launchpad/nsh/defconfig b/configs/tm4c123g-launchpad/nsh/defconfig
index 6cbee2ee05..12288ccbfc 100644
--- a/configs/tm4c123g-launchpad/nsh/defconfig
+++ b/configs/tm4c123g-launchpad/nsh/defconfig
@@ -499,7 +499,6 @@ CONFIG_DEV_NULL=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/tm4c1294-launchpad/ipv6/defconfig b/configs/tm4c1294-launchpad/ipv6/defconfig
index 075d74bce2..f016e962aa 100644
--- a/configs/tm4c1294-launchpad/ipv6/defconfig
+++ b/configs/tm4c1294-launchpad/ipv6/defconfig
@@ -560,7 +560,6 @@ CONFIG_ARCH_PHY_INTERRUPT=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/tm4c1294-launchpad/nsh/defconfig b/configs/tm4c1294-launchpad/nsh/defconfig
index d2efadd53b..3c4bcce6eb 100644
--- a/configs/tm4c1294-launchpad/nsh/defconfig
+++ b/configs/tm4c1294-launchpad/nsh/defconfig
@@ -562,7 +562,6 @@ CONFIG_ARCH_PHY_INTERRUPT=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/twr-k60n512/nsh/defconfig b/configs/twr-k60n512/nsh/defconfig
index b6d1a57df0..ddafbe24e9 100644
--- a/configs/twr-k60n512/nsh/defconfig
+++ b/configs/twr-k60n512/nsh/defconfig
@@ -465,7 +465,6 @@ CONFIG_DEV_NULL=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/u-blox-c027/nsh/defconfig b/configs/u-blox-c027/nsh/defconfig
index 022c5eec52..b1ca48a213 100644
--- a/configs/u-blox-c027/nsh/defconfig
+++ b/configs/u-blox-c027/nsh/defconfig
@@ -555,7 +555,6 @@ CONFIG_ETH1_PHY_NONE=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/ubw32/nsh/defconfig b/configs/ubw32/nsh/defconfig
index 59dee9b713..91b77cebc8 100644
--- a/configs/ubw32/nsh/defconfig
+++ b/configs/ubw32/nsh/defconfig
@@ -512,7 +512,6 @@ CONFIG_MMCSD_NSLOTS=1
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/us7032evb1/nsh/defconfig b/configs/us7032evb1/nsh/defconfig
index d8e8df8334..e64dc02107 100644
--- a/configs/us7032evb1/nsh/defconfig
+++ b/configs/us7032evb1/nsh/defconfig
@@ -238,7 +238,6 @@ CONFIG_DEV_NULL=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_16550_UART is not set
diff --git a/configs/us7032evb1/ostest/defconfig b/configs/us7032evb1/ostest/defconfig
index 1beac7ba05..0c196b33de 100644
--- a/configs/us7032evb1/ostest/defconfig
+++ b/configs/us7032evb1/ostest/defconfig
@@ -237,7 +237,6 @@ CONFIG_DEV_NULL=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
CONFIG_DEV_LOWCONSOLE=y
# CONFIG_16550_UART is not set
diff --git a/configs/viewtool-stm32f107/highpri/defconfig b/configs/viewtool-stm32f107/highpri/defconfig
index fc3a34b4d9..23206b58e0 100644
--- a/configs/viewtool-stm32f107/highpri/defconfig
+++ b/configs/viewtool-stm32f107/highpri/defconfig
@@ -737,7 +737,6 @@ CONFIG_ARCH_HAVE_SPI_BITORDER=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/viewtool-stm32f107/netnsh/defconfig b/configs/viewtool-stm32f107/netnsh/defconfig
index 5a0e0bb858..4c9058eef1 100644
--- a/configs/viewtool-stm32f107/netnsh/defconfig
+++ b/configs/viewtool-stm32f107/netnsh/defconfig
@@ -795,7 +795,6 @@ CONFIG_ETH0_PHY_DP83848C=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/viewtool-stm32f107/nsh/defconfig b/configs/viewtool-stm32f107/nsh/defconfig
index 138757c497..5da2fdda70 100644
--- a/configs/viewtool-stm32f107/nsh/defconfig
+++ b/configs/viewtool-stm32f107/nsh/defconfig
@@ -734,7 +734,6 @@ CONFIG_ARCH_HAVE_SPI_BITORDER=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/xtrs/nsh/defconfig b/configs/xtrs/nsh/defconfig
index aa63aa60f0..18cd15188b 100644
--- a/configs/xtrs/nsh/defconfig
+++ b/configs/xtrs/nsh/defconfig
@@ -192,7 +192,6 @@ CONFIG_DEV_NULL=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_16550_UART is not set
diff --git a/configs/xtrs/ostest/defconfig b/configs/xtrs/ostest/defconfig
index 39e06ae357..b03cffef6f 100644
--- a/configs/xtrs/ostest/defconfig
+++ b/configs/xtrs/ostest/defconfig
@@ -191,7 +191,6 @@ CONFIG_DEV_NULL=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
CONFIG_DEV_LOWCONSOLE=y
# CONFIG_16550_UART is not set
diff --git a/configs/xtrs/pashello/defconfig b/configs/xtrs/pashello/defconfig
index 324ef07f30..b38652e6c0 100644
--- a/configs/xtrs/pashello/defconfig
+++ b/configs/xtrs/pashello/defconfig
@@ -192,7 +192,6 @@ CONFIG_DEV_NULL=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
CONFIG_DEV_LOWCONSOLE=y
# CONFIG_16550_UART is not set
diff --git a/configs/z16f2800100zcog/nsh/defconfig b/configs/z16f2800100zcog/nsh/defconfig
index 94b2c6ff7e..781652bd58 100644
--- a/configs/z16f2800100zcog/nsh/defconfig
+++ b/configs/z16f2800100zcog/nsh/defconfig
@@ -331,7 +331,6 @@ CONFIG_DEV_NULL=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/z16f2800100zcog/ostest/defconfig b/configs/z16f2800100zcog/ostest/defconfig
index 99ec6fd098..dec05b3b6c 100644
--- a/configs/z16f2800100zcog/ostest/defconfig
+++ b/configs/z16f2800100zcog/ostest/defconfig
@@ -331,7 +331,6 @@ CONFIG_DEV_NULL=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
CONFIG_DEV_LOWCONSOLE=y
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/z16f2800100zcog/pashello/defconfig b/configs/z16f2800100zcog/pashello/defconfig
index 0594e40c9a..04d067caa4 100644
--- a/configs/z16f2800100zcog/pashello/defconfig
+++ b/configs/z16f2800100zcog/pashello/defconfig
@@ -215,7 +215,6 @@ CONFIG_DEV_NULL=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
CONFIG_DEV_LOWCONSOLE=y
# CONFIG_16550_UART is not set
diff --git a/configs/z80sim/nsh/defconfig b/configs/z80sim/nsh/defconfig
index cdc9ce0d71..7034fccbf9 100644
--- a/configs/z80sim/nsh/defconfig
+++ b/configs/z80sim/nsh/defconfig
@@ -192,7 +192,6 @@ CONFIG_DEV_NULL=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_16550_UART is not set
diff --git a/configs/z80sim/ostest/defconfig b/configs/z80sim/ostest/defconfig
index 6184bd8397..f7eb3afd2c 100644
--- a/configs/z80sim/ostest/defconfig
+++ b/configs/z80sim/ostest/defconfig
@@ -191,7 +191,6 @@ CONFIG_DEV_NULL=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
CONFIG_DEV_LOWCONSOLE=y
# CONFIG_16550_UART is not set
diff --git a/configs/z80sim/pashello/defconfig b/configs/z80sim/pashello/defconfig
index a2b5d7fb12..6945b3c547 100644
--- a/configs/z80sim/pashello/defconfig
+++ b/configs/z80sim/pashello/defconfig
@@ -191,7 +191,6 @@ CONFIG_DEV_NULL=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
CONFIG_DEV_LOWCONSOLE=y
# CONFIG_16550_UART is not set
diff --git a/configs/z8encore000zco/ostest/defconfig b/configs/z8encore000zco/ostest/defconfig
index 79a76d1ba5..7b8c2d79c8 100644
--- a/configs/z8encore000zco/ostest/defconfig
+++ b/configs/z8encore000zco/ostest/defconfig
@@ -345,7 +345,6 @@ CONFIG_DEV_NULL=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
CONFIG_DEV_LOWCONSOLE=y
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/z8f64200100kit/ostest/defconfig b/configs/z8f64200100kit/ostest/defconfig
index ec1ca29aba..31c730fc47 100644
--- a/configs/z8f64200100kit/ostest/defconfig
+++ b/configs/z8f64200100kit/ostest/defconfig
@@ -345,7 +345,6 @@ CONFIG_DEV_NULL=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/zkit-arm-1769/hello/defconfig b/configs/zkit-arm-1769/hello/defconfig
index dcda1f17fb..f3a86fcb98 100644
--- a/configs/zkit-arm-1769/hello/defconfig
+++ b/configs/zkit-arm-1769/hello/defconfig
@@ -515,7 +515,6 @@ CONFIG_ETH0_PHY_DP83848C=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
CONFIG_DEV_LOWCONSOLE=y
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/zkit-arm-1769/nsh/defconfig b/configs/zkit-arm-1769/nsh/defconfig
index 1d6cc991c1..8a675b6180 100644
--- a/configs/zkit-arm-1769/nsh/defconfig
+++ b/configs/zkit-arm-1769/nsh/defconfig
@@ -552,7 +552,6 @@ CONFIG_ETH0_PHY_DP83848C=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/zkit-arm-1769/nxhello/defconfig b/configs/zkit-arm-1769/nxhello/defconfig
index e2aebc0fed..4c7dfae49f 100644
--- a/configs/zkit-arm-1769/nxhello/defconfig
+++ b/configs/zkit-arm-1769/nxhello/defconfig
@@ -590,7 +590,6 @@ CONFIG_ETH0_PHY_DP83848C=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/zkit-arm-1769/thttpd/defconfig b/configs/zkit-arm-1769/thttpd/defconfig
index d30a0e3270..0438660456 100644
--- a/configs/zkit-arm-1769/thttpd/defconfig
+++ b/configs/zkit-arm-1769/thttpd/defconfig
@@ -518,7 +518,6 @@ CONFIG_DEV_FIFO_SIZE=1024
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
CONFIG_DEV_LOWCONSOLE=y
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/zp214xpa/nsh/defconfig b/configs/zp214xpa/nsh/defconfig
index dcb8c7e000..547c51e58c 100644
--- a/configs/zp214xpa/nsh/defconfig
+++ b/configs/zp214xpa/nsh/defconfig
@@ -393,7 +393,6 @@ CONFIG_DEV_NULL=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/configs/zp214xpa/nxlines/defconfig b/configs/zp214xpa/nxlines/defconfig
index 990185b651..06f8adea17 100644
--- a/configs/zp214xpa/nxlines/defconfig
+++ b/configs/zp214xpa/nxlines/defconfig
@@ -439,7 +439,6 @@ CONFIG_LCD_LANDSCAPE=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
CONFIG_DEV_LOWCONSOLE=y
# CONFIG_SERIAL_REMOVABLE is not set
diff --git a/drivers/Kconfig b/drivers/Kconfig
index 4ac8a9d0c6..740602b9f2 100644
--- a/drivers/Kconfig
+++ b/drivers/Kconfig
@@ -519,23 +519,6 @@ if SENSORS
source drivers/sensors/Kconfig
endif # SENSORS
-menuconfig SERCOMM_CONSOLE
- bool "Osmocom-bb Sercomm Driver Support"
- default n
- ---help---
- Sercomm is the transport used by osmocom-bb that runs on top of serial.
- See http://bb.osmocom.org/trac/wiki/nuttx-bb/run for detailed the usage
- of nuttx with sercomm.
-
- drivers/sercomm is only built if SERCOMM_CONSOLE in the NuttX
- configuration file. If you attempt to build this driver without
- osmocom-bb, you will get compilation errors because of header files
- that are needed from the osmocom-bb.
-
-if SERCOMM_CONSOLE
-source drivers/sercomm/Kconfig
-endif # SERCOMM_CONSOLE
-
menuconfig SERIAL
bool "Serial Driver Support"
default y
diff --git a/drivers/Makefile b/drivers/Makefile
index daac4cd18c..94f027afbb 100644
--- a/drivers/Makefile
+++ b/drivers/Makefile
@@ -66,7 +66,6 @@ include net$(DELIM)Make.defs
include pipes$(DELIM)Make.defs
include power$(DELIM)Make.defs
include sensors$(DELIM)Make.defs
-include sercomm$(DELIM)Make.defs
include serial$(DELIM)Make.defs
include spi$(DELIM)Make.defs
include syslog$(DELIM)Make.defs
diff --git a/drivers/README.txt b/drivers/README.txt
index fbb13ce25d..f9f23af06f 100644
--- a/drivers/README.txt
+++ b/drivers/README.txt
@@ -137,16 +137,6 @@ sensors/
measure and convert voltage levels. DACs, however, are retained in
the analog/ sub-directory.
-sercomm/
- Sercomm is the transport used by osmocom-bb that runs on top of serial.
- See http://bb.osmocom.org/trac/wiki/nuttx-bb/run for detailed the usage
- of nuttx with sercomm.
-
- drivers/sercomm is only built if CONFIG_SERCOMM_CONSOLE in the NuttX
- configuration file. If you attempt to build this driver without
- osmocom-bb, you will get compilation errors because of header files
- that are needed from the osmocom-bb.
-
serial/
Front-end character drivers for chip-specific UARTs. This provide
some TTY-like functionality and are commonly used (but not required for)
diff --git a/drivers/sercomm/Kconfig b/drivers/sercomm/Kconfig
deleted file mode 100644
index f72f3c094c..0000000000
--- a/drivers/sercomm/Kconfig
+++ /dev/null
@@ -1,4 +0,0 @@
-#
-# For a description of the syntax of this configuration file,
-# see the file kconfig-language.txt in the NuttX tools repository.
-#
diff --git a/drivers/sercomm/Make.defs b/drivers/sercomm/Make.defs
deleted file mode 100644
index 0cf93d4c80..0000000000
--- a/drivers/sercomm/Make.defs
+++ /dev/null
@@ -1,55 +0,0 @@
-############################################################################
-# drivers/serial/Make.defs
-#
-# Copyright (C) 2009, 2011 Gregory Nutt. All rights reserved.
-# Author: Gregory Nutt
-#
-# Redistribution and use in source and binary forms, with or without
-# modification, are permitted provided that the following conditions
-# are met:
-#
-# 1. Redistributions of source code must retain the above copyright
-# notice, this list of conditions and the following disclaimer.
-# 2. Redistributions in binary form must reproduce the above copyright
-# notice, this list of conditions and the following disclaimer in
-# the documentation and/or other materials provided with the
-# distribution.
-# 3. Neither the name NuttX nor the names of its contributors may be
-# used to endorse or promote products derived from this software
-# without specific prior written permission.
-#
-# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
-# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
-# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
-# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
-# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
-# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
-# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
-# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
-# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
-# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
-# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
-# POSSIBILITY OF SUCH DAMAGE.
-#
-############################################################################
-
-# File descriptor support is needed for this driver
-
-ifneq ($(CONFIG_NFILE_DESCRIPTORS),0)
-
-# The sercomm driver should not be build for all platforms. Only build it
-# is so configured
-
-ifeq ($(CONFIG_SERCOMM_CONSOLE),y)
-
-# Include serial drivers
-
-CSRCS += console.c uart.c
-
-# Include sercomm build support
-
-DEPPATH += --dep-path sercomm
-VPATH += :sercomm
-
-endif
-endif
diff --git a/drivers/sercomm/README.txt b/drivers/sercomm/README.txt
deleted file mode 100644
index 06add26e88..0000000000
--- a/drivers/sercomm/README.txt
+++ /dev/null
@@ -1,19 +0,0 @@
-drivers/sercomm README
-======================
-
-If CONFIG_SERCOMM_CONSOLE is defined in the NuttX configuration file, NuttX
-will attempt to use sercomm (HDLC protocol) to communicate with the
-host system. Sercomm is the transport used by osmocom-bb that runs on top
-of serial. See http://bb.osmocom.org/trac/wiki/nuttx-bb/run for detailed
-the usage of nuttx with sercomm.
-
-The drivers/sercomm build that you have the osmocom-bb project directory
-at same level as the nuttx project:
-
- |- nuttx
- |- apps
- `- osmocom-bb
-
-If you attempt to build this driver without osmocom-bb, you will get
-compilation errors because of header files that are needed from the
-osmocom-bb directory.
diff --git a/drivers/sercomm/console.c b/drivers/sercomm/console.c
deleted file mode 100644
index efd1174ba3..0000000000
--- a/drivers/sercomm/console.c
+++ /dev/null
@@ -1,216 +0,0 @@
-/****************************************************************************
- * drivers/sercomm/console.c
- * Driver for NuttX Console
- *
- * (C) 2010 by Harald Welte
- * (C) 2011 Stefan Richter
- *
- * This source code is derivated from Osmocom-BB project and was
- * relicensed as BSD with permission from original authors.
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
- *
- * 1. Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * 2. Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in
- * the documentation and/or other materials provided with the
- * distribution.
- * 3. Neither the name NuttX nor the names of its contributors may be
- * used to endorse or promote products derived from this software
- * without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
- * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
- * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- *
- ****************************************************************************/
-
-#include
-#include
-#include
-#include
-
-#include
-#include
-#include
-
-#include "uart.h"
-#include
-#include
-
-/************************************************************************************
- * Fileops Prototypes and Structures
- ************************************************************************************/
-
-typedef FAR struct file file_t;
-
-static ssize_t sc_console_read(file_t *filep, FAR char *buffer, size_t buflen);
-static ssize_t sc_console_write(file_t *filep, FAR const char *buffer, size_t buflen);
-static int sc_console_ioctl(file_t *filep, int cmd, unsigned long arg);
-#ifndef CONFIG_DISABLE_POLL
-static int sc_console_poll(file_t *filep, FAR struct pollfd *fds, bool setup);
-#endif
-
-static const struct file_operations g_sercom_console_ops =
-{
- 0, /* open, always opened */
- 0, /* close, stays open */
- sc_console_read, /* read */
- sc_console_write, /* write */
- 0, /* seek, not supported */
- sc_console_ioctl, /* ioctl */
-#ifndef CONFIG_DISABLE_POLL
- sc_console_poll /* poll */
-#endif
-};
-
-static FAR uart_dev_t *readdev = NULL;
-static struct msgb *recvmsg = NULL;
-
-/****************************************************************************
- * Helper functions
- ****************************************************************************/
-
-static void recv_cb(uint8_t dlci, struct msgb *msg)
-{
- sem_post(&readdev->recvsem);
- recvmsg = msg;
-}
-
-/****************************************************************************
- * Fileops
- ****************************************************************************/
-
-/* REVISIT: recvmsg is overwritten when multiple msg arrive! */
-
-static ssize_t sc_console_read(file_t *filep, FAR char *buffer, size_t buflen)
-{
- size_t len;
- struct msgb *tmp;
-
- /* Wait until data is received */
-
- while (recvmsg == NULL)
- {
- sem_wait(&readdev->recvsem);
- }
-
- len = recvmsg->len > buflen ? buflen : recvmsg->len;
- memcpy(buffer, msgb_get(recvmsg, len), len);
-
- if (recvmsg->len == 0)
- {
- /* prevent inconsistent msg by first invalidating it, then free it */
-
- tmp = recvmsg;
- recvmsg = NULL;
- msgb_free(tmp);
- }
-
- return len;
-}
-
-/* REVISIT: redirect to old Osmocom-BB comm/sercomm_cons.c -> 2 buffers */
-
-extern int sercomm_puts(const char *s);
-
-static ssize_t sc_console_write(file_t *filep, FAR const char *buffer, size_t buflen)
-{
- char dstbuf[32];
- int cnt;
-
- if (buflen >= 31)
- {
- cnt = 31;
- }
- else
- {
- cnt = buflen;
- }
-
- memcpy(dstbuf, buffer, cnt);
- dstbuf[cnt] = '\0';
-
- /* print part of our buffer */
-
- sercomm_puts(dstbuf);
-
- /* wait a little bit to get data transfered */
-
- up_mdelay(1);
-
- return cnt;
-}
-
-/* Forward ioctl to uart driver */
-
-static int sc_console_ioctl(struct file *filep, int cmd, unsigned long arg)
-{
- FAR struct inode *inode = filep->f_inode;
- FAR uart_dev_t *dev = inode->i_private;
-
- return dev->ops->ioctl(filep, cmd, arg);
-}
-
-/************************************************************************************
- * Public Functions
- ************************************************************************************/
-
-/* Use sercomm on uart driver, register console driver */
-
-int sercomm_register(FAR const char *path, FAR uart_dev_t *dev)
-{
- /* REVISIT: initialize MODEMUART to be used for sercomm */
-
- uart_init(SERCOMM_UART_NR, 1);
- uart_baudrate(SERCOMM_UART_NR, UART_115200);
- readdev = dev;
- sercomm_register_rx_cb(SC_DLCI_LOADER, &recv_cb);
-
- sem_init(&dev->xmit.sem, 0, 1);
- sem_init(&dev->recv.sem, 0, 1);
- sem_init(&dev->closesem, 0, 1);
- sem_init(&dev->xmitsem, 0, 0);
- sem_init(&dev->recvsem, 0, 0);
-#ifndef CONFIG_DISABLE_POLL
- sem_init(&dev->pollsem, 0, 1);
-#endif
-
- sem_setprotocol(&dev->xmitsem, SEM_PRIO_NONE);
- sem_setprotocol(&dev->recvsem, SEM_PRIO_NONE);
-
- _info("Registering %s\n", path);
- return register_driver(path, &g_sercom_console_ops, 0666, NULL);
-}
-
-/* Stubs to make serial driver happy */
-
-void sercomm_recvchars(void *a)
-{
-}
-
-void sercomm_xmitchars(void *a)
-{
-}
-
-/* Stubs to make memory allocator happy */
-
-void cons_puts(void *foo)
-{
-}
-
-void delay_ms(int ms)
-{
-}
diff --git a/drivers/sercomm/loadwriter.py b/drivers/sercomm/loadwriter.py
deleted file mode 100755
index 6234d6f0d3..0000000000
--- a/drivers/sercomm/loadwriter.py
+++ /dev/null
@@ -1,19 +0,0 @@
-#!/usr/bin/python
-from socket import *
-import time
-
-SOCKET_NAME = '/tmp/osmocom_loader'
-
-s = socket(AF_UNIX, SOCK_STREAM)
-s.connect(SOCKET_NAME)
-
-while 1:
- try:
- x = raw_input(">")
- y = len(x) + 1
- s.send(chr(y>>8) + chr(y&255) + x + "\n")
- except:
- print ''
- break
-
-s.close()
diff --git a/drivers/sercomm/uart.c b/drivers/sercomm/uart.c
deleted file mode 100644
index 9e257455a8..0000000000
--- a/drivers/sercomm/uart.c
+++ /dev/null
@@ -1,607 +0,0 @@
-/****************************************************************************
- * drivers/sercomm/uart.c
- * Calypso DBB internal UART Driver
- *
- * (C) 2010 by Harald Welte
- * (C) 2010 by Ingo Albrecht
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
- *
- * 1. Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * 2. Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in
- * the documentation and/or other materials provided with the
- * distribution.
- * 3. Neither the name NuttX nor the names of its contributors may be
- * used to endorse or promote products derived from this software
- * without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
- * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
- * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- *
- ****************************************************************************/
-
-#include
-#include
-#include
-
-#include
-#include
-#include
-
-#include
-#include
-
-#include
-#include
-
-#include "uart.h"
-
-#define BASE_ADDR_UART_MODEM 0xffff5000
-#define OFFSET_IRDA 0x800
-
-#define UART_REG(n,m) (BASE_ADDR_UART_MODEM + ((n)*OFFSET_IRDA)+(m))
-
-#define LCR7BIT 0x80
-#define LCRBFBIT 0x40
-#define MCR6BIT 0x20
-#define REG_OFFS(m) ((m) & ~(LCR7BIT|LCRBFBIT|MCR6BIT))
-
-/* read access LCR[7] = 0 */
-
-enum uart_reg
-{
- RHR = 0,
- IER = 1,
- IIR = 2,
- LCR = 3,
- MCR = 4,
- LSR = 5,
- MSR = 6,
- SPR = 7,
- MDR1 = 8,
- DMR2 = 9,
- SFLSR = 0x0a,
- RESUME = 0x0b,
- SFREGL = 0x0c,
- SFREGH = 0x0d,
- BLR = 0x0e,
- ACREG = 0x0f,
- SCR = 0x10,
- SSR = 0x11,
- EBLR = 0x12,
-
- /* read access LCR[7] = 1 */
-
- DLL = RHR | LCR7BIT,
- DLH = IER | LCR7BIT,
- DIV1_6 = ACREG | LCR7BIT,
-
- /* read/write access LCR[7:0] = 0xbf */
-
- EFR = IIR | LCRBFBIT,
- XON1 = MCR | LCRBFBIT,
- XON2 = LSR | LCRBFBIT,
- XOFF1 = MSR | LCRBFBIT,
- XOFF2 = SPR | LCRBFBIT,
-
- /* read/write access if EFR[4] = 1 and MCR[6] = 1 */
-
- TCR = MSR | MCR6BIT,
- TLR = SPR | MCR6BIT,
-};
-
-/* write access LCR[7] = 0 */
-
-#define THR RHR
-#define FCR IIR /* only if EFR[4] = 1 */
-#define TXFLL SFLSR
-#define TXFLH RESUME
-#define RXFLL SFREGL
-#define RXFLH SFREGH
-
-enum fcr_bits
-{
- FIFO_EN = (1 << 0),
- RX_FIFO_CLEAR = (1 << 1),
- TX_FIFO_CLEAR = (1 << 2),
- DMA_MODE = (1 << 3),
-};
-
-#define TX_FIFO_TRIG_SHIFT 4
-#define RX_FIFO_TRIG_SHIFT 6
-
-enum iir_bits
-{
- IIR_INT_PENDING = 0x01,
- IIR_INT_TYPE = 0x3E,
- IIR_INT_TYPE_RX_STATUS_ERROR = 0x06,
- IIR_INT_TYPE_RX_TIMEOUT = 0x0C,
- IIR_INT_TYPE_RHR = 0x04,
- IIR_INT_TYPE_THR = 0x02,
- IIR_INT_TYPE_MSR = 0x00,
- IIR_INT_TYPE_XOFF = 0x10,
- IIR_INT_TYPE_FLOW = 0x20,
- IIR_FCR0_MIRROR = 0xC0,
-};
-
-#define UART_REG_UIR 0xffff6000
-
-/* enable or disable the divisor latch for access to DLL, DLH */
-
-static void uart_set_lcr7bit(int uart, int on)
-{
- uint8_t reg;
-
- reg = readb(UART_REG(uart, LCR));
- if (on)
- {
- reg |= (1 << 7);
- }
- else
- {
- reg &= ~(1 << 7);
- }
-
- writeb(reg, UART_REG(uart, LCR));
-}
-
-static uint8_t old_lcr;
-static void uart_set_lcr_bf(int uart, int on)
-{
- if (on)
- {
- old_lcr = readb(UART_REG(uart, LCR));
- writeb(0xBF, UART_REG(uart, LCR));
- }
- else
- {
- writeb(old_lcr, UART_REG(uart, LCR));
- }
-}
-
-/* Enable or disable the TCR_TLR latch bit in MCR[6] */
-
-static void uart_set_mcr6bit(int uart, int on)
-{
- uint8_t mcr;
-
- /* we assume EFR[4] is always set to 1 */
-
- mcr = readb(UART_REG(uart, MCR));
- if (on)
- {
- mcr |= (1 << 6);
- }
- else
- {
- mcr &= ~(1 << 6);
- }
-
- writeb(mcr, UART_REG(uart, MCR));
-}
-
-static void uart_reg_write(int uart, enum uart_reg reg, uint8_t val)
-{
- if (reg & LCRBFBIT)
- {
- uart_set_lcr_bf(uart, 1);
- }
- else if (reg & LCR7BIT)
- {
- uart_set_lcr7bit(uart, 1);
- }
- else if (reg & MCR6BIT)
- {
- uart_set_mcr6bit(uart, 1);
- }
-
- writeb(val, UART_REG(uart, REG_OFFS(reg)));
-
- if (reg & LCRBFBIT)
- {
- uart_set_lcr_bf(uart, 0);
- }
- else if (reg & LCR7BIT)
- {
- uart_set_lcr7bit(uart, 0);
- }
- else if (reg & MCR6BIT)
- {
- uart_set_mcr6bit(uart, 0);
- }
-}
-
-/* read from a UART register, applying any required latch bits */
-
-static uint8_t uart_reg_read(int uart, enum uart_reg reg)
-{
- uint8_t ret;
-
- if (reg & LCRBFBIT)
- {
- uart_set_lcr_bf(uart, 1);
- }
- else if (reg & LCR7BIT)
- {
- uart_set_lcr7bit(uart, 1);
- }
- else if (reg & MCR6BIT)
- {
- uart_set_mcr6bit(uart, 1);
- }
-
- ret = readb(UART_REG(uart, REG_OFFS(reg)));
-
- if (reg & LCRBFBIT)
- {
- uart_set_lcr_bf(uart, 0);
- }
- else if (reg & LCR7BIT)
- {
- uart_set_lcr7bit(uart, 0);
- }
- else if (reg & MCR6BIT)
- {
- uart_set_mcr6bit(uart, 0);
- }
-
- return ret;
-}
-
-#if 0
-static void uart_irq_handler_cons(__unused enum irq_nr irqnr)
-{
- const uint8_t uart = CONS_UART_NR;
- uint8_t iir;
-
- iir = uart_reg_read(uart, IIR);
- if (iir & IIR_INT_PENDING)
- {
- return;
- }
-
- switch (iir & IIR_INT_TYPE)
- {
- case IIR_INT_TYPE_RHR:
- break;
-
- case IIR_INT_TYPE_THR:
- if (cons_rb_flush() == 1)
- {
- /* everything was flushed, disable THR IRQ */
-
- uint8_t ier = uart_reg_read(uart, IER);
- ier &= ~(1 << 1);
- uart_reg_write(uart, IER, ier);
- }
- break;
-
- case IIR_INT_TYPE_MSR:
- break;
-
- case IIR_INT_TYPE_RX_STATUS_ERROR:
- break;
-
- case IIR_INT_TYPE_RX_TIMEOUT:
- break;
-
- case IIR_INT_TYPE_XOFF:
- break;
- }
-}
-#endif
-
-static void uart_irq_handler_sercomm(__unused enum irq_nr irqnr, __unused void *context)
-{
- const uint8_t uart = SERCOMM_UART_NR;
- uint8_t iir, ch;
-
- iir = uart_reg_read(uart, IIR);
- if (iir & IIR_INT_PENDING)
- {
- return;
- }
-
- switch (iir & IIR_INT_TYPE)
- {
- case IIR_INT_TYPE_RX_TIMEOUT:
- case IIR_INT_TYPE_RHR:
- /* as long as we have rx data available */
-
- while (uart_getchar_nb(uart, &ch))
- {
- if (sercomm_drv_rx_char(ch) < 0)
- {
- /* sercomm cannot receive more data right now */
-
- uart_irq_enable(uart, UART_IRQ_RX_CHAR, 0);
- }
- }
- break;
-
- case IIR_INT_TYPE_THR:
- /* as long as we have space in the FIFO */
-
- while (!uart_tx_busy(uart))
- {
- /* get a byte from sercomm */
-
- if (!sercomm_drv_pull(&ch))
- {
- /* no more bytes in sercomm, stop TX interrupts */
-
- uart_irq_enable(uart, UART_IRQ_TX_EMPTY, 0);
- break;
- }
-
- /* write the byte into the TX FIFO */
-
- uart_putchar_nb(uart, ch);
- }
- break;
-
- case IIR_INT_TYPE_MSR:
- printf("UART IRQ MSR\n");
- break;
-
- case IIR_INT_TYPE_RX_STATUS_ERROR:
- printf("UART IRQ RX_SE\n");
- break;
-
- case IIR_INT_TYPE_XOFF:
- printf("UART IRQXOFF\n");
- break;
- }
-}
-
-static const uint8_t uart2irq[] =
-{
- [0] = IRQ_UART_IRDA,
- [1] = IRQ_UART_MODEM,
-};
-
-void uart_init(uint8_t uart, uint8_t interrupts)
-{
-#if 0
- uint8_t irq = uart2irq[uart];
-#endif
-
- uart_reg_write(uart, IER, 0x00);
-
- if (uart == SERCOMM_UART_NR)
- {
- sercomm_init();
- irq_attach(IRQ_UART_MODEM, (xcpt_t)uart_irq_handler_sercomm);
- up_enable_irq(IRQ_UART_MODEM);
- uart_irq_enable(uart, UART_IRQ_RX_CHAR, 1);
- }
-
-#if 0
- if (uart == CONS_UART_NR)
- {
- cons_init();
- if (interrupts)
- {
- irq_register_handler(irq, &uart_irq_handler_cons);
- irq_config(irq, 0, 0, 0xff);
- irq_enable(irq);
- }
- }
- else
- {
- sercomm_init();
- if (interrupts)
- {
- irq_register_handler(irq, &uart_irq_handler_sercomm);
- irq_config(irq, 0, 0, 0xff);
- irq_enable(irq);
- }
-
- uart_irq_enable(uart, UART_IRQ_RX_CHAR, 1);
- }
-#endif
-#if 0
- if (uart == 1)
- {
- /* assign UART to MCU and unmask interrupts */
-
- writeb(UART_REG_UIR, 0x00);
- }
-#endif
-
- /* if we don't initialize these, we get strange corruptions in the
- * received data... :-(
- */
-
- uart_reg_write(uart, MDR1, 0x07); /* turn off UART */
- uart_reg_write(uart, XON1, 0x00); /* Xon1/Addr Register */
- uart_reg_write(uart, XON2, 0x00); /* Xon2/Addr Register */
- uart_reg_write(uart, XOFF1, 0x00); /* Xoff1 Register */
- uart_reg_write(uart, XOFF2, 0x00); /* Xoff2 Register */
- uart_reg_write(uart, EFR, 0x00); /* Enhanced Features Register */
-
- /* select UART mode */
-
- uart_reg_write(uart, MDR1, 0);
-
- /* no XON/XOFF flow control, ENHANCED_EN, no auto-RTS/CTS */
-
- uart_reg_write(uart, EFR, (1 << 4));
-
- /* enable Tx/Rx FIFO, Tx trigger at 56 spaces, Rx trigger at 60 chars */
-
- uart_reg_write(uart, FCR, FIFO_EN | RX_FIFO_CLEAR | TX_FIFO_CLEAR |
- (3 << TX_FIFO_TRIG_SHIFT) | (3 << RX_FIFO_TRIG_SHIFT));
-
- /* THR interrupt only when TX FIFO and TX shift register are empty */
-
- uart_reg_write(uart, SCR, (1 << 0)); /* | (1 << 3)); */
-
- /* 8 bit, 1 stop bit, no parity, no break */
-
- uart_reg_write(uart, LCR, 0x03);
-
- uart_set_lcr7bit(uart, 0);
-}
-
-void uart_poll(uint8_t uart)
-{
-#if 0
- if (uart == CONS_UART_NR)
- {
- uart_irq_handler_cons(0);
- }
- else
-#endif
- {
- uart_irq_handler_sercomm(0, NULL);
- }
-}
-
-void uart_irq_enable(uint8_t uart, enum uart_irq irq, int on)
-{
- uint8_t ier = uart_reg_read(uart, IER);
- uint8_t mask = 0;
-
- switch (irq)
- {
- case UART_IRQ_TX_EMPTY:
- mask = (1 << 1);
- break;
-
- case UART_IRQ_RX_CHAR:
- mask = (1 << 0);
- break;
- }
-
- if (on)
- {
- ier |= mask;
- }
- else
- {
- ier &= ~mask;
- }
-
- uart_reg_write(uart, IER, ier);
-}
-
-void uart_putchar_wait(uint8_t uart, int c)
-{
- /* wait while TX FIFO indicates full */
-
- while (readb(UART_REG(uart, SSR)) & 0x01) { }
-
- /* put character in TX FIFO */
-
- writeb(c, UART_REG(uart, THR));
-}
-
-int uart_putchar_nb(uint8_t uart, int c)
-{
- /* if TX FIFO indicates full, abort */
-
- if (readb(UART_REG(uart, SSR)) & 0x01)
- {
- return 0;
- }
-
- writeb(c, UART_REG(uart, THR));
- return 1;
-}
-
-int uart_getchar_nb(uint8_t uart, uint8_t *ch)
-{
- uint8_t lsr;
-
- lsr = readb(UART_REG(uart, LSR));
-
- /* something strange happened */
-
- if (lsr & 0x02)
- {
- printf("LSR RX_OE\n");
- }
-
- if (lsr & 0x04)
- {
- printf("LSR RX_PE\n");
- }
-
- if (lsr & 0x08)
- {
- printf("LSR RX_FE\n");
- }
-
- if (lsr & 0x10)
- {
- printf("LSR RX_BI\n");
- }
-
- if (lsr & 0x80)
- {
- printf("LSR RX_FIFO_STS\n");
- }
-
- /* is the Rx FIFO empty? */
-
- if (!(lsr & 0x01))
- {
- return 0;
- }
-
- *ch = readb(UART_REG(uart, RHR));
- return 1;
-}
-
-int uart_tx_busy(uint8_t uart)
-{
- if (readb(UART_REG(uart, SSR)) & 0x01)
- {
- return 1;
- }
-
- return 0;
-}
-
-static const uint16_t divider[] =
-{
- [UART_38400] = 21, /* 38,690 */
- [UART_57600] = 14, /* 58,035 */
- [UART_115200] = 7, /* 116,071 */
- [UART_230400] = 4, /* 203,125! (-3% would be 223,488) */
- [UART_460800] = 2, /* 406,250! (-3% would be 446,976) */
- [UART_921600] = 1, /* 812,500! (-3% would be 893,952) */
-};
-
-int uart_baudrate(uint8_t uart, enum uart_baudrate bdrt)
-{
- uint16_t div;
-
- if (bdrt > ARRAY_SIZE(divider))
- {
- return -1;
- }
-
- div = divider[bdrt];
- uart_set_lcr7bit(uart, 1);
- writeb(div & 0xff, UART_REG(uart, DLL));
- writeb(div >> 8, UART_REG(uart, DLH));
- uart_set_lcr7bit(uart, 0);
-
- return 0;
-}
diff --git a/drivers/sercomm/uart.h b/drivers/sercomm/uart.h
deleted file mode 100644
index 81d7a15609..0000000000
--- a/drivers/sercomm/uart.h
+++ /dev/null
@@ -1,32 +0,0 @@
-#ifndef _UART_H
-#define _UART_H
-
-#include
-
-enum uart_baudrate {
- UART_38400,
- UART_57600,
- UART_115200,
- UART_230400,
- UART_460800,
- UART_614400,
- UART_921600,
-};
-
-void uart_init(uint8_t uart, uint8_t interrupts);
-void uart_putchar_wait(uint8_t uart, int c);
-int uart_putchar_nb(uint8_t uart, int c);
-int uart_getchar_nb(uint8_t uart, uint8_t *ch);
-int uart_tx_busy(uint8_t uart);
-int uart_baudrate(uint8_t uart, enum uart_baudrate bdrt);
-
-enum uart_irq {
- UART_IRQ_TX_EMPTY,
- UART_IRQ_RX_CHAR,
-};
-
-void uart_irq_enable(uint8_t uart, enum uart_irq irq, int on);
-
-void uart_poll(uint8_t uart);
-
-#endif /* _UART_H */
diff --git a/include/nuttx/sercomm/msgb.h b/include/nuttx/sercomm/msgb.h
deleted file mode 100644
index 39067c3ba3..0000000000
--- a/include/nuttx/sercomm/msgb.h
+++ /dev/null
@@ -1,218 +0,0 @@
-/****************************************************************************
- * (C) 2008-2010 by Harald Welte
- *
- * This source code is derivated from Osmocom-BB project and was
- * relicensed as BSD with permission from original authors.
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
- *
- * 1. Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * 2. Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in
- * the documentation and/or other materials provided with the
- * distribution.
- * 3. Neither the name NuttX nor the names of its contributors may be
- * used to endorse or promote products derived from this software
- * without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
- * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
- * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- *
- ****************************************************************************/
-
-#ifndef __INCLUDE_NUTTX_SERCOM_MSGB_H
-#define __INCLUDE_NUTTX_SERCOM_MSGB_H
-
-/****************************************************************************
- * Included Files
- ****************************************************************************/
-
-#include
-#include
-
-/****************************************************************************
- * Public Types
- ****************************************************************************/
-
-struct msgb
-{
- struct llist_head list;
-
- /* the layer 1 header, if any */
-
- unsigned char *l1h;
-
- /* the A-bis layer 2 header: OML, RSL(RLL), NS */
-
- unsigned char *l2h;
-
- /* the layer 3 header. For OML: FOM; RSL: 04.08; GPRS: BSSGP */
-
- unsigned char *l3h;
-
- uint16_t data_len;
- uint16_t len;
-
- unsigned char *head; /* start of buffer */
- unsigned char *tail; /* end of message */
- unsigned char *data; /* start of message */
- unsigned char _data[0];
-};
-
-/****************************************************************************
- * Public Function Prototypes
- ****************************************************************************/
-
-struct msgb *msgb_alloc(uint16_t size, const char *name);
-void msgb_free(struct msgb *m);
-void msgb_enqueue(struct llist_head *queue, struct msgb *msg);
-struct msgb *msgb_dequeue(struct llist_head *queue);
-void msgb_reset(struct msgb *m);
-
-/****************************************************************************
- * Inline Functions
- ****************************************************************************/
-
-#define msgb_l1(m) ((void *)(m->l1h))
-#define msgb_l2(m) ((void *)(m->l2h))
-#define msgb_l3(m) ((void *)(m->l3h))
-
-static inline unsigned int msgb_l1len(const struct msgb *msgb)
-{
- return msgb->tail - (uint8_t *)msgb_l1(msgb);
-}
-
-static inline unsigned int msgb_l2len(const struct msgb *msgb)
-{
- return msgb->tail - (uint8_t *)msgb_l2(msgb);
-}
-
-static inline unsigned int msgb_l3len(const struct msgb *msgb)
-{
- return msgb->tail - (uint8_t *)msgb_l3(msgb);
-}
-
-static inline unsigned int msgb_headlen(const struct msgb *msgb)
-{
- return msgb->len - msgb->data_len;
-}
-
-static inline int msgb_tailroom(const struct msgb *msgb)
-{
- return (msgb->head + msgb->data_len) - msgb->tail;
-}
-
-static inline unsigned char *msgb_put(struct msgb *msgb, unsigned int len)
-{
- unsigned char *tmp = msgb->tail;
-
- /* we intentionally call cons_puts() here to display an allocation
- * failure on the _other_ serial port (i.e. the one that doesn't
- * have the HDLC layer on it
- */
-
- if (msgb_tailroom(msgb) < len)
- {
- cons_puts("msgb_tailroom insufficient!\n");
- }
-
- msgb->tail += len;
- msgb->len += len;
- return tmp;
-}
-
-static inline void msgb_put_u8(struct msgb *msgb, uint8_t word)
-{
- uint8_t *space = msgb_put(msgb, 1);
- space[0] = word & 0xFF;
-}
-
-static inline void msgb_put_u16(struct msgb *msgb, uint16_t word)
-{
- uint8_t *space = msgb_put(msgb, 2);
- space[0] = word >> 8 & 0xFF;
- space[1] = word & 0xFF;
-}
-
-static inline void msgb_put_u32(struct msgb *msgb, uint32_t word)
-{
- uint8_t *space = msgb_put(msgb, 4);
- space[0] = word >> 24 & 0xFF;
- space[1] = word >> 16 & 0xFF;
- space[2] = word >> 8 & 0xFF;
- space[3] = word & 0xFF;
-}
-
-static inline unsigned char *msgb_get(struct msgb *msgb, unsigned int len)
-{
- unsigned char *tmp = msgb->data;
- msgb->data += len;
- msgb->len -= len;
- return tmp;
-}
-
-static inline uint8_t msgb_get_u8(struct msgb *msgb)
-{
- uint8_t *space = msgb_get(msgb, 1);
- return space[0];
-}
-
-static inline uint16_t msgb_get_u16(struct msgb *msgb)
-{
- uint8_t *space = msgb_get(msgb, 2);
- return space[0] << 8 | space[1];
-}
-
-static inline uint32_t msgb_get_u32(struct msgb *msgb)
-{
- uint8_t *space = msgb_get(msgb, 4);
- return space[0] << 24 | space[1] << 16 | space[2] << 8 | space[3];
-}
-
-static inline unsigned char *msgb_push(struct msgb *msgb, unsigned int len)
-{
- msgb->data -= len;
- msgb->len += len;
- return msgb->data;
-}
-
-static inline unsigned char *msgb_pull(struct msgb *msgb, unsigned int len)
-{
- msgb->len -= len;
- return msgb->data += len;
-}
-
-/* increase the headroom of an empty msgb, reducing the tailroom */
-
-static inline void msgb_reserve(struct msgb *msg, int len)
-{
- msg->data += len;
- msg->tail += len;
-}
-
-static inline struct msgb *msgb_alloc_headroom(int size, int headroom,
- const char *name)
-{
- struct msgb *msg = msgb_alloc(size, name);
- if (msg)
- {
- msgb_reserve(msg, headroom);
- }
-
- return msg;
-}
-
-#endif /* __INCLUDE_NUTTX_SERCOM_MSGB_H */
diff --git a/include/nuttx/sercomm/sercomm.h b/include/nuttx/sercomm/sercomm.h
deleted file mode 100644
index 260f1be57b..0000000000
--- a/include/nuttx/sercomm/sercomm.h
+++ /dev/null
@@ -1,57 +0,0 @@
-#ifndef __INCLUDE_NUTTX_SERCOMM_SERCOMM_H
-#define __INCLUDE_NUTTX_SERCOMM_SERCOMM_H
-
-/* SERCOMM layer on UART1 (modem UART) */
-
-#include
-
-#define SERCOMM_UART_NR 1
-
-#define HDLC_FLAG 0x7E
-#define HDLC_ESCAPE 0x7D
-
-#define HDLC_C_UI 0x03
-#define HDLC_C_P_BIT (1 << 4)
-#define HDLC_C_F_BIT (1 << 4)
-
-/* a low sercomm_dlci means high priority. A high DLCI means low priority */
-enum sercomm_dlci {
- SC_DLCI_HIGHEST = 0,
- SC_DLCI_DEBUG = 4,
- SC_DLCI_L1A_L23 = 5,
- SC_DLCI_LOADER = 9,
- SC_DLCI_CONSOLE = 10,
- SC_DLCI_ECHO = 128,
- _SC_DLCI_MAX
-};
-
-void sercomm_init(void);
-int sercomm_initialized(void);
-
-/* User Interface: Tx */
-
-/* user interface for transmitting messages for a given DLCI */
-void sercomm_sendmsg(uint8_t dlci, struct msgb *msg);
-/* how deep is the Tx queue for a given DLCI */
-unsigned int sercomm_tx_queue_depth(uint8_t dlci);
-
-/* User Interface: Rx */
-
-/* receiving messages for a given DLCI */
-typedef void (*dlci_cb_t)(uint8_t dlci, struct msgb *msg);
-int sercomm_register_rx_cb(uint8_t dlci, dlci_cb_t cb);
-
-/* Driver Interface */
-
-/* fetch one octet of to-be-transmitted serial data. returns 0 if no more data */
-int sercomm_drv_pull(uint8_t *ch);
-/* the driver has received one byte, pass it into sercomm layer.
- returns 1 in case of success, 0 in case of unrecognized char */
-int sercomm_drv_rx_char(uint8_t ch);
-
-static inline struct msgb *sercomm_alloc_msgb(unsigned int len)
-{
- return msgb_alloc_headroom(len+4, 4, "sercomm_tx");
-}
-
-#endif /* __INCLUDE_NUTTX_SERCOMM_SERCOMM_H */
diff --git a/include/nuttx/sercomm/sercomm_cons.h b/include/nuttx/sercomm/sercomm_cons.h
deleted file mode 100644
index eb8e7fa12b..0000000000
--- a/include/nuttx/sercomm/sercomm_cons.h
+++ /dev/null
@@ -1,10 +0,0 @@
-#ifndef __INCLUDE_NUTTX_SERCOMM_SERCOMM_CONS_H
-#define __INCLUDE_NUTTX_SERCOMM_SERCOMM_CONS_H
-
-/* how large buffers do we allocate? */
-#define SERCOMM_CONS_ALLOC 256
-
-int sercomm_puts(const char *s);
-int sercomm_putchar(int c);
-
-#endif /* __INCLUDE_NUTTX_SERCOMM_SERCOMM_CONS_H */