diff --git a/drivers/Makefile.dep b/drivers/Makefile.dep
index 11ea3d740e9739b9660e8ae52147a2b9fc837a03..a08bf70f66cef59cc00b6d8f0963c06e1e591956 100644
--- a/drivers/Makefile.dep
+++ b/drivers/Makefile.dep
@@ -30,6 +30,13 @@ ifneq (,$(filter at86rf2%,$(USEMODULE)))
   FEATURES_REQUIRED += periph_spi
 endif
 
+ifneq (,$(filter ata8520e,$(USEMODULE)))
+  USEMODULE += xtimer
+  USEMODULE += fmt
+  FEATURES_REQUIRED += periph_gpio
+  FEATURES_REQUIRED += periph_spi
+endif
+
 ifneq (,$(filter bh1750fvi,$(USEMODULE)))
   USEMODULE += xtimer
   FEATURES_REQUIRED += periph_i2c
diff --git a/drivers/Makefile.include b/drivers/Makefile.include
index e8b7d2160271f506d02a776f8aa8c129e5ad78dc..f175048f9b8d88f51f2d770bea8c4872c8d7a5ef 100644
--- a/drivers/Makefile.include
+++ b/drivers/Makefile.include
@@ -163,3 +163,6 @@ endif
 ifneq (,$(filter lis2dh12,$(USEMODULE)))
   USEMODULE_INCLUDES += $(RIOTBASE)/drivers/lis2dh12/include
 endif
+ifneq (,$(filter ata8520e,$(USEMODULE)))
+  USEMODULE_INCLUDES += $(RIOTBASE)/drivers/ata8520e/include
+endif
diff --git a/drivers/ata8520e/Makefile b/drivers/ata8520e/Makefile
new file mode 100644
index 0000000000000000000000000000000000000000..48422e909a47d7cd428d10fa73825060ccc8d8c2
--- /dev/null
+++ b/drivers/ata8520e/Makefile
@@ -0,0 +1 @@
+include $(RIOTBASE)/Makefile.base
diff --git a/drivers/ata8520e/ata8520e.c b/drivers/ata8520e/ata8520e.c
new file mode 100644
index 0000000000000000000000000000000000000000..7b1380cf5b622411671228406db88227bdd4441c
--- /dev/null
+++ b/drivers/ata8520e/ata8520e.c
@@ -0,0 +1,525 @@
+/*
+ * Copyright (C) 2017 Inria
+ *
+ * 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     drivers_ata8520e
+ * @{
+ *
+ * @file
+ * @brief       Device driver for Microchip ATA8520E transceiver
+ *
+ * @author      Alexandre Abadie <alexandre.abadie@inria.fr>
+ *
+ * @}
+ */
+
+#include <stdio.h>
+#include <stdlib.h>
+#include <inttypes.h>
+#include <string.h>
+
+#include "xtimer.h"
+#include "fmt.h"
+
+#include "periph/spi.h"
+#include "periph/gpio.h"
+
+#include "board.h"
+#include "ata8520e_internals.h"
+#include "ata8520e.h"
+
+#define ENABLE_DEBUG (0)
+/* Warning: to correctly display the debug messages in callbacks,
+   add CFLAGS+=-DTHREAD_STACKSIZE_IDLE=THREAD_STACKSIZE_DEFAULT to the build
+   command.
+*/
+#include "debug.h"
+
+#define SPIDEV               (dev->params.spi)
+#define CSPIN                (dev->params.cs_pin)
+#define INTPIN               (dev->params.int_pin)
+#define RESETPIN             (dev->params.reset_pin)
+#define POWERPIN             (dev->params.power_pin)
+#define SPI_CS_DELAY         (US_PER_MS)
+#define DELAY_10_MS          (10 * US_PER_MS) /* 10 ms */
+#define TX_TIMEOUT           (8U)             /* 8 s */
+#define TX_RX_TIMEOUT        (50U)            /* 50 s */
+
+static void _print_atmel_status(uint8_t status)
+{
+    DEBUG("[ata8520e] Atmel status: %d\n", status);
+    if (status & ATA8520E_ATMEL_PA_MASK) {
+        DEBUG("[ata8520e] Atmel: PA ON\n");
+    }
+    else {
+        DEBUG("[ata8520e] Atmel: PA OFF\n");
+    }
+    if ((status >> 1) & ATA8520E_ATMEL_SYSTEM_READY_MASK) {
+        DEBUG("[ata8520e] Atmel: System ready to operate\n");
+        return;
+    }
+    if ((status >> 1) & ATA8520E_ATMEL_FRAME_SENT_MASK) {
+        DEBUG("[ata8520e] Atmel: Frame sent\n");
+        return;
+    }
+    switch ((status >> 1) & 0x0F) {
+        case ATA8520E_ATMEL_OK:
+            DEBUG("[ata8520e] Atmel: System is ready\n");
+            break;
+        case ATA8520E_ATMEL_COMMAND_ERROR:
+            DEBUG("[ata8520e] Atmel: Command error / not supported\n");
+            break;
+        case ATA8520E_ATMEL_GENERIC_ERROR:
+            DEBUG("[ata8520e] Atmel: Generic error\n");
+            break;
+        case ATA8520E_ATMEL_FREQUENCY_ERROR:
+            DEBUG("[ata8520e] Atmel: Frequency error\n");
+            break;
+        case ATA8520E_ATMEL_USAGE_ERROR:
+            DEBUG("[ata8520e] Atmel: Usage error\n");
+            break;
+        case ATA8520E_ATMEL_OPENING_ERROR:
+            DEBUG("[ata8520e] Atmel: Opening error\n");
+            break;
+        case ATA8520E_ATMEL_CLOSING_ERROR:
+            DEBUG("[ata8520e] Atmel: Closing error\n");
+            break;
+        case ATA8520E_ATMEL_SEND_ERROR:
+            DEBUG("[ata8520e] Atmel: Send error\n");
+            break;
+        default:
+            DEBUG("[ata8520e] Atmel: Invalid status code\n");
+            break;
+    }
+}
+
+static void _print_sigfox_status(uint8_t status)
+{
+    DEBUG("[ata8520e] Sigfox status: %d\n", status);
+    switch (status) {
+        case ATA8520E_SIGFOX_OK:
+            DEBUG("[ata8520e] Sigfox: OK\n");
+            break;
+        case ATA8520E_SIGFOX_MANUFACTURER_ERROR:
+            DEBUG("[ata8520e] Sigfox: Manufacturer error\n");
+            break;
+        case ATA8520E_SIGFOX_ID_OR_KEY_ERROR:
+            DEBUG("[ata8520e] Sigfox: ID or Key error\n");
+            break;
+        case ATA8520E_SIGFOX_STATE_MACHINE_ERROR:
+            DEBUG("[ata8520e] Sigfox: State machine error\n");
+            break;
+        case ATA8520E_SIGFOX_FRAME_SIZE_ERROR:
+            DEBUG("[ata8520e] Sigfox: Frame size error\n");
+            break;
+        case ATA8520E_SIGFOX_MANUFACTURER_SEND_ERROR:
+            DEBUG("[ata8520e] Sigfox: Manufacturer send error\n");
+            break;
+        case ATA8520E_SIGFOX_GET_VOLTAGE_TEMP_ERROR:
+            DEBUG("[ata8520e] Sigfox: Get voltage/temperature error\n");
+            break;
+        case ATA8520E_SIGFOX_CLOSE_ERROR:
+            DEBUG("[ata8520e] Sigfox: Close issues encountered\n");
+            break;
+        case ATA8520E_SIGFOX_API_ERROR:
+            DEBUG("[ata8520e] Sigfox: API error indication\n");
+            break;
+        case ATA8520E_SIGFOX_GET_PN9_ERROR:
+            DEBUG("[ata8520e] Sigfox: Error getting PN9\n");
+            break;
+        case ATA8520E_SIGFOX_GET_FREQUENCY_ERROR:
+            DEBUG("[ata8520e] Sigfox: Error getting frequency\n");
+            break;
+        case ATA8520E_SIGFOX_BUILDING_FRAME_ERROR:
+            DEBUG("[ata8520e] Sigfox: Error building frame\n");
+            break;
+        case ATA8520E_SIGFOX_DELAY_ROUTINE_ERROR:
+            DEBUG("[ata8520e] Sigfox: Error in delay routine\n");
+            break;
+        case ATA8520E_SIGFOX_CALLBACK_ERROR:
+            DEBUG("[ata8520e] Sigfox: Callback causes error\n");
+            break;
+        case ATA8520E_SIGFOX_TIMING_ERROR:
+            DEBUG("[ata8520e] Sigfox: Timing error\n");
+            break;
+        case ATA8520E_SIGFOX_FREQUENCY_ERROR:
+            DEBUG("[ata8520e] Sigfox: Frequency error\n");
+            break;
+        default:
+            DEBUG("[ata8520e] Sigfox: Invalid status code [%d]\n", status);
+            break;
+    }
+}
+
+static void _irq_handler(void *arg)
+{
+    (void) arg;
+    ata8520e_t * dev = (ata8520e_t *)arg;
+    DEBUG("[ata8520e] Event received !\n");
+    dev->event_received = 1;
+    switch (dev->internal_state) {
+        case ATA8520E_STATE_IDLE:
+            DEBUG("[ata8520e] IDLE state\n");
+            break;
+        case ATA8520E_STATE_INIT:
+            DEBUG("[ata8520e] INIT state\n");
+            break;
+        case ATA8520E_STATE_TX:
+            DEBUG("[ata8520e] TX state\n");
+            break;
+        case ATA8520E_STATE_RX:
+            DEBUG("[ata8520e] RX state\n");
+            break;
+    }
+}
+
+static void _getbus(const ata8520e_t *dev)
+{
+    if (spi_acquire(SPIDEV, CSPIN, SPI_MODE_0, dev->params.spi_clk) < 0) {
+        DEBUG("[ata8520e] ERROR: Cannot acquire SPI bus!\n");
+    }
+}
+
+static void _spi_transfer_byte(const ata8520e_t *dev, bool cont, uint8_t out)
+{
+    /* Manually triggering CS because of a required delay, see datasheet,
+       section 2.1.1, page 10 */
+    gpio_clear((gpio_t)CSPIN);
+    xtimer_usleep(SPI_CS_DELAY);
+    spi_transfer_byte(SPIDEV, SPI_CS_UNDEF, cont, out);
+    xtimer_usleep(SPI_CS_DELAY);
+    gpio_set((gpio_t)CSPIN);
+}
+
+static void _spi_transfer_bytes(const ata8520e_t *dev, bool cont,
+                                const void *out, void *in, size_t len)
+{
+    /* Manually triggering CS because of a required delay, see datasheet,
+       section 2.1.1, page 10 */
+    gpio_clear((gpio_t)CSPIN);
+    xtimer_usleep(SPI_CS_DELAY);
+    spi_transfer_bytes(SPIDEV, SPI_CS_UNDEF, cont, out, in, len);
+    xtimer_usleep(SPI_CS_DELAY);
+    gpio_set((gpio_t)CSPIN);
+}
+
+static void _send_command(const ata8520e_t *dev, uint8_t command)
+{
+    _getbus(dev);
+    _spi_transfer_byte(dev, false, command);
+    spi_release(SPIDEV);
+}
+
+static void _reset(const ata8520e_t *dev)
+{
+    gpio_set(RESETPIN);
+    xtimer_usleep(DELAY_10_MS);
+    gpio_clear(RESETPIN);
+    xtimer_usleep(DELAY_10_MS);
+    gpio_set(RESETPIN);
+}
+
+static void _poweron(const ata8520e_t *dev)
+{
+    gpio_set(POWERPIN);
+    _reset(dev);
+}
+
+static void _poweroff(const ata8520e_t *dev)
+{
+    gpio_clear(POWERPIN);
+    _send_command(dev, ATA8520E_OFF_MODE);
+}
+
+int ata8520e_init(ata8520e_t *dev, const ata8520e_params_t *params)
+{
+    /* write config params to device descriptor */
+    memcpy(&dev->params, params, sizeof(ata8520e_params_t));
+
+    /* Initialize pins*/
+    if (gpio_init_int(INTPIN, GPIO_IN_PD,
+                      GPIO_FALLING, _irq_handler, dev) < 0 ) {
+        DEBUG("[ata8520e] ERROR: Interrupt pin not initialized\n");
+        return -ATA8520E_ERR_GPIO_INT;
+    }
+    if (gpio_init(POWERPIN, GPIO_OUT) < 0) {
+        DEBUG("[ata8520e] ERROR: Power pin not initialized\n");
+        return -ATA8520E_ERR_GPIO_POWER;
+    }
+    if (gpio_init(RESETPIN, GPIO_OUT) < 0) {
+        DEBUG("[ata8520e] ERROR: Reset pin not initialized\n");
+        return -ATA8520E_ERR_GPIO_RESET;
+    }
+
+    dev->internal_state = ATA8520E_STATE_INIT;
+    _poweron(dev);
+
+    /* Initialize SPI bus*/
+    if (spi_init_cs(dev->params.spi, CSPIN) < 0) {
+        DEBUG("[ata8520e] ERROR: SPI not initialized\n");
+        return -ATA8520E_ERR_SPI;
+    }
+
+    xtimer_usleep(100 * US_PER_MS); /* 100 ms */
+
+    if (ENABLE_DEBUG) {
+        char sigfox_id[SIGFOX_ID_LENGTH + 1];
+        ata8520e_read_id(dev, sigfox_id);
+
+        char sigfox_pac[SIGFOX_PAC_LENGTH + 1];
+        ata8520e_read_pac(dev, sigfox_pac);
+
+        uint8_t atmel_version[2];
+        ata8520e_read_atmel_version(dev, atmel_version);
+
+        char sigfox_version[11];
+        ata8520e_read_sigfox_version(dev, sigfox_version);
+
+        DEBUG("[ata8520e] Atmel version: %d.%d\n",
+              atmel_version[0], atmel_version[1]);
+        DEBUG("[ata8520e] Sigfox version: %s\n", sigfox_version);
+        DEBUG("[ata8520e] Sigfox ID: %s\n", sigfox_id);
+        DEBUG("[ata8520e] Sigfox PAC: %s\n", sigfox_pac);
+    }
+
+    /* Get status and clear event line */
+    ata8520e_status(dev);
+
+    dev->internal_state = ATA8520E_STATE_IDLE;
+
+    _poweroff(dev);
+
+    return ATA8520E_OK;
+}
+
+void ata8520e_system_reset(const ata8520e_t *dev)
+{
+    _send_command(dev, ATA8520E_SYSTEM_RESET);
+}
+
+void ata8520e_read_atmel_version(const ata8520e_t *dev, uint8_t *version)
+{
+    _poweron(dev);
+    _getbus(dev);
+    _spi_transfer_byte(dev, true, ATA8520E_ATMEL_VERSION);
+    _spi_transfer_byte(dev, true, 0);
+    _spi_transfer_bytes(dev, false, 0, version, 2);
+    spi_release(SPIDEV);
+    _poweroff(dev);
+}
+
+void ata8520e_read_sigfox_version(const ata8520e_t *dev, char *version)
+{
+    _poweron(dev);
+    _getbus(dev);
+    _spi_transfer_byte(dev, true, ATA8520E_SIGFOX_VERSION);
+    _spi_transfer_byte(dev, true, 0);
+    _spi_transfer_bytes(dev, false, 0, version, 11);
+    spi_release(SPIDEV);
+    _poweroff(dev);
+}
+
+void ata8520e_read_pac(const ata8520e_t *dev, char *pac)
+{
+    _poweron(dev);
+    uint8_t pac_bytes[SIGFOX_PAC_LENGTH];
+    _getbus(dev);
+    _spi_transfer_byte(dev, true, ATA8520E_GET_PAC);
+    _spi_transfer_byte(dev, true, 0);
+    _spi_transfer_bytes(dev, false, NULL, pac_bytes, SIGFOX_PAC_LENGTH / 2);
+    spi_release(SPIDEV);
+    fmt_bytes_hex(pac, pac_bytes, SIGFOX_PAC_LENGTH >> 1);
+    pac[SIGFOX_PAC_LENGTH] = '\0';
+    _poweroff(dev);
+}
+
+void ata8520e_read_id(const ata8520e_t *dev, char *id)
+{
+    _poweron(dev);
+    uint8_t id_bytes[SIGFOX_ID_LENGTH];
+    _getbus(dev);
+    _spi_transfer_byte(dev, true, ATA8520E_GET_ID);
+    _spi_transfer_byte(dev, true, 0);
+    _spi_transfer_bytes(dev, false, NULL, id_bytes, SIGFOX_ID_LENGTH);
+    spi_release(SPIDEV);
+    /* create id string (4 hexadecimal values in reversed order) */
+    fmt_bytes_hex_reverse(id, id_bytes, SIGFOX_ID_LENGTH >> 1);
+    id[SIGFOX_ID_LENGTH] = '\0';
+    _poweroff(dev);
+}
+
+
+void ata8520e_status(const ata8520e_t *dev)
+{
+    _getbus(dev);
+    _spi_transfer_byte(dev, true, ATA8520E_OFF_MODE);
+    _spi_transfer_byte(dev, true, 0);
+    _spi_transfer_byte(dev, true, 0); /* SSM unused */
+    uint8_t atmel = spi_transfer_byte(SPIDEV, CSPIN, true, 0);
+    uint8_t sigfox = spi_transfer_byte(SPIDEV, CSPIN, true, 0);
+    _spi_transfer_byte(dev, false, 0);
+    spi_release(SPIDEV);
+
+    if (ENABLE_DEBUG) {
+        _print_atmel_status(atmel);
+        _print_sigfox_status(sigfox);
+    }
+}
+
+static void isr_event_timeout(void *arg)
+{
+    ata8520e_t *dev = (ata8520e_t *)arg;
+    mutex_unlock(&(dev->event_lock));
+}
+
+static bool _wait_event(ata8520e_t *dev, uint8_t timeout)
+{
+    dev->event_received = 0;
+    xtimer_ticks64_t start_time = xtimer_now64();
+    xtimer_t event_timer;
+    event_timer.callback = isr_event_timeout;
+    event_timer.arg = dev;
+    xtimer_set(&event_timer, (uint32_t)timeout * US_PER_SEC);
+
+    /* waiting for the event */
+    while ((!dev->event_received) &&
+           xtimer_less(xtimer_diff32_64(xtimer_now64(), start_time),
+                       xtimer_ticks_from_usec(timeout * US_PER_SEC))) {
+        mutex_lock(&(dev->event_lock));
+    }
+    xtimer_remove(&event_timer);
+
+    if (dev->event_received == 0) {
+        DEBUG("[ata8520e] event timeout\n");
+        return true;
+    }
+
+    return false;
+}
+
+static void _prepare_send_frame(ata8520e_t *dev, uint8_t *msg, uint8_t msg_len)
+{
+    _poweron(dev);
+    xtimer_usleep(5 * US_PER_MS);
+    ata8520e_status(dev);
+
+    /* Verify message length */
+    if (msg_len > SIGFOX_MAX_TX_LENGTH) {
+        DEBUG("[ata8520e] Message exceeds the maximum %d characters length "
+              "allowed. It will be truncated.\n", SIGFOX_MAX_TX_LENGTH);
+        msg_len = SIGFOX_MAX_TX_LENGTH;
+    }
+
+    dev->internal_state = ATA8520E_STATE_TX;
+
+    /* Write message in TX buffer */
+    DEBUG("[ata8520e] Writing send frame to RX buffer\n");
+    _getbus(dev);
+    _spi_transfer_byte(dev, true, ATA8520E_WRITE_TX_BUFFER);
+    _spi_transfer_byte(dev, true, msg_len);
+    _spi_transfer_bytes(dev, false, msg, NULL, msg_len);
+    spi_release(SPIDEV);
+}
+
+static int _wait_send(ata8520e_t *dev, uint8_t timeout)
+{
+    DEBUG("[ata8520e] waiting for TX to complete\n");
+    /* Wait 8s maximum for the message to be sent */
+    int ret = ATA8520E_OK;
+    if (_wait_event(dev, timeout)) {
+        DEBUG("[ata8520e] failed to send message\n");
+        ret = -ATA8520E_ERR_EVENT_TIMEOUT;
+    }
+    else {
+        DEBUG("[ata8520e] message sent\n");
+    }
+
+    /* Clear event line */
+    ata8520e_status(dev);
+
+    /* back to idle state */
+    dev->internal_state = ATA8520E_STATE_IDLE;
+
+    return ret;
+}
+
+int ata8520e_send_frame(ata8520e_t *dev, uint8_t *msg, uint8_t msg_len)
+{
+    DEBUG("[ata8520e] Sending frame '%s', length: %d\n", (char*)msg, msg_len);
+    _prepare_send_frame(dev, msg, msg_len);
+
+    /* Trigger TX */
+    _send_command(dev, ATA8520E_SEND_FRAME);
+
+    int ret = _wait_send(dev, TX_TIMEOUT);
+
+    /* switch off transceiver before returning */
+    _poweroff(dev);
+
+    return ret;
+}
+
+int ata8520e_send_receive_frame(ata8520e_t *dev, uint8_t *msg, uint8_t msg_len,
+                                uint8_t *rx_payload)
+{
+    DEBUG("[ata8520e] Sending frame '%s', length: %d\n", (char*)msg, msg_len);
+    _prepare_send_frame(dev, msg, msg_len);
+
+    /* Trigger TX */
+    _send_command(dev, ATA8520E_SEND_RECEIVE_FRAME);
+
+    int ret = _wait_send(dev, TX_RX_TIMEOUT);
+    if (ret == -ATA8520E_ERR_EVENT_TIMEOUT) {
+        return ret;
+    }
+
+    /* Read RX message */
+    dev->internal_state = ATA8520E_STATE_RX;
+    DEBUG("[ata8520e] Reading RX buffer\n");
+    _getbus(dev);
+    _spi_transfer_byte(dev, true, ATA8520E_READ_RX_BUFFER);
+    _spi_transfer_byte(dev, true, 0);
+    _spi_transfer_bytes(dev, false, NULL, rx_payload, SIGFOX_RX_LENGTH);
+    spi_release(SPIDEV);
+
+    /* back to idle state */
+    dev->internal_state = ATA8520E_STATE_IDLE;
+
+    /* switch off transceiver before returning */
+    _poweroff(dev);
+
+    return ret;
+}
+
+int ata8520e_send_bit(ata8520e_t *dev, bool bit)
+{
+    DEBUG("[ata8520e] Sending bit '%d'\n", bit);
+    _poweron(dev);
+    xtimer_usleep(5 * US_PER_MS);
+    ata8520e_status(dev);
+
+    dev->internal_state = ATA8520E_STATE_TX;
+
+    /* Sends the bit */
+    _getbus(dev);
+    _spi_transfer_byte(dev, true, ATA8520E_SEND_BIT);
+    if (bit) {
+        _spi_transfer_byte(dev, false, 0x01);
+    }
+    else {
+        _spi_transfer_byte(dev, false, 0x00);
+    }
+    spi_release(SPIDEV);
+
+    int ret = _wait_send(dev, TX_TIMEOUT);
+
+    /* switch off transceiver before returning */
+    _poweroff(dev);
+
+    return ret;
+}
diff --git a/drivers/ata8520e/include/ata8520e_internals.h b/drivers/ata8520e/include/ata8520e_internals.h
new file mode 100644
index 0000000000000000000000000000000000000000..73e25815a6064dd0faebc88916301875a570ecaa
--- /dev/null
+++ b/drivers/ata8520e/include/ata8520e_internals.h
@@ -0,0 +1,67 @@
+/*
+ * Copyright (C) 2017 Inria
+ *
+ * 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     drivers_ata8520e
+ * @brief       Internal addresses, registers, constants for the ATA8520E device
+ * @{
+ * @file
+ * @brief       Internal addresses, registers, constants for the ATA8520E device
+ *
+ * @author      Alexandre Abadie <alexandre.abadie@inria.fr>
+ */
+
+#ifndef ATA8520E_INTERNALS_H
+#define ATA8520E_INTERNALS_H
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/**
+ * @name SPI commands for ATA8520E
+ * @{
+ */
+#define ATA8520E_SYSTEM_RESET                (0x01)
+#define ATA8520E_IO_INIT                     (0x02)
+#define ATA8520E_IO_WRITE                    (0x03)
+#define ATA8520E_IO_READ                     (0x04)
+#define ATA8520E_OFF_MODE                    (0x05)
+#define ATA8520E_ATMEL_VERSION               (0x06)
+#define ATA8520E_WRITE_TX_BUFFER             (0x07)
+#define ATA8520E_TEST_MODE                   (0x08)
+#define ATA8520E_SIGFOX_VERSION              (0x09)
+#define ATA8520E_GET_STATUS                  (0x0A)
+#define ATA8520E_SEND_BIT                    (0x0B)
+#define ATA8520E_SEND_FRAME                  (0x0D)
+#define ATA8520E_SEND_RECEIVE_FRAME          (0x0E)
+#define ATA8520E_GET_PAC                     (0x0F)
+#define ATA8520E_READ_RX_BUFFER              (0x10)
+#define ATA8520E_WRITE_SYS_CONF              (0x11)
+#define ATA8520E_GET_ID                      (0x12)
+#define ATA8520E_READ_SUP_TEMP               (0x13)
+#define ATA8520E_START_MEASUREMENT           (0x14)
+#define ATA8520E_TX_TEST_MODE                (0x15)
+#define ATA8520E_SEND_CW                     (0x17)
+#define ATA8520E_SET_TX_FREQUENCY            (0x1B)
+/** @} */
+
+/**
+ * @name Constants for ATA8520E
+ * @{
+ */
+#define ATA8520E_ATMEL_SYSTEM_READY_MASK     (0x20)
+#define ATA8520E_ATMEL_FRAME_SENT_MASK       (0x10)
+#define ATA8520E_ATMEL_PA_MASK               (0x01)
+/** @} */
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* ATA8520E_INTERNALS_H */
diff --git a/drivers/ata8520e/include/ata8520e_params.h b/drivers/ata8520e/include/ata8520e_params.h
new file mode 100644
index 0000000000000000000000000000000000000000..4c933589f24692175c9d4eb1c6dbcd16f4bc5c46
--- /dev/null
+++ b/drivers/ata8520e/include/ata8520e_params.h
@@ -0,0 +1,74 @@
+/*
+ * Copyright (C) 2017 Inria
+ *
+ * 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     drivers_ata8520e
+ * @brief       Default initialization parameters for the ATA8520E device
+ * @{
+ * @file
+ * @brief       Default initialization parameters for the ATA8520E device
+ *
+ * @author      Alexandre Abadie <alexandre.abadie@inria.fr>
+ */
+
+#ifndef ATA8520E_PARAMS_H
+#define ATA8520E_PARAMS_H
+
+#include "board.h"
+#include "ata8520e.h"
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/**
+ * @name    Set default configuration parameters for the ATA8520E driver
+ * @{
+ */
+#ifndef ATA8520E_PARAM_SPI
+#define ATA8520E_PARAM_SPI         SPI_DEV(0)
+#endif
+#ifndef ATA8520E_PARAM_SPI_CLK
+#define ATA8520E_PARAM_SPI_CLK     (SPI_CLK_100KHZ)
+#endif
+#ifndef ATA8520E_PARAM_CS_PIN
+#define ATA8520E_PARAM_CS_PIN      GPIO_PIN(0, 0)
+#endif
+#ifndef ATA8520E_PARAM_INT_PIN
+#define ATA8520E_PARAM_INT_PIN     GPIO_PIN(0, 1)
+#endif
+#ifndef ATA8520E_PARAM_POWER_PIN
+#define ATA8520E_PARAM_POWER_PIN   GPIO_PIN(0, 2)
+#endif
+#ifndef ATA8520E_PARAM_RESET_PIN
+#define ATA8520E_PARAM_RESET_PIN   GPIO_PIN(0, 3)
+#endif
+
+#ifndef ATA8520E_PARAMS
+#define ATA8520E_PARAMS            { .spi = ATA8520E_PARAM_SPI,             \
+                                     .spi_clk = ATA8520E_PARAM_SPI_CLK,     \
+                                     .cs_pin = ATA8520E_PARAM_CS_PIN,       \
+                                     .int_pin = ATA8520E_PARAM_INT_PIN,     \
+                                     .power_pin = ATA8520E_PARAM_POWER_PIN, \
+                                     .reset_pin = ATA8520E_PARAM_RESET_PIN }
+#endif
+/**@}*/
+
+/**
+ * @brief   ATA8520E configuration
+ */
+static const ata8520e_params_t ata8520e_params[] =
+{
+    ATA8520E_PARAMS
+};
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* ATA8520E_PARAMS_H */
diff --git a/drivers/include/ata8520e.h b/drivers/include/ata8520e.h
new file mode 100644
index 0000000000000000000000000000000000000000..4b9d5480420080fb5428c450dc5685da388cc71c
--- /dev/null
+++ b/drivers/include/ata8520e.h
@@ -0,0 +1,249 @@
+/*
+ * Copyright (C) 2017 Inria
+ *
+ * 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    drivers_ata8520e Microchip ATA8520E transceiver
+ * @ingroup     drivers_netdev
+ * @brief       Device driver for Microchip ATA8520E transceiver (Sigfox)
+ *
+ * For more information, please refer to the datasheet
+ * http://ww1.microchip.com/downloads/en/DeviceDoc/Atmel-9409-Smart-RF-ATA8520E_Datasheet.pdf
+ *
+ * @{
+ *
+ * @file
+ * @brief       Device driver for Microchip ATA8520E transceiver (Sigfox)
+ *
+ * @author      Alexandre Abadie <alexandre.abadie@inria.fr>
+ */
+
+#ifndef ATA8520E_H
+#define ATA8520E_H
+
+#include <stdint.h>
+#include <inttypes.h>
+#include "xtimer.h"
+#include "periph/gpio.h"
+#include "periph/spi.h"
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/**
+ * @name SIGFOX constants
+ * @{
+ */
+#define SIGFOX_PAC_LENGTH    (16U) /**< Length of Sigfox PAC */
+#define SIGFOX_ID_LENGTH     (8U)  /**< Length of Sigfox ID */
+#define SIGFOX_MAX_TX_LENGTH (12U) /**< Maximum length of a TX payload */
+#define SIGFOX_RX_LENGTH     (8U)  /**< RX payload length is always 8 */
+/** @} */
+
+/**
+ * @brief return codes
+ */
+enum {
+    ATA8520E_OK = 0,                /**< Everything is fine */
+    ATA8520E_ERR_SPI,               /**< An error occurred with SPI */
+    ATA8520E_ERR_GPIO_INT,          /**< An error occurred with interrupt pin */
+    ATA8520E_ERR_GPIO_RESET,        /**< An error occurred with reset pin */
+    ATA8520E_ERR_GPIO_POWER,        /**< An error occurred with power pin */
+    ATA8520E_ERR_EVENT_TIMEOUT,     /**< An expected event never happened */
+};
+
+/**
+ * @brief device internal states
+ */
+enum {
+    ATA8520E_STATE_IDLE,            /**< Device is in idle state */
+    ATA8520E_STATE_INIT,            /**< Device is in initialization phase */
+    ATA8520E_STATE_TX,              /**< Device is in TX mode */
+    ATA8520E_STATE_RX,              /**< Device is in RX mode, just after TX */
+};
+
+/**
+ * @brief device module status
+ */
+typedef enum {
+    ATA8520E_SSM,                   /**< SoC System Management status */
+    ATA8520E_ATMEL,                 /**< Atmel status */
+    ATA8520E_SIGFOX                 /**< Sigfox status */
+} ata8520e_status_type_t;
+
+/**
+ * @brief Sigfox statuses
+ *
+ * See ATA8520E datasheet, section 2.1.2.10, page 12
+ */
+typedef enum {
+    ATA8520E_ATMEL_OK,                       /**< No error */
+    ATA8520E_ATMEL_COMMAND_ERROR,            /**< Command error / not supported */
+    ATA8520E_ATMEL_GENERIC_ERROR,            /**< Generic error */
+    ATA8520E_ATMEL_FREQUENCY_ERROR,          /**< Frequency error */
+    ATA8520E_ATMEL_USAGE_ERROR,              /**< Usage error */
+    ATA8520E_ATMEL_OPENING_ERROR,            /**< Opening error */
+    ATA8520E_ATMEL_CLOSING_ERROR,            /**< Closing error */
+    ATA8520E_ATMEL_SEND_ERROR                /**< Send error */
+} ata8520e_atmel_status_t;
+
+/**
+ * @brief Sigfox statuses.
+ *
+ * See ATA8520E datasheet, section 2.1.2.10, page 12
+ */
+typedef enum {
+    ATA8520E_SIGFOX_OK,                      /**< No error */
+    ATA8520E_SIGFOX_MANUFACTURER_ERROR,      /**< Manufacturer error */
+    ATA8520E_SIGFOX_ID_OR_KEY_ERROR,         /**< ID or key error */
+    ATA8520E_SIGFOX_STATE_MACHINE_ERROR,     /**< State machine error */
+    ATA8520E_SIGFOX_FRAME_SIZE_ERROR,        /**< Frame size error */
+    ATA8520E_SIGFOX_MANUFACTURER_SEND_ERROR, /**< Manufacturer send error */
+    ATA8520E_SIGFOX_GET_VOLTAGE_TEMP_ERROR,  /**< Get voltage/temperature error */
+    ATA8520E_SIGFOX_CLOSE_ERROR,             /**< Close issues encountered */
+    ATA8520E_SIGFOX_API_ERROR,               /**< API error indication */
+    ATA8520E_SIGFOX_GET_PN9_ERROR,           /**< Error getting PN9 */
+    ATA8520E_SIGFOX_GET_FREQUENCY_ERROR,     /**< Error getting frequency */
+    ATA8520E_SIGFOX_BUILDING_FRAME_ERROR,    /**< Error building frame */
+    ATA8520E_SIGFOX_DELAY_ROUTINE_ERROR,     /**< Error in delay routine */
+    ATA8520E_SIGFOX_CALLBACK_ERROR,          /**< Callback causes error */
+    ATA8520E_SIGFOX_TIMING_ERROR,            /**< Timing error */
+    ATA8520E_SIGFOX_FREQUENCY_ERROR          /**< Frequency error */
+} ata8520e_sigfox_status_t;
+
+/**
+ * @brief Initialization parameters
+ */
+typedef struct {
+    spi_t spi;                              /**< SPI device */
+    spi_clk_t spi_clk;                      /**< SPI clock speed */
+    gpio_t cs_pin;                          /**< Chip select pin */
+    gpio_t int_pin;                         /**< IRQ pin */
+    gpio_t power_pin;                       /**< Power pin */
+    gpio_t reset_pin;                       /**< Reset pin */
+} ata8520e_params_t;
+
+/**
+ * @brief device descriptor
+ */
+typedef struct {
+    ata8520e_params_t params;               /**< Device parameters */
+    uint8_t internal_state;                 /**< current state of the device */
+    uint8_t event_received;                 /**< check if an event was received */
+    mutex_t event_lock;                     /**< mutex for waiting for event */
+} ata8520e_t;
+
+/**
+ * @brief Initialize the device
+ *
+ * This will also initialize the CS pin as a GPIO output, without pull resistors
+ * and the interrupt pin handler to manage events.
+ *
+ * @param[out] dev                Pointer to device descriptor
+ * @param[in]  params             Pointer to SPI settings
+ *
+ * @return  ATA8520E_OK on success
+ * @return -ATA8520E_ERR_SPI on SPI initialization error
+ * @return -ATA8520E_ERR_GPIO_INT on interrupt pin initialization error
+ * @return -ATA8520E_ERR_GPIO_RESET on reset pin initialization error
+ * @return -ATA8520E_ERR_GPIO_POWER on power pin initialization error
+ */
+int ata8520e_init(ata8520e_t *dev, const ata8520e_params_t *params);
+
+/**
+ * @brief Perform a complete reset of the device
+ *
+ * @param[in] dev                 Pointer to device descriptor
+ */
+void ata8520e_system_reset(const ata8520e_t *dev);
+
+/**
+ * @brief Return the Atmel version of the device
+ *
+ * @param[in] dev                 Pointer to device descriptor
+ * @param[out] version            Pointer to the string containing the version
+ */
+void ata8520e_read_atmel_version(const ata8520e_t *dev, uint8_t *version);
+
+/**
+ * @brief Return the Atmel version of the device
+ *
+ * @param[in] dev                 Pointer to device descriptor
+ * @param[out] version            String containing the version.
+ *                                The version contains 11 characters.
+ */
+void ata8520e_read_sigfox_version(const ata8520e_t *dev, char *version);
+
+/**
+ * @brief Return the porting authorization code (PAC) available in the device
+ *
+ * @param[in] dev                 Pointer to device descriptor
+ * @param[out] pac                String containing the pac
+ */
+void ata8520e_read_pac(const ata8520e_t *dev, char *pac);
+
+/**
+ * @brief Return the ID of the device
+ *
+ * @param[in] dev                 Pointer to device descriptor
+ * @param[out] id                 String containing the ID
+ */
+void ata8520e_read_id(const ata8520e_t *dev, char *id);
+
+/**
+ * @brief Check the current status of the device
+ *
+ * Calling this function clears the system event line.
+ *
+ * @param[in] dev                 Pointer to device descriptor
+ */
+void ata8520e_status(const ata8520e_t *dev);
+
+/**
+ * @brief Send a frame
+ *
+ * @param[in] dev                 Pointer to device descriptor
+ * @param[in] payload             The payload to send
+ * @param[in] payload_len         The length of the payload to send
+ *
+ * @return  ATA8520E_OK if the send was successful
+ * @return -ATA8520E_ERR_EVENT_TIMEOUT if the send failed
+ */
+int ata8520e_send_frame(ata8520e_t *dev, uint8_t *payload, uint8_t payload_len);
+
+/**
+ * @brief Send a frame and wait for a RX packet
+ *
+ * @param[in] dev                 Pointer to device descriptor
+ * @param[in] payload             The payload to send
+ * @param[in] payload_len         The length of the payload to send
+ * @param[out] rx_payload         The payload received
+ *
+ * @return  ATA8520E_OK if the send was successful
+ * @return -ATA8520E_ERR_EVENT_TIMEOUT if the send failed
+ */
+int ata8520e_send_receive_frame(ata8520e_t *dev, uint8_t *payload,
+                                uint8_t payload_len, uint8_t *rx_payload);
+
+/**
+ * @brief Send a bit
+ *
+ * @param[in] dev                 Pointer to device descriptor
+ * @param[in] bit                 The bit to send
+ *
+ * @return  ATA8520E_OK if the send was successful
+ * @return -ATA8520E_ERR_EVENT_TIMEOUT if the send failed
+ */
+int ata8520e_send_bit(ata8520e_t *dev, bool bit);
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* ATA8520E_H */
+/** @} */
diff --git a/tests/driver_ata8520e/Makefile b/tests/driver_ata8520e/Makefile
new file mode 100644
index 0000000000000000000000000000000000000000..207c000bbaca571e85776059ad5232883de8c38c
--- /dev/null
+++ b/tests/driver_ata8520e/Makefile
@@ -0,0 +1,7 @@
+include ../Makefile.tests_common
+
+USEMODULE += ata8520e
+USEMODULE += shell
+USEMODULE += shell_commands
+
+include $(RIOTBASE)/Makefile.include
diff --git a/tests/driver_ata8520e/README.md b/tests/driver_ata8520e/README.md
new file mode 100644
index 0000000000000000000000000000000000000000..7c1b1d27915a3bd4b1747763377f759cd5b2ea71
--- /dev/null
+++ b/tests/driver_ata8520e/README.md
@@ -0,0 +1,34 @@
+# About
+
+This is a manual test application for the [Microchip ATA8020E Sigfox module](http://ww1.microchip.com/downloads/en/DeviceDoc/Atmel-9409-Smart-RF-ATA8520E_Datasheet.pdf).
+
+# Usage
+
+This application provides a `sigfox` shell command to interact with the device.
+Use the subcommands to perform common Sigfox operations:
+* `sigfox info` returns the Atmel and Sigfox versions of the module
+* `sigfox keys` returns the ID and PAC keys used to activate the device in the
+  Sigfox cloud backend at https://backend.sigfox.com/activate.
+* `sigfox tx <payload>` sends a payload to the Sigfox backend. The payload can
+  be either a frame (e.g a string with 12 characters max) or a bit (e.g 0 or 1)
+* `sigfox tx_rx <payload>` is the same as the previous but after sending the
+  payload, it waits for incoming message sent from the backend
+
+# Examples:
+
+* Read the internal keys of the module:
+```
+    > sigfox keys
+    ID: 00000000
+    PAC: 0000000000000000
+```
+* Send a bit value to the backend:
+```
+    > sigfox tx 1
+    Bit sent with success
+```
+* Send a string message to the backend:
+```
+    > sigfox tx This\ is\ RIOT
+    Message sent with success
+```
diff --git a/tests/driver_ata8520e/main.c b/tests/driver_ata8520e/main.c
new file mode 100644
index 0000000000000000000000000000000000000000..97d14a30c251baf3ff941c458c2081c8326e399e
--- /dev/null
+++ b/tests/driver_ata8520e/main.c
@@ -0,0 +1,156 @@
+/*
+ * Copyright (C) 2017 Inria
+ *
+ * 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 tests
+ * @{
+ *
+ * @file
+ * @brief       Test application for the ATA8520E Sigfox module
+ *
+ * @author      Alexandre Abadie <alexandre.abadie@inria.fr>
+ *
+ * @}
+ */
+
+#include <stdlib.h>
+#include <stdio.h>
+#include <string.h>
+#include <inttypes.h>
+
+#include "shell.h"
+#include "shell_commands.h"
+
+#include "ata8520e_params.h"
+#include "ata8520e.h"
+
+static ata8520e_t dev;
+
+static void _print_sigfox_usage(void)
+{
+    puts("Usage: sigfox <info|keys|tx|tx_rx>\n\n"
+         " <info> prints information on module versions\n"
+         " <keys> prints device internal keys, use them to register the device"
+         " at https://backend.sigfox.com/activate\n"
+         " <tx> sends a frame or a bit to the Sigfox backend\n"
+         " <tx_rx> sends a frame to the Sigfox backend and waits for received "
+         "data");
+}
+
+int ata8520e_sigfox_cmd(int argc, char **argv)
+{
+    if (argc < 2) {
+        _print_sigfox_usage();
+        return 1;
+    }
+
+    if (strcmp(argv[1], "info") == 0) {
+        uint8_t atmel_version[2];
+        char sigfox_version[11];
+        ata8520e_read_atmel_version(&dev, atmel_version);
+        ata8520e_read_sigfox_version(&dev, sigfox_version);
+        printf("Atmel version : %d.%d\n", atmel_version[0], atmel_version[1]);
+        printf("Sigfox version: %s\n", sigfox_version);
+    }
+    else if (strcmp(argv[1], "keys") == 0) {
+        char sigfox_id[SIGFOX_ID_LENGTH + 1];
+        ata8520e_read_id(&dev, sigfox_id);
+        char sigfox_pac[SIGFOX_PAC_LENGTH + 1];
+        ata8520e_read_pac(&dev, sigfox_pac);
+        printf("ID: %s\nPAC: %s\n", sigfox_id, sigfox_pac);
+    }
+    else if (strcmp(argv[1], "tx") == 0) {
+        if (argc != 3) {
+            puts("Usage: sigfox tx <payload>");
+            return 1;
+        }
+        if ((strlen(argv[2]) == 1) &&
+            ((atoi(argv[2]) == 0) || (atoi(argv[2]) == 1))) {
+            bool bit = (atoi(argv[2]) == 1);
+            if (ata8520e_send_bit(&dev, bit) != ATA8520E_OK) {
+                puts("Bit not sent");
+                return 1;
+            }
+            puts("Bit sent with success");
+        }
+        else {
+            if (strlen(argv[2]) > SIGFOX_MAX_TX_LENGTH) {
+                printf("Message length cannot exceeds %d characters length, your "
+                       "message length is %d", SIGFOX_MAX_TX_LENGTH, strlen(argv[2]));
+                return 1;
+            }
+            if (ata8520e_send_frame(&dev,
+                                    (uint8_t *)argv[2],
+                                    strlen(argv[2])) != ATA8520E_OK) {
+                puts("Message not sent");
+                return 1;
+            }
+            puts("Message sent with success");
+        }
+    }
+    else if (strcmp(argv[1], "tx_rx") == 0) {
+        if (argc != 3) {
+            puts("Usage: sigfox tx_rx <payload>");
+            return 1;
+        }
+        if (strlen(argv[2]) > SIGFOX_MAX_TX_LENGTH) {
+            printf("Message length cannot exceeds %d characters length, your "
+                   "message length is %d", SIGFOX_MAX_TX_LENGTH, strlen(argv[2]));
+            return 1;
+        }
+        uint8_t rx_buf[SIGFOX_RX_LENGTH];
+        if (ata8520e_send_receive_frame(&dev,
+                                        (uint8_t *)argv[2],
+                                        strlen(argv[2]),
+                                        rx_buf) != ATA8520E_OK) {
+            puts("Message not sent");
+            return 1;
+        }
+        puts("Message sent with success");
+        printf("Data received: %s\n", (char *)rx_buf);
+    }
+    else {
+        _print_sigfox_usage();
+        return 1;
+    }
+
+    return 0;
+}
+
+static const shell_command_t shell_commands[] = {
+    { "sigfox", "interact with ATA8520E Sigfox module", ata8520e_sigfox_cmd },
+    { NULL, NULL, NULL }
+};
+
+int main(void)
+{
+    puts("ATA8520E test application\n");
+    puts("+------------Initializing------------+\n");
+    switch (ata8520e_init(&dev, &ata8520e_params[0])) {
+        case -ATA8520E_ERR_SPI:
+            puts("[Error] An error occurred when initializing SPI bus.");
+            return -1;
+        case -ATA8520E_ERR_GPIO_INT:
+            puts("[Error] An error occurred when initializing interrupt pin.");
+            return -1;
+        case -ATA8520E_ERR_GPIO_POWER:
+            puts("[Error] An error occurred when initializing poweron pin.");
+            return -1;
+        case -ATA8520E_ERR_GPIO_RESET:
+            puts("[Error] An error occurred when initializing reset- pin.");
+            return -1;
+    }
+
+    /* start the shell */
+    puts("Initialization OK, starting shell now");
+
+    char line_buf[SHELL_DEFAULT_BUFSIZE];
+    shell_run(shell_commands, line_buf, SHELL_DEFAULT_BUFSIZE);
+
+    return 0;
+}