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

Merge pull request #13256 from MichelRottleuthner/pr_sps30

Add driver for SPS30 particulate matter sensor
This commit is contained in:
benpicco 2020-02-21 18:58:56 +01:00 committed by GitHub
commit aa00191384
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
16 changed files with 1202 additions and 35 deletions

View File

@ -596,6 +596,11 @@ ifneq (,$(filter soft_spi,$(USEMODULE)))
USEMODULE += xtimer
endif
ifneq (,$(filter sps30,$(USEMODULE)))
FEATURES_REQUIRED += periph_i2c
USEMODULE += checksum
endif
ifneq (,$(filter srf02,$(USEMODULE)))
FEATURES_REQUIRED += periph_i2c
USEMODULE += xtimer

View File

@ -308,6 +308,10 @@ ifneq (,$(filter soft_spi,$(USEMODULE)))
USEMODULE_INCLUDES += $(RIOTBASE)/drivers/soft_spi/include
endif
ifneq (,$(filter sps30,$(USEMODULE)))
USEMODULE_INCLUDES += $(RIOTBASE)/drivers/sps30/include
endif
ifneq (,$(filter srf04,$(USEMODULE)))
USEMODULE_INCLUDES += $(RIOTBASE)/drivers/srf04/include
endif

View File

@ -134,6 +134,7 @@ enum {
SAUL_SENSE_ID_VOLTAGE, /**< sensor: voltage */
SAUL_SENSE_ID_PH, /**< sensor: pH */
SAUL_SENSE_ID_POWER, /**< sensor: power */
SAUL_SENSE_ID_SIZE, /**< sensor: size */
SAUL_SENSE_NUMOF /**< Number of actuators supported */
/* Extend this list as needed, but keep SAUL_SENSE_ID_ANY the first and
* SAUL_SENSE_NUMOF the last entry
@ -147,40 +148,76 @@ enum {
* and the SAUL intra-category ID (six least significant bits).
*/
enum {
SAUL_ACT_ANY = SAUL_CAT_ACT | SAUL_ACT_ID_ANY, /**< any actuator - wildcard */
SAUL_ACT_LED_RGB = SAUL_CAT_ACT | SAUL_ACT_ID_LED_RGB, /**< actuator: RGB LED */
SAUL_ACT_SERVO = SAUL_CAT_ACT | SAUL_ACT_ID_SERVO, /**< actuator: servo motor */
SAUL_ACT_MOTOR = SAUL_CAT_ACT | SAUL_ACT_ID_MOTOR, /**< actuator: motor */
SAUL_ACT_SWITCH = SAUL_CAT_ACT | SAUL_ACT_ID_SWITCH, /**< actuator: simple on/off switch */
SAUL_ACT_DIMMER = SAUL_CAT_ACT | SAUL_ACT_ID_DIMMER, /**< actuator: dimmable switch */
SAUL_SENSE_ANY = SAUL_CAT_SENSE | SAUL_SENSE_ID_ANY, /**< any sensor - wildcard */
SAUL_SENSE_BTN = SAUL_CAT_SENSE | SAUL_SENSE_ID_BTN, /**< sensor: simple button */
SAUL_SENSE_TEMP = SAUL_CAT_SENSE | SAUL_SENSE_ID_TEMP, /**< sensor: temperature */
SAUL_SENSE_HUM = SAUL_CAT_SENSE | SAUL_SENSE_ID_HUM, /**< sensor: humidity */
SAUL_SENSE_LIGHT = SAUL_CAT_SENSE | SAUL_SENSE_ID_LIGHT, /**< sensor: light */
SAUL_SENSE_ACCEL = SAUL_CAT_SENSE | SAUL_SENSE_ID_ACCEL, /**< sensor: accelerometer */
SAUL_SENSE_MAG = SAUL_CAT_SENSE | SAUL_SENSE_ID_MAG, /**< sensor: magnetometer */
SAUL_SENSE_GYRO = SAUL_CAT_SENSE | SAUL_SENSE_ID_GYRO, /**< sensor: gyroscope */
SAUL_SENSE_COLOR = SAUL_CAT_SENSE | SAUL_SENSE_ID_COLOR, /**< sensor: (light) color */
SAUL_SENSE_PRESS = SAUL_CAT_SENSE | SAUL_SENSE_ID_PRESS, /**< sensor: pressure */
SAUL_SENSE_ANALOG = SAUL_CAT_SENSE | SAUL_SENSE_ID_ANALOG, /**< sensor: raw analog value */
SAUL_SENSE_UV = SAUL_CAT_SENSE | SAUL_SENSE_ID_UV, /**< sensor: UV index */
SAUL_SENSE_OBJTEMP = SAUL_CAT_SENSE | SAUL_SENSE_ID_OBJTEMP, /**< sensor: object temperature */
SAUL_SENSE_COUNT = SAUL_CAT_SENSE | SAUL_SENSE_ID_COUNT, /**< sensor: pulse counter */
SAUL_SENSE_DISTANCE = SAUL_CAT_SENSE | SAUL_SENSE_ID_DISTANCE, /**< sensor: distance */
SAUL_SENSE_CO2 = SAUL_CAT_SENSE | SAUL_SENSE_ID_CO2, /**< sensor: CO2 Gas */
SAUL_SENSE_TVOC = SAUL_CAT_SENSE | SAUL_SENSE_ID_TVOC, /**< sensor: TVOC Gas */
SAUL_SENSE_OCCUP = SAUL_CAT_SENSE | SAUL_SENSE_ID_OCCUP, /**< sensor: occupancy */
SAUL_SENSE_PROXIMITY = SAUL_CAT_SENSE | SAUL_SENSE_ID_PROXIMITY, /**< sensor: proximity */
SAUL_SENSE_RSSI = SAUL_CAT_SENSE | SAUL_SENSE_ID_RSSI, /**< sensor: RSSI */
SAUL_SENSE_CHARGE = SAUL_CAT_SENSE | SAUL_SENSE_ID_CHARGE, /**< sensor: coulomb counter */
SAUL_SENSE_CURRENT = SAUL_CAT_SENSE | SAUL_SENSE_ID_CURRENT, /**< sensor: ammeter */
SAUL_SENSE_PM = SAUL_CAT_SENSE | SAUL_SENSE_ID_PM, /**< sensor: particulate matter */
SAUL_SENSE_CAPACITANCE = SAUL_CAT_SENSE | SAUL_SENSE_ID_CAPACITANCE, /**< sensor: capacitance */
SAUL_SENSE_VOLTAGE = SAUL_CAT_SENSE | SAUL_SENSE_ID_VOLTAGE, /**< sensor: voltage */
SAUL_SENSE_PH = SAUL_CAT_SENSE | SAUL_SENSE_ID_PH, /**< sensor: pH */
SAUL_SENSE_POWER = SAUL_CAT_SENSE | SAUL_SENSE_ID_POWER, /**< sensor: power */
SAUL_CLASS_ANY = 0xff /**< any device - wildcard */
/** any actuator - wildcard */
SAUL_ACT_ANY = SAUL_CAT_ACT | SAUL_ACT_ID_ANY,
/** actuator: RGB LED */
SAUL_ACT_LED_RGB = SAUL_CAT_ACT | SAUL_ACT_ID_LED_RGB,
/** actuator: servo motor */
SAUL_ACT_SERVO = SAUL_CAT_ACT | SAUL_ACT_ID_SERVO,
/** actuator: motor */
SAUL_ACT_MOTOR = SAUL_CAT_ACT | SAUL_ACT_ID_MOTOR,
/** actuator: simple on/off switch */
SAUL_ACT_SWITCH = SAUL_CAT_ACT | SAUL_ACT_ID_SWITCH,
/** actuator: dimmable switch */
SAUL_ACT_DIMMER = SAUL_CAT_ACT | SAUL_ACT_ID_DIMMER,
/** any sensor - wildcard */
SAUL_SENSE_ANY = SAUL_CAT_SENSE | SAUL_SENSE_ID_ANY,
/** sensor: simple button */
SAUL_SENSE_BTN = SAUL_CAT_SENSE | SAUL_SENSE_ID_BTN,
/** sensor: temperature */
SAUL_SENSE_TEMP = SAUL_CAT_SENSE | SAUL_SENSE_ID_TEMP,
/** sensor: humidity */
SAUL_SENSE_HUM = SAUL_CAT_SENSE | SAUL_SENSE_ID_HUM,
/** sensor: light */
SAUL_SENSE_LIGHT = SAUL_CAT_SENSE | SAUL_SENSE_ID_LIGHT,
/** sensor: accelerometer */
SAUL_SENSE_ACCEL = SAUL_CAT_SENSE | SAUL_SENSE_ID_ACCEL,
/** sensor: magnetometer */
SAUL_SENSE_MAG = SAUL_CAT_SENSE | SAUL_SENSE_ID_MAG,
/** sensor: gyroscope */
SAUL_SENSE_GYRO = SAUL_CAT_SENSE | SAUL_SENSE_ID_GYRO,
/** sensor: (light) color */
SAUL_SENSE_COLOR = SAUL_CAT_SENSE | SAUL_SENSE_ID_COLOR,
/** sensor: pressure */
SAUL_SENSE_PRESS = SAUL_CAT_SENSE | SAUL_SENSE_ID_PRESS,
/** sensor: raw analog value */
SAUL_SENSE_ANALOG = SAUL_CAT_SENSE | SAUL_SENSE_ID_ANALOG,
/** sensor: UV index */
SAUL_SENSE_UV = SAUL_CAT_SENSE | SAUL_SENSE_ID_UV,
/** sensor: object temperature */
SAUL_SENSE_OBJTEMP = SAUL_CAT_SENSE | SAUL_SENSE_ID_OBJTEMP,
/** sensor: pulse counter */
SAUL_SENSE_COUNT = SAUL_CAT_SENSE | SAUL_SENSE_ID_COUNT,
/** sensor: distance */
SAUL_SENSE_DISTANCE = SAUL_CAT_SENSE | SAUL_SENSE_ID_DISTANCE,
/** sensor: CO2 Gas */
SAUL_SENSE_CO2 = SAUL_CAT_SENSE | SAUL_SENSE_ID_CO2,
/** sensor: TVOC Gas */
SAUL_SENSE_TVOC = SAUL_CAT_SENSE | SAUL_SENSE_ID_TVOC,
/** sensor: occupancy */
SAUL_SENSE_OCCUP = SAUL_CAT_SENSE | SAUL_SENSE_ID_OCCUP,
/** sensor: proximity */
SAUL_SENSE_PROXIMITY = SAUL_CAT_SENSE | SAUL_SENSE_ID_PROXIMITY,
/** sensor: RSSI */
SAUL_SENSE_RSSI = SAUL_CAT_SENSE | SAUL_SENSE_ID_RSSI,
/** sensor: coulomb counter */
SAUL_SENSE_CHARGE = SAUL_CAT_SENSE | SAUL_SENSE_ID_CHARGE,
/** sensor: ammeter */
SAUL_SENSE_CURRENT = SAUL_CAT_SENSE | SAUL_SENSE_ID_CURRENT,
/** sensor: particulate matter */
SAUL_SENSE_PM = SAUL_CAT_SENSE | SAUL_SENSE_ID_PM,
/** sensor: capacitance */
SAUL_SENSE_CAPACITANCE = SAUL_CAT_SENSE | SAUL_SENSE_ID_CAPACITANCE,
/** sensor: voltage */
SAUL_SENSE_VOLTAGE = SAUL_CAT_SENSE | SAUL_SENSE_ID_VOLTAGE,
/** sensor: pH */
SAUL_SENSE_PH = SAUL_CAT_SENSE | SAUL_SENSE_ID_PH,
/** sensor: power */
SAUL_SENSE_POWER = SAUL_CAT_SENSE | SAUL_SENSE_ID_POWER,
/** sensor: size */
SAUL_SENSE_SIZE = SAUL_CAT_SENSE | SAUL_SENSE_ID_SIZE,
/** any device - wildcard */
SAUL_CLASS_ANY = 0xff
/* extend this list as needed... */
};

287
drivers/include/sps30.h Normal file
View File

@ -0,0 +1,287 @@
/*
* Copyright (C) 2020 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_sps30 Sensirion SPS30 Particulate Matter Sensor
* @ingroup drivers_sensors
* @ingroup drivers_saul
*
* About
* =====
*
* This driver provides an interface for the Sensirion SPS30 Sensor.
* The Datasheet can be found [here](https://1n.pm/oqluM).
* For now only I2C mode is supported.
* I2C speed must be set to standard mode (100 kbit/s)
*
* Wiring
* ======
*
* In ASCII-land the connector side of the sensor would look like this:
*
* ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
* +------------------------------------------------------------------------+
* | ____________________ |
* | __| |__ |
* | |__ (1) (2) (3) (4) (5) __| |
* | | | |
* | |____________________| |
* | |
* +------------[#]------------[#]------------[#]------------[#]------------+
* ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
*
* The numbers refer to following pin names:
*
* | Pin Nr. | SPS30 Signal Name | Connect to | Notes |
* |---------|-------------------|------------|-------------------------------|
* | Pin 1 | VDD | 5 V | should be within +-10 % |
* | Pin 2 | I2C_SDA / UART_RX | SDA* | config by SPS30_PARAM_I2C_DEV |
* | Pin 3 | I2C_SCL / UART_TR | SCL* | config by SPS30_PARAM_I2C_DEV |
* | Pin 4 | SEL | GND | |
* | Pin 5 | GND | GND | |
*
* *The SCL and SDA pins of the SPS30 sensor are open drain so they must be
* pulled high. Consider that internal pull resistors might be too weak.
* So using external 10 kOhm resistors is recommended for that.
*
* @{
*
* @file
* @brief Driver for the Sensirion SPS30 Particulate Matter Sensor
*
* @author Michel Rottleuthner <michel.rottleuthner@haw-hamburg.de>
*/
#ifndef SPS30_H
#define SPS30_H
#include <stdbool.h>
#include "periph/gpio.h"
#include "periph/i2c.h"
#ifdef __cplusplus
extern "C" {
#endif
/**
* @brief SPS30 device parameters
*/
typedef struct {
i2c_t i2c_dev; /**< I2C dev the sensor is connected to */
} sps30_params_t;
/**
* @brief SPS30 device instance
*/
typedef struct {
sps30_params_t p; /**< parameters of the sensor device */
} sps30_t;
/**
* @brief Set of measured particulate matter values
*
* @warning Do not change the member order, as it will break the code that
* populates the values in #sps30_read_measurement()
*
*/
typedef struct {
float mc_pm1; /**< Mass concentration of PM 1.0 [µg/m^3] */
float mc_pm2_5; /**< Mass concentration of PM 2.5 [µg/m^3] */
float mc_pm4; /**< Mass concentration of PM 4.0 [µg/m^3] */
float mc_pm10; /**< Mass concentration of PM 10 [µg/m^3] */
float nc_pm0_5; /**< Number concentration of PM 0.5 [µg/m^3] */
float nc_pm1; /**< Number concentration of PM 1.0 [µg/m^3] */
float nc_pm2_5; /**< Number concentration of PM 2.5 [µg/m^3] */
float nc_pm4; /**< Number concentration of PM 4.0 [µg/m^3] */
float nc_pm10; /**< Number concentration of PM 10 [µg/m^3] */
float ps; /**< Typical particle size [µm] */
} sps30_data_t;
/**
* @brief SPS30 error codes (returned as negative values)
*/
typedef enum {
SPS30_OK = 0, /**< Everything went fine */
SPS30_CRC_ERROR, /**< The CRC check of received data failed */
SPS30_I2C_ERROR /**< Some I2C operation failed */
} sps30_error_code_t;
/**
* @brief Seconds the fan cleaning process takes in seconds
*/
#define SPS30_FAN_CLEAN_S (10U)
/**
* @brief Length of serial and article code string
*/
#define SPS30_SER_ART_LEN (32U)
/**
* @brief Default fan auto-clean interval in seconds (1 week)
*/
#define SPS30_DEFAULT_ACI_S (604800UL)
/**
* @brief Maximum number of automatic retries on communication errors
*
* @details If no delays happen between individual requests to the sensor, it
* may happen that the sensor is not yet ready to serve data.
* Handling this within the driver simplifies application code by
* omitting sleep handling or retries there.
* This value may be overwritten to 0 if more fine-grained feedback
* is required or even increased if the device is connected over
* suboptimal wiring.
*
*/
#ifndef SPS30_ERROR_RETRY
#define SPS30_ERROR_RETRY (500U)
#endif
/**
* @brief Initialize SPS30 sensor driver.
* On success the measurement mode will be active after calling.
*
* @param[out] dev Pointer to an SPS30 device handle
* @param[in] params Parameters for device initialization
*
* @return #SPS30_OK on success, negative #sps30_error_code_t on error
*/
int sps30_init(sps30_t *dev, const sps30_params_t *params);
/**
* @brief Enable the measurement action.
*
* @details Starting the measurement activates the fan of the sensor and
* increases the power consumption from below 8 mA to an average
* of 60 mA. When the fan is starting up the consumption can reach
* up to 80 mA for around 200 ms.
* The measurement mode will stay active until either the power is
* turned off, a stop is requested (@ref sps30_stop_measurement),
* or the device is reset (#sps30_reset).
*
* @param[in] dev Pointer to an SPS30 device handle
*
* @return #SPS30_OK on success, negative #sps30_error_code_t on error
*/
int sps30_start_measurement(const sps30_t *dev);
/**
* @brief Stops the measurement action.
*
* @details Stopping the measurement sets the device back to idle mode.
*
* @param[in] dev Pointer to an SPS30 device handle
*
* @return #SPS30_OK on success, negative #sps30_error_code_t on error
*/
int sps30_stop_measurement(const sps30_t *dev);
/**
* @brief Ask the device if a measurement is ready for reading.
*
* @param[in] dev Pointer to an SPS30 device handle
* @param[out] error Pre-allocated memory to return #sps30_error_code_t
* or NULL if not interested
*
* @return true if a new measurement is available
* @return false if no new measurement is available
*/
bool sps30_data_ready(const sps30_t *dev, int *error);
/**
* @brief Read a set of particulate matter measurements.
*
* @param[in] dev Pointer to an SPS30 device handle
* @param[out] data Pre-allocated memory to return measurements
*
* @return #SPS30_OK on success, negative #sps30_error_code_t on error
*/
int sps30_read_measurement(const sps30_t *dev, sps30_data_t *data);
/**
* @brief Read the fan auto-clean interval.
*
* @details The default value is 604800 seconds (1 week).
* See also @ref sps30_start_fan_clean.
*
* @param[in] dev Pointer to an SPS30 device handle
* @param[out] seconds Pre-allocated memory for returning the interval,
* 0 stands for disabled auto-clean
*
* @return #SPS30_OK on success, negative #sps30_error_code_t on error
*/
int sps30_read_ac_interval(const sps30_t *dev, uint32_t *seconds);
/**
* @brief Write the fan auto-clean interval.
*
* @details The new value will be effective immediately after writing but
* reading the updated value is only possible after resetting the
* sensor.
* This setting is persistent across resets and powerdowns. But if
* the sensor is powered off, the active time counter starts from
* zero again. If this is expected to happen, a fan cleaning cycle
* should be triggered manually at least once a week.
* See also @ref sps30_start_fan_clean.
*
* @param[in] dev Pointer to an SPS30 device handle
* @param[out] seconds The new interval in seconds, 0 for disable
*
* @return #SPS30_OK on success, negative #sps30_error_code_t on error
*/
int sps30_write_ac_interval(const sps30_t *dev, uint32_t seconds);
/**
* @brief Run a fan cleaning cycle manually.
*
* @details This will spin up the fan to maximum speed to blow out dust for
* for 10 seconds. No new measurement values are available until
* the cleaning process is finished.
*
* @param[in] dev Pointer to an SPS30 device handle
*
* @return #SPS30_OK on success, negative #sps30_error_code_t on error
*/
int sps30_start_fan_clean(const sps30_t *dev);
/**
* @brief Read the article code from the sensor as string.
*
* @param[in] dev Pointer to an SPS30 device handle
* @param[out] str Pre-allocated memory for returning the article code
* @param[in] len Length of the \p str buffer, must be 32
*
* @return #SPS30_OK on success, negative #sps30_error_code_t on error
*/
int sps30_read_article_code(const sps30_t *dev, char *str, size_t len);
/**
* @brief Read the serial number from the sensor as string.
*
* @param[in] dev Pointer to an SPS30 device handle
* @param[out] str Pre-allocated memory for returning the serial number
* @param[in] len Length of the \p str buffer, must be 32
*
* @return #SPS30_OK on success, negative #sps30_error_code_t on error
*/
int sps30_read_serial_number(const sps30_t *dev, char *str, size_t len);
/**
* @brief Reset the sensor.
*
* @param[in] dev Pointer to an SPS30 device handle
*
* @return #SPS30_OK on success, negative #sps30_error_code_t on error
*/
int sps30_reset(const sps30_t *dev);
#ifdef __cplusplus
}
#endif
#endif /* SPS30_H */
/** @} */

View File

@ -62,6 +62,7 @@ static const char *sensors[] = {
[SAUL_SENSE_ID_VOLTAGE] = "SENSE_VOLTAGE",
[SAUL_SENSE_ID_PH] = "SENSE_PH",
[SAUL_SENSE_ID_POWER] = "SENSE_POWER",
[SAUL_SENSE_ID_SIZE] = "SENSE_SIZE",
};
const char *saul_class_to_str(const uint8_t class_id)

1
drivers/sps30/Makefile Normal file
View File

@ -0,0 +1 @@
include $(RIOTBASE)/Makefile.base

View File

@ -0,0 +1,74 @@
/*
* Copyright (C) 2020 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_sps30
* @brief Default configuration for Sensirion SPS30 sensors devices
* @author Michel Rottleuthner <michel.rottleuthner@haw-hamburg.de>
* @file
* @{
*/
#ifndef SPS30_PARAMS_H
#define SPS30_PARAMS_H
#include "board.h"
#include "sps30.h"
#include "saul_reg.h"
#ifdef __cplusplus
extern "C" {
#endif
/**
* @name SPS30 default configuration parameters
* @{
*/
#ifndef SPS30_PARAM_I2C_DEV
#define SPS30_PARAM_I2C_DEV (I2C_DEV(0))
#endif
#ifndef SPS30_PARAMS
#define SPS30_PARAMS { .i2c_dev = SPS30_PARAM_I2C_DEV }
#endif
#ifndef SPS30_SAUL_INFO
#define SPS30_SAUL_INFO { .name = "sps30" }
#endif
/**@}*/
/**
* @brief SPS30 configuration
*/
static const sps30_params_t sps30_params[] =
{
SPS30_PARAMS
};
/**
* @brief Define the number of configured sensors
*/
#define SPS30_NUM ARRAY_SIZE(sps30_params)
/**
* @brief Additional meta information to keep in the SAUL registry
*/
static const saul_reg_info_t sps30_saul_info[] =
{
SPS30_SAUL_INFO
};
/**
* @brief Number of saul info structs
*/
#define SPS30_INFO_NUM ARRAY_SIZE(sps30_saul_info)
#ifdef __cplusplus
}
#endif
#endif /* SPS30_PARAMS_H */
/** @} */

285
drivers/sps30/sps30.c Normal file
View File

@ -0,0 +1,285 @@
/*
* Copyright (C) 2020 Michel Rottleuthner
*
* 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_sps30
* @brief Device driver for the Sensirion SPS30 particulate matter sensor
* @author Michel Rottleuthner <michel.rottleuthner@haw-hamburg.de>
* @file
*/
#define LOG_LEVEL LOG_DEBUG
#include "log.h"
#include <errno.h>
#include <string.h>
#include "checksum/crc8.h"
#include "sps30.h"
#include "xtimer.h"
#include "byteorder.h"
#include "kernel_defines.h"
/**
* @name SPS30 literal definitions
* @{
*/
#define SPS30_I2C_ADDR (0x69) /**< Fixed I2C address for the Sensor */
#define SPS30_CRC_POLY (0x31) /**< Polynomial for the CRC calculation */
#define SPS30_CRC_INIT (0xFF) /**< Init value for the CRC calculation */
#define SPS30_MESAURE_MODE (0x03) /**< Fixed mode byte for start cmd */
#define SPS30_DUMMY_BYTE (0x00) /**< Fixed dummy byte for unused bytes */
#define SPS30_PTR_LEN (2) /**< Pointer address length in bytes */
/** @} */
/**
* @name Address pointer values for all SPS30 I2C commands
* @{
*/
typedef enum {
SPS30_CMD_START_MEASURE = 0x0010, /**< Start measurement mode */
SPS30_CMD_STOP_MEASURE = 0x0104, /**< Stop measurement mode */
SPS30_CMD_RD_DATA_READY = 0x0202, /**< Read data-ready flag */
SPS30_CMD_RD_MEASUREMENTS = 0x0300, /**< Read measured values */
SPS30_CMD_RW_AUTOCLEAN = 0x8004, /**< Read/write autoclean interval */
SPS30_CMD_START_FAN_CLEAN = 0x5607, /**< Start fan cleaning */
SPS30_CMD_RD_ARTICLE = 0xD025, /**< Read article code */
SPS30_CMD_RD_SERIAL = 0xD033, /**< Read serial number */
SPS30_CMD_RESET = 0xD304, /**< Reset */
} sps30_cmd_t;
/** @} */
/**
* @brief Combine payload and CRC into an SDS30 I2C data frame.
*
* @details The CRC for `data` is calculated and written to `crcd_data`
* together with the payload itself.
* The format of `data` must be just the pure payload:
* { data[0], data[1], data[2], ..., data[n]}
* The format of `crcd_data` same as it shall be sent to the SPS30.
* It consists of payload byte-pairs followed by a single CRC byte:
* { data[0], data[1], csum[0],.., data[n-1], data[n], csum[n-1] }
*
* @param[in] data Source buffer containing just the raw payload
* @param[in] len Size of the 'data' buffer
* @param[out] crcd_data Destination buffer for combined payload and CRCs
*
* @pre sizeof(crcd_data) must be equal to 1.5 * len
*
*/
static inline void _cpy_add_crc(uint8_t *data, size_t len, uint8_t *crcd_data)
{
for (size_t elem = 0; elem < len / 2; elem++) {
int idx = (elem << 1);
crcd_data[idx + elem] = data[idx];
crcd_data[idx + elem + 1] = data[idx + 1];
crcd_data[idx + elem + 2] = crc8(&data[idx], 2, SPS30_CRC_POLY,
SPS30_CRC_INIT);
}
}
/**
* @brief Check the CRC of an SDS30 I2C data frame.
*
* @details The CRC contained in the `crcd_data` is checked and the payload is
* copied to `data`.
* The format of `data` will be just the pure payload:
* { data[0], data[1], data[2], ..., data[n]}
* The format of `crcd_data` is same as it is read from the SPS30.
* It consists of payload byte-pairs followed by a single CRC byte:
* { data[0], data[1], csum[0],.., data[n-1], data[n], csum[n-1] }
*
* @pre sizeof(crcd_data) must be equal to 1.5 * len
*
* @param[out] data Destination buffer for just the raw payload
* @param[in] len Size of the 'data' buffer
* @param[in] crcd_data Source buffer containing combined payload and CRCs
*
* @return true if all CRCs are valid
* @return false if at least one CRC is invalid
*/
static inline bool _cpy_check_crc(uint8_t *data, size_t len, uint8_t *crcd_data)
{
for (size_t elem = 0; elem < len / 2; elem++) {
int idx = (elem << 1);
data[idx] = crcd_data[idx + elem];
data[idx + 1] = crcd_data[idx + elem + 1];
if (crc8(&data[idx], 2, SPS30_CRC_POLY, SPS30_CRC_INIT) !=
(crcd_data[idx + elem + 2])) {
return false;
}
}
return true;
}
/**
* @brief Communicates with an SPS30 device by reading or writing data.
*
* @details This performs all three data transfer types supported by SPS30.
* (1) `Set Pointer`: writes a 16 bit pointer address to the device
* (2) `Set Pointer & Read Data`: (1) followed by separate data-read
* (3) `Set Pointer & Write Data`: (1) combined with a data-write
*
* @param[in] dev Pointer to SPS30 device handle
* @param[in] ptr_addr 16 bit pointer address used as command
* @param[in/out] data Pre-allocated memory pointing to either the data
* that will be sent to the device or to memory that
* will hold the response. For type (1) transfers
* this parameter will be ignored.
* @param[in] len Length of `data` buffer, set to 0 for type (1)
* @param[in] read set to true for reading or false for writing
*
* @return SPS30_OK if everything went fine
* @return -SPS30_CRC_ERROR if the CRC check failed
* @return -SPS30_I2C_ERROR if the I2C communication failed
*/
static int _rx_tx_data(const sps30_t *dev, uint16_t ptr_addr,
uint8_t *data, size_t len, bool read)
{
int res = 0;
unsigned retr = SPS30_ERROR_RETRY;
if (i2c_acquire(dev->p.i2c_dev) != 0) {
LOG_ERROR("could not acquire I2C bus %d\n", dev->p.i2c_dev);
return -SPS30_I2C_ERROR;
}
do {
size_t addr_data_crc_len = SPS30_PTR_LEN + len + len / 2;
uint8_t frame_data[addr_data_crc_len];
frame_data[0] = ptr_addr >> 8;
frame_data[1] = ptr_addr & 0xFF;
/* Both transfer types, `Set Pointer` and `Set Pointer & Read Data`
require writing a pointer address to the device in a separate write
transaction */
if (len == 0 || read) {
res = i2c_write_bytes(dev->p.i2c_dev, SPS30_I2C_ADDR,
&frame_data[0], SPS30_PTR_LEN, 0);
}
if (res == 0 && read) {
/* The `Set Pointer & Read Data` transfer type requires a separate
read transaction to actually read the data */
res = i2c_read_bytes(dev->p.i2c_dev, SPS30_I2C_ADDR,
&frame_data[SPS30_PTR_LEN],
addr_data_crc_len - SPS30_PTR_LEN, 0);
if (!_cpy_check_crc(data, len, &frame_data[SPS30_PTR_LEN])) {
res = -SPS30_CRC_ERROR;
}
} else {
/* For the `Set Pointer & Write Data` transfer type the full frame
is transmitted as one single chunk */
_cpy_add_crc(data, len, &frame_data[SPS30_PTR_LEN]);
res = i2c_write_bytes(dev->p.i2c_dev, SPS30_I2C_ADDR,
&frame_data[0], addr_data_crc_len, 0);
}
} while (res != 0 && retr--);
i2c_release(dev->p.i2c_dev);
return res == 0 ? SPS30_OK : -SPS30_I2C_ERROR;
}
int sps30_init(sps30_t *dev, const sps30_params_t *params)
{
assert(dev && params);
dev->p = *params;
return sps30_start_measurement(dev);
}
int sps30_start_measurement(const sps30_t *dev)
{
assert(dev);
uint8_t data[] = {SPS30_MESAURE_MODE, SPS30_DUMMY_BYTE};
return _rx_tx_data(dev, SPS30_CMD_START_MEASURE, (uint8_t*)data,
sizeof(data), false);
}
int sps30_stop_measurement(const sps30_t *dev)
{
assert(dev);
return _rx_tx_data(dev, SPS30_CMD_STOP_MEASURE, NULL, 0, false);
}
bool sps30_data_ready(const sps30_t *dev, int *error)
{
assert(dev);
uint8_t data[2];
int res = _rx_tx_data(dev, SPS30_CMD_RD_DATA_READY, data, sizeof(data),
true);
if (*error) {
*error = res;
}
return (res == SPS30_OK) && data[1];
}
int sps30_read_measurement(const sps30_t *dev, sps30_data_t *data)
{
/* This compile time check is needed to ensure the below method used for
endianness conversion will work as expected */
BUILD_BUG_ON(sizeof(sps30_data_t) != (sizeof(float) * 10));
assert(dev && data);
/* The target buffer is also used for storing the raw data temporarily */
int res = _rx_tx_data(dev, SPS30_CMD_RD_MEASUREMENTS, (uint8_t*)data,
sizeof(sps30_data_t), true);
/* The sps30_data_t consists only of floats, so it is safe to treat it as
an array of 32 bit values for swapping to correct endianness */
uint32_t *values = (uint32_t*)data;
/* swap to the endianness of this platform */
for (unsigned i = 0; i < (sizeof(sps30_data_t) / sizeof(uint32_t)); i++) {
values[i] = ntohl(values[i]);
}
return res;
}
int sps30_read_ac_interval(const sps30_t *dev, uint32_t *seconds) {
assert(dev);
int res = _rx_tx_data(dev, SPS30_CMD_RW_AUTOCLEAN, (uint8_t*)seconds,
sizeof(uint32_t), true);
*seconds = ntohl(*seconds);
return res;
}
int sps30_write_ac_interval(const sps30_t *dev, uint32_t seconds)
{
assert(dev);
seconds = htonl(seconds);
int res = _rx_tx_data(dev, SPS30_CMD_RW_AUTOCLEAN, (uint8_t*)&seconds,
sizeof(uint32_t), false);
return res;
}
int sps30_start_fan_clean(const sps30_t *dev)
{
assert(dev);
return _rx_tx_data(dev, SPS30_CMD_START_FAN_CLEAN, NULL, 0, false);
}
int sps30_read_article_code(const sps30_t *dev, char *str, size_t len)
{
assert(dev && str && (len == SPS30_SER_ART_LEN));
return _rx_tx_data(dev, SPS30_CMD_RD_ARTICLE, (uint8_t*)str, len, true);
}
int sps30_read_serial_number(const sps30_t *dev, char *str, size_t len)
{
assert(dev && str && (len == SPS30_SER_ART_LEN));
return _rx_tx_data(dev, SPS30_CMD_RD_SERIAL, (uint8_t*)str, len, true);
}
int sps30_reset(const sps30_t *dev)
{
assert(dev);
return _rx_tx_data(dev, SPS30_CMD_RESET, NULL, 0, false);
}

185
drivers/sps30/sps30_saul.c Normal file
View File

@ -0,0 +1,185 @@
/*
* Copyright (C) 2020 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_sps30
* @brief SAUL adaption for Sensirion SPS30 sensor
* @author Michel Rottleuthner <michel.rottleuthner@haw-hamburg.de>
* @file
*/
#include <errno.h>
#include <stdio.h>
#include <string.h>
#include "phydat.h"
#include "saul.h"
#include "sps30.h"
#include "sps30_params.h"
/**
* @brief Mapping of sensor values to logical SAUL instances
*/
#define SPS30_SAUL_VAL_IDX_MC_PM_1_2P5_4 (0)
#define SPS30_SAUL_VAL_IDX_MC_PM_10 (1)
#define SPS30_SAUL_VAL_IDX_NC_PM_0P5_1_2P5 (2)
#define SPS30_SAUL_VAL_IDX_NC_PM_4_10 (3)
#define SPS30_SAUL_VAL_IDX_PS (4)
/**
* @brief Number of logical saul devices per physical sensor
*/
#define SPS30_SAUL_DEV_NUM (SPS30_SAUL_VAL_IDX_PS + 1)
extern sps30_t sps30_devs[SPS30_NUM];
/* contains a temporary copy of all sensor readings to allow returning all
* values as one consistent group over multiple read calls */
static sps30_data_t _readings[SPS30_NUM];
static bool _valid[SPS30_NUM][SPS30_SAUL_DEV_NUM] = { {false} };
static unsigned _dev2index (const sps30_t *dev)
{
for (unsigned i = 0; i < SPS30_NUM; i++) {
if (dev == &sps30_devs[i]) {
return i;
}
}
return SPS30_NUM;
}
static void _float_fit(float *src, phydat_t *data, size_t dim, uint32_t mul)
{
int32_t i32[dim];
for (unsigned i = 0; i < dim; i++) {
i32[i] = src[i] * mul;
}
data->scale = 0;
phydat_fit(data, &i32[0], dim);
}
static int read(const void *dev, phydat_t *data, unsigned int val_idx)
{
/* find the device index */
unsigned dev_idx = _dev2index((sps30_t*)dev);
if (dev_idx == SPS30_NUM) {
return -ECANCELED;
}
/* if data isn't valid form the last reading anymore, read again */
if (!_valid[dev_idx][val_idx]) {
int error_state = SPS30_OK;
while (!sps30_data_ready(&sps30_devs[dev_idx], &error_state)) {
if (error_state != SPS30_OK) {
return -ECANCELED;
}
}
if (!(sps30_read_measurement(&sps30_devs[dev_idx],
&_readings[dev_idx]) == SPS30_OK)) {
/* failure on read may corrupt _readings -> mark invalid */
for (unsigned i = 0; i < SPS30_SAUL_DEV_NUM; i++) {
_valid[dev_idx][i] = false;
}
return -ECANCELED;
}
for (unsigned i = 0; i < SPS30_SAUL_DEV_NUM; i++) {
_valid[dev_idx][i] = true;
}
}
/* mark read values as invalid */
_valid[dev_idx][val_idx] = false;
switch (val_idx) {
case SPS30_SAUL_VAL_IDX_MC_PM_1_2P5_4:
_float_fit(&_readings[dev_idx].mc_pm1, data, 3, 1000);
data->unit = UNIT_GPM3;
data->scale -= 9; /* fitted [ng/m^3] but unit is [g/m^3] */
return 3;
case SPS30_SAUL_VAL_IDX_MC_PM_10:
_float_fit(&_readings[dev_idx].mc_pm10, data, 1, 1000);
data->unit = UNIT_GPM3;
data->scale = -9; /* fitted [ng/m^3] but unit is [g/m^3] */
return 1;
case SPS30_SAUL_VAL_IDX_NC_PM_0P5_1_2P5:
_float_fit(&_readings[dev_idx].nc_pm0_5, data, 3, 1000);
data->unit = UNIT_CPM3;
data->scale = 3; /* fitted [#/dm^3] but unit is [#/m^3] */
return 3;
case SPS30_SAUL_VAL_IDX_NC_PM_4_10:
_float_fit(&_readings[dev_idx].nc_pm4, data, 2, 1000);
data->unit = UNIT_CPM3;
data->scale = 3; /* fitted [#/dm^3] but unit is [#/m^3] */
return 2;
case SPS30_SAUL_VAL_IDX_PS:
_float_fit(&_readings[dev_idx].ps, data, 1, 1000);
data->unit = UNIT_M;
data->scale -= 9; /* fitted [nm] but unit is [m] */
return 1;
}
return -ECANCELED;
}
static int read_mc_pm_1_2p5_4(const void *dev, phydat_t *data)
{
return read(dev, data, SPS30_SAUL_VAL_IDX_MC_PM_1_2P5_4);
}
static int read_mc_pm_10(const void *dev, phydat_t *data)
{
return read(dev, data, SPS30_SAUL_VAL_IDX_MC_PM_10);
}
static int read_nc_pm_0p5_1_2p5(const void *dev, phydat_t *data)
{
return read(dev, data, SPS30_SAUL_VAL_IDX_NC_PM_0P5_1_2P5);
}
static int read_nc_pm_4_10(const void *dev, phydat_t *data)
{
return read(dev, data, SPS30_SAUL_VAL_IDX_NC_PM_4_10);
}
static int read_ps(const void *dev, phydat_t *data)
{
return read(dev, data, SPS30_SAUL_VAL_IDX_PS);
}
const saul_driver_t sps30_saul_driver_mc_pm_1_2p5_4 = {
.read = read_mc_pm_1_2p5_4,
.write = saul_notsup,
.type = SAUL_SENSE_PM
};
const saul_driver_t sps30_saul_driver_mc_pm_10 = {
.read = read_mc_pm_10,
.write = saul_notsup,
.type = SAUL_SENSE_PM
};
const saul_driver_t sps30_saul_driver_nc_pm_0p5_1_2p5 = {
.read = read_nc_pm_0p5_1_2p5,
.write = saul_notsup,
.type = SAUL_SENSE_COUNT
};
const saul_driver_t sps30_saul_driver_nc_pm_4_10 = {
.read = read_nc_pm_4_10,
.write = saul_notsup,
.type = SAUL_SENSE_COUNT
};
const saul_driver_t sps30_saul_driver_ps = {
.read = read_ps,
.write = saul_notsup,
.type = SAUL_SENSE_SIZE
};

View File

@ -563,6 +563,10 @@ void auto_init(void)
extern void auto_init_si70xx(void);
auto_init_si70xx();
#endif
#ifdef MODULE_SPS30
extern void auto_init_sps30(void);
auto_init_sps30();
#endif
#ifdef MODULE_TCS37727
extern void auto_init_tcs37727(void);
auto_init_tcs37727();

View File

@ -0,0 +1,79 @@
/*
* Copyright (C) 2020 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
* @brief Auto initialization of Sensirion SPS30 device driver
* @author Michel Rottleuthner <michel.rottleuthner@haw-hamburg.de>
* @file
*/
#ifdef MODULE_SPS30
#include "assert.h"
#include "log.h"
#include "saul_reg.h"
#include "sps30.h"
#include "sps30_params.h"
/**
* @brief Number of logical saul devices per physical sensor
*/
#define SPS30_SAUL_DEV_NUM (5)
/**
* @brief Allocation of memory for device descriptors
*/
sps30_t sps30_devs[SPS30_NUM];
/**
* @brief Memory for the SAUL registry entries
*/
static saul_reg_t saul_entries[SPS30_NUM * SPS30_SAUL_DEV_NUM];
/**
* @name Reference the driver structs.
* @{
*/
extern const saul_driver_t sps30_saul_driver_mc_pm_1_2p5_4;
extern const saul_driver_t sps30_saul_driver_mc_pm_10;
extern const saul_driver_t sps30_saul_driver_nc_pm_0p5_1_2p5;
extern const saul_driver_t sps30_saul_driver_nc_pm_4_10;
extern const saul_driver_t sps30_saul_driver_ps;
/** @} */
void auto_init_sps30(void)
{
assert(SPS30_INFO_NUM == SPS30_NUM);
for (unsigned i = 0; i < SPS30_NUM; i++) {
LOG_DEBUG("[auto_init_saul] initializing sps30 #%u\n", i);
if (sps30_init(&sps30_devs[i],
&sps30_params[i]) != SPS30_OK) {
LOG_ERROR("[auto_init_saul] error initializing sps30 #%u\n", i);
continue;
}
saul_entries[i * 5].driver = &sps30_saul_driver_mc_pm_1_2p5_4;
saul_entries[i * 5 + 1].driver = &sps30_saul_driver_mc_pm_10;
saul_entries[i * 5 + 2].driver = &sps30_saul_driver_nc_pm_0p5_1_2p5;
saul_entries[i * 5 + 3].driver = &sps30_saul_driver_nc_pm_4_10;
saul_entries[i * 5 + 4].driver = &sps30_saul_driver_ps;
/* the physical device is the same for all logical SAUL instances */
for (unsigned x = 0; x < SPS30_SAUL_DEV_NUM; x++) {
saul_entries[i * 5 + x].dev = &(sps30_devs[i]);
saul_entries[i * 5 + x].name = sps30_saul_info[i].name;
saul_reg_add(&saul_entries[i * 5 + x]);
}
}
}
#else
typedef int dont_be_pedantic;
#endif /* MODULE_SPS30 */

View File

@ -117,7 +117,9 @@ enum {
UNIT_TIME, /**< the three dimensions contain sec, min, and hours */
UNIT_DATE, /**< the 3 dimensions contain days, months and years */
/* mass concentration */
UNIT_GPM3 /**< grams per cubic meters */
UNIT_GPM3, /**< grams per cubic meter */
/* number concentration */
UNIT_CPM3 /**< count per cubic meter */
/* extend this list as needed */
};

View File

@ -106,6 +106,8 @@ const char *phydat_unit_to_str(uint8_t unit)
case UNIT_GPM3: return "g/m^3";
case UNIT_F: return "F";
case UNIT_PH: return "pH";
case UNIT_CPM3: return "#/m^3";
default: return "";
}
}

View File

@ -0,0 +1,9 @@
include ../Makefile.tests_common
USEMODULE += sps30
USEMODULE += xtimer
CFLAGS+=-DPARAM_SPS30_I2C=I2C_DEV\(0\)
CFLAGS+=-DI2C0_SPEED=I2C_SPEED_NORMAL
include $(RIOTBASE)/Makefile.include

View File

@ -0,0 +1,17 @@
# Test Application for the Sensirion SPS30 Particulate Matter Sensor
## About
This is a simple test application for the SPS30 driver.
## Expected result
If everything is working as expected the following message should be printed at
the end `sps30 test: [SUCCESS]`.
## Details
The test application will execute every function supported by the sps30 driver
and check if it returns successfully.
Some steps in the test execution take a few seconds, but the overall test
should finish within one minute.
Shortly after the start you should hear the fan of the sensor spinning up for a
manual fan cleaning cycle. After that, proper operation of the auto-clean
update is verified and 10 measurements are printed to the console.

175
tests/driver_sps30/main.c Normal file
View File

@ -0,0 +1,175 @@
/*
* Copyright (C) 2020 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 Sensirion SPS30 device driver
* @author Michel Rottleuthner <michel.rottleuthner@haw-hamburg.de>
* @}
*/
#include <stdio.h>
#include <string.h>
#include "xtimer.h"
#include "sps30.h"
#include "sps30_params.h"
#define TEST_START_DELAY_S (2U)
#define SENSOR_RESET_DELAY_S (10U)
#define SENSOR_STARTUP_DELAY_S (10U)
#define POLL_FOR_READY_S (1U)
#define NUM_OF_MEASUREMENTS (10U)
#define TYPE_MC_STR "MC PM"
#define TYPE_NC_STR "NC PM"
#define TYPE_TPS_STR "TPS"
#define MC_UNIT_STR "[µg/m³]"
#define NC_UNIT_STR "[#/cm³]"
#define TPS_UNIT_STR "[µm]"
/* prints the result of an operation and returns true if an error occurred */
static bool _print_error(const char *msg, sps30_error_code_t ec)
{
printf("sps30_%s: [%s]\n", msg, (ec == SPS30_OK) ? "OK" :
(ec == SPS30_CRC_ERROR ? "CRC_ERROR"
: "I2C_ERROR"));
return ec != SPS30_OK;
}
static void _print_val_row(char *typ1, char *typ2, char *unit, float val)
{
printf("| %-5s %4s:%3"PRIu32".%03"PRIu32" %-8s |\n", typ1, typ2,
(uint32_t)val, ((uint32_t)((val + 0.0005) * 1000)) % 1000, unit);
}
int main(void)
{
sps30_t dev;
sps30_data_t data;
sps30_error_code_t ec;
char str[SPS30_SER_ART_LEN];
uint32_t ci = 0; /* clean interval */
uint32_t nci = 0; /* new clean interval */
bool error = false;
unsigned cnt = NUM_OF_MEASUREMENTS;
xtimer_sleep(TEST_START_DELAY_S);
puts("SPS30 test application\n");
ec = sps30_init(&dev, &sps30_params[0]);
error |= _print_error("init", ec);
ec = sps30_read_article_code(&dev, str, sizeof(str));
if (ec == SPS30_OK) {
printf("Article code: %s\n", str);
} else {
error |= _print_error("read_article_code", ec);
}
ec = sps30_read_serial_number(&dev, str, sizeof(str));
if (ec == SPS30_OK) {
printf("Serial: %s\n", str);
} else {
error |= _print_error("read_serial_number", ec);
}
ec = sps30_start_fan_clean(&dev);
error |= _print_error("start_fan_clean", ec);
/* wait long enough for the fan clean to be done and the fan to settle */
xtimer_sleep(2 * SPS30_FAN_CLEAN_S);
/* read the currently set value from the sensor */
ec = sps30_read_ac_interval(&dev, &ci);
error |= _print_error("read_ac_interval", ec);
nci = ci + 1;
ec = sps30_write_ac_interval(&dev, nci);
error |= _print_error("write_ac_interval", ec);
/* resetting the sensor so the updated value can be read */
ec = sps30_reset(&dev);
error |= _print_error("reset", ec);
xtimer_sleep(SENSOR_RESET_DELAY_S);
/* start the sensor again again... */
ec = sps30_start_measurement(&dev);
error |= _print_error("start_measurement", ec);
xtimer_sleep(SENSOR_STARTUP_DELAY_S);
ec = sps30_read_ac_interval(&dev, &ci);
error |= _print_error("read_ac_interval", ec);
if (ci != nci) {
printf("ERROR: the auto-clean interval was not updated properly! (%"
PRIu32" != %"PRIu32")\n", ci, nci);
}
/* restore the default auto-clean cycle */
ec = sps30_write_ac_interval(&dev, SPS30_DEFAULT_ACI_S);
error |= _print_error("write_ac_interval", ec);
while (cnt) {
int err_code;
bool ready = sps30_data_ready(&dev, &err_code);
if (!ready) {
if (err_code != SPS30_OK) {
error |= _print_error("data_ready", err_code);
cnt--; /* if errors happen, stop after NUM_OF_MEASUREMENTS */
}
/* try again after some time */
xtimer_sleep(POLL_FOR_READY_S);
continue;
}
ec = sps30_read_measurement(&dev, &data);
if (ec == SPS30_OK) {
puts("\nv==== SPS30 measurements ====v");
_print_val_row(TYPE_MC_STR, "1.0", MC_UNIT_STR, data.mc_pm1);
_print_val_row(TYPE_MC_STR, "2.5", MC_UNIT_STR, data.mc_pm2_5);
_print_val_row(TYPE_MC_STR, "4.0", MC_UNIT_STR, data.mc_pm4);
_print_val_row(TYPE_MC_STR, "10.0", MC_UNIT_STR, data.mc_pm10);
_print_val_row(TYPE_NC_STR, "0.5", NC_UNIT_STR, data.nc_pm0_5);
_print_val_row(TYPE_NC_STR, "1.0", NC_UNIT_STR, data.nc_pm1);
_print_val_row(TYPE_NC_STR, "2.5", NC_UNIT_STR, data.nc_pm2_5);
_print_val_row(TYPE_NC_STR, "4.0", NC_UNIT_STR, data.nc_pm4);
_print_val_row(TYPE_NC_STR, "10.0", NC_UNIT_STR, data.nc_pm10);
_print_val_row(TYPE_TPS_STR, "", TPS_UNIT_STR, data.ps);
puts("+----------------------------+");
puts("| MC: Mass Concentration |");
puts("| NC: Number Concentration |");
puts("| TPS: Typical Particle Size |");
printf("^========= %2u / %2u ==========^\n\n",
NUM_OF_MEASUREMENTS - cnt + 1, NUM_OF_MEASUREMENTS);
} else {
error |= _print_error("read_measurement", ec);
}
cnt--;
}
ec = sps30_stop_measurement(&dev);
error |= _print_error("stop_measurement", ec);
if (error) {
puts("sps30 test: [FAILED]");
}
else {
puts("sps30 test: [SUCCESS]");
}
return 0;
}