diff --git a/boards/pba-d-01-kw2x/Makefile.dep b/boards/pba-d-01-kw2x/Makefile.dep index 2be84deec28f..e3a585098020 100644 --- a/boards/pba-d-01-kw2x/Makefile.dep +++ b/boards/pba-d-01-kw2x/Makefile.dep @@ -5,4 +5,5 @@ endif ifneq (,$(filter saul_default,$(USEMODULE))) USEMODULE += mma8x5x USEMODULE += hdc1000 + USEMODULE += tcs37727 endif diff --git a/boards/pba-d-01-kw2x/include/board.h b/boards/pba-d-01-kw2x/include/board.h index 14270ce00fe5..37401c7b677d 100644 --- a/boards/pba-d-01-kw2x/include/board.h +++ b/boards/pba-d-01-kw2x/include/board.h @@ -112,8 +112,9 @@ extern "C" * @name Define the interface for the TCS3772 light sensor * @{ */ -#define TCS37727_I2C (I2C_DEV(0)) -#define TCS37727_ADDR (0x29) +#define TCS37727_PARAMS { .i2c = I2C_DEV(0), \ + .addr = 0x29, \ + .atime = TCS37727_PARAM_ATIME } /** @} */ /** diff --git a/drivers/include/tcs37727.h b/drivers/include/tcs37727.h index 4eee7045be1e..9d09dd9bb166 100644 --- a/drivers/include/tcs37727.h +++ b/drivers/include/tcs37727.h @@ -1,5 +1,6 @@ /* * Copyright (C) 2015 PHYTEC Messtechnik GmbH + * 2017 Freie Universität Berlin * * 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 @@ -7,7 +8,7 @@ */ /** - * @defgroup drivers_tcs37727 TCS37727 Light-To-Digital Converter + * @defgroup drivers_tcs37727 TCS37727 RGB Light Sensor * @ingroup drivers_sensors * @brief Driver for the AMS TCS37727 Color Light-To-Digital Converter * @@ -19,13 +20,15 @@ * * @author Felix Siebel * @author Johann Fischer + * @author Hauke Petersen */ #ifndef TCS37727_H #define TCS37727_H #include -#include + +#include "saul.h" #include "periph/i2c.h" #ifdef __cplusplus @@ -42,7 +45,7 @@ extern "C" #endif /** - * @brief Struct for storing TCS37727 sensor data + * @brief Struct for storing TCS37727 sensor data */ typedef struct { uint32_t red; /**< IR compensated channels red */ @@ -54,66 +57,83 @@ typedef struct { } tcs37727_data_t; /** - * @brief Device descriptor for TCS37727 sensors. + * @brief TCS37727 configuration parameters + */ +typedef struct { + i2c_t i2c; /**< I2C bus the sensor is connected to */ + uint8_t addr; /**< the sensors address on the I2C bus */ + uint32_t atime; /**< conversion time in microseconds */ +} tcs37727_params_t; + +/** + * @brief Device descriptor for TCS37727 sensors */ typedef struct { - i2c_t i2c; /**< I2C device the sensor is connected to */ - uint8_t addr; /**< the sensor's slave address on the I2C bus */ - bool initialized; /**< sensor status, true if sensor is initialized */ - int atime_us; /**< atime value conveted to microseconds */ + tcs37727_params_t p; /**< device configuration */ int again; /**< amount of gain */ } tcs37727_t; /** - * @brief Initialise the TCS37727 sensor driver. - * Settings: Gain 4x, Proximity Detection off + * @brief Possible TCS27737 return values + */ +enum { + TCS37727_OK = 0, /**< everything worked as expected */ + TCS37727_NOBUS = -1, /**< access to the configured I2C bus failed */ + TCS37727_NODEV = -2 /**< no TCS37727 device found on the bus */ +}; + +/** + * @brief Export the sensor's SAUL interface + */ +extern const saul_driver_t tcs37727_saul_driver; + +/** + * @brief Initialize the given TCS37727 sensor + * + * The sensor is initialized in RGBC only mode with proximity detection turned + * off. + * + * The gain will be initially set to 4x, but it will be adjusted + * + * The gain value will be initially set to 4x, but it will be automatically + * adjusted during runtime. * * @param[out] dev device descriptor of sensor to initialize - * @param[in] i2c I2C bus the sensor is connected to - * @param[in] address sensor's I2C slave address - * @param[in] atime_us rgbc RGBC integration time in microseconds + * @param[in] params static configuration parameters * - * @return 0 on success - * @return -1 if initialization of I2C bus failed - * @return -2 if sensor test failed - * @return -3 if sensor configuration failed + * @return TCS27737_OK on success + * @return TCS37727_NOBUS if initialization of I2C bus fails + * @return TCS37727_NODEV if no sensor can be found */ -int tcs37727_init(tcs37727_t *dev, i2c_t i2c, uint8_t address, int atime_us); +int tcs37727_init(tcs37727_t *dev, const tcs37727_params_t *params); /** * @brief Set RGBC enable, this activates periodic RGBC measurements. * * @param[out] dev device descriptor of sensor - * - * @return 0 on success - * @return -1 on error */ -int tcs37727_set_rgbc_active(tcs37727_t *dev); +void tcs37727_set_rgbc_active(tcs37727_t *dev); /** - * @brief Set RGBC disable, this deactivates periodic RGBC measurements. + * @brief Set RGBC disable, this deactivates periodic RGBC measurements + * * Also turns off the sensor when proximity measurement is disabled. * * @param[in] dev device descriptor of sensor - * - * @return 0 on success - * @return -1 on error */ -int tcs37727_set_rgbc_standby(tcs37727_t *dev); +void tcs37727_set_rgbc_standby(tcs37727_t *dev); /** - * @brief Read sensor's data. + * @brief Read sensor's data + * * Besides an Autogain routine is called. If a maximum or minimum threshold * value of the channel clear is reached, then the gain will be changed * correspond to max or min threshold. * * @param[in] dev device descriptor of sensor - * @param[out] data device sensor data - * - * @return 0 on success - * @return -1 on error + * @param[out] data device sensor data, MUST not be NULL */ -int tcs37727_read(tcs37727_t *dev, tcs37727_data_t *data); +void tcs37727_read(tcs37727_t *dev, tcs37727_data_t *data); #ifdef __cplusplus } diff --git a/drivers/tcs37727/include/tcs37727_params.h b/drivers/tcs37727/include/tcs37727_params.h new file mode 100644 index 000000000000..4920c50f1642 --- /dev/null +++ b/drivers/tcs37727/include/tcs37727_params.h @@ -0,0 +1,72 @@ +/* + * Copyright (C) 2017 Freie Universität Berlin + * + * 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_tcs37727 + * + * @{ + * @file + * @brief Default configuration for TCS37727 devices + * + * @author Hauke Petersen + */ + +#ifndef TCS37727_PARAMS_H +#define TCS37727_PARAMS_H + +#include "board.h" +#include "tcs37727.h" +#include "saul_reg.h" + +#ifdef __cplusplus +extern "C" { +#endif + +/** + * @name Set default configuration parameters for TCS37727 devices + * @{ + */ +#ifndef TCS37727_PARAM_I2C +#define TCS37727_PARAM_I2C I2C_DEV(0) +#endif +#ifndef TCS37727_PARAM_ADDR +#define TCS37727_PARAM_ADDR (TCS37727_I2C_ADDRESS) +#endif +#ifndef TCS37727_PARAM_ATIME +#define TCS37727_PARAM_ATIME (TCS37727_ATIME_DEFAULT) +#endif + +#ifndef TCS37727_PARAMS +#define TCS37727_PARAMS { .i2c = TCS37727_PARAM_I2C, \ + .addr = TCS37727_PARAM_ADDR, \ + .atime = TCS37727_PARAM_ATIME } +#endif +/**@}*/ + +/** + * @brief TCS37727 configuration + */ +static const tcs37727_params_t tcs37727_params[] = +{ + TCS37727_PARAMS +}; + +/** + * @brief Additional meta information to keep in the SAUL registry + */ +static const saul_reg_info_t tcs37727_saul_info[] = +{ + { .name = "tcs37727" } +}; + +#ifdef __cplusplus +} +#endif + +#endif /* TCS37727_PARAMS_H */ +/** @} */ diff --git a/drivers/tcs37727/tcs37727.c b/drivers/tcs37727/tcs37727.c index 4b550097aad9..9c3599379adc 100644 --- a/drivers/tcs37727/tcs37727.c +++ b/drivers/tcs37727/tcs37727.c @@ -1,5 +1,6 @@ /* * Copyright (C) 2015 PHYTEC Messtechnik GmbH + * 2017 Freie Universität Berlin * * 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 @@ -16,135 +17,93 @@ * * @author Felix Siebel * @author Johann Fischer + * @author Hauke Petersen * * @} */ -#include -#include -#include "periph/i2c.h" +#include + +#include "log.h" +#include "assert.h" + #include "tcs37727.h" #include "tcs37727-internal.h" -#define ENABLE_DEBUG (0) +#define ENABLE_DEBUG (0) #include "debug.h" -#define I2C_SPEED I2C_SPEED_FAST +#define I2C_SPEED I2C_SPEED_FAST +#define BUS (dev->p.i2c) +#define ADR (dev->p.addr) -static int tcs37727_test(tcs37727_t *dev) +int tcs37727_init(tcs37727_t *dev, const tcs37727_params_t *params) { - uint8_t id; - - i2c_acquire(dev->i2c); - - if (i2c_read_reg(dev->i2c, dev->addr, TCS37727_ID, &id) != 1) { - i2c_release(dev->i2c); - return -1; - } - - i2c_release(dev->i2c); - - if (id != TCS37727_ID_VALUE) { - return -1; - } - - return 0; -} + uint8_t tmp; -int tcs37727_init(tcs37727_t *dev, i2c_t i2c, uint8_t address, int atime_us) -{ - /* write device descriptor */ - dev->i2c = i2c; - dev->addr = address; - dev->initialized = false; + /* check parameters */ + assert(dev && params); - i2c_acquire(dev->i2c); + /* initialize the device descriptor */ + memcpy(&dev->p, params, sizeof(tcs37727_params_t)); - /* initialize the I2C bus */ - if (i2c_init_master(i2c, I2C_SPEED) < 0) { - i2c_release(dev->i2c); - return -1; + /* setup the I2C bus */ + i2c_acquire(BUS); + if (i2c_init_master(BUS, I2C_SPEED) < 0) { + i2c_release(BUS); + LOG_ERROR("[tcs37727] init: error initializing I2C bus\n"); + return TCS37727_NOBUS; } - i2c_release(dev->i2c); - - if (tcs37727_test(dev)) { - return -2; + /* check if we can communicate with the device */ + i2c_read_reg(BUS, ADR, TCS37727_ID, &tmp); + if (tmp != TCS37727_ID_VALUE) { + i2c_release(BUS); + LOG_ERROR("[tcs37727] init: error while reading ID register\n"); + return TCS37727_NODEV; } - i2c_acquire(dev->i2c); - - if (i2c_write_reg(dev->i2c, dev->addr, TCS37727_CONTROL, - TCS37727_CONTROL_AGAIN_4) != 1) { - i2c_release(dev->i2c); - return -3; - } + /* configure gain and conversion time */ + i2c_write_reg(BUS, ADR, TCS37727_ATIME, TCS37727_ATIME_TO_REG(dev->p.atime)); + i2c_write_reg(BUS, ADR, TCS37727_CONTROL, TCS37727_CONTROL_AGAIN_4); dev->again = 4; - if (i2c_write_reg(dev->i2c, dev->addr, TCS37727_ATIME, - TCS37727_ATIME_TO_REG(atime_us)) != 1) { - i2c_release(dev->i2c); - return -3; - } - dev->atime_us = atime_us; + /* enable the device */ + tmp = (TCS37727_ENABLE_AEN | TCS37727_ENABLE_PON); + i2c_write_reg(BUS, ADR, TCS37727_ENABLE, tmp); - dev->initialized = true; + i2c_release(BUS); - i2c_release(dev->i2c); - return 0; + return TCS37727_OK; } -int tcs37727_set_rgbc_active(tcs37727_t *dev) +void tcs37727_set_rgbc_active(tcs37727_t *dev) { uint8_t reg; - if (dev->initialized == false) { - return -1; - } - - i2c_acquire(dev->i2c); - if (i2c_read_regs(dev->i2c, dev->addr, TCS37727_ENABLE, ®, 1) != 1) { - i2c_release(dev->i2c); - return -1; - } + assert(dev); + i2c_acquire(BUS); + i2c_read_reg(BUS, ADR, TCS37727_ENABLE, ®); reg |= (TCS37727_ENABLE_AEN | TCS37727_ENABLE_PON); - - if (i2c_write_reg(dev->i2c, dev->addr, TCS37727_ENABLE, reg) != 1) { - i2c_release(dev->i2c); - return -1; - } - - i2c_release(dev->i2c); - return 0; + i2c_write_reg(BUS, ADR, TCS37727_ENABLE, reg); + i2c_release(BUS); } -int tcs37727_set_rgbc_standby(tcs37727_t *dev) +void tcs37727_set_rgbc_standby(tcs37727_t *dev) { uint8_t reg; - if (dev->initialized == false) { - return -1; - } - - i2c_acquire(dev->i2c); - if (i2c_read_regs(dev->i2c, dev->addr, TCS37727_ENABLE, ®, 1) != 1) { - i2c_release(dev->i2c); - return -1; - } + assert(dev); + i2c_acquire(BUS); + i2c_read_reg(BUS, ADR, TCS37727_ENABLE, ®); reg &= ~TCS37727_ENABLE_AEN; if (!(reg & TCS37727_ENABLE_PEN)) { reg &= ~TCS37727_ENABLE_PON; } - - if (i2c_write_reg(dev->i2c, dev->addr, TCS37727_ENABLE, reg) != 1) { - i2c_release(dev->i2c); - return -1; - } - - i2c_release(dev->i2c); - return 0; + i2c_write_reg(BUS, ADR, TCS37727_ENABLE, reg); + i2c_release(BUS); } static uint8_t tcs37727_trim_gain(tcs37727_t *dev, int rawc) @@ -152,10 +111,6 @@ static uint8_t tcs37727_trim_gain(tcs37727_t *dev, int rawc) uint8_t reg_again = 0; int val_again = dev->again; - if (dev->initialized == false) { - return -1; - } - if (rawc < TCS37727_AG_THRESHOLD_LOW) { switch (val_again) { case 1: @@ -204,41 +159,33 @@ static uint8_t tcs37727_trim_gain(tcs37727_t *dev, int rawc) return 0; } - i2c_acquire(dev->i2c); + i2c_acquire(BUS); uint8_t reg = 0; - if (i2c_read_reg(dev->i2c, dev->addr, TCS37727_CONTROL, ®) != 1) { - i2c_release(dev->i2c); + if (i2c_read_reg(BUS, ADR, TCS37727_CONTROL, ®) != 1) { + i2c_release(BUS); return -2; } reg &= ~TCS37727_CONTROL_AGAIN_MASK; reg |= reg_again; - if (i2c_write_reg(dev->i2c, dev->addr, TCS37727_CONTROL, reg) != 1) { - i2c_release(dev->i2c); + if (i2c_write_reg(BUS, ADR, TCS37727_CONTROL, reg) != 1) { + i2c_release(BUS); return -2; } - i2c_release(dev->i2c); + i2c_release(BUS); dev->again = val_again; return 0; } -int tcs37727_read(tcs37727_t *dev, tcs37727_data_t *data) +void tcs37727_read(tcs37727_t *dev, tcs37727_data_t *data) { uint8_t buf[8]; - if (dev->initialized == false) { - return -1; - } - - i2c_acquire(dev->i2c); - - if (i2c_read_regs(dev->i2c, dev->addr, - (TCS37727_INC_TRANS | TCS37727_CDATA), buf, 8) != 8) { - i2c_release(dev->i2c); - return -1; - } + assert(dev && data); - i2c_release(dev->i2c); + i2c_acquire(BUS); + i2c_read_regs(BUS, ADR, (TCS37727_INC_TRANS | TCS37727_CDATA), buf, 8); + i2c_release(BUS); int32_t tmpc = ((uint16_t)buf[1] << 8) | buf[0]; int32_t tmpr = ((uint16_t)buf[3] << 8) | buf[2]; @@ -259,7 +206,7 @@ int tcs37727_read(tcs37727_t *dev, tcs37727_data_t *data) /* Lux calculation as described in the DN40. */ int32_t gi = R_COEF_IF * tmpr + G_COEF_IF * tmpg + B_COEF_IF * tmpb; /* TODO: add Glass Attenuation Factor GA compensation */ - int32_t cpl = (dev->atime_us * dev->again) / DGF_IF; + int32_t cpl = (dev->p.atime * dev->again) / DGF_IF; int32_t lux = gi / cpl; /* Autogain */ @@ -271,6 +218,4 @@ int tcs37727_read(tcs37727_t *dev, tcs37727_data_t *data) data->clear = (tmpb < 0) ? 0 : (tmpc * 1000) / cpl; data->lux = (lux < 0) ? 0 : lux; data->ct = (ct < 0) ? 0 : ct; - - return 0; } diff --git a/drivers/tcs37727/tcs37727_saul.c b/drivers/tcs37727/tcs37727_saul.c new file mode 100644 index 000000000000..88719867737b --- /dev/null +++ b/drivers/tcs37727/tcs37727_saul.c @@ -0,0 +1,46 @@ +/* + * Copyright (C) 2017 Freie Universität Berlin + * + * 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 driver_tcs37727 + * @{ + * + * @file + * @brief TCS37727 adaption to the RIOT actuator/sensor interface + * + * @author Hauke Petersen + * + * @} + */ + +#include + +#include "saul.h" +#include "tcs37727.h" + +static int read(void *dev, phydat_t *res) +{ + tcs37727_t *d = (tcs37727_t *)dev; + tcs37727_data_t val; + + tcs37727_read(d, &val); + + res->val[0] = (int16_t)val.red; + res->val[1] = (int16_t)val.green; + res->val[2] = (int16_t)val.blue; + res->unit = UNIT_CD; + res->scale = 0; + + return 3; +} + +const saul_driver_t tcs37727_saul_driver = { + .read = read, + .write = saul_notsup, + .type = SAUL_SENSE_COLOR, +}; diff --git a/sys/auto_init/auto_init.c b/sys/auto_init/auto_init.c index 85f735526722..a01feb04c2c4 100644 --- a/sys/auto_init/auto_init.c +++ b/sys/auto_init/auto_init.c @@ -310,6 +310,10 @@ void auto_init(void) extern void auto_init_dht(void); auto_init_dht(); #endif +#ifdef MODULE_TCS37727 + extern void auto_init_tcs37727(void); + auto_init_tcs37727(); +#endif #endif /* MODULE_AUTO_INIT_SAUL */ diff --git a/sys/auto_init/saul/auto_init_tcs37727.c b/sys/auto_init/saul/auto_init_tcs37727.c new file mode 100644 index 000000000000..ec6824751a80 --- /dev/null +++ b/sys/auto_init/saul/auto_init_tcs37727.c @@ -0,0 +1,64 @@ +/* + * Copyright (C) 2017 Freie Universität Berlin + * + * 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 TCS37727 light sensors + * + * @author Hauke Petersen + * + * @} + */ + +#ifdef MODULE_TCS37727 + +#include "log.h" +#include "saul_reg.h" +#include "tcs37727.h" +#include "tcs37727_params.h" + +/** + * @brief Define the number of configured sensors + */ +#define TCS37727_NUM (sizeof(tcs37727_params) / sizeof(tcs37727_params[0])) + +/** + * @brief Allocate memory for the device descriptors + */ +static tcs37727_t tcs37727_devs[TCS37727_NUM]; + +/** + * @brief Memory for the SAUL registry entries + */ +static saul_reg_t saul_entries[TCS37727_NUM]; + +void auto_init_tcs37727(void) +{ + for (unsigned i = 0; i < TCS37727_NUM; i++) { + LOG_DEBUG("[auto_init_saul] initializing tcs29020 #%u\n", i); + + int res = tcs37727_init(&tcs37727_devs[i], &tcs37727_params[i]); + if (res != TCS37727_OK) { + LOG_ERROR("[auto_init_saul] error initializing tcs37727 #%u\n", i); + } + else { + saul_entries[i].dev = &(tcs37727_devs[i]); + saul_entries[i].name = tcs37727_saul_info[i].name; + saul_entries[i].driver = &tcs37727_saul_driver; + saul_reg_add(&(saul_entries[i])); + } + } +} + +#else +typedef int dont_be_pedantic; +#endif /* MODULE_TCS37727 */ diff --git a/tests/driver_tcs37727/Makefile b/tests/driver_tcs37727/Makefile index fa0941d78a53..234ce88eb811 100644 --- a/tests/driver_tcs37727/Makefile +++ b/tests/driver_tcs37727/Makefile @@ -6,12 +6,4 @@ FEATURES_REQUIRED = periph_i2c USEMODULE += tcs37727 USEMODULE += xtimer -# set default device parameters in case they are undefined -TEST_TCS37727_I2C ?= I2C_DEV\(0\) -TEST_TCS37727_ADDR ?= 0x29 - -# export parameters -CFLAGS += -DTEST_TCS37727_I2C=$(TEST_TCS37727_I2C) -CFLAGS += -DTEST_TCS37727_ADDR=$(TEST_TCS37727_ADDR) - include $(RIOTBASE)/Makefile.include diff --git a/tests/driver_tcs37727/main.c b/tests/driver_tcs37727/main.c index d5aed411ab85..e75eceb960dd 100644 --- a/tests/driver_tcs37727/main.c +++ b/tests/driver_tcs37727/main.c @@ -1,5 +1,6 @@ /* * Copyright (C) 2015 PHYTEC Messtechnik GmbH + * 2017 Freie Universität Berlin * * 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 @@ -7,30 +8,25 @@ */ /** - * @ingroup tests + * @ingroup tests * @{ * * @file * @brief Test application for the TCS37727 sensor driver. * * @author Felix Siebel + * @author Hauke Petersen * * @} */ -#ifndef TEST_TCS37727_I2C -#error "TEST_TCS37727_I2C not defined" -#endif -#ifndef TEST_TCS37727_ADDR -#error "TEST_TCS37727_ADDR not defined" -#endif - #include #include "xtimer.h" #include "tcs37727.h" +#include "tcs37727_params.h" -#define SLEEP (1000 * 1000U) +#define SLEEP (1 * US_PER_SEC) int main(void) { @@ -38,10 +34,9 @@ int main(void) tcs37727_data_t data; puts("TCS37727 RGBC Data; Sensor driver test application\n"); - printf("Initializing TCS37727 sensor at I2C_%i... ", TEST_TCS37727_I2C); + printf("Initializing first configured TCS37727 sensor..."); - if (tcs37727_init(&dev, TEST_TCS37727_I2C, TEST_TCS37727_ADDR, - TCS37727_ATIME_DEFAULT) == 0) { + if (tcs37727_init(&dev, &tcs37727_params[0]) == TCS37727_OK) { puts("[OK]\n"); } else { @@ -49,17 +44,12 @@ int main(void) return -1; } - if (tcs37727_set_rgbc_active(&dev)) { - puts("Measurement start failed."); - return -1; - } - while (1) { tcs37727_read(&dev, &data); printf("R: %5"PRIu32" G: %5"PRIu32" B: %5"PRIu32" C: %5"PRIu32"\n", data.red, data.green, data.blue, data.clear); - printf("CT : %5"PRIu32" Lux: %6"PRIu32" AGAIN: %2d ATIME %d\n", - data.ct, data.lux, dev.again, dev.atime_us); + printf("CT : %5"PRIu32" Lux: %6"PRIu32" AGAIN: %2d ATIME %"PRIu32"\n", + data.ct, data.lux, dev.again, dev.p.atime); xtimer_usleep(SLEEP); }