Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
53 changes: 30 additions & 23 deletions examples/Lab Examples/Dendrometer/hub/hub.ino
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
#include "arduino_secrets.h"

#include <Loom_Manager.h>
#include <Loom_Manager.h> //4.7

#include <Hardware/Loom_Hypnos/Loom_Hypnos.h>
#include <Radio/Loom_LoRa/Loom_LoRa.h>
Expand All @@ -11,13 +11,14 @@
const unsigned long REPORT_INTERVAL = 1 * 60 * 60 * 1000;

Manager manager("Hub", 0);

Loom_Hypnos hypnos(manager, HYPNOS_VERSION::V3_3, TIME_ZONE::PST);
Loom_Analog batteryVoltage(manager);
Loom_LoRa lora(manager);
Loom_LTE lte(manager, "hologram", "", "", A5);
Loom_MongoDB mqtt(manager, lte.getClient(), SECRET_BROKER, SECRET_PORT, DATABASE, BROKER_USER, BROKER_PASS);
Loom_MongoDB mqtt(manager, lte, SECRET_BROKER, SECRET_PORT, DATABASE, BROKER_USER, BROKER_PASS);
Loom_BatchSD batchSD(hypnos, 16); //set batch size uploading

int packetNumber = 0;
void setup()
{
// Start the serial interface
Expand All @@ -28,6 +29,10 @@ void setup()

setRTC();

// Sets the LTE board to use batch SD to only start when we actually need to publish data
lte.setBatchSD(batchSD);


// load MQTT credentials from the SD card, if they exist
mqtt.loadConfigFromJSON(hypnos.readFile("mqtt_creds.json"));

Expand All @@ -38,28 +43,30 @@ void setup()
void loop()
{
// Wait 5 seconds for a message
if (lora.receive(5000))
{
manager.display_data();
hypnos.logToSD();
mqtt.publish();
}

static unsigned long timer = millis();
if (millis() - timer > REPORT_INTERVAL)
{
manager.set_device_name("Hub");
manager.set_instance_num(0);

manager.measure();
manager.package();
manager.display_data();
mqtt.publish();

timer = millis();
}
do{
if (lora.receiveBatch(5000, &packetNumber))
{
manager.display_data();
hypnos.logToSD();
mqtt.publish(batchSD);
}
}while(packetNumber > 0);
static unsigned long timer = millis();
if (millis() - timer > REPORT_INTERVAL)
{
manager.set_device_name("Hub");
manager.set_instance_num(0);

manager.measure();
manager.package();
manager.display_data();
mqtt.publish();

timer = millis();
}
}


void setRTC()
{
if (!Serial)
Expand Down
67 changes: 19 additions & 48 deletions examples/Lab Examples/Dendrometer/node/node.ino
Original file line number Diff line number Diff line change
@@ -1,29 +1,26 @@
#include <Loom_Manager.h> //4.3
#include <Loom_Manager.h> //4.6
#include <Hardware/Loom_Hypnos/Loom_Hypnos.h>
#include <Hardware/Actuators/Loom_Neopixel/Loom_Neopixel.h>
#include <Sensors/Loom_Analog/Loom_Analog.h>
#include <Sensors/Analog/Loom_Teros10/Loom_Teros10.h>
#include <Sensors/I2C/Loom_SHT31/Loom_SHT31.h>
#include <Radio/Loom_LoRa/Loom_LoRa.h>
#include <Internet/Connectivity/Loom_Wifi/Loom_Wifi.h>
#include <Internet/Logging/Loom_MongoDB/Loom_MongoDB.h>


#include "AS5311.h"

//////////////////////////
/* DEVICE CONFIGURATION */
//////////////////////////
static const uint8_t NODE_NUMBER = 1;
static const char * DEVICE_NAME = "BlueberryDendrometer_";
static const char * DEVICE_NAME = "HazelnutDendrometer_";
////Select one wireless communication option
#define DENDROMETER_LORA
// #define DENDROMETER_WIFI
////These two time values are added together to determine the measurement interval
static const int8_t MEASUREMENT_INTERVAL_MINUTES = 15;
static const int8_t MEASUREMENT_INTERVAL_SECONDS = 0;
static const uint8_t TRANSMIT_INTERVAL = 16; // to save power, only transmit a packet every X measurements

TimeSpan sleepInterval;
static const uint8_t TRANSMIT_INTERVAL = 16; // to save power, only transmit every X measurements
////Use teros 10?
#define DENDROMETER_TEROS10
//#define DENDROMETER_TEROS10
//////////////////////////
//////////////////////////

Expand All @@ -42,20 +39,14 @@ Loom_Analog analog(manager);
Loom_Teros10 teros(manager, A0);
#endif
Loom_SHT31 sht(manager);
Loom_Neopixel statusLight(manager, false, false, true, NEO_GRB); // using channel 2 (physical pin A2). use RGB for through-hole devices
Loom_Neopixel statusLight(manager, false, false, true, NEO_GRB); // using channel 2 (physical pin A2). use RGB for through-hole LED devices. GRB otherwise.

// magnet sensor
AS5311 magnetSensor(AS5311_CS, AS5311_CLK, AS5311_DO);

// wireless
#if defined DENDROMETER_LORA && defined DENDROMETER_WIFI
#error Choose ONE wireless communication protocol.
#elif defined DENDROMETER_LORA
#if defined DENDROMETER_LORA
Loom_LoRa lora(manager, NODE_NUMBER);
#elif defined DENDROMETER_WIFI
#include "credentials/arduino_secrets.h"
Loom_WIFI wifi(manager, CommunicationMode::CLIENT, SECRET_SSID, SECRET_PASS);
Loom_MongoDB mqtt(manager, wifi.getClient(), SECRET_BROKER, SECRET_PORT, MQTT_DATABASE, BROKER_USER, BROKER_PASS);
Loom_BatchSD batchSD(hypnos, TRANSMIT_INTERVAL);
#else
#warning Wireless communication disabled!
Expand Down Expand Up @@ -84,23 +75,21 @@ void flashColor(uint8_t r, uint8_t g, uint8_t b);
*/
void setup()
{

pinMode(BUTTON_PIN, INPUT_PULLUP); // Enable pullup on button pin. this is necessary for the interrupt (and the button check on the next line)
delay(10);
bool userInput = !digitalRead(BUTTON_PIN); // wait for serial connection ONLY button is pressed (low reading)
manager.beginSerial(userInput); // wait for serial connection ONLY button is pressed

hypnos.setLogName("HazelnutDendrometer_1data"); //SD card CSV file name
hypnos.enable();
sleepInterval = hypnos.getConfigFromSD("HypnosConfig.json");

hypnos.setLogName("data");

hypnos.enable();
#if defined DENDROMETER_WIFI
wifi.setBatchSD(batchSD);
wifi.setMaxRetries(2);
mqtt.setMaxRetries(1);
wifi.loadConfigFromJSON(hypnos.readFile("wifi_creds.json"));
mqtt.loadConfigFromJSON(hypnos.readFile("mqtt_creds.json"));
#if defined DENDROMETER_LORA
lora.setBatchSD(batchSD);
#endif
manager.initialize();

setRTC(userInput);

checkMagnetSensor();
Expand Down Expand Up @@ -165,30 +154,12 @@ void measureVPD()
}

/**
* transmit the current data packet over LoRa
* loop counter starts high so an initial transmission can be triggered by pressing the button
* (the first transmission will happen the second time this function is called)
* transmit the batch data packet over LoRa
*/
void transmit()
{
#if defined DENDROMETER_LORA
static uint8_t loopCounter = TRANSMIT_INTERVAL - 2;
loopCounter++;
if (loopCounter >= TRANSMIT_INTERVAL)
{
lora.send(0);
loopCounter = 0;
}
#elif defined DENDROMETER_WIFI
if (!batchSD.shouldPublish())
{
char output[100];
snprintf_P(output, OUTPUT_SIZE, PSTR("<Dendrometer> Not ready to publish. Currently at packet %i of %i"),
batchSD.getCurrentBatch(), batchSD.getBatchSize());
Serial.println(output);
}
if (wifi.isConnected())
mqtt.publish(batchSD);
lora.sendBatch(0);
#endif
}

Expand All @@ -197,7 +168,7 @@ void transmit()
*/
void sleepCycle()
{
hypnos.setInterruptDuration(TimeSpan(0, 0, MEASUREMENT_INTERVAL_MINUTES, MEASUREMENT_INTERVAL_SECONDS));
hypnos.setInterruptDuration(sleepInterval);
// Reattach to the interrupt after we have set the alarm so we can have repeat triggers
hypnos.reattachRTCInterrupt();
attachInterrupt(digitalPinToInterrupt(BUTTON_PIN), ISR_BUTTON, FALLING);
Expand Down
14 changes: 9 additions & 5 deletions src/Radio/Loom_LoRa/Loom_LoRa.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -195,11 +195,15 @@ FragReceiveStatus Loom_LoRa::receiveFrag(uint timeout, bool shouldProxy, uint8_t

if (isReady) {
if (shouldProxy) {
const char *name = manager->getDocument()["id"]["name"];
manager->set_device_name(name);

int instNum = manager->getDocument()["id"]["instance"];
manager->set_instance_num(instNum);
// If tempdoc has an ID (not a fragment body) we can set a proxy
JsonObjectConst proxyDoc = tempDoc["id"].as<JsonObjectConst>();
if (proxyDoc.isNull()) {
proxyDoc = manager->getDocument()["id"].as<JsonObjectConst>();
}
if (!proxyDoc.isNull()) {
manager->set_device_name(proxyDoc["name"].as<const char *>());
manager->set_instance_num(proxyDoc["instance"].as<int>());
}
}

if (expectedOutstandingPackets > 0) {
Expand Down