diff --git a/.gitignore b/.gitignore
index 937bfe34593bee9d4668bd41ebdfd0259e0d0075..071b01a9bb065cf19a81aabcbe80a5c2a9830126 100644
--- a/.gitignore
+++ b/.gitignore
@@ -1,2 +1,3 @@
 bin/
 *.o
+*~
diff --git a/telosb/Makefile b/telosb/Makefile
new file mode 100644
index 0000000000000000000000000000000000000000..4f9b220a4a0b7a1ccbb084794490a0515f86a5d2
--- /dev/null
+++ b/telosb/Makefile
@@ -0,0 +1,34 @@
+SRC = $(wildcard *.c)
+BINDIR = bin/
+OBJ = $(SRC:%.c=$(BINDIR)%.o)## defines
+export ARCH = telosb_base.a
+
+DEP = $(SRC:%.c=$(BINDIR)%.d)
+
+INCLUDES += -I${RIOTBOARD}/${BOARD}/include/
+INCLUDES += -I${RIOTBASE}/core/include/
+INCLUDES += -I$(RIOTBASE)/cpu/msp430-common/include/ -I$(RIOTBASE)/cpu/msp430x16x/include/
+INCLUDES += -I$(RIOTBASE)/drivers/cc2420/include/ -I$(RIOTBASE)/sys/include
+INCLUDES += -I$(RIOTBASE)/sys/net/
+
+all: $(BINDIR)$(ARCH)
+
+$(BINDIR)$(ARCH): $(OBJ)
+	$(AR) rcs $(BINDIR)$(ARCH) $(OBJ)
+
+# pull in dependency info for *existing* .o files
+-include $(OBJ:.o=.d)
+
+# compile and generate dependency info
+$(BINDIR)%.o: %.c
+	mkdir -p $(BINDIR)
+	$(CC) $(CFLAGS) $(INCLUDES) $(BOARDINCLUDE) $(PROJECTINCLUDE) $(CPUINCLUDE) -c $*.c -o $(BINDIR)$*.o
+	$(CC) $(CFLAGS) $(INCLUDES) $(BOARDINCLUDE) $(PROJECTINCLUDE) $(CPUINCLUDE) -MM $*.c > $(BINDIR)$*.d
+	@printf "$(BINDIR)"|cat - $(BINDIR)$*.d > /tmp/riot_out && mv /tmp/riot_out $(BINDIR)$*.d
+
+# remove compilation products
+clean:
+	rm -f $(BINDIR)$(ARCH) $(OBJ) $(DEP)
+	@if [ -d $(BINDIR) ] ; \
+	then rmdir $(BINDIR) ; \
+	fi
diff --git a/telosb/Makefile.dep b/telosb/Makefile.dep
new file mode 100644
index 0000000000000000000000000000000000000000..4392a18adb85f0037d18b402effd9d8cebe34532
--- /dev/null
+++ b/telosb/Makefile.dep
@@ -0,0 +1,2 @@
+USEMODULE += msp430_common
+
diff --git a/telosb/Makefile.include b/telosb/Makefile.include
new file mode 100644
index 0000000000000000000000000000000000000000..e07ce0f5daa2046a4414f7efb509ac05605278e8
--- /dev/null
+++ b/telosb/Makefile.include
@@ -0,0 +1,25 @@
+include $(RIOTBOARD)/$(BOARD)/Makefile.dep
+## the cpu to build for
+export CPU = msp430x16x
+export MCU = msp430f1611
+
+# toolchain config
+export PREFIX = @msp430-
+export CC = @$(PREFIX)gcc
+export AR = @$(PREFIX)ar
+export CFLAGS += -std=gnu99 -Wstrict-prototypes -gdwarf-2 -Os -Wall -mmcu=$(MCU)
+export ASFLAGS += -mmcu=$(MCU) --defsym $(MCU)=1 --gdwarf-2
+export AS = $(PREFIX)as
+export LINK = $(PREFIX)gcc
+export SIZE = $(PREFIX)size
+export OBJCOPY = $(PREFIX)objcopy
+export LINKFLAGS = -mmcu=$(MCU) -lgcc $(RIOTBASE)/bin/startup.o
+export TERMPROG = $(RIOTBASE)/dist/tools/pyterm/pyterm.py
+export FLASHER = goodfet.bsl
+ifeq ($(strip $(PORT)),)
+    export PORT = /dev/ttyUSB0
+endif
+export HEXFILE = bin/$(PROJECT).hex
+export FFLAGS = --telosb -c $(PORT) -r -e -I -p $(HEXFILE)
+
+export INCLUDES += -I $(RIOTCPU)/msp430-common/include/
diff --git a/telosb/board.c b/telosb/board.c
new file mode 100644
index 0000000000000000000000000000000000000000..37b21b4caaa3e1f2f0f97b7cc29d88c8c864d39c
--- /dev/null
+++ b/telosb/board.c
@@ -0,0 +1,127 @@
+  /*
+   * board.c - Board initiazilation for the TelosB
+   * Copyright (C) 2013 Oliver Hahm <oliver.hahm@inria.fr>
+   *
+   * This file subject to the terms and conditions of the LGPLv2. See the file
+   * LICENSE in the  top level directory for more details.
+   */
+
+#include "cpu.h"
+#include "board.h"
+
+void uart_init(void);
+
+static void telosb_ports_init(void)
+{
+    /* Port 1: GDO, Flash, BSL TX */
+    P1SEL = 0x02;    /* Port1 Select: 00000010 = 0x02 */
+    P1OUT = 0x00;    /* Port1 Output: 00000000 = 0x00 */
+    P1DIR = 0x87;    /* Port1 Direction: 10000111 = 0x87 */
+
+    /* Port 2: GPIO, BSL RX, 1wire */
+    P2SEL = 0x04;    /* Port2 Select: 00000100 = 0x04 */
+    P2OUT = 0x00;    /* Port2 Output: 00000000 = 0x00 */
+    P2DIR = 0xFF;    /* Port2 Direction: 11111111 = 0xFF */
+
+    /* Port 3: UART and SPI */
+    P3SEL = 0xCE;    /* Port3 Select: 11001110 = 0xCE */
+    P3OUT = 0x00;    /* Port3 Output: 00000000 = 0x00 */
+    P3DIR = 0x4E;    /* Port3 Direction: 01001110 = 0x4E */
+
+    /* Port 4: CS */
+    P4SEL = 0x02;    /* Port4 Select: 00000010 = 0x02 */
+    P4OUT = 0x04;    /* Port4 Output: 00000100 = 0x04 */
+    P4DIR = 0x64;    /* Port4 Direction: 01100100 = 0x64 */
+
+    /* Port 5: SPI, LED */
+    P5SEL = 0x00;    /* Port5 Select: 00000000 = 0x00 */
+    P5OUT = 0x70;    /* Port5 Output: 01110000 = 0x70 */
+    P5DIR = 0x70;    /* Port5 Direction: 01110000 = 0x70 */
+
+
+    P6SEL = 0xFF;    /* Port6 Select: 11111111 = 0xFF */
+    P6OUT = 0x00;    /* Port6 Output: 00000000 = 0x00 */
+    P6DIR = 0xFF;    /* Port6 Direction: 11111000 = 0xFF */
+
+}
+
+/*---------------------------------------------------------------------------*/
+/* taken from Contiki code */
+void msp430_init_dco(void)
+{
+    /* This code taken from the FU Berlin sources and reformatted. */
+#define DELTA    (F_CPU / (F_RC_OSCILLATOR / 8))
+
+    unsigned int compare, oldcapture = 0;
+    unsigned int i;
+
+    /* 10100100 = XT2 is off, ACLK divided by 4, RSELx=4 */
+    BCSCTL1 = XT2OFF | DIVA_2 | RSEL2;
+
+    /* Init undivided DCO with internal resistor for MCLK and SMCLK
+     * DCO = 32762Hz -> FLL = 2,4576 MHz */
+    BCSCTL2 = 0x00;
+
+    BCSCTL1 |= DIVA1 + DIVA0;             /* ACLK = LFXT1CLK/8 */
+
+    for (i = 0xFFFF; i > 0; i--) {        /* Delay for XTAL to settle */
+        asm("nop");
+    }
+
+    CCTL2 = CCIS0 + CM0 + CAP;            /* Define CCR2, CAP, ACLK */
+    TACTL = TASSEL1 + TACLR + MC1;        /* SMCLK, continous mode */
+
+    while (1) {
+        while ((CCTL2 & CCIFG) != CCIFG);   /* Wait until capture occured!*/
+
+        CCTL2 &= ~CCIFG;                    /* Capture occured, clear flag */
+        compare = CCR2;                     /* Get current captured SMCLK */
+        compare = compare - oldcapture;     /* SMCLK difference */
+        oldcapture = CCR2;                  /* Save current captured SMCLK */
+
+        if (DELTA == compare) {
+            break;                            /* if equal, leave "while (1)" */
+        }
+        else if (DELTA < compare) {        /* DCO is too fast, slow it down */
+            DCOCTL--;
+
+            if (DCOCTL == 0xFF) {             /* Did DCO role under? */
+                BCSCTL1--;
+            }
+        }
+        else {                            /* -> Select next lower RSEL */
+            DCOCTL++;
+
+            if (DCOCTL == 0x00) {             /* Did DCO role over? */
+                BCSCTL1++;
+            }
+
+            /* -> Select next higher RSEL  */
+        }
+    }
+
+    CCTL2 = 0;                            /* Stop CCR2 function */
+    TACTL = 0;                            /* Stop Timer_A */
+
+    BCSCTL1 &= ~(DIVA1 + DIVA0);          /* remove /8 divisor from ACLK again */
+}
+
+
+//=========================== public ==========================================
+
+void board_init(void)
+{
+    msp430_cpu_init();
+    /* disable watchdog timer */
+    WDTCTL     =  WDTPW + WDTHOLD;
+
+    telosb_ports_init();
+
+    msp430_init_dco();
+
+    /* initialize bsp modules */
+    uart_init();
+
+    /* enable interrupts */
+    __bis_SR_register(GIE);
+}
diff --git a/telosb/driver_cc2420.c b/telosb/driver_cc2420.c
new file mode 100644
index 0000000000000000000000000000000000000000..4ee7ce9d1d43f7d126ff871b0fb7174fdca45e63
--- /dev/null
+++ b/telosb/driver_cc2420.c
@@ -0,0 +1,222 @@
+  /*
+   * driver_cc2420.c - Implementation of the board dependent cc2420 functions.
+   * Copyright (C) 2005, 2006, 2007, 2008 by Thomas Hillebrandt and Heiko Will
+   * Copyright (C) 2013 Oliver Hahm <oliver.hahm@inria.fr>
+   *
+   * This source code is licensed under the GNU Lesser General Public License,
+   * Version 2.  See the file LICENSE for more details.
+   */
+
+#include <stdio.h>
+
+#include <board.h>
+#include <cpu.h>
+#include <irq.h>
+#include <hwtimer.h>
+
+#include <cc2420.h>
+
+#define ENABLE_DEBUG    (1)
+#include "debug.h"
+
+#define CC2420_RESETn_PIN   0x40
+#define CC2420_VREGEN_PIN   0x20
+
+#define CC2420_FIFOP_PIN    0x01
+#define CC2420_GIO0_PIN     0x08
+#define CC2420_GIO1_PIN     0x10
+#define CC2420_CCA_PIN      0x40
+#define CC2420_SFD_PIN      0x02
+
+#define CC2420_FIFOP        (P1IN & CC2420_FIFOP_PIN)   /* FIFOP <-> packet interrupt (P1.0) */
+#define CC2420_GIO0         (P1IN & CC2420_GIO0_PIN)    /* FIFO  <-> GIO0 - RX data available (P1.3) */
+#define CC2420_GIO1         (P1IN & CC2420_GIO1_PIN)    /* CCA   <-> GIO1 - clear channel (P1.4) */
+#define CC2420_SFD          (P4IN & CC2420_SFD_PIN)     /* SFD   <-> TBL - start frame delimiter (P4.1) */
+
+#define CC2420_CS_LOW       (P4OUT &= ~0x04)            /* P4.2 */
+#define CC2420_CS_HIGH      (P4OUT |= 0x04)
+
+volatile int abort_count;
+volatile int retry_count = 0;
+
+void cc2420_reset(void)
+{
+    P4OUT |= CC2420_VREGEN_PIN;
+    P4OUT &= ~CC2420_RESETn_PIN;
+    hwtimer_wait(500);
+    P4OUT |= CC2420_RESETn_PIN;
+}
+
+void cc2420_gio0_enable(void)
+{
+    P1IFG &= ~CC2420_GIO0_PIN;     /* Clear IFG for GIO0 */
+    P1IE |= CC2420_GIO0_PIN;       /* Enable interrupt for GIO0 */
+}
+
+void cc2420_gio0_disable(void)
+{
+    P1IE &= ~CC2420_GIO0_PIN;      /* Disable interrupt for GIO0 */
+    P1IFG &= ~CC2420_GIO0_PIN;     /* Clear IFG for GIO0 */
+}
+
+void cc2420_gio1_enable(void)
+{
+    P1IFG &= ~CC2420_GIO1_PIN;     /* Clear IFG for GIO1 */
+    P1IE |= CC2420_GIO1_PIN;       /* Enable interrupt for GIO1 */
+}
+
+void cc2420_gio1_disable(void)
+{
+    P1IE &= ~CC2420_GIO1_PIN;      /* Disable interrupt for GIO1 */
+    P1IFG &= ~CC2420_GIO1_PIN;     /* Clear IFG for GIO1 */
+}
+
+void cc2420_before_send(void)
+{
+    /* Disable SFD interrupt before sending packet */
+    /* However this is not used atm */
+}
+
+void cc2420_after_send(void)
+{
+    /* Enable SFD interrupt after sending packet */
+    /* However this is not used atm */
+}
+
+
+int cc2420_get_gio0(void)
+{
+    return  CC2420_GIO0;
+}
+
+int cc2420_get_gio1(void)
+{
+    return  CC2420_GIO1;
+}
+
+int cc2420_get_fifop(void)
+{
+    return  CC2420_FIFOP;
+}
+
+int cc2420_get_sfd(void)
+{
+    return CC2420_SFD;
+}
+
+void cc2420_spi_cs(void)
+{
+    CC2420_CS_LOW;
+}
+
+uint8_t cc2420_txrx(uint8_t data)
+{
+    /* Ensure TX Buf is empty */
+    long c = 0;
+    IFG1 &= ~UTXIFG0;
+    IFG1 &= ~URXIFG0;
+    U0TXBUF = data;
+    while(!(IFG1 & UTXIFG0)) {
+        if (c++ == 1000000) {
+            puts("cc2420_txrx alarm()");
+        }
+    }
+    /* Wait for Byte received */
+    c = 0;
+    while(!(IFG1 & URXIFG0)) {
+        if (c++ == 1000000) {
+            puts("cc2420_txrx alarm()");
+        }
+    }
+    return U0RXBUF;
+}
+
+
+void cc2420_spi_select(void)
+{
+    CC2420_CS_LOW;
+}
+
+void cc2420_spi_unselect(void) {
+    CC2420_CS_HIGH;
+}
+
+void cc2420_init_interrupts(void)
+{
+    unsigned int state = disableIRQ();  /* Disable all interrupts */
+    P1SEL &= ~CC2420_FIFOP_PIN;         /* must be <> 1 to use interrupts */
+    P1SEL &= ~CC2420_GIO0_PIN;         /* must be <> 1 to use interrupts */
+
+    /* FIFO <-> GIO0 interrupt */
+    P1IES |= CC2420_GIO0_PIN;      /* Enables external interrupt on falling edge (for GIO0/FIFO) */
+    P1IE |= CC2420_GIO0_PIN;       /* Enable interrupt */
+    P1IFG &= ~CC2420_GIO0_PIN;     /* Clears the interrupt flag */
+
+    /* FIFOP <-> Packet interrupt */
+    P1IE |= CC2420_FIFOP_PIN;      /* Enable interrupt for FIFOP */
+    P1IFG &= ~CC2420_FIFOP_PIN;     /* Clear IFG for FIFOP */
+    restoreIRQ(state);              /* Enable all interrupts */
+}
+
+void cc2420_spi_init(void)
+{
+    /* Switch off async UART */
+    while(!(U0TCTL & TXEPT));   /* Wait for empty UxTXBUF register */
+    IE1 &= ~(URXIE0 + UTXIE0);  /* Disable USART0 receive&transmit interrupt */
+    ME1 &= ~(UTXE0 + URXE0);
+
+    /* configure SPI-related pins */
+    P3SEL     |=  0x0E;                           /* P3.1 -  SIMO mode, P3.2 - SOMI mode, P3.3 - SCL mode */
+    P3DIR     |=  0x0A;                           /* P3.1 and P3.3 as output */
+    P3DIR     &= ~(0x04);                         /* P3.2 as input for SOMI */
+    P4OUT     |=  0x04;                           /* P4.2 radio CS, hold high */
+    P4DIR     |=  0x04;                           /* P4.2 radio CS, output */
+ 
+    /* Keep peripheral in reset state */
+    U0CTL  = SWRST;
+
+    /* 8-bit SPI Master 3-pin mode, with SMCLK as clock source */
+    /* CKPL works also, but not CKPH+CKPL or none of them!! */
+    U0CTL |= CHAR + SYNC + MM;
+    U0TCTL = CKPH + SSEL1 + SSEL0 + STC + TXEPT;;
+    
+    /* Ignore clockrate argument for now, just use clock source/2 */
+    /* SMCLK = 8 MHz */
+    U0BR0 = 0x02;  /* Ensure baud rate >= 2 */
+    U0BR1 = 0x00;
+    U0MCTL = 0x00; /* No modulation */
+    U0RCTL = 0x00; /* Reset Receive Control Register */
+   
+    /* Enable SPI mode */
+    ME1 |= USPIE0;
+
+    /* Release for operation */
+    U0CTL  &= ~SWRST;
+}
+
+/*
+ * CC1100 receive interrupt
+ */
+interrupt (PORT1_VECTOR) __attribute__ ((naked)) cc2420_isr(void)
+{
+    __enter_isr();
+     /* Check IFG */
+    if ((P1IFG & CC2420_FIFOP_PIN) != 0) {
+        P1IFG &= ~CC2420_FIFOP_PIN;
+        cc2420_rx_irq();
+        DEBUG("rx interrupt");
+    }
+    /* GIO0 is falling => check if FIFOP is high, indicating an RXFIFO overflow */
+    else if ((P1IFG & CC2420_GIO0) != 0) {
+        P1IFG &= ~CC2420_GIO0_PIN;
+        if (cc2420_get_fifop()) {
+            cc2420_rxoverflow_irq();
+            DEBUG("[CC2420] rxfifo overflow");
+        }
+    }
+    else {
+        puts("cc2420_isr(): unexpected IFG!");
+        /* Should not occur - only GDO1 and GIO1 interrupts are enabled */
+    }
+    __exit_isr();
+}
diff --git a/telosb/include/board-conf.h b/telosb/include/board-conf.h
new file mode 100644
index 0000000000000000000000000000000000000000..f65074da9d00a2e5447f6d442a58f203a714fdd7
--- /dev/null
+++ b/telosb/include/board-conf.h
@@ -0,0 +1,13 @@
+/**
+  * board-conf.h.
+  *
+  * This source code is licensed under the GNU Lesser General Public License,
+  * Version 2.  See the file LICENSE for more details.
+  */
+
+#ifndef BOARD_CONF_H
+#define BOARD_CONF_H
+
+#define INFOMEM     (0x1000)
+
+#endif /* BOARD-CONF_H */
diff --git a/telosb/include/board.h b/telosb/include/board.h
new file mode 100644
index 0000000000000000000000000000000000000000..18b064d17202020b8bf02869bd6e9e8dbfe57f61
--- /dev/null
+++ b/telosb/include/board.h
@@ -0,0 +1,58 @@
+/**
+  * board.h - TelosB Board.
+  * Copyright (C) 2013 INRIA
+  *
+  * This source code is licensed under the GNU Lesser General Public License,
+  * Version 2.  See the file LICENSE for more details.
+  */
+
+#ifndef _TELOSB_BOARD_H
+#define _TELOSB_BOARD_H
+
+/**
+ * @defgroup    TelosB
+ * @ingroup		TelosB
+ *
+<h2>Compontents</h2>
+\li MSP430
+\li CC2420
+
+* @{
+*/
+
+/**
+ * @file
+ * @brief		TelosB Board
+ *
+ * @author      Oliver Hahm <oliver.hahm@inria.fr>
+ *
+ */
+
+//MSB430 core
+#define MSP430_INITIAL_CPU_SPEED    8000000uL
+#define MSP430_HAS_DCOR             0
+#define MSP430_HAS_EXTERNAL_CRYSTAL 1
+
+/* LEDs ports MSB430 */
+#define LEDS_PxDIR P5DIR
+#define LEDS_PxOUT P5OUT
+#define LEDS_CONF_RED		0x10
+#define LEDS_CONF_GREEN		0x20
+#define LEDS_CONF_BLUE	0x40
+
+#define LED_RED_ON      LEDS_PxOUT &=~LEDS_CONF_RED
+#define LED_RED_OFF     LEDS_PxOUT |= LEDS_CONF_RED
+#define LED_RED_TOGGLE     LEDS_PxOUT ^= LEDS_CONF_RED
+
+#define LED_GREEN_ON      LEDS_PxOUT &=~LEDS_CONF_GREEN
+#define LED_GREEN_OFF     LEDS_PxOUT |= LEDS_CONF_GREEN
+#define LED_GREEN_TOGGLE     LEDS_PxOUT ^= LEDS_CONF_GREEN
+
+#define LED_BLUE_ON      LEDS_PxOUT &=~LEDS_CONF_BLUE
+#define LED_BLUE_OFF     LEDS_PxOUT |= LEDS_CONF_BLUE
+#define LED_BLUE_TOGGLE     LEDS_PxOUT ^= LEDS_CONF_BLUE
+
+#include <msp430x16x.h>
+
+/** @} */
+#endif // _TELOSB_BOARD_H
diff --git a/telosb/uart.c b/telosb/uart.c
new file mode 100644
index 0000000000000000000000000000000000000000..1e97bfb569715401d35288b6163d044cab7f1f73
--- /dev/null
+++ b/telosb/uart.c
@@ -0,0 +1,118 @@
+/*
+ * uart.c - Implementation for the TelosB UART
+ * Copyright (C) 2013 Oliver Hahm <oliver.hahm@inria.fr>
+ *
+ * This file subject to the terms and conditions of the LGPLv2. See the file
+ * LICENSE in the top level directory for more details.
+ */
+
+#include <stdio.h>
+#include <stdint.h>
+#include "cpu.h"
+#include "board.h"
+#include "kernel.h"
+#include "board_uart0.h"
+
+#define   UART1_TX                  U1TXBUF
+#define   UART1_WAIT_TXDONE()       while ( (U1TCTL & TXEPT) == 0 ) { _NOP(); }
+
+#define BAUDRATE    (115200ul)
+
+static uint8_t calc_umctl(uint16_t br)
+{
+    /* from TI slaa049 */
+    register uint8_t CMOD = 256 * br - 256 * (br + 1) / 2;
+    register uint8_t c = 0;
+    register int i = 0;
+    register uint8_t a = CMOD;
+    a <<= 1;
+
+    do {
+        if (a & 0x80) {            /* Overflow to integer? */
+            a = a - 128 + CMOD;    /* Yes, subtract 1.000000 */
+            c |= 0x80;
+        }
+        else {
+            a += CMOD;              /* No, add fraction */
+        }
+
+        if (i == 7) {
+            return c;
+        }
+
+        i++;
+        c >>= 1;
+    }
+    while (1);
+}
+
+void uart_init(void)
+{
+    UCTL1     =  SWRST;           /* hold UART1 module in reset */
+    UCTL1    |=  CHAR;            /* 8-bit character */
+
+    /* 115200 baud, clocked from 4.8MHz SMCLK */
+    UTCTL1   |= SSEL1;        /* UCLK = SCLK */
+    UBR01     = F_CPU / BAUDRATE;
+    UBR11     = (F_CPU / BAUDRATE) >> 8;
+    UMCTL1    = calc_umctl(F_CPU / BAUDRATE);       /* set modulation */
+
+    ME2      |=  UTXE1 + URXE1;   /* enable UART1 TX/RX */
+    UCTL1    &= ~SWRST;           /* clear UART1 reset bit */
+
+    IE2  |= URXIE1;               /* enable rx interrupt */
+    IFG1 &= ~UTXIFG1;
+}
+
+int putchar(int c)
+{
+    UART1_TX = c;
+    UART1_WAIT_TXDONE();
+    return c;
+}
+
+uint8_t uart_readByte(void)
+{
+    return U1RXBUF;
+}
+
+void usart1irq(void);
+/**
+ * \brief the interrupt function
+ */
+interrupt(USART1RX_VECTOR) usart1irq(void)
+{
+    int c = 0;
+
+    /* Check status register for receive errors. */
+    if (U1RCTL & RXERR) {
+        if (U1RCTL & FE) {
+            puts("rx framing error");
+        }
+
+        if (U1RCTL & OE) {
+            puts("rx overrun error");
+        }
+
+        if (U1RCTL & PE) {
+            puts("rx parity error");
+        }
+
+        if (U1RCTL & BRK) {
+            puts("rx break error");
+        }
+
+        /* Clear error flags by forcing a dummy read. */
+        c = U1RXBUF;
+    }
+
+#ifdef MODULE_UART0
+    else if (uart0_handler_pid) {
+        c = U1RXBUF;
+        uart0_handle_incoming(c);
+        uart0_notify_thread();
+    }
+
+#endif
+}
+