1
0
mirror of https://github.com/RIOT-OS/RIOT.git synced 2024-12-29 04:50:03 +01:00

driver/sgp30: initial import

This commit is contained in:
Francisco Molina 2021-03-23 12:09:27 +01:00
parent e7732d9a00
commit 478624cbb6
No known key found for this signature in database
GPG Key ID: 3E94EAC3DBDEEDA8
12 changed files with 935 additions and 0 deletions

View File

@ -112,6 +112,7 @@ rsource "pulse_counter/Kconfig"
rsource "qmc5883l/Kconfig"
rsource "scd30/Kconfig"
rsource "sdp3x/Kconfig"
rsource "sgp30/Kconfig"
rsource "sds011/Kconfig"
rsource "seesaw_soil/Kconfig"
rsource "sht1x/Kconfig"

255
drivers/include/sgp30.h Normal file
View File

@ -0,0 +1,255 @@
/*
* Copyright (C) 2021 Inria
*
* 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_sgp30 SGP30 Gas Sensor
* @ingroup drivers_sensors
* @brief Device driver interface for the Sensirion SGP30 Gas Sensor
*
* About
* =====
*
* This driver provides an interface for the Sensirion SGP30 Gas Sensor.
* The Datasheet can be found [here](https://www.mouser.com/pdfdocs/Sensirion_Gas_Sensors_SGP30_Datasheet_EN-1148053.pdf)
*
* After the sensor is powered up and starts measuring air quality for the
* first 15s @ref sgp30_read_measurements calls will return fixed values of
* of 400ppm CO2eq and 0ppb TVOC. Afterwards values should be read in regular
* intervals of 1s for best operation of the dynamic baseline compensation
* algorithm.
*
* The above is not done by default unless the `sgp30_strict` module is included.
* In that case, if attempting to read before the is completed, then -EAGAIN
* will be returned. After this periodic readings happen every 1s, and the last
* value read is returned when calling @ref sgp30_read_measurements. A
* timestamp is also added to @ref sgp30_data_t.
*
* The sensor features on-chip humidity compensation for the air quality
* measurements. @ref sgp30_set_absolute_humidity can be used to change the
* absolute humidity value used. See [SGP30 driver integration] (https://files.seeedstudio.com/wiki/Grove-VOC_and_eCO2_Gas_Sensor-SGP30/res/Sensirion_Gas_Sensors_SGP30_Driver-Integration-Guide_HW_I2C.pdf)
* for more on this. The baseline values for the correction algorithm can
* also be tweaked with @ref sgp30_set_baseline. More on how to implement
* dynamic baseline compensation can be seen at [SGP30 driver integration] (https://files.seeedstudio.com/wiki/Grove-VOC_and_eCO2_Gas_Sensor-SGP30/res/Sensirion_Gas_Sensors_SGP30_Driver-Integration-Guide_HW_I2C.pdf).
*
* @{
*
* @file
*
* @author Francisco Molina <francois-xavier.molina@inria.fr>
*/
#ifndef SGP30_H
#define SGP30_H
#include "periph/i2c.h"
#include "ztimer.h"
#ifdef __cplusplus
extern "C" {
#endif
/**
* @brief Set of measured values
*/
typedef struct {
uint16_t tvoc; /**< The last measurement of the IAQ-calculated Total
Volatile Organic Compounds in ppb. */
uint16_t eco2; /**< The last measurement of the IAQ-calculated
equivalent CO2 in ppm */
#ifdef MODULE_SGP30_STRICT
uint32_t timestamp; /**< Timestamp of last measured value */
#endif
} sgp30_data_t;
/**
* @brief Set of measured raw values
*/
typedef struct {
uint16_t raw_h2; /**< raw H2 signal, only for testing purposes */
uint16_t raw_ethanol; /**< raw Ethanol signal, only for testing purposes */
} sgp30_raw_data_t;
/**
* @brief Device initialization parameters
*/
typedef struct {
i2c_t i2c_dev; /**< I2C dev the sensor is connected to */
} sgp30_params_t;
/**
* @brief Device descriptor for the driver
*/
typedef struct {
sgp30_params_t params; /**< parameters of the sensor device */
#ifdef MODULE_SGP30_STRICT
bool ready; /**< if initialization phase is over*/
ztimer_t _timer; /**< timer */
sgp30_data_t _data; /**< internal current data */
#endif
} sgp30_t;
/**
* @brief Initialize the given device
*
* @param[inout] dev Device descriptor of the driver
* @param[in] params Initialization parameters
*
* @return 0 on success
*/
int sgp30_init(sgp30_t *dev, const sgp30_params_t *params);
/**
* @brief Start air quality measurements, called on @ref sgp30_init
*
* @note Must be called after every power-cycle or soft reset.
*
* @param[inout] dev Device descriptor of the driver
*
* @retval 0 Success
* @retval -PROTO Sensor did not acknowledge command
*/
int sgp30_start_air_quality(sgp30_t *dev);
/**
* @brief Initialize the given device
*
* @param[in] dev Device descriptor of the driver
* @param[out] version The future set version
*
* @retval 0 Success
* @retval -EBADMSG CRC checksum didn't match
* @retval -EPROTO Sensor did not acknowledge command
*/
int sgp30_read_future_set(sgp30_t *dev, uint16_t *version);
/**
* @brief Performs a soft reset on the device
*
* @warning Reset is performed via a "General Call". All devices on the
* same I2C bus that support the General Call mode will perform
* a reset.
*
* @param[in] dev Device descriptor of the driver
*
* @retval 0 Success
* @retval -PROTO Sensor did not acknowledge command
*/
int sgp30_reset(sgp30_t *dev);
#if defined(MODULE_SGP30_STRICT) || defined(DOXYGEN)
/**
* @brief If device is ready to start reading measurements
*
* @note Only available if sgp30_strict is used
*
* @param[in] dev Device descriptor of the driver
*
* @retval true If ready to read measurements
* @retval false If still in warm-up period of it @ref sgp30_start_air_quality
* has not been called
*/
bool sgp30_ready(sgp30_t *dev);
#endif
/**
* @brief Read the serial number from the sensor
*
* @param[in] dev Device descriptor of the driver
* @param[out] buf Pre-allocated memory for returning the serial number
* @param[in] len Length of the \p str buffer, must be 6
*
* @retval 0 Success
* @retval -EBADMSG CRC checksum didn't match
* @retval -EPROTO Sensor did not acknowledge command
*/
int sgp30_read_serial_number(sgp30_t *dev, uint8_t *buf, size_t len);
/**
* @brief Read air quality signals
*
* @note For the first 15s after the Init_air_quality command (called
* in the init function) the sensor is in an initialization phase during
* which a Measure_air_quality command returns fixed values of 400ppm
* CO2eq and 0ppb TVOC.
*
* @param[in] dev Device descriptor of the driver
* @param[out] data Air quality measurements
*
* @retval 0 Success
* @retval -EAGAIN Sensor is not yet ready
* @retval -EBADMSG CRC checksum didn't match
* @retval -EPROTO Sensor did not acknowledge command
*/
int sgp30_read_measurements(sgp30_t *dev, sgp30_data_t *data);
/**
* @brief Set absolute humidity value for on-chop humidity compensation
*
* @note This function requires absolute humidity values, most sensors
* output relative humidity, this can be calculated if temperature is also
* known:
*
* AH = 216.7 * ((RH / 100.0) * 6.112 * exp(17.62 * T / (243.12 + T))) / (273.15 + T)
*
* Where RH is in 0-100%, and T is in C.
*
* (*) Approximation formula from Sensirion SGP30 Driver Integration chapter 3.15
*
* @param[in] dev Device descriptor of the driver
* @param[in] humidity Humidity in mg/m3 units. A values of 0 disables
* humidity compensation, max value is 255999 mg/m3.
*
* @retval 0 Success
* @retval -PROTO Sensor did not acknowledge command
*/
int sgp30_set_absolute_humidity(sgp30_t *dev, uint32_t humidity);
/**
* @brief Set new baseline values
*
* @param[in] dev Device descriptor of the driver
* @param[in] data Baseline values to be set
*
* @retval 0 Success
* @retval -PROTO Sensor did not acknowledge command
*/
int sgp30_set_baseline(sgp30_t *dev, sgp30_data_t *data);
/**
* @brief Returns baseline values
*
* @param[in] dev Device descriptor of the driver
* @param[out] data Current baseline values
*
* @retval 0 Success
* @retval -EBADMSG CRC checksum didn't match
* @retval -EPROTO Sensor did not acknowledge command
*/
int sgp30_get_baseline(sgp30_t *dev, sgp30_data_t *data);
/**
* @brief Read raw signals H2 (sout_H2) and Ethanol(sout_EthOH)
*
* It returns the sensor raw sensor signals which are used as inputs for
* the on-chip calibration and baseline compensation algorithms.
*
* @param[in] dev Device descriptor of the driver
* @param[out] data Raw measurement values
*
* @retval 0 Success
* @retval -EBADMSG CRC checksum didn't match
* @retval -EPROTO Sensor did not acknowledge command
*/
int sgp30_read_raw_measurements(sgp30_t *dev, sgp30_raw_data_t *data);
#ifdef __cplusplus
}
#endif
#endif /* SGP30_H */
/** @} */

View File

@ -0,0 +1,74 @@
/*
* Copyright (C) 2021 Inria
*
* 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
* @brief Auto initialization of AMS SGP30 digital gas sensor driver
*
* @author Francisco Molina <francois-xavier.molina@inria.fr>
* @file
*/
#include "assert.h"
#include "log.h"
#if IS_USED(MODULE_SAUL)
#include "saul_reg.h"
#endif
#include "sgp30.h"
#include "sgp30_params.h"
/**
* @brief Allocation of memory for device descriptors
*/
static sgp30_t sgp30_devs[SGP30_NUM];
#if IS_USED(MODULE_SAUL)
/**
* @brief Memory for the SAUL registry entries
*/
static saul_reg_t saul_entries[SGP30_NUM * 2];
/**
* @name Reference the driver structs.
* @{
*/
extern const saul_driver_t sgp30_saul_driver_eco2;
extern const saul_driver_t sgp30_saul_driver_tvoc;
/** @} */
#endif
void auto_init_sgp30(void)
{
assert(SGP30_INFO_NUM == SGP30_NUM);
for (unsigned i = 0; i < SGP30_NUM; i++) {
LOG_DEBUG("[auto_init_saul] initializing sgp30 #%u\n", i);
if (sgp30_init(&sgp30_devs[i], &sgp30_params[i]) != 0) {
LOG_ERROR("[auto_init_saul] error initializing sgp30 #%u\n", i);
continue;
}
#if IS_USED(MODULE_SAUL)
/* eCO2 */
saul_entries[(i * 2)].dev = &(sgp30_devs[i]);
saul_entries[(i * 2)].name = sgp30_saul_info[i].name;
saul_entries[(i * 2)].driver = &sgp30_saul_driver_eco2;
/* TVOC */
saul_entries[(i * 2) + 1].dev = &(sgp30_devs[i]);
saul_entries[(i * 2) + 1].name = sgp30_saul_info[i].name;
saul_entries[(i * 2) + 1].driver = &sgp30_saul_driver_tvoc;
/* register to saul */
saul_reg_add(&(saul_entries[(i * 2)]));
saul_reg_add(&(saul_entries[(i * 2) + 1]));
#endif
}
}

View File

@ -247,6 +247,10 @@ void saul_init_devs(void)
extern void auto_init_seesaw_soil(void);
auto_init_seesaw_soil();
}
if (IS_USED(MODULE_SGP30)) {
extern void auto_init_sgp30(void);
auto_init_sgp30();
}
if (IS_USED(MODULE_SHT3X)) {
extern void auto_init_sht3x(void);
auto_init_sht3x();

25
drivers/sgp30/Kconfig Normal file
View File

@ -0,0 +1,25 @@
# Copyright (c) 2021 Inria
#
# 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.
#
config MODULE_SGP30
bool "SGP30 Particulate Matter Sensor"
depends on HAS_PERIPH_I2C
depends on TEST_KCONFIG
select MODULE_CHECKSUM
select MODULE_PERIPH_I2C
select MODULE_ZTIMER
select MODULE_ZTIMER_PERIPH_TIMER
select MODULE_ZTIMER_USEC
config MODULE_SGP30_STRICT
bool "Strict reading period"
depends on MODULE_SGP30
default y
help
If this module is enabled regular measurements will be performed
every second and no values will be returned before the 15s warmup
period, see the datasheet for more.

7
drivers/sgp30/Makefile Normal file
View File

@ -0,0 +1,7 @@
SRC := sgp30.c
ifneq (,$(filter saul,$(USEMODULE)))
SRC += sgp30_saul.c
endif
include $(RIOTBASE)/Makefile.base

View File

@ -0,0 +1,6 @@
USEMODULE += checksum
USEMODULE += ztimer_usec
FEATURES_REQUIRED += periph_i2c
DEFAULT_MODULE += sgp30_strict

View File

@ -0,0 +1,4 @@
USEMODULE_INCLUDES_sgp30 := $(LAST_MAKEFILEDIR)/include
USEMODULE_INCLUDES += $(USEMODULE_INCLUDES_sgp30)
PSEUDOMODULES += sgp30_strict

View File

@ -0,0 +1,58 @@
/*
* Copyright (C) 2021 Inria
*
* 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_sgp30
* @{
*
* @file
* @brief Internal addresses, registers and constants
*
* @author Francisco Molina <francois-xavier.molina@inria.fr>
*/
#ifndef SGP30_CONSTANTS_H
#define SGP30_CONSTANTS_H
#include "timex.h"
#ifdef __cplusplus
extern "C" {
#endif
/**
* @brief SGP30 I2C address, only one is defined
*/
#define SGP30_I2C_ADDRESS (0x58)
/**
* @brief Minimum required feature set version for this driver
*/
#define SGP30_REQUIRED_FEATURE_SET (0x0020)
/**
* @brief Length of serial id
*/
#define SGP30_SERIAL_ID_LEN (6U)
/**
* @brief Initialization time
*/
#define SGP30_AIR_QUALITY_INIT_DELAY_US (15 * US_PER_SEC)
/**
* @brief Sampling for dynamic baseline compensation algorithm
*/
#define SGP30_RECOMMENDED_SAMPLING_PERIOD (1 * US_PER_SEC)
#ifdef __cplusplus
}
#endif
#endif /* SGP30_CONSTANTS_H */
/** @} */

View File

@ -0,0 +1,77 @@
/*
* Copyright (C) 2021 Inria
*
* 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_sgp30
*
* @{
* @file
* @brief Default configuration
*
* @author Francisco Molina <francois-xavier.molina@inria.fr>
*/
#ifndef SGP30_PARAMS_H
#define SGP30_PARAMS_H
#include "board.h"
#include "sgp30.h"
#include "sgp30_constants.h"
#include "saul_reg.h"
#ifdef __cplusplus
extern "C" {
#endif
/**
* @name Set default configuration parameters
* @{
*/
#ifndef SGP30_PARAM_I2C_DEV
#define SGP30_PARAM_I2C_DEV (I2C_DEV(0))
#endif
#ifndef SGP30_PARAMS
#define SGP30_PARAMS { .i2c_dev = SGP30_PARAM_I2C_DEV }
#endif
#ifndef SGP30_SAUL_INFO
#define SGP30_SAUL_INFO { .name = "sgp30" }
#endif
/**@}*/
/**
* @brief SGP30 configuration
*/
static const sgp30_params_t sgp30_params[] =
{
SGP30_PARAMS
};
/**
* @brief Define the number of configured sensors
*/
#define SGP30_NUM ARRAY_SIZE(sgp30_params)
/**
* @brief Additional meta information to keep in the SAUL registry
*/
static const saul_reg_info_t sgp30_saul_info[] =
{
SGP30_SAUL_INFO
};
/**
* @brief Number of saul info structs
*/
#define SGP30_INFO_NUM ARRAY_SIZE(sgp30_saul_info)
#ifdef __cplusplus
}
#endif
#endif /* SGP30_PARAMS_H */
/** @} */

359
drivers/sgp30/sgp30.c Normal file
View File

@ -0,0 +1,359 @@
/*
* Copyright (C) 2021 Inria
*
* 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_sgp30
* @{
*
* @file
* @brief Device driver implementation for the sensors
*
* @author Francisco Molina <francois-xavier.molina@inria.fr>
*
* @}
*/
#include <string.h>
#include "sgp30.h"
#include "sgp30_constants.h"
#include "sgp30_params.h"
#include "checksum/crc8.h"
#include "ztimer.h"
#define ENABLE_DEBUG 0
#include "debug.h"
/**
* @name Address pointer values for all SGP30 I2C commands
* @{
*/
typedef enum {
SGP30_CMD_INIT_AIR_QUALITY = 0x2003, /**< Start measurement mode */
SGP30_CMD_MEASURE_AIR_QUALITY = 0x2008, /**< Measure air quality values */
SGP30_CMD_GET_BASELINE = 0x2015, /**< Get baseline values */
SGP30_CMD_SET_BASELINE = 0x201e, /**< Set baseline values CMD */
SGP30_CMD_SET_HUMIDITY = 0x2061, /**< Set absolute humidity value
for compensation */
SGP30_CMD_MEASURE_TEST = 0x2032, /**< Perform on-chip self test */
SGP30_CMD_GET_FEATURE_SET_VERSION = 0x202f, /**< Get feature set version */
SGP30_CMD_MEASURE_RAW_SIGNALS = 0x2050, /**< Read raw H2 and Ethanol signals */
SGP30_CMD_READ_SERIAL = 0x3682, /**< Read serial number */
SGP30_CMD_SOFT_RESET = 0x0006, /**< Perform General Call reset */
} sgp30_cmd_t;
/** @} */
/**
* @name Max delays for SGP30 I2C commands completion
* @{
*/
#define SGP30_DELAY_INIT_AIR_QUALITY (10 * US_PER_MS)
#define SGP30_DELAY_MEASURE_AIR_QUALITY (12 * US_PER_MS)
#define SGP30_DELAY_GET_BASELINE (10 * US_PER_MS)
#define SGP30_DELAY_SET_BASELINE (10 * US_PER_MS)
#define SGP30_DELAY_SET_HUMIDITY (10 * US_PER_MS)
#define SGP30_DELAY_MEASURE_TEST (220 * US_PER_MS)
#define SGP30_DELAY_GET_FEATURE_SET_VERSION (2 * US_PER_MS)
#define SGP30_DELAY_MEASURE_RAW_SIGNALS (25 * US_PER_MS)
#define SGP30_DELAY_READ_SERIAL (500)
#define SGP30_DELAY_SOFT_RESET (60 * US_PER_MS)
/** @} */
/* Device power up time */
#define SGP30_POWER_UP_TIME (60 * US_PER_MS)
/* Polynomial used in crc check */
#define SGP30_CRC8_POLYNOMIAL 0x31
/* Seed used in crc check */
#define SGP30_CRC8_SEED 0xFF
static inline uint8_t _crc8(const void *buf, size_t len)
{
return crc8(buf, len, SGP30_CRC8_POLYNOMIAL, SGP30_CRC8_SEED);
}
void _set_uint16_and_crc(uint8_t *buf, uint16_t *val)
{
buf[0] = *val >> 8;
buf[1] = *val & 0xFF;
buf[2] = _crc8(buf, sizeof(uint16_t));
}
int _get_uint16_and_check_crc(uint8_t *buf, uint16_t *val)
{
if (_crc8(buf, sizeof(uint16_t)) == buf[2]) {
*val = (buf[0] << 8) + buf[1];
return 0;
}
return -EBADMSG;
}
static int _rx_tx_data(sgp30_t *dev, uint16_t cmd, uint8_t *data,
size_t len, uint32_t delay, bool do_read)
{
int res = 0;
if (i2c_acquire(dev->params.i2c_dev) != 0) {
DEBUG("[sgp30]: could not acquire I2C bus %d\n", dev->params.i2c_dev);
return -1;
}
uint8_t frame_cmd[sizeof(cmd) + len];
frame_cmd[0] = cmd >> 8;
frame_cmd[1] = cmd & 0xFF;
if (len == 0 || do_read) {
res = i2c_write_bytes(dev->params.i2c_dev, SGP30_I2C_ADDRESS,
&frame_cmd[0], sizeof(cmd), 0);
}
if (res == 0 && do_read) {
/* delay for command completion */
if (!irq_is_in()) {
ztimer_sleep(ZTIMER_USEC, delay);
}
else {
ztimer_spin(ZTIMER_USEC, delay);
}
res = i2c_read_bytes(dev->params.i2c_dev, SGP30_I2C_ADDRESS,
data, len, 0);
}
else if (res == 0 && !do_read) {
memcpy(&frame_cmd[2], data, len);
res = i2c_write_bytes(dev->params.i2c_dev, SGP30_I2C_ADDRESS,
frame_cmd, sizeof(cmd) + len, 0);
if (res) {
DEBUG_PUTS("[sgp30]: failed to write data");
}
}
i2c_release(dev->params.i2c_dev);
return res;
}
int _read_measurements(sgp30_t *dev, sgp30_data_t *data)
{
uint8_t frame[6];
if (_rx_tx_data(dev, SGP30_CMD_MEASURE_AIR_QUALITY, frame, sizeof(frame),
SGP30_DELAY_MEASURE_AIR_QUALITY, true)) {
return -EPROTO;
}
if (_get_uint16_and_check_crc(&frame[0], &data->eco2) ||
_get_uint16_and_check_crc(&frame[3], &data->tvoc)) {
return -EBADMSG;
}
return 0;
}
#ifdef MODULE_SGP30_STRICT
static void _read_cb(void *arg)
{
sgp30_t *dev = (sgp30_t *)arg;
if (!dev->ready) {
dev->ready = true;
}
_read_measurements(dev, &dev->_data);
dev->_data.timestamp = ztimer_now(ZTIMER_USEC);
ztimer_set(ZTIMER_USEC, &dev->_timer, SGP30_RECOMMENDED_SAMPLING_PERIOD);
}
#endif
int sgp30_start_air_quality(sgp30_t *dev)
{
int ret = _rx_tx_data(dev, SGP30_CMD_INIT_AIR_QUALITY, NULL, 0,
SGP30_DELAY_INIT_AIR_QUALITY, false);
#ifdef MODULE_SGP30_STRICT
if (ret == 0) {
ztimer_set(ZTIMER_USEC, &dev->_timer, SGP30_AIR_QUALITY_INIT_DELAY_US);
}
#endif
return ret ? -EPROTO : 0;
}
int sgp30_init(sgp30_t *dev, const sgp30_params_t *params)
{
assert(dev && params);
dev->params = *params;
#ifdef MODULE_SGP30_STRICT
dev->ready = false;
dev->_timer.callback = _read_cb;
dev->_timer.arg = dev;
#endif
/* delay while powering up */
ztimer_sleep(ZTIMER_USEC, SGP30_POWER_UP_TIME);
/* read future set */
uint16_t version;
sgp30_read_future_set(dev, &version);
if (version < SGP30_REQUIRED_FEATURE_SET) {
DEBUG("[sgp30]: wrong version number, %04x instead of %04x\n",
version, SGP30_REQUIRED_FEATURE_SET);
return -1;
}
/* read serial id */
uint8_t serial[SGP30_SERIAL_ID_LEN];
if (sgp30_read_serial_number(dev, serial, SGP30_SERIAL_ID_LEN)) {
DEBUG_PUTS("[sgp30]: could not read serial number");
return -1;
}
if (IS_ACTIVE(ENABLE_DEBUG)) {
DEBUG_PUTS("[sgp30]: serial");
for (uint8_t i = 0; i < SGP30_SERIAL_ID_LEN; i++) {
DEBUG("%02x ", serial[i]);
}
DEBUG_PUTS("\n");
}
/* start air quality measurement */
if (sgp30_start_air_quality(dev)) {
DEBUG_PUTS("[sgp30]: could not start air quality measurements ");
return -1;
}
return 0;
}
int sgp30_reset(sgp30_t *dev)
{
assert(dev);
int ret = _rx_tx_data(dev, SGP30_CMD_SOFT_RESET, NULL, 0, SGP30_DELAY_SOFT_RESET, false);
#ifdef MODULE_SGP30_STRICT
if (ret == 0) {
ztimer_remove(ZTIMER_USEC, &dev->_timer);
dev->ready = false;
}
#endif
return ret ? -EPROTO : 0;
}
int sgp30_read_serial_number(sgp30_t *dev, uint8_t *buf, size_t len)
{
assert(dev && buf && (len == SGP30_SERIAL_ID_LEN));
uint8_t frame[9];
if (_rx_tx_data(dev, SGP30_CMD_READ_SERIAL, (uint8_t *)frame, sizeof(frame),
SGP30_DELAY_READ_SERIAL, true)) {
DEBUG_PUTS("[sgp30]: fail read");
return -EPROTO;
}
/* the serial id is in big endian format */
uint16_t tmp[SGP30_SERIAL_ID_LEN/2];
if (_get_uint16_and_check_crc(&frame[0], &tmp[2]) ||
_get_uint16_and_check_crc(&frame[3], &tmp[1]) ||
_get_uint16_and_check_crc(&frame[6], &tmp[0])) {
DEBUG_PUTS("[sgp30]: wrong crc");
return -EBADMSG;
}
memcpy(buf, tmp, SGP30_SERIAL_ID_LEN);
return 0;
}
int sgp30_read_future_set(sgp30_t *dev, uint16_t *version)
{
uint8_t frame[3];
if (_rx_tx_data(dev, SGP30_CMD_GET_FEATURE_SET_VERSION, frame, sizeof(frame),
SGP30_DELAY_GET_FEATURE_SET_VERSION, true)) {
return -EPROTO;
}
if (_get_uint16_and_check_crc(&frame[0], version)) {
DEBUG_PUTS("[sgp30]: wrong crc");
return -EBADMSG;
}
return 0;
}
int sgp30_set_absolute_humidity(sgp30_t *dev, uint32_t a_humidity)
{
/* max value is (255g/m3+255/256g/m3), or 255999 mg/m3*/
if (a_humidity > 256000LU) {
return -1;
}
/* scale down to g/m^3 */
uint16_t humidity_scaled =
(uint16_t)(((uint64_t)a_humidity * 256 * 16777) >> 24);
uint8_t frame[3];
_set_uint16_and_crc(&frame[0], &humidity_scaled);
int ret = _rx_tx_data(dev, SGP30_CMD_SET_HUMIDITY, frame, sizeof(frame),
SGP30_DELAY_SET_HUMIDITY, false);
return ret ? -EPROTO : 0;
}
int sgp30_set_baseline(sgp30_t *dev, sgp30_data_t *data)
{
uint8_t frame[6];
_set_uint16_and_crc(&frame[0], &data->eco2);
_set_uint16_and_crc(&frame[3], &data->tvoc);
int ret = _rx_tx_data(dev, SGP30_CMD_SET_BASELINE, frame, sizeof(frame),
SGP30_DELAY_SET_BASELINE, false);
return ret ? -EPROTO : 0;
}
int sgp30_get_baseline(sgp30_t *dev, sgp30_data_t *data)
{
uint8_t frame[6];
if (_rx_tx_data(dev, SGP30_CMD_GET_BASELINE, frame, sizeof(frame),
SGP30_DELAY_GET_BASELINE, true)) {
return -EPROTO;
}
if (_get_uint16_and_check_crc(&frame[0], &data->eco2) ||
_get_uint16_and_check_crc(&frame[3], &data->tvoc)) {
return -EBADMSG;
}
return 0;
}
int sgp30_read_measurements(sgp30_t *dev, sgp30_data_t *data)
{
#ifdef MODULE_SGP30_STRICT
if (dev->ready) {
unsigned state = irq_disable();
memcpy(data, &dev->_data, sizeof(sgp30_data_t));
irq_restore(state);
return 0;
}
else {
return -EAGAIN;
}
return 0;
#else
return _read_measurements(dev, data);
#endif
}
int sgp30_read_raw_measurements(sgp30_t *dev, sgp30_raw_data_t *data)
{
uint8_t frame[6];
if (_rx_tx_data(dev, SGP30_CMD_MEASURE_RAW_SIGNALS, frame, sizeof(frame),
SGP30_DELAY_MEASURE_RAW_SIGNALS, true)) {
return -EPROTO;
}
if (_get_uint16_and_check_crc(&frame[0], &data->raw_ethanol) ||
_get_uint16_and_check_crc(&frame[3], &data->raw_h2)) {
DEBUG_PUTS("[sgp30]: wrong crc");
return -EBADMSG;
}
return 0;
}
#ifdef MODULE_SGP30_STRICT
bool sgp30_ready(sgp30_t *dev)
{
return dev->ready;
}
#endif

View File

@ -0,0 +1,65 @@
/*
* Copyright (C) 2021 Inria
*
* 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_sgp30
* @brief SAUL adaption for SGP30 sensor
* @{
*
* @file
*
* @author Francisco Molina <francois-xavier.molina@inria.fr>
*/
#include <errno.h>
#include <stdio.h>
#include <string.h>
#include <stdbool.h>
#include "phydat.h"
#include "saul.h"
#include "sgp30.h"
static int _read_tvoc(const void *dev, phydat_t *res)
{
sgp30_data_t data;
if (sgp30_read_measurements((sgp30_t *)dev, &data)) {
return -ECANCELED;
}
res->val[0] = data.tvoc;
res->unit = UNIT_PPB;
res->scale = 0;
return 1;
}
static int _read_eco2(const void *dev, phydat_t *res)
{
sgp30_data_t data;
if (sgp30_read_measurements((sgp30_t *)dev, &data)) {
return -ECANCELED;
}
res->val[0] = data.eco2;
res->unit = UNIT_PPM;
res->scale = 0;
return 1;
}
const saul_driver_t sgp30_saul_driver_eco2 = {
.read = _read_eco2,
.write = saul_notsup,
.type = SAUL_SENSE_CO2
};
const saul_driver_t sgp30_saul_driver_tvoc = {
.read = _read_tvoc,
.write = saul_notsup,
.type = SAUL_SENSE_TVOC
};