diff --git a/drivers/Makefile.dep b/drivers/Makefile.dep
index 135811aa16d650632513e54561783fce7bd2d181..d9319b9effc553c4ed60fc3ee8793a08f7168008 100644
--- a/drivers/Makefile.dep
+++ b/drivers/Makefile.dep
@@ -1,5 +1,9 @@
 # driver dependencies (in alphabetical order)
 
+ifneq (,$(filter ad7746,$(USEMODULE)))
+  FEATURES_REQUIRED += periph_i2c
+endif
+
 ifneq (,$(filter adc%1c,$(USEMODULE)))
   FEATURES_REQUIRED += periph_gpio_irq
   FEATURES_REQUIRED += periph_i2c
diff --git a/drivers/Makefile.include b/drivers/Makefile.include
index ec86c55380a2976e677b3b32834353a2b91d8b82..9a64c0867ec19573d84c73d7466457ded975048f 100644
--- a/drivers/Makefile.include
+++ b/drivers/Makefile.include
@@ -1,3 +1,7 @@
+ifneq (,$(filter ad7746,$(USEMODULE)))
+  USEMODULE_INCLUDES += $(RIOTBASE)/drivers/ad7746/include
+endif
+
 ifneq (,$(filter adcxx1c,$(USEMODULE)))
   USEMODULE_INCLUDES += $(RIOTBASE)/drivers/adcxx1c/include
 endif
diff --git a/drivers/ad7746/Makefile b/drivers/ad7746/Makefile
new file mode 100644
index 0000000000000000000000000000000000000000..48422e909a47d7cd428d10fa73825060ccc8d8c2
--- /dev/null
+++ b/drivers/ad7746/Makefile
@@ -0,0 +1 @@
+include $(RIOTBASE)/Makefile.base
diff --git a/drivers/ad7746/ad7746.c b/drivers/ad7746/ad7746.c
new file mode 100644
index 0000000000000000000000000000000000000000..6bf9530811b519f0dfdf3d9604bb84e91f824177
--- /dev/null
+++ b/drivers/ad7746/ad7746.c
@@ -0,0 +1,452 @@
+/*
+ * Copyright (C) 2019 HAW Hamburg
+ *
+ * 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_ad7746
+ * @{
+ *
+ * @file
+ * @brief       AD7746 Capacitance-to-digital converter with temperature
+ *              sensor driver
+ *
+ * @author      Leandro Lanzieri <leandro.lanzieri@haw-hamburg.de>
+ * @}
+ */
+
+#include "ad7746.h"
+#include "ad7746_params.h"
+#include "ad7746_internal.h"
+
+#include "periph/i2c.h"
+#include "periph/gpio.h"
+
+#define ENABLE_DEBUG (0)
+#include "debug.h"
+
+#include "xtimer.h"
+
+#define I2C (dev->params.i2c)
+#define ADDR (dev->params.addr)
+
+#define CONF_TEST_VALUE (1 << AD7746_CONFIGURATION_VTF1_BIT)
+
+/* these are the conversion times (in ms) for each sample rate of the
+ * voltage / temperature channel */
+static const unsigned char _vt_sr_times[] = {
+    21, 33, 63, 123
+};
+
+/**
+ * @brief Reads the capacitance value from a selected input. Changes the input
+ *        on the device if the requested is no the current one.
+ *
+ * @param[in] dev   device descriptor
+ * @param[out] value read value
+ * @param[in] input input to read from
+ *
+ * @return AD7746_OK on success
+ * @return AD7746_NODATA if no data is available
+ * @return AD7746_I2C on error getting a reponse
+ */
+static int _read_capacitance(ad7746_t *dev, int *value,
+                             ad7746_cap_input_t input);
+
+/**
+ * @brief   Reads the current value of voltage or temperature depending on the
+ *          @p mode. Changes the mode of the voltage / temperature channel on
+ *          the device of the requested is no the current one.
+ *
+ * @param[in] dev device descriptor
+ * @param[out] value read value
+ * @param[in] mode one of @ref ad7746_vt_mode_t
+ *
+ * @return AD7746_OK on success
+ * @return AD7746_NODATA if no data is available
+ * @return AD7746_I2C on error getting a reponse
+ */
+static int _read_voltage_temp(ad7746_t *dev, int *value, ad7746_vt_mode_t mode);
+
+/**
+ * @brief   Reads a raw value either from the capacitance channel or from the
+ *          voltage / temperature channel if available
+ *
+ * @param[in] dev   device descriptor
+ * @param[in] ch    channel to read:
+ *                      - AD7746_READ_CAP_CH: Capacitance
+ *                      - AD7746_READ_VT_CH: Voltage / temperature
+ * @param[out] raw  read value
+ *
+ * @return AD7746_OK on success
+ * @return AD7746_NODATA if no data is available
+ * @return AD7746_I2C on error getting a reponse
+ */
+static int _read_raw_ch(const ad7746_t *dev, uint8_t ch, uint32_t *raw);
+
+/**
+ * @brief   Converts a raw code into a capacitance expressed in fF
+ *
+ * @param[in] raw   Raw code from the device
+ *
+ * @return capacitance in fF
+ */
+static int _raw_to_capacitance(uint32_t raw);
+
+/**
+ * @brief   Converts a raw code into temperature expressed in celsius (C)
+ *
+ * @param[in] raw   Raw code from the device
+ *
+ * @return temperature in celsius
+ */
+static int _raw_to_temperature(uint32_t raw);
+
+/**
+ * @brief   Converts a raw code into voltage expressed in mV
+ *
+ * @param[in] raw   Raw code from the device
+ *
+ * @return voltage in mV
+ */
+static int _raw_to_voltage(uint32_t raw);
+
+int ad7746_init(ad7746_t *dev, const ad7746_params_t *params)
+{
+    int status;
+    int res = AD7746_NOI2C;
+
+    assert(dev && params);
+    dev->params = *params;
+
+    i2c_acquire(I2C);
+    uint8_t reg = 0;
+
+    /* Test communication write and read configuration register */
+    status = i2c_write_reg(I2C, ADDR, AD7746_REG_CONFIGURATION, CONF_TEST_VALUE,
+                           0);
+    status += i2c_read_reg(I2C, ADDR, AD7746_REG_CONFIGURATION, &reg, 0);
+
+    if (status < 0 || reg != CONF_TEST_VALUE) {
+        DEBUG("[ad7746] init - error: unable to communicate with the device "
+              "(reg=%x)\n", reg);
+        res = AD7746_NODEV;
+        goto release;
+    }
+
+    /* Enable capacitive channel and select input */
+    reg = (1 << AD7746_CAP_SETUP_CAPEN_BIT) |
+          (dev->params.cap_input << AD7746_CAP_SETUP_CIN2_BIT);
+    if (i2c_write_reg(I2C, ADDR, AD7746_REG_CAP_SETUP, reg, 0)) {
+        DEBUG("[ad7746] init - error: unable to enable capacitive channel\n");
+        goto release;
+    }
+
+    if (dev->params.vt_mode != AD7746_VT_MD_DIS) {
+        /* Enable voltage / temperature channel and set mode */
+        reg = (1 << AD7746_VT_SETUP_VTEN_BIT) |
+              (dev->params.vt_mode << AD7746_VT_SETUP_VTMD0_BIT) |
+              (1 << AD7746_VT_SETUP_VTCHOP_BIT);
+        if (i2c_write_reg(I2C, ADDR, AD7746_REG_VT_SETUP, reg, 0)) {
+            DEBUG("[ad7746] init - error: unable to enable the v/t channel\n");
+            goto release;
+        }
+    }
+
+    /* Set EXC sources */
+    reg = (dev->params.exc_config << AD7746_EXC_SETUP_INV_EXCA_BIT);
+    if (i2c_write_reg(I2C, ADDR, AD7746_REG_EXC_SETUP, reg, 0)) {
+        DEBUG("[ad7746] init - error: unable to set EXC outputs\n");
+        goto release;
+    }
+
+    /* Set DAC A capacitance value */
+    if (dev->params.dac_a_cap) {
+        assert(dev->params.dac_a_cap <= AD7746_DAC_MAX);
+        reg = (1 << AD7746_DACAEN_BIT) | dev->params.dac_a_cap;
+        if (i2c_write_reg(I2C, ADDR, AD7746_REG_CAP_DAC_A, reg, 0)) {
+            DEBUG("[ad7746] init - error: unable to set DAC A\n");
+            goto release;
+        }
+    }
+
+    /* Set DAC B capacitance value */
+    if (dev->params.dac_b_cap) {
+        assert(dev->params.dac_b_cap <= AD7746_DAC_MAX);
+        reg = (1 << AD7746_DACBEN_BIT) | dev->params.dac_b_cap;
+        if (i2c_write_reg(I2C, ADDR, AD7746_REG_CAP_DAC_B, reg, 0)) {
+            DEBUG("[ad7746] init - error: unable to set DAC B\n");
+            goto release;
+        }
+    }
+
+    /* Set to continuous mode and configured sample rates */
+    reg = (1 << AD7746_CONFIGURATION_MD0_BIT) |
+          (dev->params.cap_sample_rate << AD7746_CONFIGURATION_CAPF0_BIT) |
+          (dev->params.vt_sample_rate << AD7746_CONFIGURATION_VTF0_BIT);
+    if (i2c_write_reg(I2C, ADDR, AD7746_REG_CONFIGURATION, reg, 0)) {
+        DEBUG("[ad7746] init - error: unable to set mode and SR\n");
+        goto release;
+    }
+
+    res = AD7746_OK;
+
+release:
+    i2c_release(I2C);
+    return res;
+}
+
+int ad7746_set_vt_ch_mode(ad7746_t *dev, ad7746_vt_mode_t mode)
+{
+    uint8_t reg;
+    int res = AD7746_NOI2C;
+
+    assert(dev);
+    i2c_acquire(I2C);
+    if (i2c_read_reg(I2C, ADDR, AD7746_REG_VT_SETUP, &reg, 0)) {
+        goto release;
+    }
+
+    if (mode == AD7746_VT_MD_DIS) {
+        reg &= ~(1 << AD7746_VT_SETUP_VTEN_BIT);
+    }
+    else {
+        /* Enable voltage / temperature channel and set mode */
+        reg &= ~((1 << AD7746_VT_SETUP_VTMD0_BIT) |
+                 (1 << AD7746_VT_SETUP_VTMD1_BIT));
+        reg |= (1 << AD7746_VT_SETUP_VTEN_BIT) |
+               (mode << AD7746_VT_SETUP_VTMD0_BIT);
+    }
+
+    if (i2c_write_reg(I2C, ADDR, AD7746_REG_VT_SETUP, reg, 0)) {
+        DEBUG("[ad7746] set_vt_ch - error: unable to set v/t channel mode\n");
+        goto release;
+    }
+
+    res = AD7746_OK;
+    dev->params.vt_mode = mode;
+
+release:
+    i2c_release(I2C);
+    return res;
+}
+
+int ad7746_read_capacitance_1(ad7746_t *dev, int *value)
+{
+    return _read_capacitance(dev, value, AD7746_CAP_IN_1);
+}
+
+int ad7746_read_capacitance_2(ad7746_t *dev, int *value)
+{
+    return _read_capacitance(dev, value, AD7746_CAP_IN_2);
+}
+
+int ad7746_read_voltage_in(ad7746_t *dev, int *value)
+{
+    return _read_voltage_temp(dev, value, AD7746_VT_MD_VIN);
+}
+
+int ad7746_read_voltage_vdd(ad7746_t *dev, int *value)
+{
+    return _read_voltage_temp(dev, value, AD7746_VT_MD_VDD);
+}
+
+int ad7746_read_temperature_int(ad7746_t *dev, int *value)
+{
+    return _read_voltage_temp(dev, value, AD7746_VT_MD_TEMP);
+}
+
+int ad7746_read_temperature_ext(ad7746_t *dev, int *value)
+{
+    return _read_voltage_temp(dev, value, AD7746_VT_MD_ETEMP);
+}
+
+int ad7746_set_cap_ch_input(const ad7746_t *dev, ad7746_cap_input_t input)
+{
+    uint8_t reg;
+    int res = AD7746_NOI2C;
+
+    assert(dev);
+    i2c_acquire(I2C);
+
+    if (i2c_read_reg(I2C, ADDR, AD7746_REG_CAP_SETUP, &reg, 0)) {
+        goto release;
+    }
+
+    if (input == AD7746_CAP_IN_2) {
+        reg |= (1 << AD7746_CAP_SETUP_CIN2_BIT);
+    }
+    else {
+        reg &= ~(1 << AD7746_CAP_SETUP_CIN2_BIT);
+    }
+
+    if (i2c_write_reg(I2C, ADDR, AD7746_REG_CAP_SETUP, reg, 0)) {
+        goto release;
+    }
+
+    res = AD7746_OK;
+
+release:
+    i2c_release(I2C);
+    return res;
+}
+
+int ad7746_set_cap_sr(const ad7746_t *dev, ad7746_cap_sample_rate_t sr)
+{
+    uint8_t reg;
+    int res = AD7746_NOI2C;
+
+    assert(dev);
+    i2c_acquire(I2C);
+
+    if (i2c_read_reg(I2C, ADDR, AD7746_REG_CONFIGURATION, &reg, 0)) {
+        goto release;
+    }
+
+    reg &= ~(7 << AD7746_CONFIGURATION_CAPF0_BIT);
+    reg |= (sr << AD7746_CONFIGURATION_CAPF0_BIT);
+
+    if (i2c_write_reg(I2C, ADDR, AD7746_REG_CONFIGURATION, reg, 0)) {
+        goto release;
+    }
+
+    res = AD7746_OK;
+
+release:
+    i2c_release(I2C);
+    return res;
+}
+
+int ad7746_set_vt_sr(const ad7746_t *dev, ad7746_vt_sample_rate_t sr)
+{
+    uint8_t reg;
+    int res = AD7746_NOI2C;
+
+    assert(dev);
+    i2c_acquire(I2C);
+
+    if (i2c_read_reg(I2C, ADDR, AD7746_REG_CONFIGURATION, &reg, 0)) {
+        goto release;
+    }
+
+    reg &= ~(3 << AD7746_CONFIGURATION_VTF0_BIT);
+    reg |= (sr << AD7746_CONFIGURATION_VTF0_BIT);
+
+    if (i2c_write_reg(I2C, ADDR, AD7746_REG_CONFIGURATION, reg, 0)) {
+        goto release;
+    }
+
+    res = AD7746_OK;
+
+release:
+    i2c_release(I2C);
+    return res;
+}
+
+static int _read_capacitance(ad7746_t *dev, int *value,
+                             ad7746_cap_input_t input)
+{
+    int res;
+    uint32_t raw;
+
+    if (dev->params.cap_input != input) {
+        if (ad7746_set_cap_ch_input(dev, input)) {
+            return AD7746_NOI2C;
+        }
+        /* discard last reading */
+        _read_raw_ch(dev, AD7746_READ_CAP_CH, &raw);
+    }
+
+    res = _read_raw_ch(dev, AD7746_READ_CAP_CH, &raw);
+    if (res == AD7746_OK) {
+        *value = _raw_to_capacitance(raw);
+    }
+
+    return res;
+}
+
+static int _read_voltage_temp(ad7746_t *dev, int *value, ad7746_vt_mode_t mode)
+{
+    int res;
+    uint32_t raw;
+
+    if (dev->params.vt_mode != mode) {
+        if (ad7746_set_vt_ch_mode(dev, mode)) {
+            return AD7746_NOI2C;
+        }
+        /* if a mode change is needed wait for a conversion cycle and flush
+         * the first sample in order to get a stable output. Took from the Linux
+         * driver implementation */
+        xtimer_usleep(_vt_sr_times[dev->params.vt_sample_rate] * US_PER_MS);
+        _read_raw_ch(dev, AD7746_READ_VT_CH, &raw);
+    }
+
+    res = _read_raw_ch(dev, AD7746_READ_VT_CH, &raw);
+    if (res == AD7746_OK) {
+        if (mode == AD7746_VT_MD_ETEMP || mode == AD7746_VT_MD_TEMP) {
+            *value = _raw_to_temperature(raw);
+        }
+        else {
+            *value = _raw_to_voltage(raw);
+        }
+    }
+
+    return res;
+}
+
+static int _read_raw_ch(const ad7746_t *dev, uint8_t ch, uint32_t *raw)
+{
+    uint8_t buf[3];
+    int res = AD7746_NOI2C;
+    uint16_t reg = (ch == AD7746_READ_CAP_CH) ? AD7746_REG_CAP_DATA_H :
+                                                AD7746_REG_VT_DATA_H;
+
+    assert(dev);
+    assert((ch == AD7746_READ_CAP_CH) || (ch == AD7746_READ_VT_CH));
+    i2c_acquire(I2C);
+
+    if (i2c_read_reg(I2C, ADDR, AD7746_REG_STATUS, buf, 0)) {
+        goto release;
+    }
+
+    /* check if data is available from the requested channel */
+    if (buf[0] & (1 << ch)) {
+        res = AD7746_NODATA;
+        goto release;
+    }
+
+    if (i2c_read_regs(I2C, ADDR, reg, buf, 3, 0)) {
+        goto release;
+    }
+
+    *raw = (((uint32_t)buf[0] << 16) | ((uint32_t)buf[1] << 8) |
+            ((uint32_t)buf[2]));
+    res = AD7746_OK;
+
+release:
+    i2c_release(I2C);
+    return res;
+}
+
+static int _raw_to_capacitance(uint32_t raw)
+{
+    int32_t value = (raw - AD7746_ZERO_SCALE_CODE) >> 11;
+    return (int)value;
+}
+
+static int _raw_to_temperature(uint32_t raw)
+{
+    int value = (raw >> 11) - 4096;
+    return value;
+}
+
+static int _raw_to_voltage(uint32_t raw)
+{
+    int64_t value = (raw - AD7746_ZERO_SCALE_CODE);
+    value *= AD7746_INTERNAL_VREF;
+    value >>= 23;
+    return (int)value;
+}
diff --git a/drivers/ad7746/include/ad7746_internal.h b/drivers/ad7746/include/ad7746_internal.h
new file mode 100644
index 0000000000000000000000000000000000000000..d9565d55ed08610cbae4def659513f688bd68d2b
--- /dev/null
+++ b/drivers/ad7746/include/ad7746_internal.h
@@ -0,0 +1,135 @@
+/*
+ * Copyright (C) 2019 HAW Hamburg
+ *
+ * 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_ad7746
+ * @{
+ *
+ * @file
+ * @brief       Internal definitions for AD7746 capacitance sensor
+ *
+ * @author      Leandro Lanzieri <leandro.lanzieri@haw-hamburg.de>
+ */
+
+#ifndef AD7746_INTERNAL_H
+#define AD7746_INTERNAL_H
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/**
+ * @name    AD7746 registers
+ * @{
+ */
+#define AD7746_REG_STATUS          (0x00) /**< Status */
+#define AD7746_REG_CAP_DATA_H      (0x01) /**< Capacitive channel data High */
+#define AD7746_REG_CAP_DATA_M      (0x02) /**< Capacitive channel data Med */
+#define AD7746_REG_CAP_DATA_L      (0x03) /**< Capacitive channel data Low */
+#define AD7746_REG_VT_DATA_H       (0x04) /**< Voltage/Temp channel data High */
+#define AD7746_REG_VT_DATA_M       (0x05) /**< Voltage/Temp channel data Med */
+#define AD7746_REG_VT_DATA_L       (0x06) /**< Voltage/Temp channel data Low */
+#define AD7746_REG_CAP_SETUP       (0x07) /**< Capacitive channel setup */
+#define AD7746_REG_VT_SETUP        (0x08) /**< Voltage/Temp channel setup */
+#define AD7746_REG_EXC_SETUP       (0x09) /**< Capacitive channel excitation setup */
+#define AD7746_REG_CONFIGURATION   (0x0A) /**< Configuration */
+#define AD7746_REG_CAP_DAC_A       (0x0B) /**< Capacitive DAC A setup */
+#define AD7746_REG_CAP_DAC_B       (0x0C) /**< Capacitive DAC B setup */
+#define AD7746_REG_CAP_OFF_H       (0x0D) /**< Capacitive offset High */
+#define AD7746_REG_CAP_OFF_L       (0x0E) /**< Capacitive offset Low */
+#define AD7746_REG_CAP_GAIN_H      (0x0F) /**< Capacitive gain High */
+#define AD7746_REG_CAP_GAIN_L      (0x10) /**< Capacitive gain Low */
+#define AD7746_REG_VOLT_GAIN_H     (0x11) /**< Voltage gain High */
+#define AD7746_REG_VOLT_GAIN_L     (0x12) /**< Voltage gain Low */
+/** @} */
+
+/**
+ * @brief   AD7746 reset command
+ */
+#define AD7746_RESET_CMD             (0xBF)
+
+/**
+ * @name    AD7746 Status register bits
+ * @{
+ */
+#define AD7746_STATUS_EXCERR_BIT         (3) /**< excitation output error */
+#define AD7746_STATUS_RDY_BIT            (2) /**< conversion ready */
+#define AD7746_STATUS_RDYVT_BIT          (1) /**< voltage/temperature ready */
+#define AD7746_STATUS_RDYCAP_BIT         (0) /**< capacitance ready */
+/** @} */
+
+/**
+ * @name    AD7746 Capacitive channel setup register bits
+ * @{
+ */
+#define AD7746_CAP_SETUP_CAPEN_BIT       (7) /**< capacitive channel enable */
+#define AD7746_CAP_SETUP_CIN2_BIT        (6) /**< second capacitive channel */
+#define AD7746_CAP_SETUP_CAPDIFF_BIT     (5) /**< differential mode enable*/
+#define AD7746_CAP_SETUP_CACHOP_BIT      (0) /**< capacitive channel chopping */
+/** @} */
+
+/**
+ * @name    AD7746 Voltage/Temperature channel setup register bits
+ * @{
+ */
+#define AD7746_VT_SETUP_VTEN_BIT         (7)
+#define AD7746_VT_SETUP_VTMD1_BIT        (6)
+#define AD7746_VT_SETUP_VTMD0_BIT        (5)
+#define AD7746_VT_SETUP_EXTREF_BIT       (4)
+#define AD7746_VT_SETUP_VTSHORT_BIT      (1)
+#define AD7746_VT_SETUP_VTCHOP_BIT       (0)
+/** @} */
+
+/**
+ * @name    AD7746 Capacitive channel excitation setup register bits
+ * @{
+ */
+#define AD7746_EXC_SETUP_CLKCTRL_BIT     (7) /**< Clock control */
+#define AD7746_EXC_SETUP_EXCON_BIT       (6) /**< Excitation signal control */
+#define AD7746_EXC_SETUP_EXCB_BIT        (5) /**< EXCB pin enable */
+#define AD7746_EXC_SETUP_INV_EXCB_BIT    (4) /**< EXCB pin disable */
+#define AD7746_EXC_SETUP_EXCA_BIT        (3) /**< EXCA pin enable */
+#define AD7746_EXC_SETUP_INV_EXCA_BIT    (2) /**<EXCA pin disable */
+#define AD7746_EXC_SETUP_EXCLVL1_BIT     (1) /**< Excitation voltage level 1 */
+#define AD7746_EXC_SETUP_EXCLVL0_BIT     (0) /**< Excitation voltage level 0 */
+/** @} */
+
+/**
+ * @name    AD7746 Configuration register bits
+ * @{
+ */
+#define AD7746_CONFIGURATION_VTF1_BIT    (7)
+#define AD7746_CONFIGURATION_VTF0_BIT    (6)
+#define AD7746_CONFIGURATION_CAPF2_BIT   (5)
+#define AD7746_CONFIGURATION_CAPF1_BIT   (4)
+#define AD7746_CONFIGURATION_CAPF0_BIT   (3)
+#define AD7746_CONFIGURATION_MD2_BIT     (2)
+#define AD7746_CONFIGURATION_MD1_BIT     (1)
+#define AD7746_CONFIGURATION_MD0_BIT     (0)
+/** @} */
+
+/**
+ * @name    AD7746 DAC A register bits
+ * @{
+ */
+#define AD7746_DACAEN_BIT                7
+/** @} */
+
+/**
+ * @name    AD7746 DAC B register bits
+ * @{
+ */
+#define AD7746_DACBEN_BIT                7
+/** @} */
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* AD7746_INTERNAL_H */
+/** @} */
diff --git a/drivers/ad7746/include/ad7746_params.h b/drivers/ad7746/include/ad7746_params.h
new file mode 100644
index 0000000000000000000000000000000000000000..df194b9dab3882cd2ab6f4b25e3c8def979c9958
--- /dev/null
+++ b/drivers/ad7746/include/ad7746_params.h
@@ -0,0 +1,101 @@
+/*
+ * Copyright (C) 2019 HAW Hamburg
+ *
+ * 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_ad7746
+ * @{
+ *
+ * @file
+ * @brief       Default configuration for AD7746 capaticance-to-digital
+ *              converter
+ *
+ * @author      Leandro Lanzieri <leandro.lanzieri@haw-hamburg.de>
+ */
+
+#ifndef AD7746_PARAMS_H
+#define AD7746_PARAMS_H
+
+#include "board.h"
+#include "saul_reg.h"
+#include "ad7746.h"
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/**
+ * @name    Set default configuration parameters for the AD7746 driver
+ * @{
+ */
+#ifndef AD7746_PARAM_I2C
+#define AD7746_PARAM_I2C        (I2C_DEV(0))
+#endif
+#ifndef AD7746_PARAM_ADDR
+#define AD7746_PARAM_ADDR       (0x48)
+#endif
+#ifndef AD7746_PARAM_CAP_SR
+#define AD7746_PARAM_CAP_SR     (AD7746_CAP_SR_091)
+#endif
+#ifndef AD7746_PARAM_VT_SR
+#define AD7746_PARAM_VT_SR      (AD7746_VT_SR_082)
+#endif
+#ifndef AD7746_PARAM_VT_MD
+#define AD7746_PARAM_VT_MD      (AD7746_VT_MD_TEMP)
+#endif
+#ifndef AD7746_PARAM_DAC_A
+#define AD7746_PARAM_DAC_A      (39) /* ~1.2pF */
+#endif
+#ifndef AD7746_PARAM_DAC_B
+#define AD7746_PARAM_DAC_B      (0)
+#endif
+#ifndef AD7746_PARAM_EXC_CONFIG
+#define AD7746_PARAM_EXC_CONFIG (AD7746_EXC_A)
+#endif
+#ifndef AD7746_PARAM_CAP_IN
+#define AD7746_PARAM_CAP_IN     (AD7746_CAP_IN_1)
+#endif
+
+#ifndef AD7746_PARAMS
+#define AD7746_PARAMS          { .i2c        = AD7746_PARAM_I2C,         \
+                                 .addr       = AD7746_PARAM_ADDR,        \
+                                 .dac_a_cap = AD7746_PARAM_DAC_A,        \
+                                 .dac_b_cap = AD7746_PARAM_DAC_B,        \
+                                 .exc_config = AD7746_PARAM_EXC_CONFIG,  \
+                                 .cap_sample_rate = AD7746_PARAM_CAP_SR, \
+                                 .vt_sample_rate = AD7746_PARAM_VT_SR,   \
+                                 .vt_mode = AD7746_PARAM_VT_MD,          \
+                                 .cap_input = AD7746_PARAM_CAP_IN }
+#endif
+#ifndef AD7746_SAUL_INFO
+#define AD7746_SAUL_INFO       { .name = "ad7746" }
+#endif
+/** @} */
+
+/**
+ * @brief   AD7746 configuration
+ */
+static const ad7746_params_t ad7746_params[] =
+{
+    AD7746_PARAMS
+};
+
+
+/**
+ * @brief   Additional meta information to keep in the SAUL registry
+ */
+static const saul_reg_info_t ad7746_saul_info[] =
+{
+    AD7746_SAUL_INFO
+};
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* AD7746_PARAMS_H */
+/** @} */
diff --git a/drivers/include/ad7746.h b/drivers/include/ad7746.h
new file mode 100644
index 0000000000000000000000000000000000000000..a1eac6a9f9c54acea607a5bf2091a1efba2343ff
--- /dev/null
+++ b/drivers/include/ad7746.h
@@ -0,0 +1,335 @@
+/*
+ * Copyright (C) 2019 HAW Hamburg
+ *
+ * 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_ad7746 AD7746 Capacitance-to-digital converter driver
+ * @ingroup    drivers_sensors
+ * @ingroup    drivers_saul
+ * @brief      I2C Capacitance-to-digital converter with temperature and voltage
+ *             sensors. The devices has two main channels: capacitance channel
+ *             and voltage / temperature channel.
+ *
+ *             The capacitance channel can measure from two different inputs
+ *             (CIN1 and CIN2), selected using @ref ad7746_set_cap_ch_input.
+ *
+ *             The voltage / temperature channel can measure from five different
+ *             sources: Voltage from VIN pins, internal VCC, internal
+ *             temperature sensor and external temperature sensor
+ *             (see datasheet for proper setup). The mode of this channel can be
+ *             set using @ref ad7746_set_vt_ch_mode or will directly be set
+ *             when trying to read from a specific source which is not the
+ *             currently selected one. This mode change may lead to data not
+ *             being available right away (in which case the reading function
+ *             will return @ref AD7746_NODATA error code).
+ *
+ * @note       Constantly switching between modes in the voltage / temperature
+ *             channel may lead to invalid data, for what it seems to be a
+ *             device limitation.
+ *
+ * This driver provides @ref drivers_saul capabilities.
+ * @{
+ *
+ * @file
+ * @brief      AD7746 Capacitance-to-digital converter with temperature
+ *             sensor driver
+ *
+ * @author     Leandro Lanzieri <leandro.lanzieri@haw-hamburg.de>
+ */
+
+#ifndef AD7746_H
+#define AD7746_H
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+#include "periph/i2c.h"
+#include "periph/gpio.h"
+
+/**
+ * @brief 0 fF capacitance code
+ */
+#define AD7746_ZERO_SCALE_CODE  (0x800000LL)
+
+/**
+ * @brief Interval voltage reference expressed in mV
+ */
+#define AD7746_INTERNAL_VREF    (1170)
+
+/**
+ * @brief Maximum value that can be configured into the DACs.
+ */
+#define AD7746_DAC_MAX          (0x7F)
+
+/**
+ * @brief Channel numbers for reading
+ */
+enum {
+    AD7746_READ_CAP_CH = 0, /**< read capacitive channel */
+    AD7746_READ_VT_CH  = 1  /**< read voltage / temperature channel */
+};
+
+/**
+ * @brief   Named return values
+ */
+enum {
+    AD7746_OK          =  0,       /**< everything was fine */
+    AD7746_NOI2C       = -1,       /**< I2C communication failed */
+    AD7746_NODEV       = -2,       /**< no AD7746 device found on the bus */
+    AD7746_NODATA      = -3        /**< no data available */
+};
+
+/**
+ * @brief Voltage / Temperature channel sample rates
+ */
+typedef enum {
+    AD7746_VT_SR_498 = 0, /**< 49.8 Hz */
+    AD7746_VT_SR_312 = 1, /**< 31.2 Hz */
+    AD7746_VT_SR_161 = 2, /**< 16.1 Hz */
+    AD7746_VT_SR_082 = 3  /**<  8.2 Hz */
+} ad7746_vt_sample_rate_t;
+
+/**
+ * @brief Voltage / Temperature channel modes
+ */
+typedef enum {
+    AD7746_VT_MD_DIS   = -1, /**< channel disabled */
+    AD7746_VT_MD_TEMP  = 0,  /**< internal temperature sensor */
+    AD7746_VT_MD_ETEMP = 1,  /**< external temperature sensor (see datasheet) */
+    AD7746_VT_MD_VDD   = 2,  /**< Vdd voltage monitor */
+    AD7746_VT_MD_VIN   = 3   /**< external voltage input (Vin) */
+} ad7746_vt_mode_t;
+
+/**
+ * @brief Capacitance channel input
+ */
+typedef enum {
+    AD7746_CAP_IN_1 = 0, /**< CIN1 input */
+    AD7746_CAP_IN_2      /**< CIN2 input */
+} ad7746_cap_input_t;
+
+/**
+ * @brief Capacitive channel sample rate
+ */
+typedef enum {
+    AD7746_CAP_SR_909 = 0, /**< 90.9 Hz */
+    AD7746_CAP_SR_838 = 1, /**< 83.8 Hz */
+    AD7746_CAP_SR_500 = 2, /**< 50.0 Hz */
+    AD7746_CAP_SR_263 = 3, /**< 26.3 Hz */
+    AD7746_CAP_SR_161 = 4, /**< 16.1 Hz */
+    AD7746_CAP_SR_130 = 5, /**< 13.0 Hz */
+    AD7746_CAP_SR_109 = 6, /**< 10.9 Hz */
+    AD7746_CAP_SR_091 = 7  /**<  9.1 Hz */
+} ad7746_cap_sample_rate_t;
+
+/**
+ * @brief Excitation signal output configuration
+ */
+typedef enum {
+    AD7746_EXC_A  = 0x06,  /**< enable only exc A output */
+    AD7746_EXC_B  = 0x09,  /**< enable only exc B output */
+    AD7746_EXC_AB = 0x0A   /**< enable exc A and B outputs */
+} ad7746_exc_config_t;
+
+/**
+ * @brief   AD7746 params
+ */
+typedef struct ad7746_params {
+    i2c_t i2c;                                /**< i2c device */
+    uint8_t addr;                             /**< i2c address */
+    uint8_t dac_a_cap;                        /**< DAC A capacitance */
+    uint8_t dac_b_cap;                        /**< DAC B capacitance */
+    ad7746_exc_config_t exc_config;           /**< excitation signal config */
+    ad7746_cap_sample_rate_t cap_sample_rate; /**< capacitance sample rate */
+    ad7746_vt_sample_rate_t vt_sample_rate;   /**< voltage/temp sample rate */
+    ad7746_vt_mode_t vt_mode;                 /**< mode of the voltage/temp ch */
+    ad7746_cap_input_t cap_input;             /**< selected capacitance input*/
+} ad7746_params_t;
+
+/**
+ * @brief   AD7746 device descriptor
+ */
+typedef struct ad7746 {
+    ad7746_params_t params; /**< device driver configuration */
+} ad7746_t;
+
+/**
+ * @brief   Initializes an AD7746 device
+ *
+ * @param[in,out] dev  device descriptor
+ * @param[in] params   device configuration
+ *
+ * @return AD7746_OK on success
+ * @return AD7746_NODEV if no device is found on the bus
+ * @return AD7746_NOI2C if other error occurs
+ */
+int ad7746_init(ad7746_t *dev, const ad7746_params_t *params);
+
+/**
+ * @brief Reads the capacitance from the input 1 (CIN1). Returns the value in
+ *        fF.
+ *
+ * @note If the currently selected input does not match @ref AD7746_CAP_IN_1 it
+ *       will be changed to it. This may cause data not to be available right
+ *       away. The time until new data is available will depend on the
+ *       @ref ad7746_params_t::cap_sample_rate "sample rate" of the channel.
+ *
+ * @param[in, out] dev  device decriptor
+ * @param[out] value    read value in fF
+ *
+ * @return AD7746_OK on success
+ * @return AD7746_NODATA if there is no data available in the channel
+ * @return AD7746_I2C if other error occurs
+ */
+int ad7746_read_capacitance_1(ad7746_t *dev, int *value);
+
+/**
+ * @brief Reads the capacitance from the input 2 (CIN2). Returns the value in
+ *        fF.
+ *
+ * @note If the currently selected input does not match @ref AD7746_CAP_IN_2 it
+ *       will be changed to it. This may cause data not to be available right
+ *       away. The time until new data is available will depend on the
+ *       @ref ad7746_params_t::cap_sample_rate "sample rate" of the channel.
+ *
+ * @param[in, out] dev device decriptor
+ * @param[out] value read value in fF
+ *
+ * @return AD7746_OK on success
+ * @return AD7746_NODATA if there is no data available in the channel
+ * @return AD7746_I2C if other error occurs
+ */
+int ad7746_read_capacitance_2(ad7746_t *dev, int *value);
+
+/**
+ * @brief Reads the voltage from the external voltage input (VIN). Returns the
+ *        value in mV.
+ *
+ * @note If the current mode of the voltage / temperature channel does not match
+ *       @ref AD7746_VT_MD_VIN it will be changed to this mode, causing data not
+ *       to be available right away. The time until new data is available will
+ *       depend on the @ref ad7746_params_t::vt_sample_rate "sample rate" of the
+ *       channel.
+ *
+ * @param[in, out] dev device descriptor
+ * @param[out] value read value in mV
+ *
+ * @return AD7746_OK on success
+ * @return AD7746_NODATA if there is no data available in the channel
+ * @return AD7746_I2C if other error occurs
+ */
+int ad7746_read_voltage_in(ad7746_t *dev, int *value);
+
+/**
+ * @brief Reads the voltage from the VDD pin. Returns the value in mV.
+ *
+ * @note If the current mode of the voltage / temperature channel does not match
+ *       @ref AD7746_VT_MD_VDD it will be changed to this mode, causing data not
+ *       to be available right away. The time until new data is available will
+ *       depend on the @ref ad7746_params_t::vt_sample_rate "sample rate" of the
+ *       channel.
+ *
+ * @param[in, out] dev device descriptor
+ * @param[out] value read value in mV
+ *
+ * @return AD7746_OK on success
+ * @return AD7746_NODATA if there is no data available in the channel
+ * @return AD7746_I2C if other error occurs
+ */
+int ad7746_read_voltage_vdd(ad7746_t *dev, int *value);
+
+/**
+ * @brief Reads the temperature from the internal sensor.
+ *
+ * @note If the current mode of the voltage / temperature channel does not match
+ *       @ref AD7746_VT_MD_TEMP it will be changed to this mode, causing data
+ *       not to be available right away. The time until new data is available
+ *       will depend on the @ref ad7746_params_t::vt_sample_rate "sample rate"
+ *       of the channel.
+ *
+ * @param[in, out] dev device descriptor
+ * @param[out] value read value in celsius
+ *
+ * @return AD7746_OK on success
+ * @return AD7746_NODATA if there is no data available in the channel
+ * @return AD7746_I2C if other error occurs
+ */
+int ad7746_read_temperature_int(ad7746_t *dev, int *value);
+
+/**
+ * @brief Reads the temperature from the external sensor (see datasheet).
+ *
+ * @note If the current mode of the voltage / temperature channel does not match
+ *       @ref AD7746_VT_MD_ETEMP it will be changed to this mode, causing data
+ *       not to be available right away. The time until new data is available
+ *       will depend on the @ref ad7746_params_t::vt_sample_rate "sample rate"
+ *       of the channel.
+ *
+ * @param[in, out] dev device descriptor
+ * @param[out] value read value in celsius
+ *
+ * @return AD7746_OK on success
+ * @return AD7746_NODATA if there is no data available in the channel
+ * @return AD7746_I2C if other error occurs
+ */
+int ad7746_read_temperature_ext(ad7746_t *dev, int *value);
+
+/**
+ * @brief   Sets the current input for the capacitive measurement.If not
+            configured manually, the driver sets the correct mode within
+            the dedicated read function.
+ *
+ * @param[in] dev      device descriptor
+ * @param[in] input  selected input - 0 for CIN1, 1 for CIN2
+ *
+ * @return AD7746_OK on success
+ * @return AD7746_NOI2C on error
+ */
+int ad7746_set_cap_ch_input(const ad7746_t *dev, ad7746_cap_input_t input);
+
+/**
+ * @brief   Sets the mode for the voltage / temperature channel and updates the
+ *          descriptor with the new configuration. If not configured manually,
+            the driver sets the correct mode within the dedicated read function.
+ *
+ * @param[in, out]  dev   device descriptor
+ * @param[in] mode  mode to which the channel has to be set
+ *
+ * @return AD7746_OK on success
+ * @return AD7746_NOI2C on error
+ */
+int ad7746_set_vt_ch_mode(ad7746_t *dev, ad7746_vt_mode_t mode);
+
+/**
+ * @brief   Sets the sample rate for the voltage / temperature channel
+ *
+ * @param[in] dev   device descriptor
+ * @param[in] sr    sample rate
+ *
+ * @return AD7746_OK on success
+ * @return AD7746_NOI2C on error
+ */
+int ad7746_set_vt_sr(const ad7746_t *dev, ad7746_vt_sample_rate_t sr);
+
+/**
+ * @brief   Sets the sample rate for the capacitance channel
+ *
+ * @param[in] dev   device descriptor
+ * @param[in] sr    sample rate
+ *
+ * @return AD7746_OK on success
+ * @return AD7746_NOI2C on error
+ */
+int ad7746_set_cap_sr(const ad7746_t *dev, ad7746_cap_sample_rate_t sr);
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* AD7746_H */
+/** @} */