removed irrelevant files

refactored-fdrs
Timm Bogner 2 years ago
parent 921523f3d4
commit f37cb1505f

@ -1,33 +0,0 @@
// A list of all datatypes you can use within FDRS.
// If you are missing any data type, please open an issue at:
// https://github.com/timmbogner/Farm-Data-Relay-System/issues
#ifndef FDRS_DATA_TYPES
#define FDRS_DATA_TYPES
#define STATUS_T 0 // Status
#define TEMP_T 1 // Temperature
#define TEMP2_T 2 // Temperature #2
#define HUMIDITY_T 3 // Relative Humidity
#define PRESSURE_T 4 // Atmospheric Pressure
#define LIGHT_T 5 // Light (lux)
#define SOIL_T 6 // Soil Moisture
#define SOIL2_T 7 // Soil Moisture #2
#define SOILR_T 8 // Soil Resistance
#define SOILR2_T 9 // Soil Resistance #2
#define OXYGEN_T 10 // Oxygen
#define CO2_T 11 // Carbon Dioxide
#define WINDSPD_T 12 // Wind Speed
#define WINDHDG_T 13 // Wind Direction
#define RAINFALL_T 14 // Rainfall
#define MOTION_T 15 // Motion
#define VOLTAGE_T 16 // Voltage
#define VOLTAGE2_T 17 // Voltage #2
#define CURRENT_T 18 // Current
#define CURRENT2_T 19 // Current #2
#define IT_T 20 // Iterations
#define LATITUDE_T 21 // GPS Latitude
#define LONGITUDE_T 22 // GPS Longitude
#define ALTITUDE_T 23 // GPS Altitude
#endif //FDRS_DATA_TYPES

@ -1,708 +0,0 @@
// FARM DATA RELAY SYSTEM
//
// GATEWAY 2.000 Functions
// This is the 'meat and potatoes' of FDRS, and should not be fooled with unless improving/adding features.
// Developed by Timm Bogner (timmbogner@gmail.com)
#ifndef __FDRS_FUNCTIONS_H__
#define __FDRS_FUNCTIONS_H__
enum {
event_clear,
event_espnowg,
event_espnow1,
event_espnow2,
event_serial,
event_mqtt,
event_lorag,
event_lora1,
event_lora2
};
#ifdef FDRS_DEBUG
#define DBG(a) (Serial.println(a))
#else
#define DBG(a)
#endif
#if defined (ESP32)
#define UART_IF Serial1
#else
#define UART_IF Serial
#endif
#ifdef FDRS_GLOBALS
#define FDRS_WIFI_SSID GLOBAL_SSID
#define FDRS_WIFI_PASS GLOBAL_PASS
#define FDRS_MQTT_ADDR GLOBAL_MQTT_ADDR
#define FDRS_MQTT_PORT GLOBAL_MQTT_PORT
#define FDRS_MQTT_USER GLOBAL_MQTT_USER
#define FDRS_MQTT_PASS GLOBAL_MQTT_PASS
#define FDRS_BAND GLOBAL_LORA_BAND
#define FDRS_SF GLOBAL_LORA_SF
#else
#define FDRS_WIFI_SSID WIFI_SSID
#define FDRS_WIFI_PASS WIFI_PASS
#define FDRS_MQTT_ADDR MQTT_ADDR
#define FDRS_MQTT_PORT MQTT_PORT
#define FDRS_MQTT_USER MQTT_USER
#define FDRS_MQTT_PASS MQTT_PASS
#define FDRS_BAND LORA_BAND
#define FDRS_SF LORA_SF
#endif
#if defined (MQTT_AUTH) || defined (GLOBAL_MQTT_AUTH)
#define FDRS_MQTT_AUTH
#endif
#define MAC_PREFIX 0xAA, 0xBB, 0xCC, 0xDD, 0xEE // Should only be changed if implementing multiple FDRS systems.
typedef struct __attribute__((packed)) DataReading {
float d;
uint16_t id;
uint8_t t;
} DataReading;
const uint8_t espnow_size = 250 / sizeof(DataReading);
const uint8_t lora_size = 256 / sizeof(DataReading);
const uint8_t mac_prefix[] = {MAC_PREFIX};
#ifdef ESP32
esp_now_peer_info_t peerInfo;
#endif
uint8_t broadcast_mac[] = {0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF};
uint8_t selfAddress[] = {MAC_PREFIX, UNIT_MAC};
uint8_t incMAC[6];
#ifdef ESPNOW1_PEER
uint8_t ESPNOW1[] = {MAC_PREFIX, ESPNOW1_PEER};
#else
uint8_t ESPNOW1[] = {0x00, 0x00, 0x00, 0x00, 0x00, 0x00};
#endif
#ifdef ESPNOW2_PEER
uint8_t ESPNOW2[] = {MAC_PREFIX, ESPNOW2_PEER};
#else
uint8_t ESPNOW2[] = {0x00, 0x00, 0x00, 0x00, 0x00, 0x00};
#endif
#ifdef USE_LORA
uint8_t LoRa1[] = {mac_prefix[3], mac_prefix[4], LORA1_PEER};
uint8_t LoRa2[] = {mac_prefix[3], mac_prefix[4], LORA2_PEER};
//uint8_t LoRaAddress[] = {0x42, 0x00};
#endif
#if defined (USE_SD_LOG) || defined (USE_FS_LOG)
char logBuffer[512];
uint16_t logBufferPos = 0; // datatype depends on size of sdBuffer
uint32_t timeLOGBUF = 0;
#endif
DataReading theData[256];
uint8_t ln;
uint8_t newData = event_clear;
DataReading ESPNOW1buffer[256];
uint8_t lenESPNOW1 = 0;
uint32_t timeESPNOW1 = 0;
DataReading ESPNOW2buffer[256];
uint8_t lenESPNOW2 = 0;
uint32_t timeESPNOW2 = 0;
DataReading ESPNOWGbuffer[256];
uint8_t lenESPNOWG = 0;
uint32_t timeESPNOWG = 0;
DataReading SERIALbuffer[256];
uint8_t lenSERIAL = 0;
uint32_t timeSERIAL = 0;
DataReading MQTTbuffer[256];
uint8_t lenMQTT = 0;
uint32_t timeMQTT = 0;
DataReading LORAGbuffer[256];
uint8_t lenLORAG = 0;
uint32_t timeLORAG = 0;
DataReading LORA1buffer[256];
uint8_t lenLORA1 = 0;
uint32_t timeLORA1 = 0;
DataReading LORA2buffer[256];
uint8_t lenLORA2 = 0;
uint32_t timeLORA2 = 0;
WiFiClient espClient;
#ifdef USE_LED
CRGB leds[NUM_LEDS];
#endif
#ifdef USE_WIFI
PubSubClient client(espClient);
const char* ssid = FDRS_WIFI_SSID;
const char* password = FDRS_WIFI_PASS;
const char* mqtt_server = FDRS_MQTT_ADDR;
const int mqtt_port = FDRS_MQTT_PORT;
#endif
#ifdef FDRS_MQTT_AUTH
const char* mqtt_user = FDRS_MQTT_USER;
const char* mqtt_pass = FDRS_MQTT_PASS;
#else
const char* mqtt_user = NULL;
const char* mqtt_pass = NULL;
#endif
// Set ESP-NOW send and receive callbacks for either ESP8266 or ESP32
#if defined(ESP8266)
void OnDataSent(uint8_t *mac_addr, uint8_t sendStatus) {
}
void OnDataRecv(uint8_t* mac, uint8_t *incomingData, uint8_t len) {
#elif defined(ESP32)
void OnDataSent(const uint8_t *mac_addr, esp_now_send_status_t status) {
}
void OnDataRecv(const uint8_t * mac, const uint8_t *incomingData, int len) {
#endif
memcpy(&theData, incomingData, sizeof(theData));
memcpy(&incMAC, mac, sizeof(incMAC));
DBG("Incoming ESP-NOW.");
ln = len / sizeof(DataReading);
if (memcmp(&incMAC, &ESPNOW1, 6) == 0) {
newData = event_espnow1;
return;
}
if (memcmp(&incMAC, &ESPNOW2, 6) == 0) {
newData = event_espnow2;
return;
}
newData = event_espnowg;
}
void getSerial() {
String incomingString = UART_IF.readStringUntil('\n');
DynamicJsonDocument doc(24576);
DeserializationError error = deserializeJson(doc, incomingString);
if (error) { // Test if parsing succeeds.
// DBG("json parse err");
// DBG(incomingString);
return;
} else {
int s = doc.size();
//UART_IF.println(s);
for (int i = 0; i < s; i++) {
theData[i].id = doc[i]["id"];
theData[i].t = doc[i]["type"];
theData[i].d = doc[i]["data"];
}
ln = s;
newData = event_serial;
DBG("Incoming Serial.");
}
}
#if defined (USE_SD_LOG) || defined (USE_FS_LOG)
void releaseLogBuffer()
{
#ifdef USE_SD_LOG
DBG("Releasing Log buffer to SD");
File logfile = SD.open(SD_FILENAME, FILE_WRITE);
logfile.print(logBuffer);
logfile.close();
#endif
#ifdef USE_FS_LOG
DBG("Releasing Log buffer to internal flash.");
File logfile = LittleFS.open(FS_FILENAME, "a");
logfile.print(logBuffer);
logfile.close();
#endif
memset(&(logBuffer[0]), 0, sizeof(logBuffer)/sizeof(char));
logBufferPos = 0;
}
#endif
void sendLog()
{
#if defined (USE_SD_LOG) || defined (USE_FS_LOG)
DBG("Logging to buffer");
for (int i = 0; i < ln; i++)
{
char linebuf[34]; // size depends on resulting length of the formatting string
sprintf(linebuf, "%lld,%d,%d,%g\r\n", time(nullptr), theData[i].id, theData[i].t, theData[i].d);
if (logBufferPos+strlen(linebuf) >= (sizeof(logBuffer)/sizeof(char))) // if buffer would overflow, release first
{
releaseLogBuffer();
}
memcpy(&logBuffer[logBufferPos], linebuf, strlen(linebuf)); //append line to buffer
logBufferPos+=strlen(linebuf);
}
#endif
}
void reconnect(short int attempts, bool silent) {
#ifdef USE_WIFI
if (!silent) DBG("Connecting MQTT...");
for (short int i = 1; i <= attempts; i++) {
// Attempt to connect
if (client.connect("FDRS_GATEWAY", mqtt_user, mqtt_pass)) {
// Subscribe
client.subscribe(TOPIC_COMMAND);
if (!silent) DBG(" MQTT Connected");
return;
} else {
if (!silent) {
char msg[23];
sprintf(msg, " Attempt %d/%d", i, attempts);
DBG(msg);
}
if ((attempts = !1)) {
delay(3000);
}
}
}
if (!silent) DBG(" Connecting MQTT failed.");
#endif
}
void reconnect(int attempts) {
reconnect(attempts, false);
}
void mqtt_callback(char* topic, byte * message, unsigned int length) {
String incomingString;
DBG(topic);
for (unsigned int i = 0; i < length; i++) {
incomingString += (char)message[i];
}
StaticJsonDocument<2048> doc;
DeserializationError error = deserializeJson(doc, incomingString);
if (error) { // Test if parsing succeeds.
DBG("json parse err");
DBG(incomingString);
return;
} else {
int s = doc.size();
//UART_IF.println(s);
for (int i = 0; i < s; i++) {
theData[i].id = doc[i]["id"];
theData[i].t = doc[i]["type"];
theData[i].d = doc[i]["data"];
}
ln = s;
newData = event_mqtt;
DBG("Incoming MQTT.");
}
}
void mqtt_publish(const char* payload) {
#ifdef USE_WIFI
if (!client.publish(TOPIC_DATA, payload)) {
DBG(" Error on sending MQTT");
sendLog();
}
#endif
}
void getLoRa() {
#ifdef USE_LORA
int packetSize = LoRa.parsePacket();
if (packetSize) {
uint8_t packet[packetSize];
uint8_t incLORAMAC[2];
LoRa.readBytes((uint8_t *)&packet, packetSize);
ln = (packetSize - 5) / sizeof(DataReading);
DBG("Incoming LoRa.");
if (memcmp(&packet, &selfAddress[3], 3) == 0) { //Check if addressed to this device
memcpy(&incLORAMAC, &packet[3], 2); //Split off address portion of packet
memcpy(&theData, &packet[5], packetSize - 5); //Split off data portion of packet
if (memcmp(&incLORAMAC, &LoRa1, 2) == 0) { //Check if it is from a registered sender
newData = event_lora1;
return;
}
if (memcmp(&incLORAMAC, &LoRa2, 2) == 0) {
newData = event_lora2;
return;
}
newData = event_lorag;
}
}
#endif
}
void sendESPNOW(uint8_t address) {
DBG("Sending ESP-NOW.");
uint8_t NEWPEER[] = {MAC_PREFIX, address};
#if defined(ESP32)
esp_now_peer_info_t peerInfo;
peerInfo.ifidx = WIFI_IF_STA;
peerInfo.channel = 0;
peerInfo.encrypt = false;
memcpy(peerInfo.peer_addr, NEWPEER, 6);
if (esp_now_add_peer(&peerInfo) != ESP_OK) {
DBG("Failed to add peer");
return;
}
#endif
DataReading thePacket[ln];
int j = 0;
for (int i = 0; i < ln; i++) {
if ( j > espnow_size) {
j = 0;
esp_now_send(NEWPEER, (uint8_t *) &thePacket, sizeof(thePacket));
}
thePacket[j] = theData[i];
j++;
}
esp_now_send(NEWPEER, (uint8_t *) &thePacket, j * sizeof(DataReading));
esp_now_del_peer(NEWPEER);
}
void sendSerial() {
DBG("Sending Serial.");
DynamicJsonDocument doc(24576);
for (int i = 0; i < ln; i++) {
doc[i]["id"] = theData[i].id;
doc[i]["type"] = theData[i].t;
doc[i]["data"] = theData[i].d;
}
serializeJson(doc, UART_IF);
UART_IF.println();
#ifndef ESP8266
serializeJson(doc, Serial);
Serial.println();
#endif
}
void sendMQTT() {
#ifdef USE_WIFI
DBG("Sending MQTT.");
DynamicJsonDocument doc(24576);
for (int i = 0; i < ln; i++) {
doc[i]["id"] = theData[i].id;
doc[i]["type"] = theData[i].t;
doc[i]["data"] = theData[i].d;
}
String outgoingString;
serializeJson(doc, outgoingString);
mqtt_publish((char*) outgoingString.c_str());
#endif
}
void bufferESPNOW(uint8_t interface) {
DBG("Buffering ESP-NOW.");
switch (interface) {
case 0:
for (int i = 0; i < ln; i++) {
ESPNOWGbuffer[lenESPNOWG + i] = theData[i];
}
lenESPNOWG += ln;
break;
case 1:
for (int i = 0; i < ln; i++) {
ESPNOW1buffer[lenESPNOW1 + i] = theData[i];
}
lenESPNOW1 += ln;
break;
case 2:
for (int i = 0; i < ln; i++) {
ESPNOW2buffer[lenESPNOW2 + i] = theData[i];
}
lenESPNOW2 += ln;
break;
}
}
void bufferSerial() {
DBG("Buffering Serial.");
for (int i = 0; i < ln; i++) {
SERIALbuffer[lenSERIAL + i] = theData[i];
}
lenSERIAL += ln;
//UART_IF.println("SENDSERIAL:" + String(lenSERIAL) + " ");
}
void bufferMQTT() {
DBG("Buffering MQTT.");
for (int i = 0; i < ln; i++) {
MQTTbuffer[lenMQTT + i] = theData[i];
}
lenMQTT += ln;
}
//void bufferLoRa() {
// for (int i = 0; i < ln; i++) {
// LORAbuffer[lenLORA + i] = theData[i];
// }
// lenLORA += ln;
//}
void bufferLoRa(uint8_t interface) {
DBG("Buffering LoRa.");
switch (interface) {
case 0:
for (int i = 0; i < ln; i++) {
LORAGbuffer[lenLORAG + i] = theData[i];
}
lenLORAG += ln;
break;
case 1:
for (int i = 0; i < ln; i++) {
LORA1buffer[lenLORA1 + i] = theData[i];
}
lenLORA1 += ln;
break;
case 2:
for (int i = 0; i < ln; i++) {
LORA2buffer[lenLORA2 + i] = theData[i];
}
lenLORA2 += ln;
break;
}
}
void releaseESPNOW(uint8_t interface) {
DBG("Releasing ESP-NOW.");
switch (interface) {
case 0:
{
DataReading thePacket[espnow_size];
int j = 0;
for (int i = 0; i < lenESPNOWG; i++) {
if ( j > espnow_size) {
j = 0;
esp_now_send(broadcast_mac, (uint8_t *) &thePacket, sizeof(thePacket));
}
thePacket[j] = ESPNOWGbuffer[i];
j++;
}
esp_now_send(broadcast_mac, (uint8_t *) &thePacket, j * sizeof(DataReading));
lenESPNOWG = 0;
break;
}
case 1:
{
DataReading thePacket[espnow_size];
int j = 0;
for (int i = 0; i < lenESPNOW1; i++) {
if ( j > espnow_size) {
j = 0;
esp_now_send(ESPNOW1, (uint8_t *) &thePacket, sizeof(thePacket));
}
thePacket[j] = ESPNOW1buffer[i];
j++;
}
esp_now_send(ESPNOW1, (uint8_t *) &thePacket, j * sizeof(DataReading));
lenESPNOW1 = 0;
break;
}
case 2:
{
DataReading thePacket[espnow_size];
int j = 0;
for (int i = 0; i < lenESPNOW2; i++) {
if ( j > espnow_size) {
j = 0;
esp_now_send(ESPNOW2, (uint8_t *) &thePacket, sizeof(thePacket));
}
thePacket[j] = ESPNOW2buffer[i];
j++;
}
esp_now_send(ESPNOW2, (uint8_t *) &thePacket, j * sizeof(DataReading));
lenESPNOW2 = 0;
break;
}
}
}
#ifdef USE_LORA
void transmitLoRa(uint8_t* mac, DataReading * packet, uint8_t len) {
DBG("Transmitting LoRa.");
uint8_t pkt[5 + (len * sizeof(DataReading))];
memcpy(&pkt, mac, 3);
memcpy(&pkt[3], &selfAddress[4], 2);
memcpy(&pkt[5], packet, len * sizeof(DataReading));
LoRa.beginPacket();
LoRa.write((uint8_t*)&pkt, sizeof(pkt));
LoRa.endPacket();
}
#endif
void releaseLoRa(uint8_t interface) {
#ifdef USE_LORA
DBG("Releasing LoRa.");
switch (interface) {
case 0:
{
DataReading thePacket[lora_size];
int j = 0;
for (int i = 0; i < lenLORAG; i++) {
if ( j > lora_size) {
j = 0;
transmitLoRa(broadcast_mac, thePacket, j);
}
thePacket[j] = LORAGbuffer[i];
j++;
}
transmitLoRa(broadcast_mac, thePacket, j);
lenLORAG = 0;
break;
}
case 1:
{
DataReading thePacket[lora_size];
int j = 0;
for (int i = 0; i < lenLORA1; i++) {
if ( j > lora_size) {
j = 0;
transmitLoRa(LoRa1, thePacket, j);
}
thePacket[j] = LORA1buffer[i];
j++;
}
transmitLoRa(LoRa1, thePacket, j);
lenLORA1 = 0;
break;
}
case 2:
{
DataReading thePacket[lora_size];
int j = 0;
for (int i = 0; i < lenLORA2; i++) {
if ( j > lora_size) {
j = 0;
transmitLoRa(LoRa2, thePacket, j);
}
thePacket[j] = LORA2buffer[i];
j++;
}
transmitLoRa(LoRa2, thePacket, j);
lenLORA2 = 0;
break;
}
}
#endif //USE_LORA
}
void releaseSerial() {
DBG("Releasing Serial.");
DynamicJsonDocument doc(24576);
for (int i = 0; i < lenSERIAL; i++) {
doc[i]["id"] = SERIALbuffer[i].id;
doc[i]["type"] = SERIALbuffer[i].t;
doc[i]["data"] = SERIALbuffer[i].d;
}
serializeJson(doc, UART_IF);
UART_IF.println();
lenSERIAL = 0;
}
void releaseMQTT() {
#ifdef USE_WIFI
DBG("Releasing MQTT.");
DynamicJsonDocument doc(24576);
for (int i = 0; i < lenMQTT; i++) {
doc[i]["id"] = MQTTbuffer[i].id;
doc[i]["type"] = MQTTbuffer[i].t;
doc[i]["data"] = MQTTbuffer[i].d;
}
String outgoingString;
serializeJson(doc, outgoingString);
mqtt_publish((char*) outgoingString.c_str());
lenMQTT = 0;
#endif
}
void begin_espnow() {
DBG("Initializing ESP-NOW!");
WiFi.mode(WIFI_STA);
WiFi.disconnect();
// Init ESP-NOW for either ESP8266 or ESP32 and set MAC address
#if defined(ESP8266)
wifi_set_macaddr(STATION_IF, selfAddress);
if (esp_now_init() != 0) {
return;
}
esp_now_set_self_role(ESP_NOW_ROLE_COMBO);
esp_now_register_send_cb(OnDataSent);
esp_now_register_recv_cb(OnDataRecv);
// Register peers
#ifdef ESPNOW1_PEER
esp_now_add_peer(ESPNOW1, ESP_NOW_ROLE_COMBO, 0, NULL, 0);
#endif
#ifdef ESPNOW2_PEER
esp_now_add_peer(ESPNOW2, ESP_NOW_ROLE_COMBO, 0, NULL, 0);
#endif
#elif defined(ESP32)
esp_wifi_set_mac(WIFI_IF_STA, &selfAddress[0]);
if (esp_now_init() != ESP_OK) {
DBG("Error initializing ESP-NOW");
return;
}
esp_now_register_send_cb(OnDataSent);
esp_now_register_recv_cb(OnDataRecv);
peerInfo.channel = 0;
peerInfo.encrypt = false;
// Register first peer
memcpy(peerInfo.peer_addr, broadcast_mac, 6);
if (esp_now_add_peer(&peerInfo) != ESP_OK) {
DBG("Failed to add peer bcast");
return;
}
#ifdef ESPNOW1_PEER
memcpy(peerInfo.peer_addr, ESPNOW1, 6);
if (esp_now_add_peer(&peerInfo) != ESP_OK) {
DBG("Failed to add peer 1");
return;
}
#endif
#ifdef ESPNOW2_PEER
memcpy(peerInfo.peer_addr, ESPNOW2, 6);
if (esp_now_add_peer(&peerInfo) != ESP_OK) {
DBG("Failed to add peer 2");
return;
}
#endif
#endif //ESP8266
DBG(" ESP-NOW Initialized.");
}
void begin_lora() {
#ifdef USE_LORA
DBG("Initializing LoRa!");
#ifdef ESP32
SPI.begin(SPI_SCK, SPI_MISO, SPI_MOSI);
#endif
LoRa.setPins(LORA_SS, LORA_RST, LORA_DIO0);
if (!LoRa.begin(FDRS_BAND)) {
DBG(" Initialization failed!");
while (1);
}
LoRa.setSpreadingFactor(FDRS_SF);
DBG(" LoRa initialized.");
#endif //USE_LORA
}
void begin_SD() {
#ifdef USE_SD_LOG
DBG("Initializing SD card...");
#ifdef ESP32
SPI.begin(SCK, MISO, MOSI);
#endif
if (!SD.begin(SD_SS)) {
DBG(" Initialization failed!");
while (1);
} else {
DBG(" SD initialized.");
}
#endif //USE_SD_LOG
}
void begin_FS() {
#ifdef USE_FS_LOG
DBG("Initializing LittleFS...");
if (!LittleFS.begin())
{
DBG(" initialization failed");
while (1);
}
else
{
DBG(" LittleFS initialized");
}
#endif
}
#endif //__FDRS_FUNCTIONS_H__

@ -1,22 +0,0 @@
/* FARM DATA RELAY SYSTEM
*
* "fdrs_globals.h"
*
* Developed by Timm Bogner (timmbogner@gmail.com) for Sola Gratia Farm in Urbana, Illinois, USA.
*/
#ifndef FDRS_GLOBALS
#define FDRS_GLOBALS
#define GLOBAL_SSID "Your SSID"
#define GLOBAL_PASS "Password"
#define GLOBAL_MQTT_ADDR "192.168.0.8"
#define GLOBAL_MQTT_PORT 1883
//#define GLOBAL_MQTT_AUTH //Enable MQTT authentication
#define GLOBAL_MQTT_USER "Your MQTT Username"
#define GLOBAL_MQTT_PASS "Your MQTT Password"
#define GLOBAL_LORA_BAND 915E6 //LoRa Frequency Band
#define GLOBAL_LORA_SF 7 //LoRa Spreading Factor
#endif //FDRS_GLOBALS

@ -1,157 +0,0 @@
// FARM DATA RELAY SYSTEM
//
// "fdrs_sensor.h"
//
// Developed by Timm Bogner (timmbogner@gmail.com) for Sola Gratia Farm in Urbana, Illinois, USA.
//
#include <fdrs_datatypes.h>
#if defined(ESP8266)
#include <ESP8266WiFi.h>
#include <espnow.h>
#elif defined(ESP32)
#include <esp_now.h>
#include <WiFi.h>
#include <esp_wifi.h>
#endif
#ifdef USE_LORA
#include <LoRa.h>
#endif
#ifdef FDRS_GLOBALS
#define FDRS_BAND GLOBAL_LORA_BAND
#define FDRS_SF GLOBAL_LORA_SF
#else
#define FDRS_BAND LORA_BAND
#define FDRS_SF LORA_SF
#endif
#ifdef FDRS_DEBUG
#define DBG(a) (Serial.println(a))
#else
#define DBG(a)
#endif
#define MAC_PREFIX 0xAA, 0xBB, 0xCC, 0xDD, 0xEE // Should only be changed if implementing multiple FDRS systems.
typedef struct __attribute__((packed)) DataReading {
float d;
uint16_t id;
uint8_t t;
} DataReading;
const uint16_t espnow_size = 250 / sizeof(DataReading);
uint8_t gatewayAddress[] = {MAC_PREFIX, GTWY_MAC};
uint8_t gtwyAddress[] = {gatewayAddress[3], gatewayAddress[4], GTWY_MAC};
uint8_t LoRaAddress[] = {0x42, 0x00};
uint32_t wait_time = 0;
DataReading fdrsData[espnow_size];
uint8_t data_count = 0;
void beginFDRS() {
#ifdef FDRS_DEBUG
Serial.begin(115200);
#endif
DBG("FDRS Sensor ID " + String(READING_ID) + " initializing...");
DBG(" Gateway: " + String (GTWY_MAC, HEX));
#ifdef POWER_CTRL
DBG("Powering up the sensor array!");
pinMode(POWER_CTRL, OUTPUT);
digitalWrite(POWER_CTRL, 1);
#endif
// Init ESP-NOW for either ESP8266 or ESP32 and set MAC address
#ifdef USE_ESPNOW
DBG("Initializing ESP-NOW!");
WiFi.mode(WIFI_STA);
WiFi.disconnect();
#if defined(ESP8266)
if (esp_now_init() != 0) {
return;
}
esp_now_set_self_role(ESP_NOW_ROLE_COMBO);
// Register peers
esp_now_add_peer(gatewayAddress, ESP_NOW_ROLE_COMBO, 0, NULL, 0);
#elif defined(ESP32)
if (esp_now_init() != ESP_OK) {
DBG("Error initializing ESP-NOW");
return;
}
esp_now_peer_info_t peerInfo;
peerInfo.ifidx = WIFI_IF_STA;
peerInfo.channel = 0;
peerInfo.encrypt = false;
// Register first peer
memcpy(peerInfo.peer_addr, gatewayAddress, 6);
if (esp_now_add_peer(&peerInfo) != ESP_OK) {
DBG("Failed to add peer");
return;
}
#endif
DBG(" ESP-NOW Initialized.");
#endif
#ifdef USE_LORA
DBG("Initializing LoRa!");
DBG(FDRS_BAND);
DBG(FDRS_SF);
#ifdef ESP32
SPI.begin(SPI_SCK, SPI_MISO, SPI_MOSI);
#endif
LoRa.setPins(LORA_SS, LORA_RST, LORA_DIO0);
if (!LoRa.begin(FDRS_BAND)) {
DBG("Unable to initialize LoRa!");
while (1);
}
LoRa.setSpreadingFactor(FDRS_SF);
DBG(" LoRa Initialized.");
#endif
}
void transmitLoRa(uint8_t* mac, DataReading * packet, uint8_t len) {
#ifdef USE_LORA
uint8_t pkt[5 + (len * sizeof(DataReading))];
memcpy(&pkt, mac, 3); //
memcpy(&pkt[3], &LoRaAddress, 2);
memcpy(&pkt[5], packet, len * sizeof(DataReading));
LoRa.beginPacket();
LoRa.write((uint8_t*)&pkt, sizeof(pkt));
LoRa.endPacket();
#endif
}
void sendFDRS() {
DBG("Sending FDRS Packet!");
#ifdef USE_ESPNOW
esp_now_send(gatewayAddress, (uint8_t *) &fdrsData, data_count * sizeof(DataReading));
delay(5);
DBG(" ESP-NOW sent.");
#endif
#ifdef USE_LORA
transmitLoRa(gtwyAddress, fdrsData, data_count);
DBG(" LoRa sent.");
#endif
data_count = 0;
}
void loadFDRS(float d, uint8_t t) {
DBG("Data loaded. Type: " + String(t));
if (data_count > espnow_size) sendFDRS();
DataReading dr;
dr.id = READING_ID;
dr.t = t;
dr.d = d;
fdrsData[data_count] = dr;
data_count++;
}
void sleepFDRS(int sleep_time) {
DBG("Sleepytime!");
#ifdef DEEP_SLEEP
DBG(" Deep sleeping.");
#ifdef ESP32
esp_sleep_enable_timer_wakeup(sleep_time * 1000000);
esp_deep_sleep_start();
#endif
#ifdef ESP8266
ESP.deepSleep(sleep_time * 1000000);
#endif
#endif
DBG(" Delaying.");
delay(sleep_time * 1000);
}
Loading…
Cancel
Save