diff --git a/drivers/Makefile.dep b/drivers/Makefile.dep
index 7f9f85aed7..920a2aec7d 100644
--- a/drivers/Makefile.dep
+++ b/drivers/Makefile.dep
@@ -397,6 +397,11 @@ ifneq (,$(filter nvram_spi,$(USEMODULE)))
USEMODULE += xtimer
endif
+ifneq (,$(filter opt3001,$(USEMODULE)))
+ FEATURES_REQUIRED += periph_i2c
+ USEMODULE += xtimer
+endif
+
ifneq (,$(filter pca9685,$(USEMODULE)))
FEATURES_REQUIRED += periph_gpio
FEATURES_REQUIRED += periph_i2c
diff --git a/drivers/Makefile.include b/drivers/Makefile.include
index 7816c9ca8c..0754596fcc 100644
--- a/drivers/Makefile.include
+++ b/drivers/Makefile.include
@@ -210,6 +210,10 @@ ifneq (,$(filter nrf24l01p,$(USEMODULE)))
USEMODULE_INCLUDES += $(RIOTBASE)/drivers/nrf24l01p/include
endif
+ifneq (,$(filter opt3001,$(USEMODULE)))
+ USEMODULE_INCLUDES += $(RIOTBASE)/drivers/opt3001/include
+endif
+
ifneq (,$(filter pca9685,$(USEMODULE)))
USEMODULE_INCLUDES += $(RIOTBASE)/drivers/pca9685/include
endif
diff --git a/drivers/include/opt3001.h b/drivers/include/opt3001.h
new file mode 100644
index 0000000000..ed89010c3b
--- /dev/null
+++ b/drivers/include/opt3001.h
@@ -0,0 +1,153 @@
+/*
+ * 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_opt3001 OPT3001 Ambient Light Sensor
+ * @ingroup drivers_sensors
+ * @ingroup drivers_saul
+ * @brief Driver for the Texas Instruments OPT3001 sensor.
+ *
+ * The TI OPT3001 (Ambient Light Sensor) measures
+ * the intensity of visible light with a spectal response comparable to the human eye,
+ * with simultaneous rejection of infrared light.
+ * The conversion time, mode of conversion and the interrupt reporting mechanism mode can be set
+ * by the sensor initialization.
+ * After initialization the raw sensor values can be read.
+ * The ambient light can be calculated as follows:
+ * Result register translation into lux:
+ * \f{eqnarray*}{
+ * Lux &=& LSB\_Size \cdot R[11:0]
+ * \f}
+ * Where LSB\_Size:
+ * \f{eqnarray*}{
+ * LSB\_Size &=& 0.01 \cdot 2^{E[3:0]}
+ * \f}
+ *
+ * The calculation is wrapped from TI OPT3001 Ambient Light Sensor (ALS) datasheet (Rev. C).
+ *
+ * This driver provides @ref drivers_saul capabilities.
+ * @{
+ *
+ * @file
+ * @brief Interface definition for the OPT3001 sensor driver.
+ *
+ * @author Jannes Volkens
+ */
+
+#ifndef OPT3001_H
+#define OPT3001_H
+
+#include
+#include "periph/i2c.h"
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/**
+ * @brief OPT3001 Default Address
+ *
+ * If set to 0x44 the corresponding ADDR PIN is GND.
+ */
+#ifndef OPT3001_I2C_ADDRESS
+#define OPT3001_I2C_ADDRESS (0x45)
+#endif
+
+/**
+ * @name Conversion time
+ * @{
+ */
+#define OPT3001_CONVERSION_TIME_100_MS (0x0000) /**< Conversion time of 100ms */
+#define OPT3001_CONVERSION_TIME_800_MS (0x0800) /**< Conversion time of 800ms */
+/** @} */
+
+/**
+ * @brief OPT3001 Default conversion time
+ *
+ * If set to 0x0000, the conversion time will be 100ms.
+ * If set to 0x0800, the conversion time will be 800ms
+ */
+#ifndef OPT3001_CONVERSION_TIME
+#define OPT3001_CONVERSION_TIME OPT3001_CONVERSION_TIME_800_MS
+#endif
+
+/**
+ * @brief Parameters needed for device initialization
+ */
+typedef struct {
+ i2c_t i2c_dev; /**< I2C device, the sensor is connected to */
+ uint8_t i2c_addr; /**< The sensor's slave address on the I2C bus */
+} opt3001_params_t;
+
+/**
+ * @brief Device descriptor for OPT3001 sensors
+ */
+typedef struct {
+ opt3001_params_t params; /**< Configuration parameters */
+} opt3001_t;
+
+/**
+ * @brief OPT3001 specific return values
+ */
+enum {
+ OPT3001_OK, /**< Success, no error */
+ OPT3001_ERROR_BUS, /**< I2C bus error */
+ OPT3001_ERROR_DEV, /**< Internal device error */
+ OPT3001_ERROR /**< General error */
+};
+
+/**
+ * @brief Initialize the OPT3001 sensor driver.
+ *
+ * @param[out] dev device descriptor of sensor to initialize
+ * @param[in] params configuration parameters
+ *
+ * @return 0 on success
+ * @return -OPT3001_ERROR_BUS on I2C bus error
+ * @return -OPT3001_ERROR_DEV if sensor test failed
+ */
+int opt3001_init(opt3001_t *dev, const opt3001_params_t *params);
+
+/**
+ * @brief Reset the OPT3001 sensor while simultaneous deactivating measurements.
+ * Afterwards the sensor should be idle.
+ *
+ * @param[out] dev device descriptor of sensor
+ *
+ * @return 0 on success
+ * @return -1 on error
+ */
+int opt3001_reset(const opt3001_t *dev);
+
+/**
+ * @brief Set active mode, this enables periodic measurements.
+ *
+ * @param[in] dev device descriptor of sensor
+ *
+ * @return 0 on success
+ * @return -1 on error
+ */
+int opt3001_set_active(const opt3001_t *dev);
+
+/**
+ * @brief Read sensor's raw data and convert it to milliLux.
+ *
+ * @param[in] dev device descriptor of sensor
+ * @param[out] convl ambient light in milliLux
+ *
+ * @return 0 on success
+ * @return -1 on error
+ */
+int opt3001_read_lux(const opt3001_t *dev, uint32_t *convl);
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* OPT3001_H */
+/** @} */
diff --git a/drivers/opt3001/Makefile b/drivers/opt3001/Makefile
new file mode 100644
index 0000000000..a5773c5f38
--- /dev/null
+++ b/drivers/opt3001/Makefile
@@ -0,0 +1,3 @@
+MODULE = opt3001
+
+include $(RIOTBASE)/Makefile.base
diff --git a/drivers/opt3001/include/opt3001_params.h b/drivers/opt3001/include/opt3001_params.h
new file mode 100644
index 0000000000..a1af689a0f
--- /dev/null
+++ b/drivers/opt3001/include/opt3001_params.h
@@ -0,0 +1,73 @@
+/*
+ * 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_opt3001
+ *
+ * @{
+ * @file
+ * @brief Default configuration for OPT3001 devices
+ *
+ * @author Jannes Volkens
+ */
+
+#ifndef OPT3001_PARAMS_H
+#define OPT3001_PARAMS_H
+
+#include "board.h"
+#include "opt3001.h"
+#include "saul_reg.h"
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/**
+ * @name Set default configuration parameters fot the opt3001
+ * @ingroup config
+ * @{
+ */
+ #ifndef OPT3001_PARAM_I2C_DEV
+ #define OPT3001_PARAM_I2C_DEV I2C_DEV(0)
+ #endif
+ #ifndef OPT3001_PARAM_I2C_ADDR
+ #define OPT3001_PARAM_I2C_ADDR (OPT3001_I2C_ADDRESS)
+ #endif
+
+ #ifndef OPT3001_PARAMS
+ #define OPT3001_PARAMS { .i2c_dev = OPT3001_PARAM_I2C_DEV, \
+ .i2c_addr = OPT3001_PARAM_I2C_ADDR}
+
+ #endif
+ #ifndef OPT3001_SAUL_INFO
+ #define OPT3001_SAUL_INFO { .name = "opt3001" }
+ #endif
+ /**@}*/
+
+ /**
+ * @brief OPT3001 configuration
+ */
+ static const opt3001_params_t opt3001_params[] =
+ {
+ OPT3001_PARAMS
+ };
+
+ /**
+ * @brief Additional meta information to keep in the SAUL registry
+ */
+ static const saul_reg_info_t opt3001_saul_info[] =
+ {
+ OPT3001_SAUL_INFO
+ };
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* OPT3001_PARAMS_H */
+/** @} */
diff --git a/drivers/opt3001/include/opt3001_regs.h b/drivers/opt3001/include/opt3001_regs.h
new file mode 100644
index 0000000000..ad4d3b32c4
--- /dev/null
+++ b/drivers/opt3001/include/opt3001_regs.h
@@ -0,0 +1,91 @@
+/*
+ * 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_opt3001
+ *
+ * @{
+ * @file
+ * @brief Register definitions for OPT3001 devices
+ *
+ * @author Jannes Volkens
+ */
+
+#ifndef OPT3001_REGS_H
+#define OPT3001_REGS_H
+
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/**
+ * @name OPT3001 registers
+ * @{
+ */
+ #define OPT3001_REGS_RESULT 0x00 /**< Result register */
+ #define OPT3001_REGS_CONFIG 0x01 /**< Configuration register */
+ #define OPT3001_REGS_LOW_LIMIT 0x02 /**< Low Limit register */
+ #define OPT3001_REGS_HIGH_LIMIT 0x03 /**< High Limit register */
+ #define OPT3001_REGS_MANUFACTURER_ID 0x7E /**< Manufacturer ID register */
+ #define OPT3001_REGS_DEVICE_ID 0x7F /**< Device ID register */
+
+ #define OPT3001_DID_VALUE (0x3001) /**< Device ID value */
+
+ #define OPT3001_CONFIG_RESET (0xC810) /**< Reset value */
+
+ #define OPT3001_CONFIG_RN_FSR (0xC000) /**< Automatic full-scale setting mode */
+
+ #define OPT3001_REGS_CONFIG_CT_MASK (0x0800) /**< Conversion time mask */
+ #define OPT3001_REGS_CONFIG_CT(x) (((uint16_t)(x)) \
+ & OPT3001_REGS_CONFIG_CT_MASK) /**< Conversion time field */
+
+ #define OPT3001_CONFIG_M_SHUTDOWN (0x0) /**< Shutdown mode */
+ #define OPT3001_CONFIG_M_SINGLE (0x1) /**< Single-shot mode */
+ #define OPT3001_CONFIG_M_CONTINUOUS (0x2) /**< Continuous mode (also 0x3) */
+ #define OPT3001_CONFIG_MOC_SHIFT (9U) /**< Mode of conversion shift */
+ #define OPT3001_CONFIG_MOC_MASK (0x0600) /**< Mode of conversion mask */
+ #define OPT3001_REGS_CONFIG_MOC(x) (((uint16_t)(((uint16_t)(x)) \
+ << OPT3001_CONFIG_MOC_SHIFT)) \
+ & OPT3001_CONFIG_MOC_MASK) /**< Mode of conversion field */
+
+ #define OPT3001_REGS_CONFIG_OVF (1 << 8) /**< Overflow flag field */
+ #define OPT3001_REGS_CONFIG_CRF (1 << 7) /**< Conversion ready field */
+ #define OPT3001_REGS_CONFIG_FH (1 << 6) /**< Flag high field */
+ #define OPT3001_REGS_CONFIG_FL (1 << 5) /**< Flag low field */
+ #define OPT3001_REGS_CONFIG_L (1 << 4) /**< Latch field */
+ #define OPT3001_REGS_CONFIG_POL (1 << 3) /**< Polarity field */
+ #define OPT3001_REGS_CONFIG_ME (1 << 2) /**< Mask exponent field */
+
+ #define OPT3001_REGS_CONFIG_FC_MASK (0x0003) /**< Fault count field mask */
+
+ #define OPT3001_REGS_LOW_LIMIT_EOC_ENABLE (0xC000) /**< End-of-conversion enable */
+
+ #define OPT3001_REGS_REG_EXPONENT(x) ((x) >> 12) /**< Exponent */
+ #define OPT3001_REGS_REG_MANTISSA(x) ((x) & 0xFFF) /**< Mantissa */
+
+/*
+ * Time to wait for the conversion to complete.
+ * The data sheet of the device (sect. 6.5) indicates that the conversion time is the integration time plus 3 ms.
+ * It has been added a bit more time just to be safe.
+ */
+ #define OPT3001_REGS_INT_TIME_SHORT 100000 /**< Integration time of 100ms */
+ #define OPT3001_REGS_INT_TIME_LONG 800000 /**< Integration time of 800ms */
+
+ #define OPT3001_CONVERSION_TIME_OFFSET 4000 /**< Conversion time offset */
+
+ #define OPT3001_CONVERSION_TIME_COMBINED OPT3001_REGS_INT_TIME_SHORT \
+ + OPT3001_REGS_INT_TIME_LONG \
+ + OPT3001_CONVERSION_TIME_OFFSET /**< Combination of the conversion times */
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* OPT3001_REGS_H */
+/** @} */
diff --git a/drivers/opt3001/opt3001.c b/drivers/opt3001/opt3001.c
new file mode 100644
index 0000000000..46ecd58eeb
--- /dev/null
+++ b/drivers/opt3001/opt3001.c
@@ -0,0 +1,169 @@
+/*
+ * 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_opt3001
+ * @{
+ *
+ * @file
+ * @brief Driver for the TI OPT3001 Ambient Light Sensor.
+ *
+ * @author Jannes Volkens
+ *
+ * @}
+ */
+
+#include "opt3001.h"
+#include "opt3001_regs.h"
+#include "periph/i2c.h"
+#include "xtimer.h"
+#include "log.h"
+#include "byteorder.h"
+#include "math.h"
+
+#define ENABLE_DEBUG (0)
+#include "debug.h"
+
+#define DEV_I2C (dev->params.i2c_dev) /**< BUS */
+#define DEV_ADDR (dev->params.i2c_addr) /**< ADDR */
+
+int opt3001_init(opt3001_t *dev, const opt3001_params_t *params)
+{
+ /* Check parameters */
+ assert(dev && params);
+
+ uint16_t reg;
+
+ dev->params = *params;
+
+ /* Test device id */
+ i2c_acquire(DEV_I2C);
+ if (i2c_read_regs(DEV_I2C, DEV_ADDR, OPT3001_REGS_DEVICE_ID, ®, 2, 0) < 0) {
+ i2c_release(DEV_I2C);
+ LOG_ERROR("opt3001_init: Error reading device ID!\n");
+ return -OPT3001_ERROR_BUS;
+ }
+
+ reg = htons(reg);
+ if (reg != OPT3001_DID_VALUE) {
+ return -OPT3001_ERROR_DEV;
+ }
+
+ /* Set range number, mode of conversion and conversion time */
+ reg = OPT3001_CONFIG_RN_FSR;
+ reg |= OPT3001_REGS_CONFIG_MOC(OPT3001_CONFIG_M_SHUTDOWN);
+ reg |= OPT3001_REGS_CONFIG_CT(OPT3001_CONVERSION_TIME);
+
+ /* Configure for latched window-style comparison operation */
+ reg |= OPT3001_REGS_CONFIG_L;
+ reg &= ~OPT3001_REGS_CONFIG_POL;
+ reg &= ~OPT3001_REGS_CONFIG_ME;
+ reg &= ~OPT3001_REGS_CONFIG_FC_MASK;
+
+ reg = htons(reg);
+
+ if (i2c_write_regs(DEV_I2C, DEV_ADDR, OPT3001_REGS_CONFIG, ®, 2, 0) < 0) {
+ i2c_release(DEV_I2C);
+ LOG_ERROR("opt3001_init: Error setting device configuration\n");
+ return -OPT3001_ERROR_BUS;
+ }
+ i2c_release(DEV_I2C);
+
+ return OPT3001_OK;
+}
+
+int opt3001_reset(const opt3001_t *dev)
+{
+ uint16_t reg = OPT3001_CONFIG_RESET;
+ reg &= (0xF0FF | OPT3001_REGS_CONFIG_CT(OPT3001_CONVERSION_TIME));
+ reg = htons(reg);
+
+ /* Acquire exclusive access to the bus. */
+ i2c_acquire(DEV_I2C);
+ if (i2c_write_regs(DEV_I2C, DEV_ADDR, OPT3001_REGS_CONFIG, ®, 2, 0) < 0) {
+ i2c_release(DEV_I2C);
+ LOG_ERROR("opt3001_reset: Error setting device configuration\n");
+ return -OPT3001_ERROR_BUS;
+ }
+ i2c_release(DEV_I2C);
+ return OPT3001_OK;
+}
+
+int opt3001_set_active(const opt3001_t *dev)
+{
+ uint16_t reg;
+
+ i2c_acquire(DEV_I2C);
+
+ if (i2c_read_regs(DEV_I2C, DEV_ADDR, OPT3001_REGS_CONFIG, ®, 2, 0) < 0) {
+ i2c_release(DEV_I2C);
+ LOG_ERROR("opt3001_set_active: Error reading BUS!\n");
+ return -OPT3001_ERROR_BUS;
+ }
+
+ reg = htons(reg);
+ reg |= OPT3001_REGS_CONFIG_MOC(OPT3001_CONFIG_M_CONTINUOUS);
+
+ reg = htons(reg);
+ if (i2c_write_regs(DEV_I2C, DEV_ADDR, OPT3001_REGS_CONFIG, ®, 2, 0) < 0) {
+ i2c_release(DEV_I2C);
+ LOG_ERROR("opt3001_set_active: Error setting device configuration\n");
+ return -OPT3001_ERROR_BUS;
+ }
+
+ i2c_release(DEV_I2C);
+ return OPT3001_OK;
+}
+
+int opt3001_read_lux(const opt3001_t *dev, uint32_t *convl)
+{
+ uint8_t exponent;
+ uint16_t reg, mantissa;
+ uint32_t conversion_time = 0;
+
+ i2c_acquire(DEV_I2C);
+
+ while (1) {
+ if (conversion_time >= OPT3001_CONVERSION_TIME_COMBINED) {
+ i2c_release(DEV_I2C);
+ LOG_ERROR("opt3001_read: Conversion in progress!\n");
+ return -OPT3001_ERROR;
+ }
+
+ if (i2c_read_regs(DEV_I2C, DEV_ADDR, OPT3001_REGS_CONFIG, ®, 2, 0) < 0) {
+ i2c_release(DEV_I2C);
+ LOG_ERROR("opt3001_read: Error reading BUS!\n");
+ return -OPT3001_ERROR_BUS;
+ }
+
+ if (htons(reg) & OPT3001_REGS_CONFIG_CRF) {
+ break;
+ }
+
+ i2c_release(DEV_I2C);
+ xtimer_usleep(1000);
+ i2c_acquire(DEV_I2C);
+
+ conversion_time += 1000;
+ }
+
+ if (i2c_read_regs(DEV_I2C, DEV_ADDR, OPT3001_REGS_RESULT, ®, 2, 0) < 0) {
+ i2c_release(DEV_I2C);
+ LOG_ERROR("opt3001_read: Error reading BUS!\n");
+ return -OPT3001_ERROR_BUS;
+ }
+
+ exponent = OPT3001_REGS_REG_EXPONENT(htons(reg));
+ mantissa = OPT3001_REGS_REG_MANTISSA(htons(reg));
+
+ *convl = (1 << exponent) * mantissa * 10;
+
+ i2c_release(DEV_I2C);
+ return OPT3001_OK;
+}
diff --git a/drivers/opt3001/opt3001_saul.c b/drivers/opt3001/opt3001_saul.c
new file mode 100644
index 0000000000..1b40fd8f17
--- /dev/null
+++ b/drivers/opt3001/opt3001_saul.c
@@ -0,0 +1,48 @@
+/*
+ * 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_opt3001
+ * @{
+ *
+ * @file
+ * @brief OPT3001 adaption to the RIOT actuator/sensor interface
+ *
+ * @author Jannes Volkens
+
+#include "saul.h"
+#include "opt3001.h"
+
+static int read_lux(const void *dev, phydat_t *res)
+{
+ uint32_t convlux;
+
+ if (opt3001_read_lux((const opt3001_t *)dev, &convlux) != OPT3001_OK) {
+ return -ECANCELED;
+ }
+
+ res->val[0] = convlux / 1000;
+ res->val[1] = 0;
+ res->val[2] = 0;
+
+ res->unit = UNIT_LUX;
+ res->scale = 0;
+
+ return 1;
+ }
+
+const saul_driver_t opt3001_saul_driver = {
+ .read = read_lux,
+ .write = saul_notsup,
+ .type = SAUL_SENSE_LIGHT,
+};
diff --git a/sys/auto_init/auto_init.c b/sys/auto_init/auto_init.c
index 091171214d..8f8bed1995 100644
--- a/sys/auto_init/auto_init.c
+++ b/sys/auto_init/auto_init.c
@@ -486,6 +486,10 @@ void auto_init(void)
extern void auto_init_mpu9150(void);
auto_init_mpu9150();
#endif
+#ifdef MODULE_OPT3001
+ extern void auto_init_opt3001(void);
+ auto_init_opt3001();
+#endif
#ifdef MODULE_PCA9685
extern void auto_init_pca9685(void);
auto_init_pca9685();
diff --git a/sys/auto_init/saul/auto_init_opt3001.c b/sys/auto_init/saul/auto_init_opt3001.c
new file mode 100644
index 0000000000..0e473975b3
--- /dev/null
+++ b/sys/auto_init/saul/auto_init_opt3001.c
@@ -0,0 +1,76 @@
+/*
+ * 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 sys_auto_init_saul
+ * @{
+ *
+ * @file
+ * @brief Auto initialization of OPT3001 Ambient Light Sensor
+ *
+ * @author Jannes Volkens
+ *
+ * @}
+ */
+
+ #ifdef MODULE_OPT3001
+
+ #include "assert.h"
+ #include "log.h"
+ #include "saul_reg.h"
+
+ #include "opt3001.h"
+ #include "opt3001_params.h"
+
+ /**
+ * @brief Define the number of configured sensors
+ */
+ #define OPT3001_NUM ARRAY_SIZE(opt3001_params)
+
+ /**
+ * @brief Allocate memory for the device descriptors
+ */
+ static opt3001_t opt3001_devs[OPT3001_NUM];
+
+ /**
+ * @brief Memory for the SAUL registry entries
+ */
+ static saul_reg_t saul_entries[OPT3001_NUM];
+
+ /**
+ * @brief Define the number of saul info
+ */
+ #define OPT3001_INFO_NUM ARRAY_SIZE(opt3001_saul_info)
+
+ /**
+ * @brief Reference the driver struct
+ */
+ extern const saul_driver_t opt3001_saul_driver;
+
+ void auto_init_opt3001(void)
+ {
+ assert(OPT3001_NUM == OPT3001_INFO_NUM);
+
+ for (unsigned i = 0; i < OPT3001_NUM; i++) {
+ LOG_DEBUG("[auto_init_saul] initializing opt3001 #%u\n", i);
+
+ if (opt3001_init(&opt3001_devs[i], &opt3001_params[i]) != OPT3001_OK) {
+ LOG_ERROR("[auto_init_saul] error initializing opt3001 #%u\n", i);
+ continue;
+ }
+ saul_entries[i].dev = &(opt3001_devs[i]);
+ saul_entries[i].name = opt3001_saul_info[i].name;
+ saul_entries[i].driver = &opt3001_saul_driver;
+ saul_reg_add(&(saul_entries[i]));
+ }
+ }
+
+ #else
+ typedef int dont_be_pedantic;
+ #endif /* MODULE_OPT3001 */
diff --git a/tests/driver_opt3001/Makefile b/tests/driver_opt3001/Makefile
new file mode 100644
index 0000000000..d503b84c13
--- /dev/null
+++ b/tests/driver_opt3001/Makefile
@@ -0,0 +1,6 @@
+include ../Makefile.tests_common
+
+USEMODULE += opt3001
+USEMODULE += xtimer
+
+include $(RIOTBASE)/Makefile.include
diff --git a/tests/driver_opt3001/README.md b/tests/driver_opt3001/README.md
new file mode 100644
index 0000000000..4c84a1aab7
--- /dev/null
+++ b/tests/driver_opt3001/README.md
@@ -0,0 +1,6 @@
+# About
+This is a manual test application for the OPT3001 ambient light sensor driver.
+
+# Usage
+This test application will initialize the OPT3001 sensor and read the light values every 1s
+and prints them to STDOUT.
diff --git a/tests/driver_opt3001/main.c b/tests/driver_opt3001/main.c
new file mode 100644
index 0000000000..abf69227e4
--- /dev/null
+++ b/tests/driver_opt3001/main.c
@@ -0,0 +1,62 @@
+/*
+ * 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 tests
+ * @{
+ *
+ * @file
+ * @brief Test application for the OPT3001 sensor driver.
+ *
+ * @author Jannes Volkens
+ *
+ * @}
+ */
+
+#include
+#include
+
+#include "opt3001_params.h"
+#include "opt3001.h"
+#include "xtimer.h"
+
+#define OPT3001_TEST_TIME 1000000
+
+int main(void){
+
+ opt3001_t dev;
+ uint32_t convlux;
+
+ puts("OPT3001 test application\n");
+ printf("Initializing OPT3001 sensor at I2C_%i ... ", opt3001_params[0].i2c_dev);
+
+ if (opt3001_init(&dev, &opt3001_params[0]) != OPT3001_OK) {
+ puts("init device [ERROR]");
+ return -1;
+ }
+
+ if (opt3001_set_active(&dev) != OPT3001_OK) {
+ puts("set active [ERROR]");
+ return -1;
+ }
+
+ puts("[SUCCESS]\n");
+
+ printf("\n+--------Starting Measurements--------+\n");
+
+ while(1){
+ opt3001_read_lux(&dev, &convlux);
+
+ printf("MilliLux: %" PRIu32 "\n", convlux);
+ printf("\n+-------------------------------------+\n");
+
+ xtimer_usleep(OPT3001_TEST_TIME);
+ }
+
+ return 0;
+}