Skip to content
Snippets Groups Projects

Compare revisions

Changes are shown as if the source revision was being merged into the target revision. Learn more about comparing revisions.

Source

Select target project
No results found

Target

Select target project
  • informatik/qe/forte/sensor-system
1 result
Show changes
Commits on Source (2)
......@@ -26,17 +26,14 @@ build_unflags = -std=gnu++11
monitor_port = /dev/ttyUSB0
upload_port = /dev/ttyUSB0
lib_deps =
sparkfun/SparkFun SCD30 Arduino Library@^1.0.18
Wire
adafruit/Adafruit ADS1X15@^2.4.0
wollewald/INA219_WE@^1.3.1
adafruit/Adafruit BusIO@^1.13.2
Adafruit_I2CDevice
SPI
envirodiy/SDI-12@^2.1.4
fbiego/ESP32Time@^2.0.0
bblanchon/ArduinoJson@^6.19.4
plerup/EspSoftwareSerial@6.16.1
4-20ma/ModbusMaster@^2.0.1
adafruit/RTClib@^2.1.1
sensirion/arduino-sht@^1.2.2
......
#include "Arduino.h"
#include "ESPNow.hpp"
#include "rs485.hpp"
#include "NoDataAvailableException.hpp"
#include "rs485.hpp"
#define uS_TO_S_FACTOR 1000000 /* Conversion factor for micro seconds to seconds */
#define TIME_TO_SLEEP 60 /* Time ESP32 will go to sleep (in seconds) */
static const char *TAG = "MAIN";
#define uS_TO_S_FACTOR 1000000 /* Conversion factor for micro seconds to seconds */
#define TIME_TO_SLEEP 5 * 60 /* Time ESP32 will go to sleep (in seconds) */
Forte_RS485 rs485;
void setup()
float getBatteryVoltage()
{
rs485.setup();
espnow_setup();
//************ Measuring Battery Voltage ***********
// reference voltage of microcontroller 3.3v for esp32
const float reference_vcc = 3.3;
// value of R2 resistor [kOhm]
const float bat_res_gnd = 20;
// value of R1 resistor [kOhm]
const float bat_res_vcc = 68;
// max ADC value
const int adc = 4095;
float sample = 0;
// Get 100 analog read to prevent unusefully read
for (int i = 0; i < 100; i++) {
sample = sample + analogRead(35); // read the voltage from the divider circuit
delay(2);
}
sample = sample / 100;
float battery_voltage = (sample / 4095 * reference_vcc * (bat_res_vcc + bat_res_gnd) / bat_res_gnd);
ESP_LOGI(TAG, "Battery Voltage: %4.2f V", battery_voltage);
ESP_LOGD(TAG, "ADC mean Value: %4.2f", sample);
return battery_voltage;
}
void loop() {
try {
// FIXME: put this in ESPNow.hpp and let stupid Markus Rampp know how you did it. After years of Python he moved past
// the idea of types and declarations
void send_msgs(const std::__cxx11::list<Message> msgs)
{
for (const Message &msg : msgs) {
auto messages = rs485.buildMessages();
for (const Message &message : messages) {
if(message.send() != ESP_OK){
RtcMemory::store(message.getMessageAsMinifiedJsonString());
}
delay(5000);
if(!was_msg_received()){
RtcMemory::store(message.getMessageAsMinifiedJsonString());
if (msg.send() != ESP_OK) {
RtcMemory::store(msg.getMessageAsMinifiedJsonString());
}
unsigned long ts = millis();
// it takes ~110ms for receiving an acknowledgement by the host in perfect conditions
uint16_t message_timeout = 2000;
while (!was_msg_received()) {
if ((millis() - ts) > message_timeout) {
RtcMemory::store(msg.getMessageAsMinifiedJsonString());
ESP_LOGE(TAG, "Timeout: Host not available\n");
break;
}
}
ESP_LOGD(TAG, "Time until acknowledgement: %ld", millis() - ts);
}
}
void setup()
{
// whole loop should be around ~3000 ms
Serial.begin(115200);
rs485.setup();
getBatteryVoltage();
// ~2100ms
try {
auto messages = rs485.buildMessages();
espnow_setup();
send_msgs(messages);
} catch (const NoDataAvailableException &e) {
std::cerr << e.what() << '\n';
}
Serial.print("Going to sleep for secounds:");
Serial.println(TIME_TO_SLEEP);
esp_sleep_enable_timer_wakeup(TIME_TO_SLEEP * uS_TO_S_FACTOR);
esp_deep_sleep_start();
ESP_LOGD(TAG, "Going to sleep for %d seconds", TIME_TO_SLEEP);
esp_sleep_enable_timer_wakeup(TIME_TO_SLEEP * uS_TO_S_FACTOR);
esp_deep_sleep_start();
}
void loop() {}
......@@ -6,14 +6,20 @@
#include <Arduino.h>
// Execution time:
// FIXME: Boot: needs to be measured with oscilloscope and optimised. should be around a few hundres ms, can be <100ms
// FIXME: Boot: needs to be optimised. should be around 300 ms, can be <100ms
// https://github.com/makermoekoe/Picoclick-C3#speed-up-boot-process
// Part [ms]
// Boot: 300
// First setup: 150
// Data aquisition: 500
// Data aquisition: 500 (4 Dendrometers)
// ESPNow setup: 220
// Sending 1200
// TOTAL: 2200
// Sending 580
// TOTAL: 1450
// Measurement Summary, 2 Dendrometers connected, measuring 4 Dendrometers:
// Duration: 1.74 [s]
// Current consumption: 141.09 [mA*s]
// Average current: 81.16 [mA]
static const char *TAG = "MAIN";
......@@ -61,6 +67,11 @@ void setup()
DeepSleep::print_wakeup_reason();
DeepSleep::bootCount++;
ESP_LOGD(TAG, "Boot number: %d", DeepSleep::bootCount);
// battery protection: go to deep sleep for unlimited time when voltage less than 3.2V
if (battery_monitor.cellVoltage_mV() < 3200) {
battery_monitor.setPowerMode(LC709203F_POWER_SLEEP);
esp_deep_sleep_start();
}
gpio_set_level(GPIO_NUM_32, 1);
// delay(100);
......
#include "NoDataAvailableException.hpp"
#include <SentecSensors.h>
/***************************************
* RS485 SENSOR READOUT
****************************************/
SentecSensorRS485::SentecSensorRS485(SoftwareSerial *ser, byte add)
static const char *TAG = "SENTEC";
SentecSensorRS485::SentecSensorRS485(HardwareSerial *ser, byte add)
{
address = add;
RS485 = ser;
}
SentecSensorRS485::SentecSensorRS485(SoftwareSerial *ser, byte add, uint8_t serialControlPin)
SentecSensorRS485::SentecSensorRS485(HardwareSerial *ser, byte add, uint8_t serialControlPin)
{
address = add;
RS485 = ser;
......@@ -46,22 +47,23 @@ String SentecSensorRS485::getValueStr(int value)
}
}
void SentecSensorRS485::queryAddress()
SentecSensorRS485::ReturnCode SentecSensorRS485::queryAddress()
{
// request the address of the sensor with ONLY ONE SENSOR ON THE BUS
byte tmp_addr = address; // store the address in a temporary byte
address = 0xFF; // change the address to FF (0) for address check
readRegister(word(0x07, 0xD0), 2);
SentecSensorRS485::ReturnCode tmp = readRegister(word(0x07, 0xD0), 2);
address = tmp_addr; // set the original address back
return tmp;
}
void SentecSensorRS485::readRegister(int registerStartAddress)
SentecSensorRS485::ReturnCode SentecSensorRS485::readRegister(int registerStartAddress)
{
readRegister(registerStartAddress, 1);
return readRegister(registerStartAddress, 1);
}
void SentecSensorRS485::readRegister(int registerStartAddress, int registerLength)
SentecSensorRS485::ReturnCode SentecSensorRS485::readRegister(int registerStartAddress, int registerLength)
{
// function code 0x03: get data measured by the sensor
byte query[8];
......@@ -81,10 +83,10 @@ void SentecSensorRS485::readRegister(int registerStartAddress, int registerLengt
// write the data request to the modbus line
write(query, sizeof(query));
// get response from sensor
getResponse();
return getResponse();
}
void SentecSensorRS485::writeRegister(int registerAddress, int value)
SentecSensorRS485::ReturnCode SentecSensorRS485::writeRegister(int registerAddress, int value)
{
// function code 0x06: change sensor settings
// e.g. a new address, reset rainfal data...
......@@ -100,18 +102,20 @@ void SentecSensorRS485::writeRegister(int registerAddress, int value)
query[4] = value >> 8;
query[5] = value & 0xFF;
calculateCRC(query, sizeof(query) - 2);
Serial.print("Query (settings): ");
ESP_LOGD(TAG, "Query (settings): ");
printBytes(query, 8);
write(query, sizeof(query));
getResponse();
return getResponse();
}
void SentecSensorRS485::setAddress(byte add)
SentecSensorRS485::ReturnCode SentecSensorRS485::setAddress(byte add)
{
// change the address of a sensor
writeRegister(word(0x07, 0xD0), add);
SentecSensorRS485::ReturnCode tmp = writeRegister(word(0x07, 0xD0), add);
if (tmp == SentecSensorRS485::ReturnCode::OK)
address = add;
// TODO check response: matches the sent message exactly
address = add;
return tmp;
}
void SentecSensorRS485::resetAnswerFrame()
......@@ -121,9 +125,10 @@ void SentecSensorRS485::resetAnswerFrame()
}
}
bool SentecSensorRS485::getResponse()
SentecSensorRS485::ReturnCode SentecSensorRS485::getResponse()
{
// reads the response of a sensor
SentecSensorRS485::ReturnCode returnCode = SentecSensorRS485::ReturnCode::OK;
valid = true;
int idx = 0;
int byteReceived;
......@@ -134,7 +139,7 @@ bool SentecSensorRS485::getResponse()
const int timeout = 200;
const int retries = 1; // #editet to q
size_t tries = 1;
// it doesn't seem to help to request multiple times if first time goes wrong
for (tries; tries <= retries; tries++) {
// if we lose connection with the sensor, we get an array of zeros back
resetAnswerFrame();
......@@ -146,50 +151,48 @@ bool SentecSensorRS485::getResponse()
// Serial.println(byteReceived, HEX);
// check for first byte. It has to be the device address unless for broadcasts with address = 0xFF
if (idx == 0 && address != 0xFF && byteReceived != address) {
Serial.print("Invalid byte. First byte needs to be address 0x");
Serial.print(address, HEX);
Serial.print(" but got 0x");
Serial.print(byteReceived, HEX);
Serial.println("instead");
ESP_LOGE(TAG, "Invalid byte. First byte needs to be address 0x%02X but got 0x%02Xinstead");
} else {
answerFrame[idx] = byteReceived;
// for reading register: third received byte is data length, read number of bytes accordingly
if (idx == 2 && answerFrame[1] == 0x03) {
// 5 bytes for address, function, data length, CRC_H, CRC_L
// 5 bytes for address, function code, data length, CRC_H, CRC_L
responseLength = 5 + byteReceived;
}
idx++;
}
}
}
delay(10);
Serial.print("Response: 0x");
printBytes(answerFrame, responseLength);
Serial.print("Tries: ");
Serial.println(tries);
Serial.print("Bytes received: ");
Serial.println(idx);
ESP_LOGD(TAG, "-----------------------------------------------------------------------------------------");
ESP_LOGD(TAG, "Response: 0x%s", formatBytes(answerFrame, responseLength).c_str());
// ESP_LOGD(TAG, "Tries: %d", tries);
// ESP_LOGD(TAG, "Bytes received: %d", idx);
if (answerFrame[0] == 0) {
ESP_LOGE(TAG, "Check sensor connection. First byte is 0x00.");
valid = false;
returnCode = SentecSensorRS485::ReturnCode::NO_CONNECTION;
} else if (idx < responseLength) {
ESP_LOGE(TAG, "Response too short: %d bytes < %d bytes. Unfinished transmission.", idx, responseLength);
valid = false;
returnCode = SentecSensorRS485::ReturnCode::SHORT_RESPONSE;
}
word crc_received = word(answerFrame[responseLength - 2], answerFrame[responseLength - 1]);
word crc = calculateCRC(answerFrame, responseLength - 2);
if (crc_received != word(crc)) {
Serial.print("CRC wrong: Expected ");
printBytes(crc);
Serial.print(" got ");
printBytes(crc_received);
Serial.println();
if (valid && crc_received != word(crc)) {
ESP_LOGE(TAG, "CRC wrong: Expected 0x%s got 0x%s", formatBytes(crc).c_str(),
formatBytes(crc_received).c_str());
valid = false;
resetAnswerFrame();
returnCode = SentecSensorRS485::ReturnCode::WRONG_CRC;
}
if (answerFrame[0] == 0) {
valid = false;
}
if (valid) {
// breaking after first successfull try
if (returnCode == SentecSensorRS485::ReturnCode::OK) {
break;
}
}
return valid;
// ESP_LOGE(TAG, "Returncode: %d", returnCode);
return returnCode;
}
unsigned int SentecSensorRS485::calculateCRC(byte query[], int length)
......@@ -241,13 +244,31 @@ void SentecSensorRS485::printBytes(word data)
Serial.print(tmp);
}
std::string SentecSensorRS485::formatBytes(byte *data, int length)
{
// pls don't hate me for building strings like that.
// I also wish that I would be good at programming
std::string tmp;
// prints 8-bit data in hex with leading zeroes
char buff[4];
for (int i = 0; i < length; i++) {
snprintf(buff, sizeof(buff), "%02X ", data[i]);
tmp += buff;
}
return tmp;
}
std::string SentecSensorRS485::formatBytes(word data)
{
byte arr[2] = {data >> 8, data & 0xFF};
return formatBytes(arr, 2);
}
word SolarRadiationSensor::getSolarRadiation()
{
readRegister(0, 1);
glob = word(answerFrame[3], answerFrame[4]);
Serial.print("Global solar radiation: ");
Serial.print(glob, DEC);
Serial.println(" W/m^2");
ESP_LOGI(TAG, "Global solar radiation: %d W/m^2", glob);
return glob;
}
......@@ -282,9 +303,8 @@ word RainGaugeSensor::getInstantaneousPrecipitation()
// manual says this is current precipitation - is it?
readRegister(0, 0x01);
precipitation = word(answerFrame[3], answerFrame[4]);
Serial.print("Precipitation: ");
Serial.print(precipitation / 10.0, 1);
Serial.println(" mm");
ESP_LOGI(TAG, "Precipitation: %.1f mm", precipitation / 10.0);
// resetPrecipitation();
return precipitation;
}
......@@ -304,13 +324,8 @@ float SoilMoistureSensor::getMoistureTemp()
} else {
temperatureRaw = (answerFrame[5] << 8) + answerFrame[6] - 65536;
}
Serial.begin(115200);
Serial.print("Soil moisture: ");
Serial.print((moistureRaw - moistureOffset) / 10.0, 1);
Serial.println(" %");
Serial.print("Temperature: ");
Serial.print((temperatureRaw - temperatureOffset) / 10.0, 1);
Serial.println(" °C");
ESP_LOGI(TAG, "Soil moisture: %.1f %", (moistureRaw - moistureOffset) / 10.0);
ESP_LOGI(TAG, "Soil temperature: %.1f °C", (temperatureRaw - temperatureOffset) / 10.0);
return (temperatureRaw - temperatureOffset) / 10.0;
}
......
......@@ -2,32 +2,41 @@
#define SENTECSENSORS_H
#include <Arduino.h>
#include <SoftwareSerial.h>
class SentecSensorRS485 {
public:
byte address;
uint8_t serialCommunicationControlPin = 19;
SoftwareSerial *RS485;
HardwareSerial *RS485;
byte answerFrame[10];
// TODO use valid flag to log None
bool valid = false;
SentecSensorRS485(SoftwareSerial *ser, byte add);
SentecSensorRS485(SoftwareSerial *ser, byte add, uint8_t serialControlPin);
SentecSensorRS485(HardwareSerial *ser, byte add);
SentecSensorRS485(HardwareSerial *ser, byte add, uint8_t serialControlPin);
enum class ReturnCode {
OK,
NO_CONNECTION,
SHORT_RESPONSE, // connection ended prematurely
WRONG_CRC // corrupted data package
};
void write(byte queryFrame[], int length);
String getValueStr(float value);
String getValueStr(int value);
void queryAddress();
void readRegister(int registerStartAddress);
void readRegister(int registerStartAddress, int registerLength);
void writeRegister(int registerAddress, int value);
void setAddress(byte add);
SentecSensorRS485::ReturnCode queryAddress();
SentecSensorRS485::ReturnCode readRegister(int registerStartAddress);
SentecSensorRS485::ReturnCode readRegister(int registerStartAddress, int registerLength);
SentecSensorRS485::ReturnCode writeRegister(int registerAddress, int value);
SentecSensorRS485::ReturnCode setAddress(byte add);
void resetAnswerFrame();
bool getResponse();
SentecSensorRS485::ReturnCode getResponse();
unsigned int calculateCRC(byte query[], int length);
void printBytes(byte *data, int length);
void printBytes(word data);
std::string formatBytes(byte *data, int length);
std::string formatBytes(word data);
};
class SolarRadiationSensor : public SentecSensorRS485 {
......
#include "rs485.hpp"
// RS485 control
#define RS485Serial Serial2
#define RXPin 14 // Serial Receive pin
#define TXPin 15 // Serial Transmit pin
......@@ -8,8 +9,9 @@
#define POWER_SWITCH_PIN_12V 12
#define POWER_SWITCH_PIN_5V 13
static const char *TAG = "RS485";
// Configure sensors
SoftwareSerial RS485Serial(TXPin, RXPin);
SolarRadiationSensor solarSensor(&RS485Serial, 1, RE_DE_PIN);
RainGaugeSensor rainGauge = RainGaugeSensor(&RS485Serial, 2, RE_DE_PIN); // Give 2 Sensor Adress 2
SoilMoistureSensor soilSensor3 = SoilMoistureSensor(&RS485Serial, 3, RE_DE_PIN); //.....
......@@ -22,9 +24,7 @@ void Forte_RS485::setup()
pinMode(RE_DE_PIN, OUTPUT);
pinMode(POWER_SWITCH_PIN_12V, OUTPUT);
pinMode(POWER_SWITCH_PIN_5V, OUTPUT);
// Set data rates: Serial baud rate has to be WAY HIGHER than RS485Serial!
Serial.begin(115200);
RS485Serial.begin(4800);
RS485Serial.begin(4800, SERIAL_8N1, TXPin, RXPin);
}
out_data_rs485 Forte_RS485::readData()
......@@ -34,8 +34,9 @@ out_data_rs485 Forte_RS485::readData()
digitalWrite(POWER_SWITCH_PIN_5V, HIGH);
// Wait for sensors to power up
// TODO minimize delay
delay(500);
delay(300);
out_data_rs485 output;
unsigned long ts = millis();
output.solarRadiation = solarSensor.getSolarRadiation();
output.soilTemperature3 = soilSensor3.getMoistureTemp();
output.soilTemperature4 = soilSensor4.getMoistureTemp();
......
#ifndef _RS485
#define _RS485
#include "SPI.h"
// RTC (I2C)
#include "RTClib.h"
#include "Message.hpp"
#include "ForteSensor.hpp"
#include "SentecSensors.h"
......
This diff is collapsed.
......@@ -131,6 +131,14 @@ void setupSDCard();
void syncUTCTimeToRTC();
void on_data_recv(const uint8_t *mac, const uint8_t *incomingData, int len)
{
response response = {};
response.type = dataAck;
esp_read_mac(response.mac, ESP_MAC_WIFI_STA);
response.time = rtc.getEpoch();
esp_err_t success = esp_now_send(mac, (uint8_t*) &response, sizeof(response));
esp_log_write(ESP_LOG_DEBUG, TAG_ESPNOW.c_str(),
(success == ESP_OK) ? "Response sent\n" : "Failed to respond\n");
esp_log_write(ESP_LOG_INFO, TAG_ESPNOW.c_str(), "Message recieved\n");
// copy received data to a char array
char data[len];
......