Skip to content
Snippets Groups Projects
Commit 3935b909 authored by Zoe Pfister's avatar Zoe Pfister :speech_balloon:
Browse files

Merge branch 'develop-central-mast-client' into 'develop'

Develop central mast client

See merge request !21
parents c68a65e0 56a676f3
No related branches found
No related tags found
2 merge requests!39Merge Develop into Main,!21Develop central mast client
...@@ -26,17 +26,14 @@ build_unflags = -std=gnu++11 ...@@ -26,17 +26,14 @@ build_unflags = -std=gnu++11
monitor_port = /dev/ttyUSB0 monitor_port = /dev/ttyUSB0
upload_port = /dev/ttyUSB0 upload_port = /dev/ttyUSB0
lib_deps = lib_deps =
sparkfun/SparkFun SCD30 Arduino Library@^1.0.18
Wire Wire
adafruit/Adafruit ADS1X15@^2.4.0 adafruit/Adafruit ADS1X15@^2.4.0
wollewald/INA219_WE@^1.3.1 wollewald/INA219_WE@^1.3.1
adafruit/Adafruit BusIO@^1.13.2 adafruit/Adafruit BusIO@^1.13.2
Adafruit_I2CDevice Adafruit_I2CDevice
SPI SPI
envirodiy/SDI-12@^2.1.4
fbiego/ESP32Time@^2.0.0 fbiego/ESP32Time@^2.0.0
bblanchon/ArduinoJson@^6.19.4 bblanchon/ArduinoJson@^6.19.4
plerup/EspSoftwareSerial@6.16.1
4-20ma/ModbusMaster@^2.0.1 4-20ma/ModbusMaster@^2.0.1
adafruit/RTClib@^2.1.1 adafruit/RTClib@^2.1.1
sensirion/arduino-sht@^1.2.2 sensirion/arduino-sht@^1.2.2
......
#include "Arduino.h" #include "Arduino.h"
#include "ESPNow.hpp" #include "ESPNow.hpp"
#include "rs485.hpp"
#include "NoDataAvailableException.hpp" #include "NoDataAvailableException.hpp"
#include "rs485.hpp"
#define uS_TO_S_FACTOR 1000000 /* Conversion factor for micro seconds to seconds */ static const char *TAG = "MAIN";
#define TIME_TO_SLEEP 60 /* Time ESP32 will go to sleep (in seconds) */
#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; Forte_RS485 rs485;
void setup() float getBatteryVoltage()
{ {
rs485.setup(); //************ Measuring Battery Voltage ***********
espnow_setup(); // 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() { // FIXME: put this in ESPNow.hpp and let stupid Markus Rampp know how you did it. After years of Python he moved past
try { // the idea of types and declarations
void send_msgs(const std::__cxx11::list<Message> msgs)
{
for (const Message &msg : msgs) {
auto messages = rs485.buildMessages(); if (msg.send() != ESP_OK) {
RtcMemory::store(msg.getMessageAsMinifiedJsonString());
for (const Message &message : messages) { }
if(message.send() != ESP_OK){ unsigned long ts = millis();
RtcMemory::store(message.getMessageAsMinifiedJsonString()); // it takes ~110ms for receiving an acknowledgement by the host in perfect conditions
} uint16_t message_timeout = 2000;
delay(5000); while (!was_msg_received()) {
if(!was_msg_received()){ if ((millis() - ts) > message_timeout) {
RtcMemory::store(message.getMessageAsMinifiedJsonString()); 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) { } catch (const NoDataAvailableException &e) {
std::cerr << e.what() << '\n'; 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_LOGD(TAG, "Going to sleep for %d seconds", TIME_TO_SLEEP);
esp_deep_sleep_start();
esp_sleep_enable_timer_wakeup(TIME_TO_SLEEP * uS_TO_S_FACTOR);
esp_deep_sleep_start();
} }
void loop() {}
...@@ -6,14 +6,20 @@ ...@@ -6,14 +6,20 @@
#include <Arduino.h> #include <Arduino.h>
// Execution time: // 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 // https://github.com/makermoekoe/Picoclick-C3#speed-up-boot-process
// Part [ms] // Part [ms]
// Boot: 300
// First setup: 150 // First setup: 150
// Data aquisition: 500 // Data aquisition: 500 (4 Dendrometers)
// ESPNow setup: 220 // ESPNow setup: 220
// Sending 1200 // Sending 580
// TOTAL: 2200 // 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"; static const char *TAG = "MAIN";
...@@ -61,6 +67,11 @@ void setup() ...@@ -61,6 +67,11 @@ void setup()
DeepSleep::print_wakeup_reason(); DeepSleep::print_wakeup_reason();
DeepSleep::bootCount++; DeepSleep::bootCount++;
ESP_LOGD(TAG, "Boot number: %d", 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); gpio_set_level(GPIO_NUM_32, 1);
// delay(100); // delay(100);
......
#include "NoDataAvailableException.hpp"
#include <SentecSensors.h> #include <SentecSensors.h>
/*************************************** /***************************************
* RS485 SENSOR READOUT * RS485 SENSOR READOUT
****************************************/ ****************************************/
static const char *TAG = "SENTEC";
SentecSensorRS485::SentecSensorRS485(SoftwareSerial *ser, byte add) SentecSensorRS485::SentecSensorRS485(HardwareSerial *ser, byte add)
{ {
address = add; address = add;
RS485 = ser; RS485 = ser;
} }
SentecSensorRS485::SentecSensorRS485(SoftwareSerial *ser, byte add, uint8_t serialControlPin) SentecSensorRS485::SentecSensorRS485(HardwareSerial *ser, byte add, uint8_t serialControlPin)
{ {
address = add; address = add;
RS485 = ser; RS485 = ser;
...@@ -46,22 +47,23 @@ String SentecSensorRS485::getValueStr(int value) ...@@ -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 // request the address of the sensor with ONLY ONE SENSOR ON THE BUS
byte tmp_addr = address; // store the address in a temporary byte byte tmp_addr = address; // store the address in a temporary byte
address = 0xFF; // change the address to FF (0) for address check 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 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 // function code 0x03: get data measured by the sensor
byte query[8]; byte query[8];
...@@ -81,10 +83,10 @@ void SentecSensorRS485::readRegister(int registerStartAddress, int registerLengt ...@@ -81,10 +83,10 @@ void SentecSensorRS485::readRegister(int registerStartAddress, int registerLengt
// write the data request to the modbus line // write the data request to the modbus line
write(query, sizeof(query)); write(query, sizeof(query));
// get response from sensor // 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 // function code 0x06: change sensor settings
// e.g. a new address, reset rainfal data... // e.g. a new address, reset rainfal data...
...@@ -100,18 +102,20 @@ void SentecSensorRS485::writeRegister(int registerAddress, int value) ...@@ -100,18 +102,20 @@ void SentecSensorRS485::writeRegister(int registerAddress, int value)
query[4] = value >> 8; query[4] = value >> 8;
query[5] = value & 0xFF; query[5] = value & 0xFF;
calculateCRC(query, sizeof(query) - 2); calculateCRC(query, sizeof(query) - 2);
Serial.print("Query (settings): "); ESP_LOGD(TAG, "Query (settings): ");
printBytes(query, 8); printBytes(query, 8);
write(query, sizeof(query)); write(query, sizeof(query));
getResponse(); return getResponse();
} }
void SentecSensorRS485::setAddress(byte add) SentecSensorRS485::ReturnCode SentecSensorRS485::setAddress(byte add)
{ {
// change the address of a sensor // 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 // TODO check response: matches the sent message exactly
address = add; return tmp;
} }
void SentecSensorRS485::resetAnswerFrame() void SentecSensorRS485::resetAnswerFrame()
...@@ -121,9 +125,10 @@ void SentecSensorRS485::resetAnswerFrame() ...@@ -121,9 +125,10 @@ void SentecSensorRS485::resetAnswerFrame()
} }
} }
bool SentecSensorRS485::getResponse() SentecSensorRS485::ReturnCode SentecSensorRS485::getResponse()
{ {
// reads the response of a sensor // reads the response of a sensor
SentecSensorRS485::ReturnCode returnCode = SentecSensorRS485::ReturnCode::OK;
valid = true; valid = true;
int idx = 0; int idx = 0;
int byteReceived; int byteReceived;
...@@ -134,7 +139,7 @@ bool SentecSensorRS485::getResponse() ...@@ -134,7 +139,7 @@ bool SentecSensorRS485::getResponse()
const int timeout = 200; const int timeout = 200;
const int retries = 1; // #editet to q const int retries = 1; // #editet to q
size_t tries = 1; size_t tries = 1;
// it doesn't seem to help to request multiple times if first time goes wrong
for (tries; tries <= retries; tries++) { for (tries; tries <= retries; tries++) {
// if we lose connection with the sensor, we get an array of zeros back // if we lose connection with the sensor, we get an array of zeros back
resetAnswerFrame(); resetAnswerFrame();
...@@ -146,50 +151,48 @@ bool SentecSensorRS485::getResponse() ...@@ -146,50 +151,48 @@ bool SentecSensorRS485::getResponse()
// Serial.println(byteReceived, HEX); // Serial.println(byteReceived, HEX);
// check for first byte. It has to be the device address unless for broadcasts with address = 0xFF // check for first byte. It has to be the device address unless for broadcasts with address = 0xFF
if (idx == 0 && address != 0xFF && byteReceived != address) { if (idx == 0 && address != 0xFF && byteReceived != address) {
Serial.print("Invalid byte. First byte needs to be address 0x"); ESP_LOGE(TAG, "Invalid byte. First byte needs to be address 0x%02X but got 0x%02Xinstead");
Serial.print(address, HEX);
Serial.print(" but got 0x");
Serial.print(byteReceived, HEX);
Serial.println("instead");
} else { } else {
answerFrame[idx] = byteReceived; answerFrame[idx] = byteReceived;
// for reading register: third received byte is data length, read number of bytes accordingly // for reading register: third received byte is data length, read number of bytes accordingly
if (idx == 2 && answerFrame[1] == 0x03) { 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; responseLength = 5 + byteReceived;
} }
idx++; idx++;
} }
} }
} }
ESP_LOGD(TAG, "-----------------------------------------------------------------------------------------");
delay(10); ESP_LOGD(TAG, "Response: 0x%s", formatBytes(answerFrame, responseLength).c_str());
Serial.print("Response: 0x"); // ESP_LOGD(TAG, "Tries: %d", tries);
printBytes(answerFrame, responseLength); // ESP_LOGD(TAG, "Bytes received: %d", idx);
Serial.print("Tries: "); if (answerFrame[0] == 0) {
Serial.println(tries); ESP_LOGE(TAG, "Check sensor connection. First byte is 0x00.");
Serial.print("Bytes received: "); valid = false;
Serial.println(idx); 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_received = word(answerFrame[responseLength - 2], answerFrame[responseLength - 1]);
word crc = calculateCRC(answerFrame, responseLength - 2); word crc = calculateCRC(answerFrame, responseLength - 2);
if (crc_received != word(crc)) { if (valid && crc_received != word(crc)) {
Serial.print("CRC wrong: Expected "); ESP_LOGE(TAG, "CRC wrong: Expected 0x%s got 0x%s", formatBytes(crc).c_str(),
printBytes(crc); formatBytes(crc_received).c_str());
Serial.print(" got ");
printBytes(crc_received);
Serial.println();
valid = false; valid = false;
resetAnswerFrame(); resetAnswerFrame();
returnCode = SentecSensorRS485::ReturnCode::WRONG_CRC;
} }
// breaking after first successfull try
if (answerFrame[0] == 0) { if (returnCode == SentecSensorRS485::ReturnCode::OK) {
valid = false;
}
if (valid) {
break; break;
} }
} }
return valid;
// ESP_LOGE(TAG, "Returncode: %d", returnCode);
return returnCode;
} }
unsigned int SentecSensorRS485::calculateCRC(byte query[], int length) unsigned int SentecSensorRS485::calculateCRC(byte query[], int length)
...@@ -241,13 +244,31 @@ void SentecSensorRS485::printBytes(word data) ...@@ -241,13 +244,31 @@ void SentecSensorRS485::printBytes(word data)
Serial.print(tmp); 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() word SolarRadiationSensor::getSolarRadiation()
{ {
readRegister(0, 1); readRegister(0, 1);
glob = word(answerFrame[3], answerFrame[4]); glob = word(answerFrame[3], answerFrame[4]);
Serial.print("Global solar radiation: "); ESP_LOGI(TAG, "Global solar radiation: %d W/m^2", glob);
Serial.print(glob, DEC);
Serial.println(" W/m^2");
return glob; return glob;
} }
...@@ -282,9 +303,8 @@ word RainGaugeSensor::getInstantaneousPrecipitation() ...@@ -282,9 +303,8 @@ word RainGaugeSensor::getInstantaneousPrecipitation()
// manual says this is current precipitation - is it? // manual says this is current precipitation - is it?
readRegister(0, 0x01); readRegister(0, 0x01);
precipitation = word(answerFrame[3], answerFrame[4]); precipitation = word(answerFrame[3], answerFrame[4]);
Serial.print("Precipitation: ");
Serial.print(precipitation / 10.0, 1); ESP_LOGI(TAG, "Precipitation: %.1f mm", precipitation / 10.0);
Serial.println(" mm");
// resetPrecipitation(); // resetPrecipitation();
return precipitation; return precipitation;
} }
...@@ -304,13 +324,8 @@ float SoilMoistureSensor::getMoistureTemp() ...@@ -304,13 +324,8 @@ float SoilMoistureSensor::getMoistureTemp()
} else { } else {
temperatureRaw = (answerFrame[5] << 8) + answerFrame[6] - 65536; temperatureRaw = (answerFrame[5] << 8) + answerFrame[6] - 65536;
} }
Serial.begin(115200); ESP_LOGI(TAG, "Soil moisture: %.1f %", (moistureRaw - moistureOffset) / 10.0);
Serial.print("Soil moisture: "); ESP_LOGI(TAG, "Soil temperature: %.1f °C", (temperatureRaw - temperatureOffset) / 10.0);
Serial.print((moistureRaw - moistureOffset) / 10.0, 1);
Serial.println(" %");
Serial.print("Temperature: ");
Serial.print((temperatureRaw - temperatureOffset) / 10.0, 1);
Serial.println(" °C");
return (temperatureRaw - temperatureOffset) / 10.0; return (temperatureRaw - temperatureOffset) / 10.0;
} }
......
...@@ -2,32 +2,41 @@ ...@@ -2,32 +2,41 @@
#define SENTECSENSORS_H #define SENTECSENSORS_H
#include <Arduino.h> #include <Arduino.h>
#include <SoftwareSerial.h>
class SentecSensorRS485 { class SentecSensorRS485 {
public: public:
byte address; byte address;
uint8_t serialCommunicationControlPin = 19; uint8_t serialCommunicationControlPin = 19;
SoftwareSerial *RS485; HardwareSerial *RS485;
byte answerFrame[10]; byte answerFrame[10];
// TODO use valid flag to log None // TODO use valid flag to log None
bool valid = false; bool valid = false;
SentecSensorRS485(SoftwareSerial *ser, byte add); SentecSensorRS485(HardwareSerial *ser, byte add);
SentecSensorRS485(SoftwareSerial *ser, byte add, uint8_t serialControlPin); 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); void write(byte queryFrame[], int length);
String getValueStr(float value); String getValueStr(float value);
String getValueStr(int value); String getValueStr(int value);
void queryAddress(); SentecSensorRS485::ReturnCode queryAddress();
void readRegister(int registerStartAddress); SentecSensorRS485::ReturnCode readRegister(int registerStartAddress);
void readRegister(int registerStartAddress, int registerLength); SentecSensorRS485::ReturnCode readRegister(int registerStartAddress, int registerLength);
void writeRegister(int registerAddress, int value); SentecSensorRS485::ReturnCode writeRegister(int registerAddress, int value);
void setAddress(byte add); SentecSensorRS485::ReturnCode setAddress(byte add);
void resetAnswerFrame(); void resetAnswerFrame();
bool getResponse(); SentecSensorRS485::ReturnCode getResponse();
unsigned int calculateCRC(byte query[], int length); unsigned int calculateCRC(byte query[], int length);
void printBytes(byte *data, int length); void printBytes(byte *data, int length);
void printBytes(word data); void printBytes(word data);
std::string formatBytes(byte *data, int length);
std::string formatBytes(word data);
}; };
class SolarRadiationSensor : public SentecSensorRS485 { class SolarRadiationSensor : public SentecSensorRS485 {
......
#include "rs485.hpp" #include "rs485.hpp"
// RS485 control // RS485 control
#define RS485Serial Serial2
#define RXPin 14 // Serial Receive pin #define RXPin 14 // Serial Receive pin
#define TXPin 15 // Serial Transmit pin #define TXPin 15 // Serial Transmit pin
...@@ -8,8 +9,9 @@ ...@@ -8,8 +9,9 @@
#define POWER_SWITCH_PIN_12V 12 #define POWER_SWITCH_PIN_12V 12
#define POWER_SWITCH_PIN_5V 13 #define POWER_SWITCH_PIN_5V 13
static const char *TAG = "RS485";
// Configure sensors // Configure sensors
SoftwareSerial RS485Serial(TXPin, RXPin);
SolarRadiationSensor solarSensor(&RS485Serial, 1, RE_DE_PIN); SolarRadiationSensor solarSensor(&RS485Serial, 1, RE_DE_PIN);
RainGaugeSensor rainGauge = RainGaugeSensor(&RS485Serial, 2, RE_DE_PIN); // Give 2 Sensor Adress 2 RainGaugeSensor rainGauge = RainGaugeSensor(&RS485Serial, 2, RE_DE_PIN); // Give 2 Sensor Adress 2
SoilMoistureSensor soilSensor3 = SoilMoistureSensor(&RS485Serial, 3, RE_DE_PIN); //..... SoilMoistureSensor soilSensor3 = SoilMoistureSensor(&RS485Serial, 3, RE_DE_PIN); //.....
...@@ -22,9 +24,7 @@ void Forte_RS485::setup() ...@@ -22,9 +24,7 @@ void Forte_RS485::setup()
pinMode(RE_DE_PIN, OUTPUT); pinMode(RE_DE_PIN, OUTPUT);
pinMode(POWER_SWITCH_PIN_12V, OUTPUT); pinMode(POWER_SWITCH_PIN_12V, OUTPUT);
pinMode(POWER_SWITCH_PIN_5V, OUTPUT); pinMode(POWER_SWITCH_PIN_5V, OUTPUT);
// Set data rates: Serial baud rate has to be WAY HIGHER than RS485Serial! RS485Serial.begin(4800, SERIAL_8N1, TXPin, RXPin);
Serial.begin(115200);
RS485Serial.begin(4800);
} }
out_data_rs485 Forte_RS485::readData() out_data_rs485 Forte_RS485::readData()
...@@ -34,8 +34,9 @@ out_data_rs485 Forte_RS485::readData() ...@@ -34,8 +34,9 @@ out_data_rs485 Forte_RS485::readData()
digitalWrite(POWER_SWITCH_PIN_5V, HIGH); digitalWrite(POWER_SWITCH_PIN_5V, HIGH);
// Wait for sensors to power up // Wait for sensors to power up
// TODO minimize delay // TODO minimize delay
delay(500); delay(300);
out_data_rs485 output; out_data_rs485 output;
unsigned long ts = millis();
output.solarRadiation = solarSensor.getSolarRadiation(); output.solarRadiation = solarSensor.getSolarRadiation();
output.soilTemperature3 = soilSensor3.getMoistureTemp(); output.soilTemperature3 = soilSensor3.getMoistureTemp();
output.soilTemperature4 = soilSensor4.getMoistureTemp(); output.soilTemperature4 = soilSensor4.getMoistureTemp();
......
#ifndef _RS485 #ifndef _RS485
#define _RS485 #define _RS485
#include "SPI.h"
// RTC (I2C)
#include "RTClib.h"
#include "Message.hpp" #include "Message.hpp"
#include "ForteSensor.hpp" #include "ForteSensor.hpp"
#include "SentecSensors.h" #include "SentecSensors.h"
......
This diff is collapsed.
...@@ -131,6 +131,14 @@ void setupSDCard(); ...@@ -131,6 +131,14 @@ void setupSDCard();
void syncUTCTimeToRTC(); void syncUTCTimeToRTC();
void on_data_recv(const uint8_t *mac, const uint8_t *incomingData, int len) 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"); esp_log_write(ESP_LOG_INFO, TAG_ESPNOW.c_str(), "Message recieved\n");
// copy received data to a char array // copy received data to a char array
char data[len]; char data[len];
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment