From 8b8790c18f12404ca8e00a605b4e9acd7014e8cd Mon Sep 17 00:00:00 2001
From: Frits Kuipers <f.p.kuipers@student.utwente.nl>
Date: Thu, 26 Jan 2017 21:18:55 +0100
Subject: [PATCH] drivers/ds18: Add Maxim Integrated ds18 driver

tests/driver_ds18: Add test application for DS18B20 sensor.

tests/driver_ds18: Add whitelist of boards
---
 drivers/Makefile.dep                |   5 +
 drivers/Makefile.include            |   4 +
 drivers/ds18/Makefile               |   1 +
 drivers/ds18/ds18.c                 | 221 ++++++++++++++++++++++++++++
 drivers/ds18/ds18_internal.h        |  64 ++++++++
 drivers/ds18/ds18_saul.c            |  42 ++++++
 drivers/ds18/include/ds18_params.h  |  69 +++++++++
 drivers/include/ds18.h              | 127 ++++++++++++++++
 makefiles/pseudomodules.inc.mk      |   3 +
 sys/auto_init/auto_init.c           |   4 +
 sys/auto_init/saul/auto_init_ds18.c |  74 ++++++++++
 tests/driver_ds18/Makefile          |  11 ++
 tests/driver_ds18/Readme.md         |   7 +
 tests/driver_ds18/main.c            |  63 ++++++++
 14 files changed, 695 insertions(+)
 create mode 100644 drivers/ds18/Makefile
 create mode 100644 drivers/ds18/ds18.c
 create mode 100644 drivers/ds18/ds18_internal.h
 create mode 100644 drivers/ds18/ds18_saul.c
 create mode 100644 drivers/ds18/include/ds18_params.h
 create mode 100644 drivers/include/ds18.h
 create mode 100644 sys/auto_init/saul/auto_init_ds18.c
 create mode 100644 tests/driver_ds18/Makefile
 create mode 100644 tests/driver_ds18/Readme.md
 create mode 100644 tests/driver_ds18/main.c

diff --git a/drivers/Makefile.dep b/drivers/Makefile.dep
index 6a3de6c93d..9204a35499 100644
--- a/drivers/Makefile.dep
+++ b/drivers/Makefile.dep
@@ -119,6 +119,11 @@ ifneq (,$(filter dynamixel,$(USEMODULE)))
   USEMODULE += uart_half_duplex
 endif
 
+ifneq (,$(filter ds18,$(USEMODULE)))
+    USEMODULE += xtimer
+    FEATURES_REQUIRED += periph_gpio
+endif
+
 ifneq (,$(filter enc28j60,$(USEMODULE)))
   FEATURES_REQUIRED += periph_gpio
   FEATURES_REQUIRED += periph_gpio_irq
diff --git a/drivers/Makefile.include b/drivers/Makefile.include
index 19bb780f39..56d6b7f373 100644
--- a/drivers/Makefile.include
+++ b/drivers/Makefile.include
@@ -214,6 +214,10 @@ ifneq (,$(filter si114x,$(USEMODULE)))
   USEMODULE_INCLUDES += $(RIOTBASE)/drivers/si114x/include
 endif
 
+ifneq (,$(filter ds18,$(USEMODULE)))
+    USEMODULE_INCLUDES += $(RIOTBASE)/drivers/ds18/include
+endif
+
 ifneq (,$(filter si70xx,$(USEMODULE)))
   USEMODULE_INCLUDES += $(RIOTBASE)/drivers/si70xx/include
 endif
diff --git a/drivers/ds18/Makefile b/drivers/ds18/Makefile
new file mode 100644
index 0000000000..48422e909a
--- /dev/null
+++ b/drivers/ds18/Makefile
@@ -0,0 +1 @@
+include $(RIOTBASE)/Makefile.base
diff --git a/drivers/ds18/ds18.c b/drivers/ds18/ds18.c
new file mode 100644
index 0000000000..f2bae940fe
--- /dev/null
+++ b/drivers/ds18/ds18.c
@@ -0,0 +1,221 @@
+/*
+ * Copyright (C) 2017 Frits Kuipers
+ *               2018 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_ds18
+ * @{
+ *
+ * @file
+ * @brief       Device driver implementation for the Maxim Integrated DS1822 and
+ *              DS18B20 temperature sensors.
+ *
+ * @author      Frits Kuipers <frits.kuipers@gmail.com>
+ * @author      Leandro Lanzieri <leandro.lanzieri@haw-hamburg.de>
+ * @}
+ */
+
+#include "ds18.h"
+#include "ds18_internal.h"
+
+#include "log.h"
+#include "periph/gpio.h"
+#include "xtimer.h"
+
+#define ENABLE_DEBUG (0)
+#include "debug.h"
+
+static void ds18_low(ds18_t *dev)
+{
+    /* Set gpio as output and clear pin */
+    gpio_init(dev->pin, GPIO_OUT);
+    gpio_clear(dev->pin);
+}
+
+static void ds18_release(ds18_t *dev)
+{
+    /* Init pin as input */
+    gpio_init(dev->pin, dev->in_mode);
+}
+
+static void ds18_write_bit(ds18_t *dev, uint8_t bit)
+{
+    /* Initiate write slot */
+    ds18_low(dev);
+
+    /* Release pin when bit==1 */
+    if (bit) {
+        ds18_release(dev);
+    }
+
+    /* Wait for slot to end */
+    xtimer_usleep(DS18_DELAY_SLOT);
+    ds18_release(dev);
+    xtimer_usleep(1);
+}
+
+static int ds18_read_bit(ds18_t *dev, uint8_t *bit)
+{
+    /* Initiate read slot */
+    ds18_low(dev);
+    ds18_release(dev);
+
+#if defined(MODULE_DS18_OPTIMIZED)
+    xtimer_usleep(DS18_SAMPLE_TIME);
+    *bit = gpio_read(dev->pin);
+    xtimer_usleep(DS18_DELAY_R_RECOVER);
+    return DS18_OK;
+#else
+    uint32_t start, measurement = 0;
+
+    /* Measure time low of device pin, timeout after slot time*/
+    start = xtimer_now_usec();
+    while (!gpio_read(dev->pin) && measurement < DS18_DELAY_SLOT) {
+        measurement = xtimer_now_usec() - start;
+    }
+
+    /* If there was a timeout return error */
+    if (measurement >= DS18_DELAY_SLOT) {
+        return DS18_ERROR;
+    }
+
+    /* When gpio was low for less than the sample time, bit is high*/
+    *bit = measurement < DS18_SAMPLE_TIME;
+
+    /* Wait for slot to end */
+    xtimer_usleep(DS18_DELAY_SLOT - measurement);
+
+    return DS18_OK;
+#endif
+}
+
+static int ds18_read_byte(ds18_t *dev, uint8_t *byte)
+{
+    uint8_t bit = 0;
+    *byte = 0;
+
+    for (int i = 0; i < 8; i++) {
+        if (ds18_read_bit(dev, &bit) == DS18_OK) {
+            *byte |= (bit << i);
+        }
+        else {
+            return DS18_ERROR;
+        }
+    }
+
+    return DS18_OK;
+}
+
+static void ds18_write_byte(ds18_t *dev, uint8_t byte)
+{
+    for (int i = 0; i < 8; i++) {
+        ds18_write_bit(dev, byte & (0x01 << i));
+    }
+}
+
+static int ds18_reset(ds18_t *dev)
+{
+    int res;
+
+    /* Line low and sleep the reset delay */
+    ds18_low(dev);
+    xtimer_usleep(DS18_DELAY_RESET);
+
+    /* Release and wait for the presence response */
+    ds18_release(dev);
+    xtimer_usleep(DS18_DELAY_PRESENCE);
+
+    /* Check device presence */
+    res = gpio_read(dev->pin);
+
+    /* Sleep for reset delay */
+    xtimer_usleep(DS18_DELAY_RESET);
+
+    return res;
+}
+
+int ds18_trigger(ds18_t *dev)
+{
+    int res;
+
+    res = ds18_reset(dev);
+    if (res) {
+        return DS18_ERROR;
+    }
+
+    /* Please note that this command triggers a conversion on all devices
+     * connected to the bus. */
+    ds18_write_byte(dev, DS18_CMD_SKIPROM);
+    ds18_write_byte(dev, DS18_CMD_CONVERT);
+
+    return DS18_OK;
+}
+
+int ds18_read(ds18_t *dev, int16_t *temperature)
+{
+    int res;
+    uint8_t b1 = 0, b2 = 0;
+
+    DEBUG("[DS18] Reset and read scratchpad\n");
+    res = ds18_reset(dev);
+    if (res) {
+        return DS18_ERROR;
+    }
+
+    ds18_write_byte(dev, DS18_CMD_SKIPROM);
+    ds18_write_byte(dev, DS18_CMD_RSCRATCHPAD);
+
+    if (ds18_read_byte(dev, &b1) != DS18_OK) {
+        DEBUG("[DS18] Error reading temperature byte 1\n");
+        return DS18_ERROR;
+    }
+
+    DEBUG("[DS18] Received byte: 0x%02x\n", b1);
+
+    if (ds18_read_byte(dev, &b2) != DS18_OK) {
+        DEBUG("[DS18] Error reading temperature byte 2\n");
+        return DS18_ERROR;
+    }
+
+    DEBUG("[DS18] Received byte: 0x%02x\n", b2);
+
+    int32_t measurement = ((int32_t)(b2 << 8 | b1) * 625);
+    *temperature = (int16_t)(measurement / 100);
+
+    return DS18_OK;
+}
+
+int ds18_get_temperature(ds18_t *dev, int16_t *temperature)
+{
+
+    DEBUG("[DS18] Convert T\n");
+    if (ds18_trigger(dev)) {
+        return DS18_ERROR;
+    }
+
+    DEBUG("[DS18] Wait for convert T\n");
+    xtimer_usleep(DS18_DELAY_CONVERT);
+
+    return ds18_read(dev, temperature);
+}
+
+int ds18_init(ds18_t *dev, const ds18_params_t *params)
+{
+    int res;
+
+    /* Deduct the input mode from the output mode. If pull-up resistors are
+     * used for output then will be used for input as well. */
+    dev->in_mode = (params->out_mode == GPIO_OD_PU) ? GPIO_IN_PU : GPIO_IN;
+
+    /* Initialize the device and the pin */
+    dev->pin = params->pin;
+    dev->out_mode = params->out_mode;
+    res = gpio_init(dev->pin, dev->in_mode) == 0 ? DS18_OK : DS18_ERROR;
+
+    return res;
+}
diff --git a/drivers/ds18/ds18_internal.h b/drivers/ds18/ds18_internal.h
new file mode 100644
index 0000000000..d079be08e7
--- /dev/null
+++ b/drivers/ds18/ds18_internal.h
@@ -0,0 +1,64 @@
+/*
+ * Copyright (C) 2017 Frits Kuipers
+ *               2018 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_sensors
+ * @{
+ *
+ * @file
+ * @brief       Internal addresses, registers, constants for DS1822 and DS18B20 temperature sensors.
+ *
+ * @author      Frits Kuipers <frits.kuipers@gmail.com>
+ * @author      Leandro Lanzieri <leandro.lanzieri@haw-hamburg.de>
+ */
+
+#ifndef DS18_INTERNAL_H
+#define DS18_INTERNAL_H
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/**
+ * @name ds18 commands
+ * @{
+ */
+#define DS18_CMD_CONVERT            (0x44)
+#define DS18_CMD_RSCRATCHPAD        (0xbe)
+#define DS18_CMD_WRITESCRATCHPAD    (0x4e)
+#define DS18_CMD_COPYSCRATCHPAD     (0x48)
+#define DS18_CMD_RECALLE            (0xb8)
+#define DS18_CMD_RPWRSPPLY          (0xb4)
+#define DS18_CMD_SEARCHROM          (0xf0)
+#define DS18_CMD_READROM            (0x33)
+#define DS18_CMD_MATCHROM           (0x55)
+#define DS18_CMD_SEARCHROM          (0xf0)
+#define DS18_CMD_ALARMSEARCH        (0xec)
+#define DS18_CMD_SKIPROM            (0xcc)
+/** @} */
+
+/**
+ * @name ds18 delays
+ * @{
+ */
+#define DS18_DELAY_RESET            (480U)
+#define DS18_DELAY_PRESENCE         (60U)
+#define DS18_DELAY_SLOT             (60U)
+#define DS18_SAMPLE_TIME            (10U)
+#define DS18_DELAY_CONVERT          (750U * US_PER_MS)
+#define DS18_DELAY_RW_PULSE         (1U)
+#define DS18_DELAY_R_RECOVER        (DS18_DELAY_SLOT - DS18_SAMPLE_TIME)
+/** @} */
+
+#ifdef __cplusplus
+}
+#endif
+/** @} */
+
+#endif /* DS18_INTERNAL_H */
diff --git a/drivers/ds18/ds18_saul.c b/drivers/ds18/ds18_saul.c
new file mode 100644
index 0000000000..996d3bd295
--- /dev/null
+++ b/drivers/ds18/ds18_saul.c
@@ -0,0 +1,42 @@
+/*
+ * Copyright (C) 2017 Frits Kuipers
+ *               2018 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_ds18
+ * @{
+ *
+ * @file
+ * @brief       SAUL adaption for Maxim Integrated DS1822 and DS18B20 temperature sensors
+ *
+ * @author      Frits Kuipers <frits.kuipers@gmail.com>
+ * @author      Leandro Lanzieri <leandro.lanzieri@haw-hamburg.de>
+ * @}
+ */
+
+#include <string.h>
+
+#include "saul.h"
+#include "ds18.h"
+
+static int read_temperature(const void *dev, phydat_t *res)
+{
+    if (ds18_get_temperature((ds18_t *)dev, &res->val[0]) == DS18_ERROR) {
+        return -ECANCELED;
+    }
+
+    res->unit = UNIT_TEMP_C;
+    res->scale = -2;
+    return 1;
+}
+
+const saul_driver_t ds18_temperature_saul_driver = {
+    .read = read_temperature,
+    .write = saul_notsup,
+    .type = SAUL_SENSE_TEMP
+};
diff --git a/drivers/ds18/include/ds18_params.h b/drivers/ds18/include/ds18_params.h
new file mode 100644
index 0000000000..3bf3c3cf3d
--- /dev/null
+++ b/drivers/ds18/include/ds18_params.h
@@ -0,0 +1,69 @@
+/*
+ * Copyright (C) 2017 Frits Kuipers
+ *
+ * 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_ds18
+ *
+ * @{
+ * @file
+ * @brief       Default configuration for DS1822 and DS18B20 temperature sensors
+ *
+ * @author      Frits Kuipers <frits.kuipers@gmail.com>
+ */
+
+#ifndef DS18_PARAMS_H
+#define DS18_PARAMS_H
+
+#include "ds18.h"
+#include "saul_reg.h"
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/**
+ * @brief   Set default configuration parameters for the ds18
+ * @{
+ */
+#ifndef DS18_PARAM_PIN
+#define DS18_PARAM_PIN             (GPIO_PIN(0, 0))
+#endif
+#ifndef DS18_PARAM_PULL
+#define DS18_PARAM_PULL            (GPIO_OD_PU)
+#endif
+
+#define DS18_PARAMS_DEFAULT        { .pin     = DS18_PARAM_PIN, \
+                                     .out_mode = DS18_PARAM_PULL }
+/**@}*/
+
+/**
+ * @brief   Configure ds18
+ */
+static const ds18_params_t ds18_params[] =
+{
+#ifdef DS18_PARAMS_BOARD
+    DS18_PARAMS_BOARD,
+#else
+    DS18_PARAMS_DEFAULT,
+#endif
+};
+
+/**
+ * @brief   Configure SAUL registry entries
+ */
+static const saul_reg_info_t ds18_saul_reg_info[] =
+{
+    { .name = "ds18" }
+};
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* DS18_PARAMS_H */
+/** @} */
diff --git a/drivers/include/ds18.h b/drivers/include/ds18.h
new file mode 100644
index 0000000000..8840c3dccb
--- /dev/null
+++ b/drivers/include/ds18.h
@@ -0,0 +1,127 @@
+/*
+ * Copyright (C) 2017 Frits Kuipers
+ *
+ * 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_ds18 DS18 temperature sensor driver
+ * @ingroup     drivers_sensors
+ * @ingroup     drivers_saul
+ * @brief       Driver interface for the DS18 temperature sensors
+ *
+ * This driver provides @ref drivers_saul capabilities.
+ * Currently the driver has the following limitations:
+ *- Does not allow addressing devices, only supports a single device on the bus.
+ *- The 1-Wire bus handling is hardcoded to the driver.
+ *- Does not allow configuration of sampling width.
+ *
+ * @note Due to timing issues present on some boards this drivers features two
+ * ways of reading information from the sensor. The optimized uses accurate
+ * delays to handle this, while the second way polls the line for changes. If
+ * you know that your board can handle ~3us resolution with the xtimer module,
+ * then the optimized way is recommended. To used the optimized way add the
+ * ds18_optimized module. Also this driver test application has a whitelist of
+ * the boards this driver has been tested on and known to work.
+ *
+ * @{
+ *
+ * @file
+ * @brief       Driver for Maxim Integrated DS1822 and DS18B20 temperature
+ *              sensors.
+ *
+ * @author      Frits Kuipers <frits.kuipers@gmail.com>
+ */
+
+#ifndef DS18_H
+#define DS18_H
+
+#include "periph/gpio.h"
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/**
+ * @name ds18 status return codes
+ * @{
+ */
+#define DS18_OK                       (0)
+#define DS18_ERROR                    (-1)
+/** @} */
+
+
+/**
+ * @brief   Device descriptor for a ds18 device
+ */
+typedef struct {
+    gpio_t pin;             /**< Pin the sensor is connected to */
+    gpio_mode_t out_mode;  /**< Pin output mode */
+    gpio_mode_t in_mode;    /**< Pin input mode */
+} ds18_t;
+
+/**
+ * @brief Device initialization parameters
+ */
+typedef struct {
+    gpio_t pin;             /**< Pin the sensor is connected to */
+    gpio_mode_t out_mode;    /**< Pin output mode */
+} ds18_params_t;
+
+/**
+ * @brief   Initialize a ds18 device
+ *
+ * @param[out] dev          device descriptor
+ * @param[in]  params       ds18 initialization struct
+ *
+ *
+ * @return                   0 on success
+ * @return                  -1 on error
+ */
+int ds18_init(ds18_t *dev, const ds18_params_t *params);
+
+/**
+ * @brief Triggers a temperature conversion
+ * @note This also triggers a conversion on all devices connected to the bus
+ *
+ * @param[in] dev           device descriptor
+ *
+ * @return                  0 on success
+ * @return                 -1 on error
+ */
+int ds18_trigger(ds18_t *dev);
+
+/**
+ * @brief Reads the scratchpad for the last conversion
+ *
+ * @param[in] dev           device descriptor
+ * @param[out] temperature  buffer to write the temperature in centi-degrees
+ *
+ * @return                  0 on success
+ * @return                 -1 on error
+ */
+int ds18_read(ds18_t *dev, int16_t *temperature);
+
+/**
+ * @brief   convenience fuction for triggering a conversion and reading the
+ * value
+ *
+ * @note This function will block for the convertion time. The current
+ * implementation of the driver uses 12-bit resolution, so this time is 750 ms.
+ *
+ * @param[in] dev           device descriptor
+ * @param[out] temperature  buffer to write the temperature in centi-degrees
+ *
+ * @return                   0 on success
+ * @return                  -1 on error
+ */
+int ds18_get_temperature(ds18_t *dev, int16_t *temperature);
+
+#ifdef __cplusplus
+}
+#endif
+
+/** @} */
+#endif /* DS18_H */
diff --git a/makefiles/pseudomodules.inc.mk b/makefiles/pseudomodules.inc.mk
index f27ea28fb4..c6dbd47ac7 100644
--- a/makefiles/pseudomodules.inc.mk
+++ b/makefiles/pseudomodules.inc.mk
@@ -123,4 +123,7 @@ PSEUDOMODULES += auto_init_skald
 PSEUDOMODULES += skald_ibeacon
 PSEUDOMODULES += skald_eddystone
 
+# define optimized read function of DS18 driver as a pseudo module
+PSEUDOMODULES += ds18_optimized
+
 # Packages may also add modules to PSEUDOMODULES in their `Makefile.include`.
diff --git a/sys/auto_init/auto_init.c b/sys/auto_init/auto_init.c
index d81277d478..702dfeec52 100644
--- a/sys/auto_init/auto_init.c
+++ b/sys/auto_init/auto_init.c
@@ -340,6 +340,10 @@ void auto_init(void)
     extern void auto_init_dht(void);
     auto_init_dht();
 #endif
+#ifdef MODULE_DS18
+    extern void auto_init_ds18(void);
+    auto_init_ds18();
+#endif
 #ifdef MODULE_FXOS8700
     extern void auto_init_fxos8700(void);
     auto_init_fxos8700();
diff --git a/sys/auto_init/saul/auto_init_ds18.c b/sys/auto_init/saul/auto_init_ds18.c
new file mode 100644
index 0000000000..ea12fbac1c
--- /dev/null
+++ b/sys/auto_init/saul/auto_init_ds18.c
@@ -0,0 +1,74 @@
+/*
+ * Copyright (C) 2017 Frits Kuipers
+ *
+ * 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     auto_init_saul
+ * @{
+ *
+ * @file
+ * @brief       Auto initialization of ds18 driver.
+ *
+ * @author      Frits Kuipers <frits.kuipers@gmail.com>
+ *
+ * @}
+ */
+
+#ifdef MODULE_DS18
+
+#include "log.h"
+#include "saul_reg.h"
+
+#include "ds18.h"
+#include "ds18_params.h"
+
+/**
+ * @brief   Define the number of configured sensors
+ */
+#define DS18_NUMOF    (sizeof(ds18_params) / sizeof(ds18_params[0]))
+
+/**
+ * @brief   Allocation of memory for device descriptors
+ */
+static ds18_t ds18_devs[DS18_NUMOF];
+
+/**
+ * @brief   Memory for the SAUL registry entries
+ */
+static saul_reg_t saul_entries[DS18_NUMOF];
+
+/**
+ * @brief   Reference the driver structs.
+ * @{
+ */
+extern const saul_driver_t ds18_temperature_saul_driver;
+/** @} */
+
+void auto_init_ds18(void)
+{
+    for (unsigned i = 0; i < DS18_NUMOF; i++) {
+        const ds18_params_t *p = &ds18_params[i];
+
+        LOG_DEBUG("[auto_init_saul] initializing ds18 #%u\n", i);
+
+        if (ds18_init(&ds18_devs[i], (ds18_params_t *) p) < 0) {
+            LOG_ERROR("[auto_init_saul] error initializing ds18 #%u\n", i);
+            return;
+        }
+
+        /* temperature */
+        saul_entries[i].dev = &(ds18_devs[i]);
+        saul_entries[i].name = ds18_saul_reg_info[i].name;
+        saul_entries[i].driver = &ds18_temperature_saul_driver;
+
+        /* register to saul */
+        saul_reg_add(&(saul_entries[i]));
+    }
+}
+#else
+typedef int dont_be_pedantic;
+#endif /* MODULE_DS18 */
diff --git a/tests/driver_ds18/Makefile b/tests/driver_ds18/Makefile
new file mode 100644
index 0000000000..781ffbc12b
--- /dev/null
+++ b/tests/driver_ds18/Makefile
@@ -0,0 +1,11 @@
+include ../Makefile.tests_common
+
+BOARD_WHITELIST := sensebox_samd21 samr21-xpro nucleo-l152re
+
+USEMODULE += ds18
+USEMODULE += xtimer
+USEMODULE += printf_float
+# Use the module if you have an accurate sleep with xtimer (~3us)
+#USEMODULE += ds18_optimized
+
+include $(RIOTBASE)/Makefile.include
diff --git a/tests/driver_ds18/Readme.md b/tests/driver_ds18/Readme.md
new file mode 100644
index 0000000000..108faa555a
--- /dev/null
+++ b/tests/driver_ds18/Readme.md
@@ -0,0 +1,7 @@
+## About
+This is a test application for the Maxime [DS18B20](https://datasheets.maximintegrated.com/en/ds/DS18B20.pdf) 1-Wire temperature
+sensor.
+
+## Usage
+The application will initialize the DS18B20 sensor and every 2 seconds will read
+the temperature and print the measurement to STDOUT.
\ No newline at end of file
diff --git a/tests/driver_ds18/main.c b/tests/driver_ds18/main.c
new file mode 100644
index 0000000000..4d8d3a0d83
--- /dev/null
+++ b/tests/driver_ds18/main.c
@@ -0,0 +1,63 @@
+/*
+ * Copyright (C) 2018 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 tests
+ * @{
+ *
+ * @file
+ * @brief       Test application for the DS18B20 1-Wire temperature sensor.
+ *
+ * @author      Leandro Lanzieri <leandro.lanzieri@haw-hamburg.de>
+ *
+ * @}
+ */
+
+#include <stdio.h>
+#include <inttypes.h>
+
+#include "board.h"
+#include "ds18.h"
+#include "ds18_params.h"
+#include "xtimer.h"
+
+#define SAMPLING_PERIOD     2
+
+int main(void)
+{
+    ds18_t dev;
+    int result;
+
+    puts("DS18B20 test application\n");
+
+    printf("+------------Initializing------------+\n");
+    result = ds18_init(&dev, &ds18_params[0]);
+    if (result == DS18_ERROR) {
+        puts("[Error] The sensor pin could not be initialized");
+        return 1;
+    }
+
+    printf("\n+--------Starting Measurements--------+\n");
+    while (1) {
+        int16_t temperature;
+
+        /* Get temperature in centidegrees celsius */
+        if (ds18_get_temperature(&dev, &temperature) == DS18_OK) {
+            printf("Temperature [ºC]: %d.%d"
+                   "\n+-------------------------------------+\n",
+                   (temperature / 100), (int)(temperature % 100));
+        }
+        else {
+            puts("[Error] Could not read temperature");
+        }
+
+        xtimer_sleep(SAMPLING_PERIOD);
+    }
+
+    return 0;
+}
-- 
GitLab