Compare commits
4 commits
108a0f911c
...
e9067dd4a3
Author | SHA1 | Date | |
---|---|---|---|
e9067dd4a3 | |||
8656968f48 | |||
0159a9c68e | |||
c970e4a8ee |
14 changed files with 330 additions and 151 deletions
30
README.md
30
README.md
|
@ -16,6 +16,36 @@ Before programming a node, copy src/config.h.example to src/config.h and set the
|
|||
|
||||
Programming is done using a [MicroUPDI Programmer](https://github.com/MCUdude/microUPDI), settings in platformio.ini are set to use it. For other pogrammer options see the PlatformIO Documentation
|
||||
|
||||
## Multisensor Mode
|
||||
|
||||
The Firmware can be configured for multiple sensors at once (see comments in config.h.example). In this case the default payload decoder from the website will not be able to correctly determine the used sensors. You **must** define a specific decoder in this case. In the TTN v3 Stack a decoder can be set per device. Use the following as an example, and uncomment the parts for each enabled sensor, then make sure the placeholder for the byte index (**ii**)
|
||||
is filled in ascending order, starting with the first enabled sensor from left to right, beginning with 1
|
||||
|
||||
function decodeUplink(input) {
|
||||
var decoded = {};
|
||||
// Battery Voltage, always enabled
|
||||
decoded.v = (input.bytes[0] * 20) / 1000.0;
|
||||
|
||||
// CO2-Sensor (SG112A, MH-Z19C, Sensair S8)
|
||||
// decoded.ppm = ((input.bytes[ii]) | (input.bytes[ii] << 8 ));
|
||||
|
||||
// Temperature and Humidity (BME280 / SHT21)
|
||||
// decoded.t = ((input.bytes[ii]) | (input.bytes[ii] << 8 ) | (input.bytes[ii] << 16 ) | (input.bytes[ii] << 24)) / 100.0;
|
||||
// decoded.h = ((input.bytes[ii]) | (input.bytes[ii] << 8 ) | (input.bytes[ii] << 16 ) | (input.bytes[ii] << 24)) / 100.0;
|
||||
|
||||
// Atmospheric Pressure (BME280)
|
||||
// decoded.p = ((input.bytes[ii]) | (input.bytes[ii] << 8 ) | (input.bytes[ii] << 16 ) | (input.bytes[ii] << 24)) / 100.0;
|
||||
|
||||
// Leave this part as is
|
||||
return {
|
||||
data: decoded,
|
||||
warnings: [],
|
||||
errors: []
|
||||
};
|
||||
}
|
||||
|
||||
Please be also aware, that not all sensor combinations are valid. Some might use the same interface and interfere with each others readings. Also keep in mind that RAM- and Flash-Space are limited, which might lead to crashes or the code not compiling/flashing correctly if to many sensors are enabled at the same time.
|
||||
|
||||
## Configuring via Downlink
|
||||
|
||||
It is possible to change the sending interval via Downlink-Packets at runtime. The time between Transmits is specified in minutes (or more exactly, 64 Second intervals) and has to be sent as a 2 byte value, which will be interpreted as an uint. so for example 0x0001 means 1 Minute, 0x0002 means 2 Minutes and so on. Sending 0xFFFF resets the value to the compiled in default.
|
||||
|
|
44
include/attsensor.h
Normal file
44
include/attsensor.h
Normal file
|
@ -0,0 +1,44 @@
|
|||
/*
|
||||
attsensor.h - Define the Base Sensor Interface Class
|
||||
Copyright (c) 2020-2021, Stefan Brand
|
||||
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 copyright holder 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 COPYRIGHT HOLDERS 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 COPYRIGHT HOLDER 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.
|
||||
*/
|
||||
#ifndef ATTSENSOR_H
|
||||
#define ATTSENSOR_H
|
||||
|
||||
#include <inttypes.h>
|
||||
|
||||
class AttSensor {
|
||||
public:
|
||||
// Put the Data into the Payload Array starting at <startbyte>
|
||||
// Return the next startbyte when done
|
||||
virtual uint8_t getSensorData(char *payload, uint8_t startbyte) = 0;
|
||||
|
||||
// Called in Setup, Do any Necessary Initialization
|
||||
virtual void initialize(void) = 0;
|
||||
|
||||
// Return the number of Bytes added to the Payload
|
||||
virtual uint8_t numBytes(void) = 0;
|
||||
};
|
||||
|
||||
#endif
|
|
@ -1,5 +1,4 @@
|
|||
#include <Arduino.h>
|
||||
#include <stdint.h>
|
||||
#include <Wire.h>
|
||||
#include "BME280.h"
|
||||
|
||||
|
@ -78,10 +77,10 @@ int32_t BME280::compensate_h(int32_t adc_H)
|
|||
return (uint32_t)((v_x1_u32r>>12)/10);
|
||||
}
|
||||
|
||||
void BME280::getSensorData(lora_data &loradata) {
|
||||
uint8_t BME280::getSensorData(char *payload, uint8_t startbyte) {
|
||||
|
||||
int32_t UP, UT, UH;
|
||||
int32_t rawP, rawT;
|
||||
int32_t rawP, rawT, value;
|
||||
|
||||
// Trigger Measurement
|
||||
// Set Sensor Config
|
||||
|
@ -105,10 +104,28 @@ void BME280::getSensorData(lora_data &loradata) {
|
|||
// Read Humidity
|
||||
UH = read16(0xFD);
|
||||
|
||||
// Compensate Values and Return
|
||||
loradata.temperature = compensate_t(UT);
|
||||
loradata.pressure = compensate_p(UP);
|
||||
loradata.humidity = compensate_h(UH);
|
||||
|
||||
// Temperature
|
||||
value = compensate_t(UT);
|
||||
payload[startbyte] = (value) & 0XFF;
|
||||
payload[startbyte+1] = (value >> 8) & 0XFF;
|
||||
payload[startbyte+2] = (value >> 16) & 0XFF;
|
||||
payload[startbyte+3] = (value >> 24) & 0XFF;
|
||||
|
||||
// Humidity
|
||||
value = compensate_h(UH);
|
||||
payload[startbyte+4] = (value) & 0XFF;
|
||||
payload[startbyte+5] = (value >> 8) & 0XFF;
|
||||
payload[startbyte+6] = (value >> 16) & 0XFF;
|
||||
payload[startbyte+7] = (value >> 24) & 0XFF;
|
||||
|
||||
// Pressure
|
||||
value = compensate_p(UP);
|
||||
payload[startbyte+8] = (value) & 0XFF;
|
||||
payload[startbyte+9] = (value >> 8) & 0XFF;
|
||||
payload[startbyte+10] = (value >> 16) & 0XFF;
|
||||
payload[startbyte+11] = (value >> 24) & 0XFF;
|
||||
return startbyte+12;
|
||||
}
|
||||
|
||||
uint8_t BME280::read8(uint8_t addr) {
|
||||
|
|
|
@ -1,19 +1,11 @@
|
|||
#ifndef BME280_H
|
||||
#define BME280_H
|
||||
|
||||
#include <stdint.h>
|
||||
#include "../../include/attsensor.h"
|
||||
|
||||
#define BME280_I2CADDR 0x76
|
||||
|
||||
struct lora_data {
|
||||
uint8_t bat;
|
||||
int32_t temperature;
|
||||
int32_t humidity;
|
||||
int32_t pressure;
|
||||
} __attribute__ ((packed));
|
||||
|
||||
class BME280
|
||||
{
|
||||
class BME280 : public AttSensor {
|
||||
private:
|
||||
// Variables for Calibration Values
|
||||
uint8_t dig_H1, dig_H3;
|
||||
|
@ -36,13 +28,12 @@ private:
|
|||
int16_t readS16(uint8_t addr);
|
||||
int16_t readS16_LE(uint8_t addr);
|
||||
void write8(uint8_t addr, uint8_t data);
|
||||
void getCalData(void);
|
||||
|
||||
public:
|
||||
BME280(void);
|
||||
|
||||
// Get Calibration Data from Sensor
|
||||
void getCalData(void);
|
||||
// Read Pressure From Sensor
|
||||
void getSensorData(lora_data &loradata);
|
||||
uint8_t getSensorData(char *payload, uint8_t startbyte);
|
||||
void initialize(void) {getCalData();};
|
||||
uint8_t numBytes(void) {return 12;};
|
||||
};
|
||||
#endif
|
||||
|
|
|
@ -41,19 +41,23 @@ void MHZ19C::initialize(void) {
|
|||
#endif
|
||||
}
|
||||
|
||||
void MHZ19C::getSensorData(lora_data &loradata) {
|
||||
uint8_t MHZ19C::getSensorData(char * payload, uint8_t startbyte) {
|
||||
write(MHZ19C_CMD_GET_PPM, 0x00);
|
||||
delay(50);
|
||||
uint8_t readBytes = read();
|
||||
|
||||
loradata.ppm = 0;
|
||||
payload[startbyte] = 0x00;
|
||||
payload[startbyte+1] = 0x00;
|
||||
if (readBytes > 0) {
|
||||
switch(buffer[1]) {
|
||||
case 0x86:
|
||||
loradata.ppm = (buffer[2]*256) + buffer[3];
|
||||
uint16_t value = (buffer[2]*256) + buffer[3];
|
||||
payload[startbyte] = (value) & 0xFF;
|
||||
payload[startbyte+1] = (value >> 8) & 0xFF;
|
||||
break;
|
||||
}
|
||||
}
|
||||
return startbyte+2;
|
||||
}
|
||||
|
||||
// Turn Self Calibration Routine On or Off
|
||||
|
|
|
@ -27,11 +27,7 @@
|
|||
#ifndef MHZ19C_H
|
||||
#define MHZ19C_H
|
||||
|
||||
// Data Structure for the LoRa Packet
|
||||
struct lora_data {
|
||||
uint8_t bat;
|
||||
int16_t ppm;
|
||||
} __attribute__ ((packed));
|
||||
#include "../../include/attsensor.h"
|
||||
|
||||
#define MHZ19C_READ_TIMEOUT 500 // Timeout for Serial Communication
|
||||
#define MHZ19C_SER_BUF_LEN 9 // Length of the Internal Serial Message Buffer
|
||||
|
@ -39,7 +35,7 @@ struct lora_data {
|
|||
#define MHZ19C_CMD_SET_AUTOCAL 0x79 // Turn Self Calibration on/off
|
||||
#define MHZ19C_CMD_GET_PPM 0x86 // Get Current PPM Reading
|
||||
|
||||
class MHZ19C {
|
||||
class MHZ19C : public AttSensor {
|
||||
private:
|
||||
uint8_t buffer[MHZ19C_SER_BUF_LEN];
|
||||
|
||||
|
@ -51,8 +47,9 @@ class MHZ19C {
|
|||
|
||||
public:
|
||||
MHZ19C(void);
|
||||
void MHZ19C::initialize(void);
|
||||
void getSensorData(lora_data &loradata);
|
||||
void initialize(void);
|
||||
uint8_t numBytes(void) {return 2;};
|
||||
uint8_t getSensorData(char *payload, uint8_t startbyte);
|
||||
void setSelfCalibration(bool state);
|
||||
};
|
||||
|
||||
|
|
|
@ -33,7 +33,7 @@ SENSAIRS8::SENSAIRS8(void) {
|
|||
Serial.setTimeout(READ_TIMEOUT);
|
||||
}
|
||||
|
||||
void SENSAIRS8::getSensorData(lora_data &loradata) {
|
||||
uint8_t SENSAIRS8::getSensorData(char *payload, uint8_t startbyte) {
|
||||
uint8_t _cmd[7] = {0xFE, 0x44, 0x00, 0x08, 0x02, 0x9F, 0x25};
|
||||
while (Serial.available() > 0) Serial.read();
|
||||
Serial.write(_cmd, 7);
|
||||
|
@ -41,9 +41,14 @@ void SENSAIRS8::getSensorData(lora_data &loradata) {
|
|||
delay(1000);
|
||||
uint8_t readBytes = read();
|
||||
|
||||
payload[startbyte] = 0x00;
|
||||
payload[startbyte+1] = 0x00;
|
||||
if (readBytes > 0) {
|
||||
loradata.ppm = (buffer[3]*256) + buffer[4];
|
||||
uint16_t value = (buffer[3]*256) + buffer[4];
|
||||
payload[startbyte] = (value) & 0xFF;
|
||||
payload[startbyte+1] = (value >> 8) & 0xFF;
|
||||
}
|
||||
return startbyte+2;
|
||||
}
|
||||
|
||||
// Read a Sensor Response
|
||||
|
|
|
@ -27,16 +27,12 @@
|
|||
#ifndef SENSAIRS8_H
|
||||
#define SENSAIRS8_H
|
||||
|
||||
// Data Structure for the LoRa Packet
|
||||
struct lora_data {
|
||||
uint8_t bat;
|
||||
int16_t ppm;
|
||||
} __attribute__ ((packed));
|
||||
#include "../../include/attsensor.h"
|
||||
|
||||
#define READ_TIMEOUT 500 // Timeout for Serial Communication
|
||||
#define SER_BUF_LEN 7 // Length of the Internal Serial Message Buffer
|
||||
|
||||
class SENSAIRS8 {
|
||||
class SENSAIRS8 : public AttSensor {
|
||||
private:
|
||||
uint8_t buffer[SER_BUF_LEN];
|
||||
|
||||
|
@ -46,7 +42,9 @@ class SENSAIRS8 {
|
|||
|
||||
public:
|
||||
SENSAIRS8(void);
|
||||
void getSensorData(lora_data &loradata);
|
||||
uint8_t getSensorData(char *payload, uint8_t startbyte);
|
||||
void initialize(void) {};
|
||||
uint8_t numBytes(void) {return 2;};
|
||||
};
|
||||
|
||||
#endif
|
|
@ -33,18 +33,24 @@ SG112A::SG112A(void) {
|
|||
Serial.setTimeout(READ_TIMEOUT);
|
||||
}
|
||||
|
||||
void SG112A::getSensorData(lora_data &loradata) {
|
||||
|
||||
uint8_t SG112A::getSensorData(char *payload, uint8_t startbyte) {
|
||||
write(CMD_GET_PPM);
|
||||
delay(50);
|
||||
uint8_t readBytes = read();
|
||||
|
||||
payload[startbyte] = 0x00;
|
||||
payload[startbyte+1] = 0x00;
|
||||
if (readBytes > 0) {
|
||||
switch(buffer[2]) {
|
||||
case 0x15:
|
||||
loradata.ppm = (buffer[5]*256) + buffer[4];
|
||||
uint16_t value = (buffer[5]*256) + buffer[4];
|
||||
payload[startbyte] = (value) & 0xFF;
|
||||
payload[startbyte+1] = (value >> 8) & 0xFF;
|
||||
break;
|
||||
}
|
||||
}
|
||||
return startbyte+2;
|
||||
}
|
||||
|
||||
// Write a Command to the Sensor
|
||||
|
|
|
@ -27,11 +27,7 @@
|
|||
#ifndef SG112A_H
|
||||
#define SG112A_H
|
||||
|
||||
// Data Structure for the LoRa Packet
|
||||
struct lora_data {
|
||||
uint8_t bat;
|
||||
int16_t ppm;
|
||||
} __attribute__ ((packed));
|
||||
#include "../../include/attsensor.h"
|
||||
|
||||
#define READ_TIMEOUT 500 // Timeout for Serial Communication
|
||||
#define SER_BUF_LEN 16 // Length of the Internal Serial Message Buffer
|
||||
|
@ -40,7 +36,7 @@ struct lora_data {
|
|||
#define CMD_GET_SER 0x12 // Get Sensor Serial
|
||||
#define CMD_GET_PPM 0x14 // Get Current PPM Reading
|
||||
|
||||
class SG112A {
|
||||
class SG112A : public AttSensor {
|
||||
private:
|
||||
uint8_t buffer[SER_BUF_LEN];
|
||||
|
||||
|
@ -52,7 +48,9 @@ class SG112A {
|
|||
|
||||
public:
|
||||
SG112A(void);
|
||||
void getSensorData(lora_data &loradata);
|
||||
uint8_t getSensorData(char *payload, uint8_t startbyte);
|
||||
void initialize(void) {};
|
||||
uint8_t numBytes(void) {return 2;};
|
||||
};
|
||||
|
||||
#endif
|
|
@ -52,7 +52,20 @@ uint16_t SHT21::sensorRead(uint8_t command) {
|
|||
return result;
|
||||
}
|
||||
|
||||
void SHT21::getSensorData(lora_data &loradata) {
|
||||
loradata.temperature = (int32_t)((-46.85 + 175.72 / 65536.0 * (float)(sensorRead(SHT21_TEMPHOLD)))*100);
|
||||
loradata.humidity = (int32_t)((-6.0 + 125.0 / 65536.0 * (float)(sensorRead(SHT21_HUMIHOLD)))*100);
|
||||
uint8_t SHT21::getSensorData(char *payload, uint8_t startbyte) {
|
||||
// Temperature
|
||||
int32_t value = (int32_t)((-46.85 + 175.72 / 65536.0 * (float)(sensorRead(SHT21_TEMPHOLD)))*100);
|
||||
payload[startbyte] = (value) & 0XFF;
|
||||
payload[startbyte+1] = (value >> 8) & 0XFF;
|
||||
payload[startbyte+2] = (value >> 16) & 0XFF;
|
||||
payload[startbyte+3] = (value >> 24) & 0XFF;
|
||||
|
||||
// Humidity
|
||||
value = (int32_t)((-6.0 + 125.0 / 65536.0 * (float)(sensorRead(SHT21_HUMIHOLD)))*100);
|
||||
payload[startbyte+4] = (value) & 0XFF;
|
||||
payload[startbyte+5] = (value >> 8) & 0XFF;
|
||||
payload[startbyte+6] = (value >> 16) & 0XFF;
|
||||
payload[startbyte+7] = (value >> 24) & 0XFF;
|
||||
|
||||
return startbyte+8;
|
||||
}
|
|
@ -27,7 +27,7 @@
|
|||
#ifndef SHT21_H
|
||||
#define SHT21_H
|
||||
|
||||
#include <inttypes.h>
|
||||
#include "../../include/attsensor.h"
|
||||
|
||||
#define SHT21_I2CADDR 0x40
|
||||
|
||||
|
@ -37,20 +37,15 @@
|
|||
#define SHT21_HUMINOHOLD 0xF5
|
||||
#define SHT21_SOFTRESET 0xFE
|
||||
|
||||
struct lora_data {
|
||||
uint8_t bat;
|
||||
int32_t temperature;
|
||||
int32_t humidity;
|
||||
} __attribute__ ((packed));
|
||||
|
||||
class SHT21
|
||||
{
|
||||
class SHT21 : public AttSensor {
|
||||
private:
|
||||
uint16_t sensorRead(uint8_t command);
|
||||
|
||||
public:
|
||||
SHT21(void);
|
||||
void getSensorData(lora_data &loradata);
|
||||
uint8_t getSensorData(char *payload, uint8_t startbyte);
|
||||
void initialize(void) {};
|
||||
uint8_t numBytes(void) {return 8;};
|
||||
};
|
||||
|
||||
#endif
|
|
@ -1,48 +1,80 @@
|
|||
#ifndef CONFIG_H
|
||||
#define CONFIG_H
|
||||
// ALL EDITS BELOW THIS LINE!
|
||||
|
||||
// ATTNode v3 Onboard LED is on PIN_PA7
|
||||
/**************************************************************************************************************************
|
||||
* Use a Single Color LED for Status Signaling
|
||||
* At Startup the LED will blink twice to signal a sucessfull OTAA Join
|
||||
*************************************************************************************************************************/
|
||||
#define LED_PIN PIN_PA7
|
||||
|
||||
// Enable WS2812B RGB LED Support for the CO2 Addon Board
|
||||
// * First LED shows CO2-Level (green: <1000, yellow: 1000-1800, red: >=1800)
|
||||
// * Second LED shows LoRa Status (yellow: Joining, green 1s: Joined, green 100ms: Sending, blue 250ms: Received Downlink)
|
||||
// WS2812B_BRIGHT can be set to the desired brightness value for the LEDs (0=off, 255=brightest)
|
||||
// Uncomment the 3 following lines to get the default behaviour
|
||||
/**************************************************************************************************************************
|
||||
* Enable WS2812B RGB LED Support for the CO2 Addon Board
|
||||
* * First LED shows CO2-Level (green: <1000, yellow: 1000-1800, red: >=1800)
|
||||
* * Second LED shows LoRa Status (yellow: Joining, green 1s: Joined, green 100ms: Sending, blue 250ms: Received Downlink)
|
||||
* WS2812B_BRIGHT can be set to the desired brightness value for the LEDs (0=off, 255=brightest)
|
||||
* Uncomment the 3 following lines to get the default behaviour
|
||||
*************************************************************************************************************************/
|
||||
// #define WS2812B_PIN PIN_PC1
|
||||
// #define WS2812B_NUM 2
|
||||
// #define WS2812B_BRIGHT 32
|
||||
|
||||
// Enable Sending on Button Press, as well as Calibration by Pressing Button for 4s with MH-Z19C Addon
|
||||
// The Button has to be connected to a pin that is capable of Fully Asynchronus Interrupts.
|
||||
// For The ATTNode this means Pin PC2 if you don't want to block any other Interfaces
|
||||
/**************************************************************************************************************************
|
||||
* Enable Sending on Button Press, as well as CO2 Background Level Calibration by Pressing Button for 4s with MH-Z19C Addon
|
||||
* The Button has to be connected to a pin that is capable of Fully Asynchronus Interrupts.
|
||||
* For The ATTNode this means Pin PC2 if you don't want to block any other Interfaces
|
||||
*************************************************************************************************************************/
|
||||
// #define BTN_PIN PIN_PC2
|
||||
|
||||
// Enable Serial Debugging. Parameters for the Serial Port are 115200
|
||||
// Please be aware that the SG112A/B CO2 Sensor uses the HW-UART, so
|
||||
// Serial Debug Output is not available with this Sensor.
|
||||
/**************************************************************************************************************************
|
||||
* Enable Serial Debugging. Parameters for the Serial Port are 115200 Baud 8n1
|
||||
* By default the Firmware will output some messages about LoRa-Status and indicate sending
|
||||
* The Macros DEBUG_PRINT() and DEBUG_PRINTLN() can be used to produce debug output depending on this define
|
||||
* Please be aware that this will not work when a Serial Sensor like the SG112A/MH-Z19C or Sensair S8 ist used
|
||||
*************************************************************************************************************************/
|
||||
// #define DEBUG
|
||||
|
||||
// Define which Sensor is installed
|
||||
|
||||
/**************************************************************************************************************************
|
||||
* Number of active Sensors (used as long as HAS_NO_SENSOR is not enabled)
|
||||
* Set to the correct number of enabled sensors below
|
||||
* Not doing so will lead to unpredictable results or not work at all
|
||||
* The default payload decoder will NOT WORK if more than one sensor is enabled, so you MUST define a specific
|
||||
* decoder for this case. See the README.md for details
|
||||
*************************************************************************************************************************/
|
||||
#define NUM_SENSORS 1
|
||||
|
||||
/**************************************************************************************************************************
|
||||
* Define which Sensors are installed
|
||||
* Not all sensors can be used at the same time
|
||||
* For example you can only have one sensor using serial UART
|
||||
* If HAS_NO_SENSOR is selected all other activated sensor will be ignored
|
||||
*************************************************************************************************************************/
|
||||
#define HAS_NO_SENSOR
|
||||
// #define HAS_MHZ19C
|
||||
// #define HAS_SG112A
|
||||
// #define HAS_SENSAIRS8
|
||||
// #define HAS_BME280
|
||||
// #define HAS_SHT21
|
||||
// #define HAS_SG112A
|
||||
// #define HAS_MHZ19C
|
||||
|
||||
|
||||
// How many minutes to sleep between Measuring/Sending
|
||||
// Since this is a 2-byte value internally, intervals between 1 and 65536 are possible
|
||||
// This is the default interval to use, which can be overwritten via DownLink. If an interval
|
||||
// is set via DownLink it will be saved in EEPROM and the time specified here will no longer be used.
|
||||
// Actual Sleep Time is SLEEP_TIME*2*32 Seconds due to the 32s sleep intervals of the ATTiny3216
|
||||
/**************************************************************************************************************************
|
||||
* How many minutes to sleep between Measuring/Sending
|
||||
* Since this is a 2-byte value internally, intervals between 1 and 65536 are possible
|
||||
* This is the default interval to use, which can be overwritten via DownLink. If an interval
|
||||
* is set via DownLink it will be saved in EEPROM and the time specified here will no longer be used.
|
||||
* Actual sleep Time is sleep_time*2*32 seconds due to the 32s sleep intervals of the ATTiny3216
|
||||
*************************************************************************************************************************/
|
||||
uint16_t sleep_time = 10;
|
||||
|
||||
// Keys for OTAA Mode
|
||||
// APPEUI and DEVEUI from TTN, LSB!
|
||||
static const u1_t PROGMEM APPEUI[8]={ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 };
|
||||
static const u1_t PROGMEM DEVEUI[8]={ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 };
|
||||
// APPKey from TTN, MSB!
|
||||
/**************************************************************************************************************************
|
||||
* LoRa Keys for OTAA Mode
|
||||
* Please make sure to use the correct byte order when copying these from the TTN-Console!
|
||||
* APPEUI and DEVEUI need to be inserted in LSB order
|
||||
* APPKEY needs to be inserted in MSB order
|
||||
* in some cases there is no APPEUI, for example when using Chirpstack. leave it set to all 0x00 in these cases
|
||||
*************************************************************************************************************************/
|
||||
static const u1_t PROGMEM APPEUI[8] = { 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 };
|
||||
static const u1_t PROGMEM DEVEUI[8] = { 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 };
|
||||
static const u1_t PROGMEM APPKEY[16] = { 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 };
|
||||
|
||||
// ALL EDITS ABOVE THIS LINE!
|
||||
|
|
171
src/main.cpp
171
src/main.cpp
|
@ -11,10 +11,31 @@
|
|||
// Keep Track of used EEPROM Addresses
|
||||
#define ADDR_SLP 0 // Sleep Interval, 2 Bytes
|
||||
|
||||
// Include Config and Helpers
|
||||
#include "config.h"
|
||||
#include "debug.h"
|
||||
#include "attsensor.h"
|
||||
|
||||
// define the blink function and BLINK_LED Macro depending
|
||||
// Include All Sensors Activated in config.h
|
||||
#ifndef HAS_NO_SENSOR
|
||||
#ifdef HAS_MHZ19C
|
||||
#include <MHZ19C.h>
|
||||
#endif
|
||||
#ifdef HAS_SG112A
|
||||
#include <SG112A.h>
|
||||
#endif
|
||||
#ifdef HAS_SENSAIRS8
|
||||
#include <SENSAIRS8.h>
|
||||
#endif
|
||||
#ifdef HAS_BME280
|
||||
#include <BME280.h>
|
||||
#endif
|
||||
#ifdef HAS_SHT21
|
||||
#include <SHT21.h>
|
||||
#endif
|
||||
#endif
|
||||
|
||||
// Define the blink function and BLINK_LED Macro depending
|
||||
// on the definition of LED_PIN
|
||||
#ifdef LED_PIN
|
||||
void blink(uint8_t num) {
|
||||
|
@ -44,31 +65,14 @@ void blink(uint8_t num) {
|
|||
#define WS2812B_BLINK(led,r,g,b,ms)
|
||||
#endif
|
||||
|
||||
// Create the Sensor Objects
|
||||
#if defined HAS_NO_SENSOR
|
||||
struct lora_data {
|
||||
uint8_t bat;
|
||||
} __attribute ((packed));
|
||||
#elif defined HAS_MHZ19C
|
||||
#include <MHZ19C.h>
|
||||
MHZ19C sensor;
|
||||
#elif defined HAS_SG112A
|
||||
#include <SG112A.h>
|
||||
SG112A sensor;
|
||||
#elif defined HAS_SENSAIRS8
|
||||
#include <SENSAIRS8.h>
|
||||
SENSAIRS8 sensor;
|
||||
#elif defined HAS_BME280
|
||||
#include <BME280.h>
|
||||
BME280 sensor;
|
||||
#elif defined HAS_SHT21
|
||||
#include <SHT21.h>
|
||||
SHT21 sensor;
|
||||
#elif defined HAS_SG112A
|
||||
#include <SG112A.h>
|
||||
SG112A sensor;
|
||||
// Create Array for the Sensor Objects
|
||||
#ifndef HAS_NO_SENSORS
|
||||
AttSensor* sensors[NUM_SENSORS];
|
||||
#endif
|
||||
|
||||
// Track Length of Payload (Depends on Active Sensors)
|
||||
int payloadBytes = 1;
|
||||
|
||||
// Define some LMIC Callbacks and Variables
|
||||
void os_getArtEui (u1_t* buf) {
|
||||
memcpy_P(buf, APPEUI, 8);
|
||||
|
@ -97,6 +101,7 @@ const int disabledPins[] = {PIN_PB5, PIN_PB4, PIN_PB1, PIN_PB0, PIN_PC3, PIN_PC2
|
|||
const int disabledPins[] = {PIN_PB5, PIN_PB4, PIN_PB3, PIN_PB2, PIN_PB1, PIN_PB0, PIN_PC3, PIN_PC2, PIN_PC1, PIN_PC0};
|
||||
#endif
|
||||
|
||||
// Helper variables and Interrupt Routine for Button
|
||||
#ifdef BTN_PIN
|
||||
volatile bool btn_pressed = 0;
|
||||
volatile unsigned long btn_millis = 0;
|
||||
|
@ -109,19 +114,19 @@ void btn_press() {
|
|||
}
|
||||
#endif
|
||||
|
||||
// ISR Routine for Sleep
|
||||
// Interrupt Routine for Sleep
|
||||
ISR(RTC_PIT_vect)
|
||||
{
|
||||
/* Clear interrupt flag by writing '1' (required) */
|
||||
RTC.PITINTFLAGS = RTC_PI_bm;
|
||||
}
|
||||
|
||||
// Sleep Routine
|
||||
// Sleep Routine, Sleep for 32 Seconds
|
||||
void sleep_32s() {
|
||||
cli();
|
||||
while (RTC.PITSTATUS > 0) {}
|
||||
RTC.PITINTCTRL = RTC_PI_bm;
|
||||
// 32 Sekunden
|
||||
// 32 Seconds
|
||||
RTC.PITCTRLA = RTC_PERIOD_CYC32768_gc | RTC_PITEN_bm;
|
||||
while (RTC.PITSTATUS & RTC_CTRLBUSY_bm) {}
|
||||
set_sleep_mode(SLEEP_MODE_PWR_DOWN);
|
||||
|
@ -159,6 +164,7 @@ void onEvent(ev_t ev) {
|
|||
// Got to sleep for specified Time
|
||||
DEBUG_PRINTLN("Going to Sleep");
|
||||
for (uint16_t i = 0; i < sleep_time*2; i++) {
|
||||
// Cancel sleep Cycle if Button was Pressed
|
||||
#ifdef BTN_PIN
|
||||
if (btn_pressed) {
|
||||
i = sleep_time*2;
|
||||
|
@ -194,55 +200,65 @@ uint16_t readSupplyVoltage() { //returns value in millivolts to avoid floating p
|
|||
|
||||
// Read Sensors and Send Data
|
||||
void do_send(osjob_t* j) {
|
||||
// Prepare LoRa Data Packet
|
||||
// The struct is defined in the sensor class (or above for use without a sensor)
|
||||
lora_data data;
|
||||
// Array of Bytes for the Payload
|
||||
// Length is defined by the Enabled Sensors
|
||||
char payload[payloadBytes];
|
||||
|
||||
if (LMIC.opmode & OP_TXRXPEND) {
|
||||
// Wayt if LMIC is busy
|
||||
delay(1);
|
||||
} else {
|
||||
// Track Current Position in Payload Array
|
||||
uint8_t curByte = 0;
|
||||
|
||||
// Add Battery Voltage (0.2V Accuracy stored in 1 byte)
|
||||
uint32_t batv = readSupplyVoltage();
|
||||
data.bat = (uint8_t)(batv / 20);
|
||||
payload[curByte] = (uint8_t)(batv / 20);
|
||||
if (batv % 20 > 9)
|
||||
data.bat += 1;
|
||||
|
||||
// Get Sensor Readings Into Data Paket
|
||||
#ifndef HAS_NO_SENSOR
|
||||
sensor.getSensorData(data);
|
||||
payload[curByte] += 1;
|
||||
curByte++;
|
||||
|
||||
// Queue Packet for Sending
|
||||
DEBUG_PRINTLN("LoRa-Packet Queued");
|
||||
LMIC_setTxData2(1, (unsigned char *)&data, sizeof(data), 0);
|
||||
|
||||
#if defined WS2812B_PIN && (defined HAS_SG112A || defined HAS_MHZ19C)
|
||||
|
||||
#ifndef HAS_NO_SENSOR
|
||||
// Put Sensor Readings into the Payload Array
|
||||
for (int i=0; i < NUM_SENSORS; i++)
|
||||
curByte = sensors[i]->getSensorData(payload, curByte);
|
||||
|
||||
// If CO2 Addon Boards with RGB-LEDS is installed, set LED according to the current CO2 Reading
|
||||
#if defined WS2812B_PIN && (defined HAS_SG112A || defined HAS_MHZ19C || defined HAS_SENSAIRS8)
|
||||
// CO2 PPM Levels and LED Colors
|
||||
// < 1000 ppm green
|
||||
// < 1800 ppm yellow
|
||||
// > 1000 ppm red
|
||||
|
||||
if (data.ppm > 0 && data.ppm <= 1000) {
|
||||
// Get PPM from Payload:
|
||||
uint16_t ppm = word(payload[2], payload[1]);
|
||||
|
||||
// Set WS2812B-LED accodring to PPM Value
|
||||
if (ppm > 0 && ppm <= 1000) {
|
||||
WS2812B_SETLED(0,0,127,0);
|
||||
} else if (data.ppm > 1000 && data.ppm <= 1800) {
|
||||
} else if (ppm > 1000 && ppm <= 1800) {
|
||||
WS2812B_SETLED(0,127,127,0);
|
||||
} else if (data.ppm > 1800) {
|
||||
} else if (ppm > 1800) {
|
||||
WS2812B_SETLED(0,127,0,0);
|
||||
} else {
|
||||
WS2812B_SETLED(0,0,0,0);
|
||||
}
|
||||
#endif // WS2812B
|
||||
#endif // #infdef HAS_NO_SENSOR
|
||||
|
||||
|
||||
#endif // HAS_NO_SENSOR
|
||||
|
||||
// Queue Packet for Sending
|
||||
DEBUG_PRINTLN("LoRa-Packet Queued");
|
||||
LMIC_setTxData2(1, payload, sizeof(payload), 0);
|
||||
}
|
||||
}
|
||||
|
||||
void setup()
|
||||
{
|
||||
// Initialize Serial if Debug is enabled
|
||||
#ifdef DEBUG
|
||||
Serial.begin(115200);
|
||||
#endif
|
||||
|
||||
// Initialize SPI and I2C
|
||||
Wire.begin();
|
||||
SPI.begin();
|
||||
|
@ -251,36 +267,67 @@ void setup()
|
|||
for (int i = 0; i < (sizeof(disabledPins) / sizeof(disabledPins[0])) - 1; i++)
|
||||
pinMode(disabledPins[i], INPUT_PULLUP);
|
||||
|
||||
// Setup WS2812B LEDs
|
||||
#ifdef WS2812B_PIN
|
||||
pinMode(WS2812B_PIN, OUTPUT);
|
||||
leds.setBrightness(WS2812B_BRIGHT);
|
||||
#endif
|
||||
|
||||
// Setup Button Interrupt
|
||||
#ifdef BTN_PIN
|
||||
pinMode(BTN_PIN, INPUT_PULLUP);
|
||||
attachInterrupt(digitalPinToInterrupt(BTN_PIN), btn_press, FALLING);
|
||||
#endif
|
||||
|
||||
// Set RTC
|
||||
// Setup all Sensors and Calculate the Payload Length
|
||||
// Order of the Sensors here is Order in the Payload
|
||||
#ifndef HAS_NO_SENSOR
|
||||
uint8_t i = 0;
|
||||
#ifdef HAS_MHZ19C
|
||||
sensors[i] = new MHZ19C();
|
||||
payloadBytes += sensors[i]->numBytes();
|
||||
i++;
|
||||
#endif
|
||||
#ifdef HAS_SG112A
|
||||
sensors[i] = new SG112A();
|
||||
payloadBytes += sensors[i]->numBytes();
|
||||
i++;
|
||||
#endif
|
||||
#ifdef HAS_SENSAIRS8
|
||||
sensors[i] = new SENSAIRS8();
|
||||
payloadBytes += sensors[i]->numBytes();
|
||||
i++;
|
||||
#endif
|
||||
#ifdef HAS_BME280
|
||||
sensors[i] = new BME280();
|
||||
payloadBytes += sensors[i]->numBytes();
|
||||
i++;
|
||||
#endif
|
||||
#ifdef HAS_SHT21
|
||||
sensors[i] = new SHT21();
|
||||
payloadBytes += sensors[i]->numBytes();
|
||||
i++;
|
||||
#endif
|
||||
#endif // HAS_NO_SENSOR
|
||||
|
||||
// Initialize all Sensors
|
||||
#ifndef HAS_NO_SENSOR
|
||||
for (i = 0; i < NUM_SENSORS; i++)
|
||||
sensors[i]->initialize();
|
||||
#endif
|
||||
|
||||
// Setup RTC
|
||||
while (RTC.STATUS > 0) {}
|
||||
RTC.CLKSEL = RTC_CLKSEL_INT1K_gc;
|
||||
while (RTC.PITSTATUS > 0) {}
|
||||
|
||||
// Initialize Sensor(s)
|
||||
#ifdef HAS_BME280
|
||||
sensor.getCalData();
|
||||
#endif
|
||||
#ifdef HAS_MHZ19C
|
||||
sensor.initialize();
|
||||
#endif
|
||||
|
||||
// Setup LMIC
|
||||
DEBUG_PRINT("Initializing LMIC...")
|
||||
os_init();
|
||||
LMIC_reset(); // Reset LMIC state and cancel all queued transmissions
|
||||
LMIC_reset(); // Reset LMIC state and cancel all queued transmissions
|
||||
LMIC_setClockError(MAX_CLOCK_ERROR * 10 / 100); // Compensate for Clock Skew
|
||||
LMIC.dn2Dr = DR_SF9; // Downlink Band
|
||||
LMIC_setDrTxpow(DR_SF7, 14); // Default to SF7
|
||||
LMIC.dn2Dr = DR_SF9; // Downlink Band
|
||||
LMIC_setDrTxpow(DR_SF7, 14); // Default to SF7
|
||||
DEBUG_PRINTLN("Done");
|
||||
|
||||
// Check if Sending Interval is set in EEPROM
|
||||
|
@ -295,13 +342,15 @@ void setup()
|
|||
|
||||
DEBUG_PRINTLN("Setup Finished");
|
||||
|
||||
// Schedule First Send (Triggers OTAA Join as well)
|
||||
// Set WS2812B to Yellow for "Joining" (if enabled)
|
||||
WS2812B_SETLED(1,127,127,0);
|
||||
// Schedule First Send (Triggers OTAA Join as well)
|
||||
do_send(&sendjob);
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
// Handle long Button Press for Calibration with MH-Z19C Sensor
|
||||
#if defined HAS_MHZ19C && defined BTN_PIN
|
||||
if (digitalRead(BTN_PIN) == LOW) {
|
||||
// Press Button longer than 4 Seconds -> Start MH-Z19C Calibration Routine
|
||||
|
|
Loading…
Reference in a new issue