From 05980765f2d3af8835149b3e51f32aadb1a5dddf Mon Sep 17 00:00:00 2001 From: Dirk Ehmen Date: Mon, 11 Nov 2019 15:02:22 +0100 Subject: [PATCH] drivers/sdp3x: Driver for sensirion sdp3x sensor --- drivers/Makefile.dep | 7 + drivers/Makefile.include | 4 + drivers/include/sdp3x.h | 198 ++++++++++ drivers/saul/init_devs/auto_init_sdp3x.c | 74 ++++ drivers/saul/init_devs/init.c | 4 + drivers/sdp3x/Makefile | 1 + drivers/sdp3x/include/sdp3x_params.h | 105 ++++++ drivers/sdp3x/sdp3x.c | 457 +++++++++++++++++++++++ drivers/sdp3x/sdp3x_saul.c | 60 +++ tests/driver_sdp3x/Makefile | 12 + tests/driver_sdp3x/README.md | 21 ++ tests/driver_sdp3x/main.c | 93 +++++ 12 files changed, 1036 insertions(+) create mode 100644 drivers/include/sdp3x.h create mode 100644 drivers/saul/init_devs/auto_init_sdp3x.c create mode 100644 drivers/sdp3x/Makefile create mode 100644 drivers/sdp3x/include/sdp3x_params.h create mode 100644 drivers/sdp3x/sdp3x.c create mode 100644 drivers/sdp3x/sdp3x_saul.c create mode 100644 tests/driver_sdp3x/Makefile create mode 100644 tests/driver_sdp3x/README.md create mode 100644 tests/driver_sdp3x/main.c diff --git a/drivers/Makefile.dep b/drivers/Makefile.dep index e313b9d206..a3141ca625 100644 --- a/drivers/Makefile.dep +++ b/drivers/Makefile.dep @@ -656,6 +656,13 @@ ifneq (,$(filter sdcard_spi,$(USEMODULE))) USEMODULE += xtimer endif +ifneq (,$(filter sdp3x,$(USEMODULE))) + FEATURES_REQUIRED += periph_i2c + FEATURES_REQUIRED += periph_gpio_irq + USEMODULE += checksum + USEMODULE += xtimer +endif + ifneq (,$(filter sds011,$(USEMODULE))) FEATURES_REQUIRED += periph_uart endif diff --git a/drivers/Makefile.include b/drivers/Makefile.include index 9d4d3d9746..56dc25a4a2 100644 --- a/drivers/Makefile.include +++ b/drivers/Makefile.include @@ -308,6 +308,10 @@ ifneq (,$(filter sdcard_spi,$(USEMODULE))) USEMODULE_INCLUDES += $(RIOTBASE)/drivers/sdcard_spi/include endif +ifneq (,$(filter sdp3x,$(USEMODULE))) + USEMODULE_INCLUDES += $(RIOTBASE)/drivers/sdp3x/include +endif + ifneq (,$(filter sds011,$(USEMODULE))) USEMODULE_INCLUDES += $(RIOTBASE)/drivers/sds011/include endif diff --git a/drivers/include/sdp3x.h b/drivers/include/sdp3x.h new file mode 100644 index 0000000000..673cb9a7f5 --- /dev/null +++ b/drivers/include/sdp3x.h @@ -0,0 +1,198 @@ +/* + * Copyright (C) 2019 Dirk Ehmen + * 2020 Nishchay Agrawal + * + * 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_sdp3x SDP3x temperature and differential pressure sensor + * @ingroup drivers_sensors + * @{ + * @file + * @brief Device driver interface for the SDP3x sensor. + * + * @author Dirk Ehmen + * @author Nishchay Agrawal + * @} + */ + +#ifndef SDP3X_H +#define SDP3X_H + +#include "saul.h" +#include "xtimer.h" +#include "mutex.h" +#include "periph/i2c.h" +#include "periph/gpio.h" + +#ifdef __cplusplus +extern "C" { +#endif + +/** + * @brief Flags for sensor reading + * @{ + */ +#define SDP3X_FLAG_MASS_FLOW 0x02 /**< Use Mass Flow for Temperature Compensation */ +#define SDP3X_FLAG_DIFF_PRESS 0x00 /**< Use Differential Pressure for Temperature Compensation */ +#define SDP3X_FLAG_AVERAGE 0x01 /**< Average values */ +#define SDP3X_FLAG_NO_AVERAGE 0x00 /**< Don't Average values */ +/** @} */ + +/** + * @brief Device initialization parameters + */ +typedef struct { + i2c_t i2c_dev; /**< I2C device which is used */ + uint8_t i2c_addr; /**< I2C address */ + gpio_t irq_pin; /**< IRQ pin to check data ready */ +} sdp3x_params_t; + +/** + * @brief Device descriptor for the SDP3x sensor + */ +typedef struct { + bool continuous_measurement; /**< Device measuring data continuously */ + sdp3x_params_t params; /**< Device initialization parameters */ + mutex_t mutex; /**< Mutex for this sdp3x dev */ +} sdp3x_t; + +/** + * @brief Measurement from SDP3x sensor + */ +typedef struct { + int32_t differential_pressure; /**< Differential Pressure measured + in centiPa */ + int32_t temperature; /**< Temperature measured in centi°C */ +} sdp3x_measurement_t; + +/** + * @brief Status and error return codes + */ +enum { + SDP3x_OK = 0, /**< all went as expected */ + SDP3x_CRCERROR = -1, /**< CRC-Check failed */ + SDP3x_NODATA = -2, /**< No Data available */ + SDP3x_IOERROR = -3, /**< I/O error */ + SDP3x_WRONGSIZE = -4 /**< Wrong size of array for method */ +}; + +/** + * @brief Initialize SDP3x + * + * @param dev sdp3x device + * @param params sdp3x device params + * + * @return 1 if device started + */ +int sdp3x_init(sdp3x_t *dev, const sdp3x_params_t *params); + +/** + * @brief Start Continuous Measuring + * + * @param dev sdp3x device + * @param flags stores Temperature compensation and averaging flags + * 0th bit-> 0 = No averaging, 1 = Average values + * 1st bit-> 0 = Differential pressure, 1 = Mass Flow + * + * @return 1 if device started + */ +int8_t sdp3x_start_continuous(sdp3x_t *dev, uint8_t flags); + +/** + * @brief read temperature and differential pressure + * + * @param result struct to store result + * @param dev sdp3x device + * + * @return 1 on success + */ + +int8_t sdp3x_read_continuous(sdp3x_measurement_t *result, sdp3x_t *dev); + +/** + * @brief Read current temperature value + * + * @param dev sdp3x device + * @param flags stores Temperature compensation + * 1st bit-> 0 = Differential pressure, 1 = Mass Flow + * + * @return Current temperature in celsius multiplied by 100 + * to preserve accuracy and return in integer + */ +int32_t sdp3x_read_single_temperature(sdp3x_t *dev, uint8_t flags); + +/** + * @brief Read current differential_pressure value + * + * @param dev sdp3x device + * @param flags stores Temperature compensation + * 1st bit-> 0 = Differential pressure, 1 = Mass Flow + * + * @return current differential pressure in centipascal + */ +int32_t sdp3x_read_single_differential_pressure(sdp3x_t *dev, + uint8_t flags); + +/** + * @brief read temperature and differential pressure + * + * @param dev sdp3x device + * @param flags stores Temperature compensation + * 1st bit-> 0 = Differential pressure, 1 = Mass Flow + * @param result Values are stored in this struct + * + * @return 1 on success + */ +int8_t sdp3x_read_single_measurement(sdp3x_t *dev, uint8_t flags, + sdp3x_measurement_t *result); + +/** + * @brief Stop Continuous Measuring + * + * It takes 500 us till next command. + * + * @param dev device + * @param continuous_timer timer running to trigger reading data + * + * @return 0 if measurement stopped + */ +int8_t sdp3x_stop_continuous(sdp3x_t *dev, xtimer_t *continuous_timer); + +/** + * @brief Resets all I2C devices + * + * @param dev device + * + * @return 0 if reset is started + */ +int8_t sdp3x_soft_reset(const sdp3x_t *dev); + +/** + * @brief Activates sleep mode + * + * Only activates Sleep Mode if the device is in Idle Mode + * + * @param dev device + * + * @return 0 if sleep is activated + */ +int8_t sdp3x_enter_sleep(const sdp3x_t *dev); + +/** + * @brief Exit sleep mode + * + * @param dev device + * + * @return 0 if sleep is deactivated + */ +int8_t sdp3x_exit_sleep(const sdp3x_t *dev); + +#ifdef __cplusplus +} +#endif + +#endif /* SDP3X_H */ diff --git a/drivers/saul/init_devs/auto_init_sdp3x.c b/drivers/saul/init_devs/auto_init_sdp3x.c new file mode 100644 index 0000000000..9c4d13ca66 --- /dev/null +++ b/drivers/saul/init_devs/auto_init_sdp3x.c @@ -0,0 +1,74 @@ +/* + * Copyright (C) 2019 Dirk Ehmen + * 2020 Nishchay Agrawal + * + * 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 SDP3X driver. + * + * @author Dirk Ehmen + * @author Nishchay Agrawal + * + * @} + */ + +#include +#include "log.h" +#include "saul_reg.h" + +#include "sdp3x_params.h" +#include "sdp3x.h" + +/** + * @brief Allocation of memory for device descriptors + */ +static sdp3x_t sdp3x_devs[SDP3X_NUMOF]; + +/** + * @brief Reference the driver structs. + * @{ + */ +extern const saul_driver_t sdp3x_temperature_saul_driver; +extern const saul_driver_t sdp3x_differential_pressure_saul_driver; +/** @} */ + +/** + * @brief Memory for the SAUL registry entries + */ +#define SENSORS_NUMOF 2 +static saul_reg_t saul_entries[SDP3X_NUMOF * SENSORS_NUMOF]; + +void auto_init_sdp3x(void) +{ + size_t se_ix = 0; + + for (size_t i = 0; i < SDP3X_NUMOF; i++) { + int res = sdp3x_init(&sdp3x_devs[i], &sdp3x_params[i]); + if (res < 0) { + LOG_ERROR("[auto_init_saul] error initializing SDP3X #%u\n", i); + continue; + } + + /* temperature */ + saul_entries[se_ix].dev = &sdp3x_devs[i]; + saul_entries[se_ix].name = sdp3x_saul_info[i].name; + saul_entries[se_ix].driver = &sdp3x_temperature_saul_driver; + saul_reg_add(&saul_entries[se_ix]); + se_ix++; + + /* differential presure */ + saul_entries[se_ix].dev = &sdp3x_devs[i]; + saul_entries[se_ix].name = sdp3x_saul_info[i].name; + saul_entries[se_ix].driver = &sdp3x_differential_pressure_saul_driver; + saul_reg_add(&saul_entries[se_ix]); + se_ix++; + } +} diff --git a/drivers/saul/init_devs/init.c b/drivers/saul/init_devs/init.c index 2b52ff8640..dfe5a0c225 100644 --- a/drivers/saul/init_devs/init.c +++ b/drivers/saul/init_devs/init.c @@ -219,6 +219,10 @@ void saul_init_devs(void) extern void auto_init_sht2x(void); auto_init_sht2x(); } + if (IS_USED(MODULE_SDP3X)) { + extern void auto_init_sdp3x(void); + auto_init_sdp3x(); + } if (IS_USED(MODULE_SHT3X)) { extern void auto_init_sht3x(void); auto_init_sht3x(); diff --git a/drivers/sdp3x/Makefile b/drivers/sdp3x/Makefile new file mode 100644 index 0000000000..48422e909a --- /dev/null +++ b/drivers/sdp3x/Makefile @@ -0,0 +1 @@ +include $(RIOTBASE)/Makefile.base diff --git a/drivers/sdp3x/include/sdp3x_params.h b/drivers/sdp3x/include/sdp3x_params.h new file mode 100644 index 0000000000..4ac0a58f3e --- /dev/null +++ b/drivers/sdp3x/include/sdp3x_params.h @@ -0,0 +1,105 @@ +/* + * Copyright (C) 2019 Dirk Ehmen + * 2020 Nishchay Agrawal + * + * 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 Device driver params interface for the SDP3x sensor. + * + * @author Dirk Ehmen + * @author Nishchay Agrawal + * @} + */ + +#ifndef SDP3X_PARAMS_H +#define SDP3X_PARAMS_H + +#include "board.h" +#include "sdp3x.h" +#include "saul_reg.h" +#include "periph/gpio.h" + +#ifdef __cplusplus +extern "C" { +#endif + +/** + * @name SDP3x I2C addresses + * @{ + */ +#define SDP3X_ADDR1 (0x21) /* 7 bit address */ +#define SDP3X_ADDR2 (0x22) /* 7 bit address */ +#define SDP3X_ADDR3 (0x23) /* 7 bit address */ +/** @} */ + +/** + * @name SDP3x Models + * @{ + */ +#define SDP3X_MODEL_31 1 +#define SDP3X_MODEL_32 2 + +#define SDP31_PRODUCT_NO_BYTE_0 0x03 +#define SDP31_PRODUCT_NO_BYTE_1 0x01 +#define SDP31_PRODUCT_NO_BYTE_3 0x01 +/** @} */ + +/** + * @name Set default configuration parameters for the SDP3X + * @{ + */ +#ifndef SDP3X_PARAM_I2C_DEV +#define SDP3X_PARAM_I2C_DEV I2C_DEV(0) +#endif +#ifndef SDP3X_PARAM_I2C_ADDR +#define SDP3X_PARAM_I2C_ADDR SDP3X_ADDR1 +#endif +#ifndef SDP3X_PARAM_IRQ_PIN +#define SDP3X_PARAM_IRQ_PIN (GPIO_PIN(0, 2)) +#endif + +#ifndef SDP3X_PARAMS +#define SDP3X_PARAMS { .i2c_dev = SDP3X_PARAM_I2C_DEV, \ + .i2c_addr = SDP3X_PARAM_I2C_ADDR, \ + .irq_pin = SDP3X_PARAM_IRQ_PIN } +#endif + +#ifndef SDP3X_SAUL_INFO +#define SDP3X_SAUL_INFO { .name = "sdp3x" } +#endif + +/**@}*/ + +/** + * @brief Configure SDP3X + */ +static const sdp3x_params_t sdp3x_params[] = +{ + SDP3X_PARAMS +}; + +/** + * @brief Get the number of configured SDP3X devices + */ +#define SDP3X_NUMOF ARRAY_SIZE(sdp3x_params) + +/** + * @brief Configure SAUL registry entries + */ +static const saul_reg_info_t sdp3x_saul_info[SDP3X_NUMOF] = +{ + SDP3X_SAUL_INFO +}; + +#ifdef __cplusplus +} +#endif + +#endif /* SDP3X_PARAMS_H */ diff --git a/drivers/sdp3x/sdp3x.c b/drivers/sdp3x/sdp3x.c new file mode 100644 index 0000000000..4a60e6a580 --- /dev/null +++ b/drivers/sdp3x/sdp3x.c @@ -0,0 +1,457 @@ +/* + * Copyright (C) 2019 Dirk Ehmen + * 2020 Jan Schlichter + * 2020 Nishchay Agrawal + * + * 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_sdp3x + * @{ + * @file + * @brief Sensirion SDP3x sensor driver implementation + * + * @author Dirk Ehmen + * @author Jan Schlichter + * @author Nishchay Agrawal + * @} + */ + +#include +#include +#include "sdp3x_params.h" +#include "sdp3x.h" +#include "checksum/crc8.h" +#include "thread.h" + +#define ENABLE_DEBUG (0) +#include "debug.h" + +#define DEV_I2C (dev->params.i2c_dev) +#define DEV_ADDR (dev->params.i2c_addr) + +#define DATA_READY_SLEEP_US (50 * US_PER_MS) + +static bool _check_product_number(uint8_t *readData); +static void _sdp3x_irq_callback(void *arg); +static int8_t _checkCRC(uint16_t value, uint8_t test); +static int8_t _SDP3x_read_data(const sdp3x_t *dev, int16_t *data); +static int32_t _SDP3x_convert_to_pascal(int16_t value, + int16_t dp_scale_factor); +static int32_t _SDP3x_convert_to_celsius(int16_t value); +static int8_t _SDP3x_start_triggered(const sdp3x_t *dev, uint8_t flags); +static int32_t _SDP3x_read_temp(const sdp3x_t *dev); +static int32_t _SDP3x_read_pressure(const sdp3x_t *dev); + +int sdp3x_init(sdp3x_t *dev, const sdp3x_params_t *params) +{ + DEBUG("[SDP3x] init: Initializing device\n"); + + dev->params = *params; + dev->continuous_measurement = false; + + i2c_init(DEV_I2C); + sdp3x_soft_reset(dev); + + /* try to read product number to check if sensor is connected and working */ + int ret = 0; + /* Command to get sensor product information */ + uint8_t cmd1[2] = { 0x36, 0x7C }; + uint8_t cmd2[2] = { 0xE1, 0x02 }; + i2c_acquire(DEV_I2C); + ret = i2c_write_bytes(DEV_I2C, DEV_ADDR, cmd1, 2, I2C_NOSTOP); + if (ret != 0) { + i2c_release(DEV_I2C); + return ret; + } + ret = i2c_write_bytes(DEV_I2C, DEV_ADDR, cmd2, 2, I2C_NOSTOP); + if (ret != 0) { + i2c_release(DEV_I2C); + return ret; + } + + /* Read information from the sensor to verify it's correct */ + uint8_t readData[5]; + ret = i2c_read_bytes(DEV_I2C, DEV_ADDR, readData, sizeof(readData), 0); + i2c_release(DEV_I2C); + + if (ret != 0) { + DEBUG("[SDP3x] read_data: ret %i\n", ret); + return ret; + } + if (!_check_product_number(readData)) { + DEBUG("[SDP3x] Sensor not working or incorrectly configured\n"); + return ret; + } + +#ifdef SDP3X_PARAM_IRQ_PIN + mutex_init(&dev->mutex); + /* lock mutex initially to be unlocked when interrupt is raised */ + mutex_lock(&dev->mutex); + /* Interrupt set to trigger on falling edge of interrupt pin */ + gpio_init_int(params->irq_pin, GPIO_IN, GPIO_FALLING, _sdp3x_irq_callback, + dev); +#endif + + DEBUG("[SDP3x] init: Init done\n"); + return 1; +} + +int32_t sdp3x_read_single_temperature(sdp3x_t *dev, uint8_t flags) +{ + _SDP3x_start_triggered(dev, flags); +#ifndef SDP3X_PARAM_IRQ_PIN + /* Wait for measurement to be ready if irq pin not used */ + xtimer_usleep(DATA_READY_SLEEP_US); +#else + /* Try to lock mutex till the interrupt is raised or till timeut happens */ + xtimer_mutex_lock_timeout(&dev->mutex, DATA_READY_SLEEP_US); +#endif + return _SDP3x_read_temp(dev); +} + +int32_t sdp3x_read_single_differential_pressure(sdp3x_t *dev, + uint8_t flags) +{ + _SDP3x_start_triggered(dev, flags); +#ifndef SDP3X_PARAM_IRQ_PIN + /* Wait for measurement to be ready if irq pin not used */ + xtimer_usleep(DATA_READY_SLEEP_US); +#else + /* Try to lock mutex till the interrupt is raised or till timeut happens */ + xtimer_mutex_lock_timeout(&dev->mutex, DATA_READY_SLEEP_US); +#endif + return _SDP3x_read_pressure(dev); +} + +int8_t sdp3x_read_single_measurement(sdp3x_t *dev, uint8_t flags, + sdp3x_measurement_t *result) +{ + _SDP3x_start_triggered(dev, flags); +#ifndef SDP3X_PARAM_IRQ_PIN + /* Wait for measurement to be ready if irq pin not used */ + xtimer_usleep(DATA_READY_SLEEP_US); +#else + /* Try to lock mutex till the interrupt is raised or till timeut happens */ + xtimer_mutex_lock_timeout(&dev->mutex, DATA_READY_SLEEP_US); +#endif + /* read in sensor values here */ + int16_t data[3]; + uint8_t ret = _SDP3x_read_data(dev, data); + if (ret != 0) { + DEBUG("[SDP3x] Error reading data\n"); + return 0; + } + else { + result->differential_pressure = _SDP3x_convert_to_pascal(data[0], + data[2]); + result->temperature = _SDP3x_convert_to_celsius(data[1]); + } + return 1; +} + +int8_t sdp3x_start_continuous(sdp3x_t *dev, uint8_t flags) +{ + int ret = 0; + uint8_t cmd[2] = { 0x36, 0 }; + if (((flags >> 1) & 1) == 1) { + if ((flags & 1) == 0) { + cmd[1] = 0x08; + } + else { + cmd[1] = 0x03; + } + } + else { + if ((flags & 1) == 0) { + cmd[1] = 0x1E; + } + else { + cmd[1] = 0x15; + } + } + + i2c_acquire(DEV_I2C); + ret = i2c_write_bytes(DEV_I2C, DEV_ADDR, cmd, 2, 0); + i2c_release(DEV_I2C); + + if (ret != 0) { + DEBUG("[SDP3x] Error starting continuous measurement\n"); + } + + dev->continuous_measurement = true; + return ret; +} + +int8_t sdp3x_read_continuous(sdp3x_measurement_t *result, sdp3x_t *dev) +{ + /* read in sensor values here */ + int16_t data[3]; + uint8_t ret = _SDP3x_read_data(dev, data); + + if (ret != 0) { + DEBUG("[SDP3x] Error reading date\n"); + } + else { + result->differential_pressure = _SDP3x_convert_to_pascal(data[0], + data[2]); + result->temperature = _SDP3x_convert_to_celsius(data[1]); + } + return ret; +} + +/** + * intern function to start triggered measurement + * @param dev device + * @param flags stores Temperature compensation + * 1st bit-> 0 = Differential pressure, 1 = Mass Flow + * @return i2c error code + */ +static int8_t _SDP3x_start_triggered(const sdp3x_t *dev, uint8_t flags) +{ + int ret = 0; + uint8_t cmd[2]; + + cmd[0] = 0x36; + if (flags == SDP3X_FLAG_MASS_FLOW) { + cmd[1] = 0x24; + } + else { + cmd[1] = 0x2F; + } + + i2c_acquire(DEV_I2C); + ret = i2c_write_bytes(DEV_I2C, DEV_ADDR, cmd, 2, 0); + i2c_release(DEV_I2C); + return ret; +} + +int8_t sdp3x_stop_continuous(sdp3x_t *dev, xtimer_t *continuous_timer) +{ + int ret = 0; + uint8_t cmd[2] = { 0x3F, 0xF9 }; + + DEBUG("[SDP3x] stop_continuous: Stopping continuous\ + measurement on device %#X\n", DEV_ADDR); + i2c_acquire(DEV_I2C); + ret = i2c_write_bytes(DEV_I2C, DEV_ADDR, cmd, 2, 0); + i2c_release(DEV_I2C); + + xtimer_remove(continuous_timer); + dev->continuous_measurement = false; + + return ret; +} + +int8_t sdp3x_soft_reset(const sdp3x_t *dev) +{ + int ret = 0; + + DEBUG("[SDP3x] soft_reset: Sending soft reset to all devices\n"); + i2c_acquire(DEV_I2C); + /* General Call Reset */ + ret = i2c_write_byte(DEV_I2C, 0x00, 0x06, 0); + i2c_release(DEV_I2C); + /* Wait 20ms for the reset to be processed */ + xtimer_usleep(20000); + DEBUG("[SDP3x] soft_reset: reset done\n"); + return ret; +} + +int8_t sdp3x_enter_sleep(const sdp3x_t *dev) +{ + int ret = 0; + uint8_t cmd[2] = { 0x36, 0x77 }; + + DEBUG("[SDP3x] enter_sleep: Entering sleep mode on device %#X\n", DEV_ADDR); + i2c_acquire(DEV_I2C); + ret = i2c_write_bytes(DEV_I2C, DEV_ADDR, cmd, 2, 0); + i2c_release(DEV_I2C); + + return ret; +} + +int8_t sdp3x_exit_sleep(const sdp3x_t *dev) +{ + int ret = 0; + uint8_t ptr[1] = { 0 }; + + DEBUG("[SDP3x] exit_sleep: Exiting sleep mode on device %#X\n", DEV_ADDR); + i2c_acquire(DEV_I2C); + ret = i2c_write_bytes(DEV_I2C, DEV_ADDR, ptr, 0, 0); + + if (ret != 0) { + DEBUG("[SDP3x] Error exiting sleep mode\n"); + i2c_release(DEV_I2C); + return ret; + } + xtimer_usleep(2000); + ret = i2c_write_bytes(DEV_I2C, DEV_ADDR, ptr, 0, 0); + i2c_release(DEV_I2C); + + return ret; +} + +/** + * intern function to read temperature + * @param dev device + * @return Temperature value in celsius + */ +static int32_t _SDP3x_read_temp(const sdp3x_t *dev) +{ + int16_t data[3]; + uint8_t ret = _SDP3x_read_data(dev, data); + + if (ret != 0) { + DEBUG("[SDP3x] Error reading date\n"); + return ret; + } + DEBUG("[SDP3x] read temperature bare value %i\n", data[1]); + return _SDP3x_convert_to_celsius(data[1]); +} + +/** + * intern function to read differential pressure + * @param dev device + * @return Pressure value in pascals + */ +static int32_t _SDP3x_read_pressure(const sdp3x_t *dev) +{ + int16_t data[3]; + uint8_t ret = _SDP3x_read_data(dev, data); + + if (ret != 0) { + DEBUG("[SDP3x] Error reading date\n"); + return ret; + } + return _SDP3x_convert_to_pascal(data[0], data[2]); +} + +/** Read measurements + * + * Data consists of: + * 2 byte Differential Pressure, + * 1 byte CRC + * 2 byte Temperature, + * 1 byte CRC + * 2 byte Scale Factor differential pressure + * 1 byte CRC + * + * @param addr Address byte 1 = 0x21, 2 = 0x22, 3 = 0x23, + * else = Last address + * @param data Data will be stored here + * + * @return 0 if data could be read, 1 if CRC-Error + */ +static int8_t _SDP3x_read_data(const sdp3x_t *dev, int16_t *data) +{ + int ret = 0; + uint8_t readData[9]; + + i2c_acquire(DEV_I2C); + ret = i2c_read_bytes(DEV_I2C, DEV_ADDR, readData, sizeof(readData), 0); + i2c_release(DEV_I2C); + + if (ret != 0) { + DEBUG("[SDP3x] read_data: ret %i\n", ret); + return ret; + } + data[2] = (readData[6] << 8) + readData[7]; + data[1] = (readData[3] << 8) + readData[4]; + data[0] = (readData[0] << 8) + readData[1]; + + uint8_t correct = 1; + + correct &= _checkCRC(data[2], readData[8]); + correct &= _checkCRC(data[1], readData[5]); + correct &= _checkCRC(data[0], readData[2]); + + if (correct == 0) { + DEBUG("[SDP3x] read_data: CRC-Failure\n"); + return SDP3x_CRCERROR; + } + + return 0; +} + +/** + * intern method to convert sensor value to pascal + * @param dev device + * @param value raw sensor value + * @return pressure value in centiPa + */ +static int32_t _SDP3x_convert_to_pascal(int16_t value, int16_t dp_scale_factor) +{ + /* Multiplying by 100 to convert to centiPa */ + return ((value * 100) / dp_scale_factor); +} + +/** + * intern method to convert sensor value to celsius + * @param dev device + * @param value raw sensor value + * @return temperature in centi°C + */ +static int32_t _SDP3x_convert_to_celsius(int16_t value) +{ + int16_t div = 200; + /* Multiplying by 100 to convert the final temperature in 100*°C */ + return ((value * 100) / div); +} + +/** + * check if crc is valid + * @param value Number whose crc has to be calculated + * @param test CRC value with which it will compared + * @return 1 on success + */ +static int8_t _checkCRC(uint16_t value, uint8_t test) +{ + uint8_t crc; + uint8_t data[2] = { value >> 8, value & 0x00FF }; + + crc = crc8(data, 2, 0x31, 0xFF); + + return (crc == test ? 1 : 0); +} + +/** + * Callback function to handle trigger on irq + * @param arguments passed when interrupt is raised + * (in this case sdp3x dev) + */ +static void _sdp3x_irq_callback(void *arg) +{ + sdp3x_t *dev = (sdp3x_t *)arg; + if (!dev->continuous_measurement) { + mutex_unlock(&(dev->mutex)); + } +} + +/** + * Function to check if the product number set + * is the one we get from the sensor + * @param data data read from the sensor + * @param dev sdp3x device + * @return true if values from sensor were correct + */ +static bool _check_product_number(uint8_t *readData) +{ + if (readData[0] != SDP31_PRODUCT_NO_BYTE_0) { + return false; + } + if (readData[1] != SDP31_PRODUCT_NO_BYTE_1) { + return false; + } + if ((readData[3] != SDP3X_MODEL_31) || (readData[3] != SDP3X_MODEL_32)) { + return false; + } + if (readData[4] != SDP31_PRODUCT_NO_BYTE_3) { + return false; + } + + return true; +} diff --git a/drivers/sdp3x/sdp3x_saul.c b/drivers/sdp3x/sdp3x_saul.c new file mode 100644 index 0000000000..c1ee58d9c1 --- /dev/null +++ b/drivers/sdp3x/sdp3x_saul.c @@ -0,0 +1,60 @@ +/* + * Copyright (C) 2019 Jan Schlichter + * 2020 Nishchay Agrawal + * + * 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_sdp3x + * @{ + * @file + * @brief SAUL adaption for Sensirion SDP3x devices + * + * @author Jan Schlichter + * @author Nishchay Agrawal + * + * @} + */ + +#include "saul.h" + +#include "sdp3x.h" + +static int read_temperature(const void *dev, phydat_t *res) +{ + int32_t temp = sdp3x_read_single_temperature((sdp3x_t *)dev, + SDP3X_FLAG_DIFF_PRESS); + + /* Fit 32 bit data into 16 bit fields of phydat_t */ + phydat_fit(res, &temp, 1); + res->unit = UNIT_TEMP_C; + res->scale = -2; + return 1; +} + +static int read_differential_pressure(const void *dev, phydat_t *res) +{ + int32_t pres = sdp3x_read_single_differential_pressure((sdp3x_t *)dev, + SDP3X_FLAG_DIFF_PRESS); + + /* Fit 32 bit data into 16 bit fields of phydat_t */ + phydat_fit(res, &pres, 1); + res->unit = UNIT_PA; + res->scale = -2; + return 1; +} + +const saul_driver_t sdp3x_temperature_saul_driver = { + .read = read_temperature, + .write = saul_notsup, + .type = SAUL_SENSE_TEMP, +}; + +const saul_driver_t sdp3x_differential_pressure_saul_driver = { + .read = read_differential_pressure, + .write = saul_notsup, + .type = SAUL_SENSE_PRESS, +}; diff --git a/tests/driver_sdp3x/Makefile b/tests/driver_sdp3x/Makefile new file mode 100644 index 0000000000..e2bdc2174e --- /dev/null +++ b/tests/driver_sdp3x/Makefile @@ -0,0 +1,12 @@ +include ../Makefile.tests_common + +DRIVER ?= sdp3x + +USEMODULE += $(DRIVER) +USEMODULE += printf_float + +TEST_ITERATIONS ?= 10 +# export iterations for continuous measurements +CFLAGS += -DTEST_ITERATIONS=$(TEST_ITERATIONS) + +include $(RIOTBASE)/Makefile.include diff --git a/tests/driver_sdp3x/README.md b/tests/driver_sdp3x/README.md new file mode 100644 index 0000000000..a4248fd1aa --- /dev/null +++ b/tests/driver_sdp3x/README.md @@ -0,0 +1,21 @@ +## About +This is a test application for the SDP3x temperature and differential pressure sensor. + +## Usage +This test application will initialize the SDP3x sensor and print TEST_ITERATIONS number +of following values first in continuous mode and then triggered mode every second: + +* Temperature +* Differential pressure + +The user can specify the number of iterations by setting the variable `TEST_ITERATIONS` +(default value is 10) from commandline as follows: +``` +make BOARD=... TEST_ITERATIONS=... -C tests/driver_sdp3x +``` + +##Features +The sensor has an IRQn pin which indicates data ready on the sensor. This pin can be +connected on the GPIO ports and configured in the variable `SDP3X_PARAM_IRQ_PIN`. This +helps getting measurements as soon as they are ready instead of the 46ms wait (which is +the maximum time the sensor might take the get the measurement ready). \ No newline at end of file diff --git a/tests/driver_sdp3x/main.c b/tests/driver_sdp3x/main.c new file mode 100644 index 0000000000..ea9b962d7b --- /dev/null +++ b/tests/driver_sdp3x/main.c @@ -0,0 +1,93 @@ +/* + * Copyright (C) 2019 Jan Schlichter + 2020 Nishchay Agrawal + * + * 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 sdp3x temperature and differential + * pressure sensor driver + * + * @author Jan Schlichter + * @author Nishchay Agrawal + * @} + */ +#include + +#include "xtimer.h" +#include "sdp3x_params.h" +#include "sdp3x.h" + +#define MEASUREMENT_INTERVAL_US (1 * US_PER_SEC) + +static sdp3x_t sdp3x_dev; +static sdp3x_params_t params = SDP3X_PARAMS; +sdp3x_measurement_t result; +xtimer_t continuous_timer; + +void continuous_measurement_callback(void *arg) +{ + uint32_t *interval = (uint32_t *)arg; + + sdp3x_read_continuous(&result, &sdp3x_dev); + + xtimer_set(&continuous_timer, *interval); +} + +int main(void) +{ + + sdp3x_init(&sdp3x_dev, ¶ms); + + xtimer_sleep(1); + + uint32_t interval = MEASUREMENT_INTERVAL_US; + + uint32_t i = 0; + + sdp3x_start_continuous(&sdp3x_dev, + SDP3X_FLAG_DIFF_PRESS|SDP3X_FLAG_AVERAGE); + + continuous_timer.callback = (void *)continuous_measurement_callback; + continuous_timer.arg = &interval; + + xtimer_set(&continuous_timer, interval); + + /* + * Get measurements using continuous method for TEST_ITERATIONS + * number of iterations + */ + while (i < (uint32_t)TEST_ITERATIONS) { + printf( + "Continuous values for temp: %.02f°C pressure: %.02fPa \n", + result.temperature/100.f, result.differential_pressure/100.f); + xtimer_sleep(1); + i++; + } + + sdp3x_stop_continuous(&sdp3x_dev, &continuous_timer); + i = 0; + + /* + * Get measurements using triggered method for TEST_ITERATIONS + * number of iterations + */ + while (i < (uint32_t)TEST_ITERATIONS) { + sdp3x_read_single_measurement(&sdp3x_dev, SDP3X_FLAG_DIFF_PRESS, + &result); + printf( + "Triggered values for temp: %.02f°C pressure: %.02fPa \n", + result.temperature/100.f, result.differential_pressure/100.f); + xtimer_sleep(1); + i++; + } + + return 0; +}