diff --git a/boards/arduino-mega2560/Makefile b/boards/arduino-mega2560/Makefile
new file mode 100644
index 0000000000000000000000000000000000000000..aa1b315c5d7f9bdc411079eac899d17ea7692a3b
--- /dev/null
+++ b/boards/arduino-mega2560/Makefile
@@ -0,0 +1,3 @@
+MODULE = $(BOARD)_base
+
+include $(RIOTBASE)/Makefile.base
diff --git a/boards/arduino-mega2560/Makefile.include b/boards/arduino-mega2560/Makefile.include
new file mode 100644
index 0000000000000000000000000000000000000000..1ed943f90b5ae36e6e01c5099702c39d81a3d3fb
--- /dev/null
+++ b/boards/arduino-mega2560/Makefile.include
@@ -0,0 +1,43 @@
+
+# define the cpu used by the arduino mega2560 board
+export CPU = atmega2560
+
+# define tools used for building the project
+export PREFIX = avr-
+export CC = $(PREFIX)gcc
+export CXX = $(PREFIX)c++
+export AR = $(PREFIX)ar
+export AS = $(PREFIX)as
+export LINK = $(PREFIX)gcc
+export SIZE = $(PREFIX)size
+export OBJCOPY = $(PREFIX)objcopy
+export TERMPROG = $(RIOTBASE)/dist/tools/pyterm/pyterm
+export TERMFLAGS = -b 38400 -p $(PORT)
+
+#define the flash-tool and default port depending on the host operating system
+OS = $(shell uname)
+ifeq ($(OS),Linux)
+  PORT ?= /dev/ttyACM0
+  FLASHER = avrdude
+#else ifeq ($(OS),Darwin)
+#  PORT ?=
+#  FLASHER =
+else
+  $(info CAUTION: No flash tool for your host system found!)
+  # TODO: fix for building under windows/MacOS
+endif
+export FLASHER
+export PORT
+
+# define build specific options
+export CPU_USAGE = -mmcu=atmega2560
+export CFLAGS += -ggdb -g3 -std=gnu99 -Os -Wall -Wstrict-prototypes $(CPU_USAGE)
+export ASFLAGS += -ggdb -g3 $(CPU_USAGE) $(FPU_USAGE)
+export LINKFLAGS += -g3 -ggdb -std=gnu99 $(CPU_USAGE) $(FPU_USAGE) -static -lgcc -e reset_handler
+# linkerscript specified in cpu/Makefile.include
+#export LINKFLAGS += -T$(LINKERSCRIPT)
+export OFLAGS += -j .text -j .data -O ihex
+export FFLAGS += -p m2560 -c stk500v2 -P $(PORT) -b 115200 -F -U flash:w:bin/$(BOARD)/$(PROJECT)$(APPLICATION).hex
+
+# export board specific includes to the global includes-listing
+export INCLUDES += -I$(RIOTBOARD)/$(BOARD)/include
diff --git a/boards/arduino-mega2560/board.c b/boards/arduino-mega2560/board.c
new file mode 100644
index 0000000000000000000000000000000000000000..4aac6d761c540e87fedbddb5792294c175ea1af5
--- /dev/null
+++ b/boards/arduino-mega2560/board.c
@@ -0,0 +1,148 @@
+/*
+ * Copyright (C) 2014 Freie Universität Berlin, Hinnerk van Bruinehsen
+ *
+ * This file is subject to the terms and conditions of the GNU Lesser
+ * General Public License v2.1. See the file LICENSE in the top level
+ * directory for more details.
+ */
+
+/**
+ * @ingroup     board_arduino-mega2560
+ * @{
+ *
+ * @file        board.c
+ * @brief       Board specific implementations for the Arduino Mega 2560 board
+ *
+ * @author      Hinnerk van Bruinehsen <h.v.bruinehsen@fu-berlin.de>
+ *
+ * @}
+ */
+
+#include <stdio.h>
+#include <avr/io.h>
+
+#include "board.h"
+#include "cpu.h"
+#include "periph/uart.h"
+
+#ifndef MODULE_UART0
+#include "ringbuffer.h"
+#include "mutex.h"
+#endif
+
+#ifdef MODULE_UART0
+#include "board_uart0.h"
+#endif
+
+/**
+ * @brief use mutex for waiting on incoming UART chars
+ */
+#ifndef MODULE_UART0
+static mutex_t uart_rx_mutex;
+static char rx_buf_mem[STDIO_RX_BUFSIZE];
+static ringbuffer_t rx_buf;
+#endif
+
+void led_init(void);
+void SystemInit(void);
+static int uart_putchar(unsigned char c, FILE *stream);
+static char uart_getchar(FILE *stream);
+
+static FILE uart_stdout = FDEV_SETUP_STREAM(uart_putchar, NULL, _FDEV_SETUP_WRITE);
+static FILE uart_stdin = FDEV_SETUP_STREAM(NULL, uart_getchar, _FDEV_SETUP_READ);
+
+
+/**
+ * @brief Receive a new character from the UART and put it into the receive
+ * buffer
+ *
+ * @param[in] data    the newly received byte
+ */
+
+void rx_cb(void *arg, char data)
+{
+    LED_TOGGLE;
+#ifndef MODULE_UART0
+    ringbuffer_add_one(&rx_buf, data);
+    mutex_unlock(&uart_rx_mutex);
+#elif MODULE_UART0
+
+    if (uart0_handler_pid) {
+        uart0_handle_incoming(data);
+        uart0_notify_thread();
+    }
+
+#endif
+}
+
+void board_init(void)
+{
+    /* initialize stdio via USART_0 */
+    SystemInit();
+
+    /* initialize the CPU */
+    cpu_init();
+
+    /* initialize the boards LEDs */
+    led_init();
+
+    enableIRQ();
+}
+
+
+/**
+ * @brief Initialize the boards on-board LED (Amber LED "L")
+ *
+ * The LED initialization is hard-coded in this function. As the LED is soldered
+ * onto the board it is fixed to its CPU pins.
+ *
+ * The LED is connected to the following pin:
+ * - LED: PB27
+ */
+void led_init(void)
+{
+    LED_ENABLE_PORT;
+    LED_ON;
+}
+
+/**
+ * @brief Initialize the System, initialize IO via UART_0
+ */
+void SystemInit(void)
+{
+    /* initialize UART_0 for use as stdout */
+#ifndef MODULE_UART0
+    mutex_init(&uart_rx_mutex);
+    ringbuffer_init(&rx_buf, rx_buf_mem, STDIO_RX_BUFSIZE);
+#endif
+    uart_init(STDIO, STDIO_BAUDRATE, (uart_rx_cb_t) rx_cb, NULL, NULL);
+
+    stdout = &uart_stdout;
+    stdin = &uart_stdin;
+
+    /* Flush stdout */
+    puts("\f");
+}
+
+static int uart_putchar(unsigned char c, FILE *stream)
+{
+    uart_write_blocking(UART_0, c);
+    return 0;
+}
+
+char uart_getchar(FILE *stream)
+{
+#ifndef MODULE_UART0
+
+    if (rx_buf.avail == 0) {
+        mutex_lock(&uart_rx_mutex);
+    }
+
+    return ringbuffer_get_one(&rx_buf);
+#else
+    LED_TOGGLE;
+    char temp;
+    temp = (char) uart0_readc();
+    return temp;
+#endif
+}
diff --git a/boards/arduino-mega2560/include/board.h b/boards/arduino-mega2560/include/board.h
new file mode 100644
index 0000000000000000000000000000000000000000..352aea0e9d78ddb143a8b6798029c7dccdd72377
--- /dev/null
+++ b/boards/arduino-mega2560/include/board.h
@@ -0,0 +1,80 @@
+/*
+ * Copyright (C) 2014 Freie Universität Berlin, Hinnerk van Bruinehsen
+ *
+ * This file is subject to the terms and conditions of the GNU Lesser
+ * General Public License v2.1. See the file LICENSE in the top level
+ * directory for more details.
+ */
+
+/**
+ * @defgroup    board_arduino-mega2560 Arduino Mega 2560
+ * @ingroup     boards
+ * @brief       Board specific files for the Arduino Mega 2560 board.
+ * @{
+ *
+ * @file
+ * @brief       Board specific definitions for the Arduino Mega 2560 board.
+ *
+ * @author      Hinnerk van Bruinehsen <h.v.bruinehsen@fu-berlin.de>
+ */
+
+#ifndef __BOARD_H
+#define __BOARD_H
+
+#include "cpu.h"
+
+/**
+ * Define the nominal CPU core clock in this board
+ */
+#define F_CPU               (16000000L)
+
+
+/**
+ * Assign the hardware timer
+ */
+#define HW_TIMER            TIMER_0
+
+/**
+* @name Define UART device and baudrate for stdio
+* @{
+*/
+#define STDIO UART_0
+#define STDIO_BAUDRATE (38400U)
+#define STDIO_RX_BUFSIZE (64U)
+/** @} */
+
+/**
+ * @name LED pin definitions
+ * @{
+ */
+#define LED_PORT            PORTB
+#define LED_PIN             (1 << 7)
+/** @} */
+
+/**
+ * @name Macros for controlling the on-board LEDs.
+ * @{
+ */
+#define LED_ENABLE_PORT     DDRB |= (1 << DDB7)
+#define LED_ON              LED_PORT |= LED_PIN
+#define LED_OFF             LED_PORT &= ~LED_PIN
+#define LED_TOGGLE          LED_PORT ^= LED_PIN;
+
+/* for compatability to other boards */
+#define LED_GREEN_ON        LED_ON
+#define LED_GREEN_OFF       LED_OFF
+#define LED_GREEN_TOGGLE    LED_TOGGLE
+#define LED_RED_ON          /* not available */
+#define LED_RED_OFF         /* not available */
+#define LED_RED_TOGGLE      /* not available */
+/** @} */
+
+
+/**
+ * @brief Initialize board specific hardware, including clock, LEDs and std-IO
+ */
+void board_init(void);
+
+
+#endif /** __BOARD_H */
+/** @} */
diff --git a/boards/arduino-mega2560/include/periph_conf.h b/boards/arduino-mega2560/include/periph_conf.h
new file mode 100644
index 0000000000000000000000000000000000000000..4bfe9f18e510c84d3b2c319540c0af1ba624a770
--- /dev/null
+++ b/boards/arduino-mega2560/include/periph_conf.h
@@ -0,0 +1,282 @@
+/*
+ * Copyright (C) 2014 Freie Universität Berlin, Hinnerk van Bruinehsen
+ *
+ * This file is subject to the terms and conditions of the GNU Lesser
+ * General Public License v2.1. See the file LICENSE in the top level
+ * directory for more details.
+ */
+
+/**
+ * @ingroup     board_arduino-mega2560
+ * @{
+ *
+ * @file
+ * @brief       Peripheral MCU configuration for the Arduino Mega 2560 board
+ *
+ * @author      Hinnerk van Bruinehsen <h.v.bruinehsen@fu-berlin.de>
+ */
+
+#ifndef __PERIPH_CONF_H
+#define __PERIPH_CONF_H
+
+
+/**
+ * @name        Timer peripheral configuration
+ * @brief       The ATmega2560 has 6 timers. Timer0 and Timer2 are 8 Bit Timers,
+ *              Timer0 has special uses too and therefore we'll avoid using it.
+ *              Timer5 has special uses with certain Arduino Shields, too.
+ *              Therefore we'll also avoid using Timer5.
+ *              This results in the following mapping to use the left over 16 Bit
+ *              timers:
+ *
+ *              Timer1 -> TIMER_0
+ *              Timer3 -> TIMER_1
+ *              Timer4 -> TIMER_2
+ *
+ * @{
+ */
+#define TIMER_NUMOF         (3U)
+#define TIMER_0_EN          1
+#define TIMER_1_EN          0
+#define TIMER_2_EN          0
+
+/* Timer 0 configuration */
+#define TIMER_0_CHANNELS    3
+#define TIMER_0_MAX_VALUE   (0xffff)
+
+/* Timer 0 register and flags */
+#define TIMER0_CONTROL_A    TCCR1A
+#define TIMER0_CONTROL_B    TCCR1B
+#define TIMER0_CONTROL_C    TCCR1C
+#define TIMER0_COUNTER      TCNT1
+#define TIMER0_IRQ_FLAG_REG TIFR1
+#define TIMER0_IRQ_MASK_REG TIMSK1
+#define TIMER0_COMP_A       OCR1A
+#define TIMER0_COMP_B       OCR1B
+#define TIMER0_COMP_C       OCR1C
+#define TIMER0_COMP_A_FLAG  OCF1A
+#define TIMER0_COMP_B_FLAG  OCF1B
+#define TIMER0_COMP_C_FLAG  OCF1C
+#define TIMER0_COMP_A_EN    OCIE1A
+#define TIMER0_COMP_B_EN    OCIE1B
+#define TIMER0_COMP_C_EN    OCIE1C
+#define TIMER0_FREQ_16MHZ   (0 << CS12) | (0 << CS11) | (1 << CS10)
+#define TIMER0_FREQ_DISABLE (0 << CS12) | (0 << CS11) | (0 << CS10)
+#define TIMER0_COMPA_ISR    TIMER1_COMPA_vect
+#define TIMER0_COMPB_ISR    TIMER1_COMPB_vect
+#define TIMER0_COMPC_ISR    TIMER1_COMPC_vect
+
+/* Timer 1 configuration */
+#define TIMER_1_CHANNELS    3
+#define TIMER_1_MAX_VALUE   (0xffff)
+
+/* Timer 1 register and flags */
+#define TIMER1_CONTROL_A    TCCR3A
+#define TIMER1_CONTROL_B    TCCR3B
+#define TIMER1_CONTROL_C    TCCR3C
+#define TIMER1_COUNTER      TCNT3
+#define TIMER1_IRQ_FLAG_REG TIFR3
+#define TIMER1_IRQ_MASK_REG TIMSK3
+#define TIMER1_COMP_A       OCR3A
+#define TIMER1_COMP_B       OCR3B
+#define TIMER1_COMP_C       OCR3C
+#define TIMER1_COMP_A_FLAG  OCF3A
+#define TIMER1_COMP_B_FLAG  OCF3B
+#define TIMER1_COMP_C_FLAG  OCF3C
+#define TIMER1_COMP_A_EN    OCIE3A
+#define TIMER1_COMP_B_EN    OCIE3B
+#define TIMER1_COMP_C_EN    OCIE3C
+#define TIMER1_FREQ_16MHZ   (0 << CS32) | (0 << CS31) | (1 << CS30)
+#define TIMER1_FREQ_DISABLE (0 << CS32) | (0 << CS31) | (0 << CS30)
+#define TIMER1_COMPA_ISR    TIMER3_COMPA_vect
+#define TIMER1_COMPB_ISR    TIMER3_COMPB_vect
+#define TIMER1_COMPC_ISR    TIMER3_COMPC_vect
+
+/* Timer 2 configuration */
+#define TIMER_2_CHANNELS    3
+#define TIMER_2_MAX_VALUE   (0xffff)
+
+/* Timer 2 register and flags */
+#define TIMER2_CONTROL_A    TCCR4A
+#define TIMER2_CONTROL_B    TCCR4B
+#define TIMER2_CONTROL_C    TCCR4C
+#define TIMER2_COUNTER      TCNT4
+#define TIMER2_IRQ_FLAG_REG TIFR4
+#define TIMER2_IRQ_MASK_REG TIMSK4
+#define TIMER2_COMP_A       OCR4A
+#define TIMER2_COMP_B       OCR4B
+#define TIMER2_COMP_C       OCR4C
+#define TIMER2_COMP_A_FLAG  OCF4A
+#define TIMER2_COMP_B_FLAG  OCF4B
+#define TIMER2_COMP_C_FLAG  OCF4C
+#define TIMER2_COMP_A_EN    OCIE4A
+#define TIMER2_COMP_B_EN    OCIE4B
+#define TIMER2_COMP_C_EN    OCIE4C
+#define TIMER2_FREQ_16MHZ   (0 << CS42) | (0 << CS41) | (1 << CS40)
+#define TIMER2_FREQ_DISABLE (0 << CS42) | (0 << CS41) | (0 << CS40)
+#define TIMER2_COMPA_ISR    TIMER4_COMPA_vect
+#define TIMER2_COMPB_ISR    TIMER4_COMPB_vect
+#define TIMER2_COMPC_ISR    TIMER4_COMPC_vect
+
+/**
+ * @name UART configuration
+ * @{
+ */
+#define UART_NUMOF          (1U)
+#define UART_0_EN           1
+#define UART_1_EN           0
+#define UART_2_EN           0
+#define UART_3_EN           0
+
+/* UART 0 registers */
+#define UART0_CTRL_STAT_A   UCSR0A
+#define UART0_CTRL_STAT_B   UCSR0B
+#define UART0_CTRL_STAT_C   UCSR0C
+#define UART0_BAUD_RATE_L   UBRR0L
+#define UART0_BAUD_RATE_H   UBRR0H
+#define UART0_DATA_REGISTER UDR0
+
+/* Flags */
+#define UART0_RX_COMPLETE   RXC0
+#define UART0_DATA_EMPTY    UDRE0
+#define UART0_RX_EN         RXEN0
+#define UART0_TX_EN         TXEN0
+#define UART0_RXC_IRQ_EN    RXCIE0
+#define UART0_TXC_IRQ_EN    TXCIE0
+#define UART0_8BIT_SIZE     (1 << UCSZ00) | (1 << UCSZ01)
+
+/* UART0 helper macros */
+#define UART0_RX_TX_EN      UART0_CTRL_STAT_B |= (1 << UART0_RX_EN) | (1 << UART0_TX_EN)
+#define UART0_RX_IRQ_EN     UART0_CTRL_STAT_B |= (1 << UART0_RXC_IRQ_EN)
+#define UART0_SET_8BIT_SIZE UART0_CTRL_STAT_C |= UART0_8BIT_SIZE
+#define UART0_RECEIVED_DATA (UART0_CTRL_STAT_A & (1 << UART0_RX_COMPLETE))
+#define UART0_DTREG_EMPTY   (UART0_CTRL_STAT_A & (1 << UART0_DATA_EMPTY))
+
+/* UART 1 registers */
+#define UART1_CTRL_STAT_A   UCSR1A
+#define UART1_CTRL_STAT_B   UCSR1B
+#define UART1_CTRL_STAT_C   UCSR1C
+#define UART1_BAUD_RATE_L   UBRR1L
+#define UART1_BAUD_RATE_H   UBRR1H
+#define UART1_DATA_REGISTER UDR1
+
+/* Flags */
+#define UART1_RX_COMPLETE   RXC1
+#define UART1_DATA_EMPTY    UDRE1
+#define UART1_RX_EN         RXEN1
+#define UART1_TX_EN         TXEN1
+#define UART1_RXC_IRQ_EN    RXCIE1
+#define UART1_TXC_IRQ_EN    TXCIE1
+#define UART1_8BIT_SIZE     (1 << UCSZ10) | (1 << UCSZ11)
+
+/* UART1 helper macros */
+#define UART1_RX_TX_EN      UART1_CTRL_STAT_B |= (1 << UART1_RX_EN) | (1 << UART1_TX_EN)
+#define UART1_RX_IRQ_EN     UART1_CTRL_STAT_B |= (1 << UART1_RXC_IRQ_EN)
+#define UART1_SET_8BIT_SIZE UART1_CTRL_STAT_C |= UART1_8BIT_SIZE
+#define UART1_RECEIVED_DATA (UART1_CTRL_STAT_A & (1 << UART1_RX_COMPLETE))
+#define UART1_DTREG_EMPTY   (UART1_CTRL_STAT_A & (1 << UART1_DATA_EMPTY))
+
+/* UART 2 registers */
+#define UART2_CTRL_STAT_A   UCSR2A
+#define UART2_CTRL_STAT_B   UCSR2B
+#define UART2_CTRL_STAT_C   UCSR2C
+#define UART2_BAUD_RATE_L   UBRR2L
+#define UART2_BAUD_RATE_H   UBRR2H
+#define UART2_DATA_REGISTER UDR2
+
+/* Flags */
+#define UART2_RX_COMPLETE   RXC2
+#define UART2_DATA_EMPTY    UDRE2
+#define UART2_RX_EN         RXEN2
+#define UART2_TX_EN         TXEN2
+#define UART2_RXC_IRQ_EN    RXCIE2
+#define UART2_TXC_IRQ_EN    TXCIE2
+#define UART2_8BIT_SIZE     (1 << UCSZ20) | (1 << UCSZ21)
+
+/* UART2 helper macros */
+#define UART2_RX_TX_EN      UART2_CTRL_STAT_B |= (1 << UART2_RX_EN) | (1 << UART2_TX_EN)
+#define UART2_RX_IRQ_EN     UART2_CTRL_STAT_B |= (1 << UART2_RXC_IRQ_EN)
+#define UART2_SET_8BIT_SIZE UART2_CTRL_STAT_C |= UART2_8BIT_SIZE
+#define UART2_RECEIVED_DATA (UART2_CTRL_STAT_A & (1 << UART2_RX_COMPLETE))
+#define UART2_DTREG_EMPTY   (UART2_CTRL_STAT_A & (1 << UART2_DATA_EMPTY))
+
+/* UART 2 registers */
+#define UART3_CTRL_STAT_A   UCSR3A
+#define UART3_CTRL_STAT_B   UCSR3B
+#define UART3_CTRL_STAT_C   UCSR3C
+#define UART3_BAUD_RATE_L   UBRR3L
+#define UART3_BAUD_RATE_H   UBRR3H
+#define UART3_DATA_REGISTER UDR3
+
+/* Flags */
+#define UART3_RX_COMPLETE   RXC3
+#define UART3_DATA_EMPTY    UDRE3
+#define UART3_RX_EN         RXEN3
+#define UART3_TX_EN         TXEN3
+#define UART3_RXC_IRQ_EN    RXCIE3
+#define UART3_TXC_IRQ_EN    TXCIE3
+#define UART3_8BIT_SIZE     (1 << UCSZ30) | (1 << UCSZ31)
+
+/* UART3 helper macros */
+#define UART3_RX_TX_EN      UART3_CTRL_STAT_B |= (1 << UART3_RX_EN) | (1 << UART3_TX_EN)
+#define UART3_RX_IRQ_EN     UART3_CTRL_STAT_B |= (1 << UART3_RXC_IRQ_EN)
+#define UART3_SET_8BIT_SIZE UART3_CTRL_STAT_C |= UART3_8BIT_SIZE
+#define UART3_RECEIVED_DATA (UART3_CTRL_STAT_A & (1 << UART3_RX_COMPLETE))
+#define UART3_DTREG_EMPTY   (UART3_CTRL_STAT_A & (1 << UART3_DATA_EMPTY))
+
+
+
+/* TODO: add defines for device agnostic implementation */
+/** @} */
+
+
+/**
+ * @brief ADC configuration
+ */
+#define ADC_NUMOF           (0U)
+#define ADC_0_EN            0
+#define ADC_1_EN            0
+
+/**
+ * @brief PWM configuration
+ */
+#define PWM_NUMOF           (0U)
+#define PWM_0_EN            0
+#define PWM_1_EN            0
+
+/**
+ * @brief SPI configuration
+ */
+#define SPI_NUMOF           (0U)                                                    /* TODO */
+#define SPI_0_EN            0
+#define SPI_1_EN            0
+
+/**
+ * @brief I2C configuration
+ */
+#define I2C_NUMOF           (0U)                                                    /* TODO */
+#define I2C_0_EN            0
+#define I2C_0_EN            0
+
+/**
+ * @brief GPIO configuration
+ */
+#define GPIO_NUMOF          (15U)
+#define GPIO_0_EN           0
+#define GPIO_1_EN           0
+#define GPIO_2_EN           0
+#define GPIO_3_EN           0
+#define GPIO_4_EN           0
+#define GPIO_5_EN           0
+#define GPIO_6_EN           0
+#define GPIO_7_EN           0
+#define GPIO_8_EN           0
+#define GPIO_9_EN           0
+#define GPIO_10_EN          0
+#define GPIO_11_EN          0
+#define GPIO_12_EN          0
+#define GPIO_13_EN          0
+#define GPIO_14_EN          0
+#define GPIO_15_EN          0
+
+#endif /* __PERIPH_CONF_H */
diff --git a/cpu/atmega2560/periph/timer.c b/cpu/atmega2560/periph/timer.c
index a8616c424510d2e572f29919217f45d7e159dc42..45d5b5b73d1141a5563b3da70f4e709da4b85fd0 100644
--- a/cpu/atmega2560/periph/timer.c
+++ b/cpu/atmega2560/periph/timer.c
@@ -119,7 +119,7 @@ int timer_clear(tim_t dev, int channel)
 {
 
     switch (dev) {
-#if TIMER_0_DIS
+#if TIMER_0_EN
 
         case TIMER_0:
             switch (channel) {
@@ -144,7 +144,7 @@ int timer_clear(tim_t dev, int channel)
 
             break;
 #endif
-#if TIMER_1_DIS
+#if TIMER_1_EN
 
         case TIMER_1:
             switch (channel) {
@@ -170,7 +170,7 @@ int timer_clear(tim_t dev, int channel)
 
             break;
 #endif
-#if TIMER_2_DIS
+#if TIMER_2_EN
 
         case TIMER_2:
             switch (channel) {