diff --git a/dev/pms5003/README.pms5003 b/dev/pms5003/README.pms5003 new file mode 100644 index 000000000..ae1d21367 --- /dev/null +++ b/dev/pms5003/README.pms5003 @@ -0,0 +1,21 @@ +Contiki implementation for Plantower PMS 5003 series +dust sensors. + +The PMS sensors support serial communication through UART and +I2C. This implementation supports both modes, and they can be +individually turned on/off through config options. Both can be +enabled at the same time. + +In UART mode, the operation is asynchronous; the sensor periodically +outputs a frame of data, which is assembled by the sensor driver +through a UART callback function. + +In I2C mode, the I2C bus is probed and if the sensor is found, +the frame is read. This is synchronous, triggered by a configurable +timer. + +The sensor is duty-cycled through the SET input signal. The duty-cycling +intervals are configurable. + +This implementation has been tested against the PMS 5003i (I2C) and +PMS 3003 (UART) sensors. diff --git a/dev/pms5003/pms5003-sensor.c b/dev/pms5003/pms5003-sensor.c new file mode 100644 index 000000000..118381140 --- /dev/null +++ b/dev/pms5003/pms5003-sensor.c @@ -0,0 +1,118 @@ +/* + * Copyright (c) 2017, Peter Sjodin, KTH Royal Institute of Technology + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * 3. Neither the name of the Institute nor the names of its contributors + * may be used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE INSTITUTE AND CONTRIBUTORS ``AS IS'' AND + * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE INSTITUTE OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY + * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF + * SUCH DAMAGE. + * + * This file is part of the Contiki operating system. + * + * Author : Peter Sjodin, KTH Royal Institute of Technology + * Created : 2017-04-21 + */ + +#include + +#include "contiki.h" +#include "lib/sensors.h" +#include "pms5003.h" +#include "pms5003-sensor.h" + +const struct sensors_sensor pms5003_sensor; + +enum { + ON, OFF +}; +static uint8_t state = OFF; + +/*---------------------------------------------------------------------------*/ +PROCESS(pms5003_sensor_process, "PMS5003 sensor process"); +/*---------------------------------------------------------------------------*/ +static int +value(int type) +{ + switch(type) { + case PMS5003_SENSOR_PM1: + return pms5003_pm1(); + case PMS5003_SENSOR_PM2_5: + return pms5003_pm2_5(); + case PMS5003_SENSOR_PM10: + return pms5003_pm10(); + case PMS5003_SENSOR_PM1_ATM: + return pms5003_pm1_atm(); + case PMS5003_SENSOR_PM2_5_ATM: + return pms5003_pm2_5_atm(); + case PMS5003_SENSOR_PM10_ATM: + return pms5003_pm10_atm(); + case PMS5003_SENSOR_TIMESTAMP: + return pms5003_timestamp(); + } + return 0; +} +/*---------------------------------------------------------------------------*/ +static int +status(int type) +{ + switch(type) { + case SENSORS_ACTIVE: + case SENSORS_READY: + return state == ON; + } + return 0; +} +/*---------------------------------------------------------------------------*/ +static int +configure(int type, int c) +{ + switch(type) { + case SENSORS_ACTIVE: + if(c) { + if(!status(SENSORS_ACTIVE)) { + pms5003_init(); + process_start(&pms5003_sensor_process, NULL); + state = ON; + } + } else { + pms5003_off(); + state = OFF; + } + } + return 0; +} +/*---------------------------------------------------------------------------*/ +SENSORS_SENSOR(pms5003_sensor, "pms5003", + value, configure, status); +/*---------------------------------------------------------------------------*/ +PROCESS_THREAD(pms5003_sensor_process, ev, data) +{ + + PROCESS_BEGIN(); + while(1) { + do { + PROCESS_WAIT_EVENT(); + } while(ev != pms5003_event); + sensors_changed(&pms5003_sensor); + } + PROCESS_END(); +} diff --git a/dev/pms5003/pms5003-sensor.h b/dev/pms5003/pms5003-sensor.h new file mode 100644 index 000000000..033d356f3 --- /dev/null +++ b/dev/pms5003/pms5003-sensor.h @@ -0,0 +1,52 @@ +/* + * Copyright (c) 2017, Peter Sjodin, KTH Royal Institute of Technology + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * 3. Neither the name of the Institute nor the names of its contributors + * may be used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE INSTITUTE AND CONTRIBUTORS ``AS IS'' AND + * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE INSTITUTE OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY + * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF + * SUCH DAMAGE. + * + * + * + * ----------------------------------------------------------------- + * + * Author : Peter Sjodin, KTH Royal Institute of Technology + * Created : 2017-04-21 + */ + +#ifndef PMS5003_SENSOR_H_ +#define PMS5003_SENSOR_H_ + +#include "lib/sensors.h" + +extern const struct sensors_sensor pms5003_sensor; + +#define PMS5003_SENSOR_PM1 0 +#define PMS5003_SENSOR_PM2_5 1 +#define PMS5003_SENSOR_PM10 2 +#define PMS5003_SENSOR_PM1_ATM 3 +#define PMS5003_SENSOR_PM2_5_ATM 4 +#define PMS5003_SENSOR_PM10_ATM 5 +#define PMS5003_SENSOR_TIMESTAMP 6 + +#endif /* PMS5003_SENSOR_H_ */ diff --git a/dev/pms5003/pms5003.c b/dev/pms5003/pms5003.c new file mode 100644 index 000000000..2f1f35d64 --- /dev/null +++ b/dev/pms5003/pms5003.c @@ -0,0 +1,403 @@ +/* + * Copyright (c) 2017, Peter Sjodin, KTH Royal Institute of Technology + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * 3. Neither the name of the Institute nor the names of its contributors + * may be used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE INSTITUTE AND CONTRIBUTORS ``AS IS'' AND + * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE INSTITUTE OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY + * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF + * SUCH DAMAGE. + * + * This file is part of the Contiki operating system. + * + * Author : Peter Sjodin, KTH Royal Institute of Technology + * Created : 2017-04-21 + */ + +/* + * \file + * Driver for Planttower PMSX003 dust sensors + */ + +#include "contiki.h" +#include "sys/etimer.h" +#include "sys/pt.h" +#include +#include "i2c.h" +#include "watchdog.h" +#include "dev/leds.h" +#include "dev/rs232.h" +#include "dev/pms5003-arch.h" +#include "pms5003.h" + +#include "lib/ringbuf.h" + +/* + * Definitions for frames from PMSX003 sensors + */ + +/* Two preamble bytes */ +#define PRE1 0x42 +#define PRE2 0x4d +/* Valid values for body length field */ +#define PMSMINBODYLEN 20 +#define PMSMAXBODYLEN 28 +/* Buffer holds frame body plus preamble (two bytes) + * and length field (two bytes) */ +#define PMSBUFFER (PMSMAXBODYLEN + 4) + +/* Frame assembly statistics */ +static uint32_t invalid_frames, valid_frames; + +/* Sensor configured on? */ +static uint8_t configured_on = 0; +/* When sensor entered current power save mode, in clock_seconds()*/ +static unsigned long when_mode; + +/* Last readings of sensor data */ +static uint16_t PM1, PM2_5, PM10; +static uint16_t PM1_ATM, PM2_5_ATM, PM10_ATM; +/* Time when last sensor data was read, in clock_seconds()*/ +static unsigned long timestamp = 0; + +#if PMS_SERIAL_UART +#if (PMS_BUFSIZE & (PMS_BUFSIZE - 1)) != 0 +#error PMS5003_CONF_UART_BUFSIZE must be a power of two (i.e., 1, 2, 4, 8, 16, 32, 64, ...). +#endif /* PMS_BUFSIZE */ + +/* Ring buffer for storing input from uart */ +static struct ringbuf rxbuf; +static uint8_t rxbuf_data[PMS_BUFSIZE]; + +static int uart_input_byte(unsigned char); +#endif /* PMS_SERIAL_UART */ + +/*---------------------------------------------------------------------------*/ +#if PMS_SERIAL_UART +PROCESS(pms5003_uart_process, "PMS5003/UART dust sensor process"); +#endif /* PMS_SERIAL_UART */ +PROCESS(pms5003_timer_process, "PMS5003 periodic dust sensor process"); +/*---------------------------------------------------------------------------*/ +/** + * Initialize. Create event, and start timer-driven process. + * If UART enabled, also install UART callback function and + * start PMS frame assembly process. + */ +void +pms5003_init() +{ + pms5003_event = process_alloc_event(); + process_start(&pms5003_timer_process, NULL); + +#if PMS_SERIAL_UART + ringbuf_init(&rxbuf, rxbuf_data, sizeof(rxbuf_data)); + rs232_set_input(PMS_UART_PORT, uart_input_byte); + process_start(&pms5003_uart_process, NULL); +#endif /* PMS_SERIAL_UART */ + + configured_on = 1; + +#ifdef DEBUG + printf("PMS5003: UART %d, I2C %d, sample period %d, startup interval %d\n", + PMS_SERIAL_UART, PMS_SERIAL_I2C, PMS_SAMPLE_PERIOD, PMS_STARTUP_INTERVAL); +#endif /* DEBUG */ +} +/*---------------------------------------------------------------------------*/ +/** + * Sensor API for PMS5003 + */ + +void +pms5003_off() +{ + pms5003_set_standby_mode(STANDBY_MODE_ON); + configured_on = 0; +} +uint16_t +pms5003_pm1() +{ + return PM1; +} +uint16_t +pms5003_pm2_5() +{ + return PM2_5; +} +uint16_t +pms5003_pm10() +{ + return PM10; +} +uint16_t +pms5003_pm1_atm() +{ + return PM1_ATM; +} +uint16_t +pms5003_pm2_5_atm() +{ + return PM2_5_ATM; +} +uint16_t +pms5003_pm10_atm() +{ + return PM10_ATM; +} +uint32_t +pms5003_timestamp() +{ + return timestamp; +} +uint32_t +pms5003_valid_frames() +{ + return valid_frames; +} +uint32_t +pms5003_invalid_frames() +{ + return invalid_frames; +} +/*---------------------------------------------------------------------------*/ +/** + * Validate frame by checking preamble, length field and checksum. + * Return 0 if invalid frame, otherwise 1. + */ +static int +check_pmsframe(uint8_t *buf) +{ + int sum, pmssum; + int i; + int len; + + if(buf[0] != PRE1 || buf[1] != PRE2) { + return 0; + } + /* len is length of frame not including preamble and checksum */ + len = (buf[2] << 8) + buf[3]; + if(len < PMSMINBODYLEN || len > PMSMAXBODYLEN) { + return 0; + } + /* Sum data bytewise, including preamble but excluding checksum */ + sum = 0; + for(i = 0; i < len + 2; i++) { + sum += buf[i]; + } + /* Compare with received checksum last in frame*/ + pmssum = (buf[len + 2] << 8) + buf[len + 3]; + return pmssum == sum; +} +/*---------------------------------------------------------------------------*/ +static void +printpm() +{ + printf("PMS frames: valid %lu, invalid %lu\n", + valid_frames, invalid_frames); + printf("PM1 = %04d, PM2.5 = %04d, PM10 = %04d\n", PM1, PM2_5, PM10); + printf("PM1_ATM = %04d, PM2.5_ATM = %04d, PM10_ATM = %04d\n", + PM1_ATM, PM2_5_ATM, PM10_ATM); +} +/*---------------------------------------------------------------------------*/ +/** + * Frame received from PMS sensor. Validate and update sensor data. + * Return 1 if valid frame, otherwise 0 + */ +static int +pmsframe(uint8_t *buf) +{ + + if(check_pmsframe(buf)) { + timestamp = clock_seconds(); + valid_frames++; + /* Update sensor readings */ + PM1 = (buf[4] << 8) | buf[5]; + PM2_5 = (buf[6] << 8) | buf[7]; + PM10 = (buf[8] << 8) | buf[9]; + PM1_ATM = (buf[10] << 8) | buf[11]; + PM2_5_ATM = (buf[12] << 8) | buf[13]; + PM10_ATM = (buf[14] << 8) | buf[15]; +#ifdef DEBUG + printpm(); +#endif /* DEBUG */ + return 1; + } else { + invalid_frames++; +#ifdef DEBUG + printpm(); +#endif /* DEBUG */ + return 0; + } +} +/*---------------------------------------------------------------------------*/ +#if PMS_SERIAL_UART +/** + * State machine for assembling PMS5003 frames + * from uart. Use protothread for state machine. + */ +static +PT_THREAD(pms5003_uart_fsm_pt(struct pt *pt, uint8_t data)) { + static uint8_t buf[PMSBUFFER], *bufp; + static int remain; + static unsigned long mode_secs; + + PT_BEGIN(pt); + bufp = buf; + if(data != PRE1) { + PT_RESTART(pt); + } + *bufp++ = data; + PT_YIELD(pt); + if(data != PRE2) { + PT_RESTART(pt); + } + *bufp++ = data; + /* Found preamble. Then get length (two bytes) */ + PT_YIELD(pt); + *bufp++ = data; + PT_YIELD(pt); + *bufp++ = data; + + /* Get body length -- no of bytes that remain */ + remain = (buf[2] << 8) + buf[3]; + if(remain < PMSMINBODYLEN || remain > PMSMAXBODYLEN) { + invalid_frames++; + } else { + while(remain--) { + PT_YIELD(pt); + *bufp++ = data; + } + /* We have a frame! */ + mode_secs = clock_seconds() - when_mode; + /* Frames received while sensor is starting up are ignored */ + if((pms5003_get_standby_mode() == STANDBY_MODE_OFF) && + (mode_secs >= PMS_STARTUP_INTERVAL)) { + /* Check frame and update sensor readings */ + if(pmsframe(buf)) { + /* Tell other processes there is new data */ + (void)process_post(PROCESS_BROADCAST, pms5003_event, NULL); + /* Enter standby mode */ + pms5003_set_standby_mode(STANDBY_MODE_ON); + when_mode = clock_seconds(); + } + } + } + PT_RESTART(pt); + + PT_END(pt); +} +/*---------------------------------------------------------------------------*/ +/** + * UART callback function. + */ +static int +uart_input_byte(unsigned char c) +{ + + /* Add char to buffer. Unlike serial line input, ignore buffer overflow */ + (void)ringbuf_put(&rxbuf, c); + /* Wake up consumer process */ + process_poll(&pms5003_uart_process); + return 1; +} +/*---------------------------------------------------------------------------*/ +static struct pt uart_pt; +/** + * Consumer thread for UART process. Pick up data from input buffer and + * dispatch to FSM for frame assembly. + */ +PROCESS_THREAD(pms5003_uart_process, ev, data) +{ + + PROCESS_BEGIN(); + PT_INIT(&uart_pt); + while(1) { + int c = ringbuf_get(&rxbuf); + if(c == -1) { + PROCESS_YIELD_UNTIL(ev == PROCESS_EVENT_POLL); + } else if(configured_on) { + pms5003_uart_fsm_pt(&uart_pt, c); + } + } + PROCESS_END(); +} +#endif /* PMS_SERIAL_UART */ +/*---------------------------------------------------------------------------*/ +/** + * Timer thread: duty-cycle sensor. Toggle between idle and active mode. + * For I2C, also read data when it is due. + */ +PROCESS_THREAD(pms5003_timer_process, ev, data) +{ + static struct etimer pmstimer; + static unsigned long mode_secs; + static uint8_t standbymode; + + PROCESS_BEGIN(); + etimer_set(&pmstimer, CLOCK_SECOND * PMS_PROCESS_PERIOD); + pms5003_set_standby_mode(STANDBY_MODE_ON); + when_mode = clock_seconds(); + pms5003_event = process_alloc_event(); + + /* Main loop */ + while(1) { + PROCESS_YIELD(); + if(!configured_on) { + continue; + } + + if((ev == PROCESS_EVENT_TIMER) && (data == &pmstimer)) { + mode_secs = clock_seconds() - when_mode; + standbymode = pms5003_get_standby_mode(); + if(standbymode == STANDBY_MODE_OFF) { +#if PMS_SERIAL_I2C + static uint8_t buf[PMSBUFFER]; + /* Read data over I2C if it is time */ + if(mode_secs >= PMS_STARTUP_INTERVAL) { + if(pms5003_i2c_probe()) { + leds_on(LEDS_RED); + i2c_read_mem(I2C_PMS5003_ADDR, 0, buf, PMSBUFFER); + /* Check frame and update sensor readings */ + if(pmsframe(buf)) { + /* Tell other processes there is new data */ + if(process_post(PROCESS_BROADCAST, pms5003_event, NULL) == PROCESS_ERR_OK) { + PROCESS_WAIT_EVENT_UNTIL(ev == pms5003_event); + } + pms5003_set_standby_mode(STANDBY_MODE_ON); + when_mode = clock_seconds(); + } + } + } +#else + /* Do nothing -- UART process puts sensor in standby */ + ; +#endif /* PMS_SERIAL_I2C */ + } else if(standbymode == STANDBY_MODE_ON) { + if(mode_secs >= (PMS_SAMPLE_PERIOD - PMS_STARTUP_INTERVAL)) { + pms5003_set_standby_mode(STANDBY_MODE_OFF); + when_mode = clock_seconds(); + } + } + etimer_reset(&pmstimer); + } + } + PROCESS_END(); +} +/*---------------------------------------------------------------------------*/ diff --git a/dev/pms5003/pms5003.h b/dev/pms5003/pms5003.h new file mode 100644 index 000000000..f2b3255cb --- /dev/null +++ b/dev/pms5003/pms5003.h @@ -0,0 +1,106 @@ +/* + * Copyright (c) 2017, Peter Sjodin, KTH Royal Institute of Technology + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * 3. Neither the name of the Institute nor the names of its contributors + * may be used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE INSTITUTE AND CONTRIBUTORS ``AS IS'' AND + * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE INSTITUTE OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY + * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF + * SUCH DAMAGE. + * + * This file is part of the Contiki operating system. + * + * + * Author : Peter Sjodin, KTH Royal Institute of Technology + * Created : 2017-04-21 + */ + +#ifndef PMS5003_H +#define PMS5003_H + +/* How often sensor process runs (secs) -- defines resolution + * of warmup time and sample period + */ +#ifdef PMS5003_CONF_PROCESS_PERIOD +#define PMS_PROCESS_PERIOD PMS5003_CONF_PROCESS_PERIOD +#else +#define PMS_PROCESS_PERIOD 5 +#endif /* PMS5003_CONF_PROCESS_PERIOD */ + +/* How often sensor data is collected (secs) */ +#ifdef PMS5003_CONF_SAMPLE_PERIOD +#define PMS_SAMPLE_PERIOD PMS5003_CONF_SAMPLE_PERIOD +#else +#define PMS_SAMPLE_PERIOD 30 +#endif /* PMS5003_CONF_SAMPLE_PERIOD */ + +/* Warmup time before sensor data can be read (secs) */ +#ifdef PMS5003_CONF_STARTUP_INTERVAL +#define PMS_STARTUP_INTERVAL PMS5003_CONF_STARTUP_INTERVAL +#else +#define PMS_STARTUP_INTERVAL 10 +#endif /* PMS5003_STARTUP_INTERVAL */ + +/* Use I2C interface? */ +#ifdef PMS5003_CONF_SERIAL_I2C +#define PMS_SERIAL_I2C PMS5003_CONF_SERIAL_I2C +#else +#define PMS_SERIAL_I2C 1 +#endif /* PMS_CONF_SERIAL_I2C */ + +/* Use UART interface? */ +#ifdef PMS5003_CONF_SERIAL_UART +#define PMS_SERIAL_UART PMS5003_CONF_SERIAL_UART +#else +#define PMS_SERIAL_UART 1 +#endif /* PMS_CONF_SERIAL_UART */ + +#if PMS_SERIAL_UART +/* What buffer size to use */ +#ifdef PMS5003_CONF_UART_BUFSIZE +#define PMS_BUFSIZE PMS5003_CONF_UART_BUFSIZE +#else /* PMS5003_CONF_UART_BUFSIZE */ +#define PMS_BUFSIZE 128 +#endif /* PMS5003_CONF_UART_BUFSIZE */ + +/* What UART port to use */ +#ifdef PMS5003_CONF_UART_PORT +#define PMS_UART_PORT PMS5003_CONF_UART_PORT +#else +#define PMS_UART_PORT RS232_PORT_0 +#endif /* PMS_CONF_UART_RS232_PORT */ +#endif /* PMS_SERIAL_UART */ + +/* Event to signal presence of new sensor data */ +process_event_t pms5003_event; + +void pms5003_init(); +void pms5003_off(); + +uint16_t pms5003_pm1(); +uint16_t pms5003_pm2_5(); +uint16_t pms5003_pm10(); +uint16_t pms5003_pm1_atm(); +uint16_t pms5003_pm2_5_atm(); +uint16_t pms5003_pm10_atm(); +uint32_t pms5003_timestamp(); + +#endif /* PMS5003_H */ diff --git a/platform/avr-rss2/dev/i2c.c b/platform/avr-rss2/dev/i2c.c index ee0d29125..9c3a5493e 100644 --- a/platform/avr-rss2/dev/i2c.c +++ b/platform/avr-rss2/dev/i2c.c @@ -230,5 +230,11 @@ i2c_probe(void) probed |= I2C_BME280; print_delim(p++, "BME280", del); } + watchdog_periodic(); + if(!i2c_start(I2C_PMS5003_ADDR)) { + i2c_stop(); + probed |= I2C_PMS5003; + print_delim(p++, "PMS5003", del); + } return probed; } diff --git a/platform/avr-rss2/dev/i2c.h b/platform/avr-rss2/dev/i2c.h index e380cda52..ed5c90f5d 100644 --- a/platform/avr-rss2/dev/i2c.h +++ b/platform/avr-rss2/dev/i2c.h @@ -41,12 +41,14 @@ #define I2C_AT24MAC_ADDR 0xB0 /* EUI64 ADDR */ #define I2C_SHT2X_ADDR (0x40 << 1) /* SHT2X ADDR */ #define I2C_BME280_ADDR (0x77 << 1) /* Alternative 0x76 */ +#define I2C_PMS5003_ADDR (0x12 << 1) /* PM sensor */ /* Here we define a enumration for devices */ #define I2C_AT24MAC (1<<0) #define I2C_SHT2X (1<<1) #define I2C_CO2SA (1<<2) /* Sense-Air CO2 */ #define I2C_BME280 (1<<3) +#define I2C_PMS5003 (1<<4) #define I2C_READ 1 #define I2C_WRITE 0 diff --git a/platform/avr-rss2/dev/pms5003-arch.c b/platform/avr-rss2/dev/pms5003-arch.c new file mode 100644 index 000000000..119a58858 --- /dev/null +++ b/platform/avr-rss2/dev/pms5003-arch.c @@ -0,0 +1,80 @@ +/* + * Copyright (c) 2017, Peter Sjodin, KTH Royal Institute of Technology + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * 3. Neither the name of the Institute nor the names of its contributors + * may be used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE INSTITUTE AND CONTRIBUTORS ``AS IS'' AND + * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE INSTITUTE OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY + * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF + * SUCH DAMAGE. + * + * This file is part of the Contiki operating system. + * + * + * Author : Peter Sjodin psj@kth.se + * Created : 2017-01-06 + */ + +#include "contiki.h" +#include "i2c.h" +#include "watchdog.h" +#include "dev/pms5003/pms5003.h" +#include "pms5003-arch.h" + +static uint8_t standbymode; +/*---------------------------------------------------------------------------*/ +/* + * Configure low power standby mode (PIN3, SET) + */ +void +pms5003_set_standby_mode(uint8_t mode) { + SET_PMS_DDR |= (1 << PMS_SET); + if (mode == STANDBY_MODE_OFF) + SET_PMS_PORT |= (1 << PMS_SET); + else if (mode == STANDBY_MODE_ON) + SET_PMS_PORT &= ~(1 << PMS_SET); + standbymode = mode; +} +/*---------------------------------------------------------------------------*/ +/* + * Return current standby mode + */ +uint8_t +pms5003_get_standby_mode(void) { + return standbymode; +} +/*---------------------------------------------------------------------------*/ +/* + * Probe I2C bus for PMS5003 device + */ +uint8_t +pms5003_i2c_probe(void) { + watchdog_periodic(); + if(!i2c_start(I2C_PMS5003_ADDR)) { + i2c_stop(); + i2c_probed |= I2C_PMS5003; + return 1; + + } + i2c_probed &= ~I2C_PMS5003; + return 0; +} +/*---------------------------------------------------------------------------*/ diff --git a/platform/avr-rss2/dev/pms5003-arch.h b/platform/avr-rss2/dev/pms5003-arch.h new file mode 100644 index 000000000..76142cdc3 --- /dev/null +++ b/platform/avr-rss2/dev/pms5003-arch.h @@ -0,0 +1,56 @@ +/* + * Copyright (c) 2017, Peter Sjodin, KTH Royal Institute of Technology + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * 3. Neither the name of the Institute nor the names of its contributors + * may be used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE INSTITUTE AND CONTRIBUTORS ``AS IS'' AND + * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE INSTITUTE OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY + * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF + * SUCH DAMAGE. + * + * This file is part of the Contiki operating system. + * + * + * Author : Peter Sjodin psj@kth.se + * Created : 2017-01-06 + */ + +#ifndef PMS5003_ARCH_H +#define PMS5003_ARCH_H + +/** + * \file + * Architecture-specific definitions for the Plantower PMS X003 dust sensors for avr-rss2 + */ + +/* AVR configuration for controlling dust sensor */ +#define SET_PMS_DDR DDRB /* Data Direction Register: Port B */ +#define SET_PMS_PORT PORTB /* Serial Peripheral Interface */ +#define PMS_SET 2 /* PD1: OW2_PIN, Chip Select */ + +/* Duty cycle mode -- STANDBY_MODE_OFF means device is active, etc. */ +#define STANDBY_MODE_OFF 0 +#define STANDBY_MODE_ON 1 + +extern void pms5003_set_standby_mode(uint8_t mode); +extern uint8_t pms5003_get_standby_mode(void); +extern uint8_t pms5003_i2c_probe(void); +#endif /* PMS5003_ARCH_H */