OPEnSLab-OSU / Loom-V4

Open Source Internet Of Things Rapid Prototyping Framework For Environmental Sensing Applications
12 stars 1 forks source link

LoRa packet collision issue #138

Open nicholasqle opened 8 months ago

nicholasqle commented 8 months ago

Describe the bug When graphing the data from LoRa batch on MongoDB, we sometimes get weird noise or spikes in the data that do not appear on the SD card. For example here I graphed the same exact time period using the data on MongoDB vs data from SD card over the same time period. lb2 mongo lb2 sd When looking at individual packets sometimes there it seems that there is an outlier packet with values that are off from the rest of the data. These weird packets also have an extra field under displacement of undefined: null that the rest of the packets do not have. displacement

Hardware in Use Dendrometer sending LoRa batch, Feather M0 LoRa, Hypnos v3.3. Hub receiving LoRa batch, Feather M0 LoRa, Hypnos v3.3, 4G LTE Board.

To Reproduce Steps to reproduce the behavior:

  1. Setup LoRa batch on Dendrometer with hub uploading to MongoDB.
  2. Collect data over a period of time

Expected behavior Data should not contain unexpected values.

Code In the Arduino IDE while editing the main.ino, goto 'Edit' -> 'Copy for HTML' and paste the output of that here Receiving hub:

#include "arduino_secrets.h"

#include <Loom_Manager.h> //4.6

#include <Hardware/Loom_Hypnos/Loom_Hypnos.h>
#include <Radio/Loom_LoRa/Loom_LoRa.h>
#include <Sensors/Loom_Analog/Loom_Analog.h>
#include <Internet/Connectivity/Loom_LTE/Loom_LTE.h>
#include <Internet/Logging/Loom_MongoDB/Loom_MongoDB.h>

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_BatchSD batchSD(hypnos, 16); //set batch size uploading

int packetNumber = 0;
void setup()
{
    // Start the serial interface
    manager.beginSerial();

    // Enable the power rails on the hypnos
    hypnos.enable();

    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"));

    // Initialize the modules
    manager.initialize();
}

void loop()
{
    // Wait 5 seconds for a message
    do{
      if (lora.receiveBatch(5000, &packetNumber))
      {
          manager.display_data();
          hypnos.logToSD();
          mqtt.publish(batchSD);
      }
      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();
        //restart LTE if connection to internet fails
        if (!lte.verifyConnection())
        {
            lte.power_down();
            delay(5000);
            lte.power_up();
        }

        timer = millis();
    }
    }while(packetNumber > 0);
}

void setRTC()
{
    if (!Serial)
        return;

    Serial.println(F("Adjust RTC time? (y/n)"));
    unsigned long timer = millis();
    while (!Serial.available() && (millis() - timer) < 7000)
        ;
    if (!Serial.available())
        return;
    int val = Serial.read();
    delay(50);
    while (Serial.available())
        Serial.read(); // flush the input buffer to avoid invalid input to rtc function

    if (val == 'y')
    {
        hypnos.set_custom_time();
    }
}

Sending node:

#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 = 6;
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 every X measurements
////Use teros 10?
#define DENDROMETER_TEROS10
//////////////////////////
//////////////////////////

// Pins
#define AS5311_CS A3 // 9 for LB version, A3 otherwise
#define AS5311_CLK A5
#define AS5311_DO A4
#define BUTTON_PIN A1 // 11 for LB, A1 otherwise

// Loom
Manager manager(DEVICE_NAME, NODE_NUMBER);
Loom_Hypnos hypnos(manager, HYPNOS_VERSION::V3_3, TIME_ZONE::PST); // 3_2 for LB, 3_3 otherwise
// Loom Sensors
Loom_Analog analog(manager);
#ifdef DENDROMETER_TEROS10
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 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
Loom_LoRa lora(manager, NODE_NUMBER);
Loom_BatchSD batchSD(hypnos, TRANSMIT_INTERVAL);
#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!
#endif

// Global Variables
volatile bool buttonPressed = false; // Check to see if button was pressed

void sleepCycle();
void ISR_RTC();
void ISR_BUTTON();

void measure();
void measureVPD();
void transmit();

void setRTC(bool);
void checkMagnetSensor();
void alignMagnetSensor();
bool checkStableAlignment();
void displayMagnetStatus(magnetStatus);
void flashColor(uint8_t r, uint8_t g, uint8_t b);

/**
 * Program setup
 */
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_6data"); //SD card CSV file name

#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"));
    hypnos.setNetworkInterface(&wifi);
    hypnos.networkTimeUpdate();
#elif defined DENDROMETER_LORA
    lora.setBatchSD(batchSD);
#endif
    hypnos.enable();
    manager.initialize();
    setRTC(userInput);

    checkMagnetSensor();
    alignMagnetSensor();

    hypnos.registerInterrupt(ISR_RTC);
}

/**
 * Main loop
 */
void loop()
{
    measure();
    if (buttonPressed) // if interrupt button was pressed, display staus of magnet sensor
    {
        displayMagnetStatus(magnetSensor.getMagnetStatus());
    #if defined DENDROMETER_WIFI
        hypnos.networkTimeUpdate();
    #endif
        delay(3000);
        statusLight.set_color(2, 0, 0, 0, 0); // LED Off
        buttonPressed = false;
    }
    transmit();
    sleepCycle();
}

/**
 * Perform all measurements for the dendrometer and put them into a packet.
 * Log to SD card.
 */
void measure()
{
    manager.measure();
    manager.package();

    measureVPD();
    magnetSensor.measure(manager);
    // Log whether system woke up from button or not
    manager.addData("Button", "Pressed?", buttonPressed);

    hypnos.logToSD();

    // delay(5000);
    // manager.display_data();
}

/**
 * Log readings from the SHT31 sensor. Also calculate and log VPD.
 */
void measureVPD()
{
    float SVP, VPD, temperature, humidity;
    float e = 2.71828;

    temperature = sht.getTemperature();
    humidity = sht.getHumidity();

    // Tetens equation
    SVP = (0.61078 * pow(e, (17.2694 * temperature) / (temperature + 237.3)));
    VPD = SVP * (1 - (humidity / 100));

    manager.addData("SHT31", "VPD", VPD);
}

/**
 * transmit the batch data packet over LoRa
 */
void transmit()
{
#if defined DENDROMETER_LORA
    lora.sendBatch(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);
#endif
}

/**
 * Shut down the device for a specified time period to save power.
 */
void sleepCycle()
{
    hypnos.setInterruptDuration(TimeSpan(0, 0, MEASUREMENT_INTERVAL_MINUTES, MEASUREMENT_INTERVAL_SECONDS));
    // 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);

    // Put the device into a deep sleep, operation HALTS here until the interrupt is triggered
    hypnos.sleep();
    detachInterrupt(digitalPinToInterrupt(BUTTON_PIN));
}

// Interrupt routines
void ISR_RTC()
{
    hypnos.wakeup();
}

void ISR_BUTTON()
{
    buttonPressed = true;
    hypnos.wakeup();
}

/**
 * Magnet alignment procedure. Displays magnet sensor to user until
 * the magnet is determined to be properly aligned and maintains that alignment
 * for a certain amount of time
 */
void alignMagnetSensor()
{
    magnetStatus status;

    Serial.println(F("<Dendrometer> Waiting for magnet alignment"));
    while (1)
    {
        // Watchdog.reset();
        status = magnetSensor.getMagnetStatus();
        displayMagnetStatus(status);
        delay(100);
        if (status == magnetStatus::green && checkStableAlignment())
            break;
    }
    flashColor(0, 255, 0);
}

/**
 * Check the magnet sensor alignment status and display it on the multi-color LED
 * @param   status  the magnetStatus to display
 */
void displayMagnetStatus(magnetStatus status)
{
    switch (status)
    {
    case magnetStatus::yellow:
        statusLight.set_color(2, 0, 255, 100, 0); // yellow
        break;
    case magnetStatus::green:
        statusLight.set_color(2, 0, 0, 255, 0); // green
        break;
    case magnetStatus::error: // Fall through
    case magnetStatus::red:   // Fall through
    default:
        statusLight.set_color(2, 0, 255, 0, 0); // red
        break;                                  // do nothing
    }
}

/**
 * Flashes status light
 * @param   r   red color value (unsigned 8 bit number)
 * @param   g   green color value (unsigned 8 bit number)
 * @param   b   blue color value (unsigned 8 bit number)
 */
void flashColor(uint8_t r, uint8_t g, uint8_t b)
{
    for (auto _ = 6; _--;)
    {
        // Watchdog.reset();
        statusLight.set_color(2, 0, r, g, b);
        delay(250);
        statusLight.set_color(2, 0, 0, 0, 0); // off
        delay(250);
    }
}

/**
 * Make sure calibration is stable before proceeding
 * Returns true if the sensor remains aligned for the next five seconds
 */
bool checkStableAlignment()
{
    const unsigned int CHECK_TIME = 3000;
    magnetStatus status;
    bool aligned = true;

    for (int i = 0; i < (CHECK_TIME / 100); i++)
    {
        // Watchdog.reset();
        status = magnetSensor.getMagnetStatus();
        if (status != magnetStatus::green)
        {
            aligned = false;
            break;
        }
        delay(100);
    }

    return aligned;
}

/**
 * Checks to see if a magnet sensor is connected and functioning.
 */
void checkMagnetSensor()
{
    uint32_t data = magnetSensor.getRawData();
    if (__builtin_parity(data) == 0 && data != 0) //__builtin_parity() returns 0 if value has even parity
        return;
    for (auto _ = 6; _--;)
        flashColor(255, 100, 0); // if the check didn't pass, alert the user by flashing the LED
}

/**
 * Ask the user to set a custom time
 */
void setRTC(bool wait)
{
    if (!wait || !Serial)
        return;

    Serial.println(F("<Dendrometer> Adjust RTC time? (y/n)"));
    while (!Serial.available())
        ;
    int val = Serial.read();
    delay(50);
    while (Serial.available())
        Serial.read(); // flush the input buffer to avoid invalid input to rtc function

    if (val == 'y')
    {
        hypnos.set_custom_time();
    }
}

Output Copy and paste the serial output here if possible wrapped in ``` ```

Additional context This is different than the previous null packet issue

WL-Richards commented 8 months ago

Can you paste your code for how you are measuring your magnet sensor here too

nicholasqle commented 8 months ago

AS5311.h

#pragma once

#include <Arduino.h>
#include <Loom_Manager.h>

enum class magnetStatus
{
    red,
    green,
    yellow,
    error
};

class AS5311
{
public:
    AS5311(uint8_t cs_pin, uint8_t clk_pin, uint8_t do_pin);
    magnetStatus getMagnetStatus();
    uint16_t getFilteredPosition();
    uint16_t getFieldStrength();
    uint32_t getRawData();

    void measure(Manager &);
    float measureDisplacement(int);

private:
    const uint8_t CS_PIN;
    const uint8_t CLK_PIN;
    const uint8_t DO_PIN;

    static const int DATA_TIMING_US;
    static const int AVERAGE_MEASUREMENTS;

    int initialPosition = -1; //negative number indicates that initial position has not been measured
    int lastPosition = 0;
    int overflows = 0;

    void recordMagnetStatus(Manager &);

    void initializePins();
    void deinitializePins();
    uint16_t getPosition();
    uint32_t bitbang(bool);
};

// bit definitions - See pages 12 and 13 of the AS5311 datasheet for more information
#define PAR 0
#define MAGDEC 1
#define MAGINC 2
#define LIN 3
#define COF 4
#define OCF 5

#define DATAOFFSET 6

AS5311.cpp

#include "AS5311.h"

const int AS5311::DATA_TIMING_US = 12;
// 1000us/bit was the value in the V3 code
// according to the datasheet the chip's limit is 1MHz

const int AS5311::AVERAGE_MEASUREMENTS = 16;

AS5311::AS5311(uint8_t cs_pin, uint8_t clk_pin, uint8_t do_pin)
    : CS_PIN(cs_pin), CLK_PIN(clk_pin), DO_PIN(do_pin) {}

/**
 *  Initialize pins for serial read procedure
 */
void AS5311::initializePins()
{
    // initalize pins
    digitalWrite(CS_PIN, HIGH);
    pinMode(CS_PIN, OUTPUT);
    digitalWrite(CLK_PIN, HIGH);
    pinMode(CLK_PIN, OUTPUT);
    pinMode(DO_PIN, INPUT);
}

/**
 * deinitialize pins after serial read
 */
void AS5311::deinitializePins()
{
    pinMode(CS_PIN, INPUT);
    digitalWrite(CS_PIN, LOW);
    pinMode(CLK_PIN, INPUT);
    digitalWrite(CLK_PIN, LOW);
    pinMode(DO_PIN, INPUT);
}

/**
 *  Returns the serial output from AS533
 * @return 32 bit value, of which the 18 least signifcant bits contain the sensor data
 */
uint32_t AS5311::bitbang(bool angleData = true)
{
    initializePins();

    if (angleData)
    {
        digitalWrite(CLK_PIN, HIGH); // write clock high to select the angular position data
    }
    else
    {
        digitalWrite(CLK_PIN, LOW); // write clock high to select the magnetic field strength data
    }

    delayMicroseconds(DATA_TIMING_US);
    // select the chip
    digitalWrite(CS_PIN, LOW);
    delayMicroseconds(DATA_TIMING_US);

    // begin the data transfer
    digitalWrite(CLK_PIN, LOW);

    uint32_t data = 0;
    const uint8_t BITS = 18;
    for (int i = 0; i < BITS; i++)
    {
        delayMicroseconds(DATA_TIMING_US);
        digitalWrite(CLK_PIN, HIGH);

        // don't set clock low on last bit
        if (i < (BITS - 1))
        {
            delayMicroseconds(DATA_TIMING_US);
            digitalWrite(CLK_PIN, LOW);
        }

        delayMicroseconds(DATA_TIMING_US);

        auto readval = digitalRead(DO_PIN);
        if (readval == HIGH)
        {
            data |= 1 << (BITS - 1) - i;
        }
    }

    digitalWrite(CS_PIN, HIGH);
    digitalWrite(CLK_PIN, HIGH);
    delayMicroseconds(DATA_TIMING_US);
    deinitializePins();

    return data;
}

/**
 * Determine the magnet alignment status
 * See pages 12 to 15 of the AS5311 datasheet for more information
 * @return magnetStatus enum
 */
magnetStatus AS5311::getMagnetStatus()
{
    uint32_t data = bitbang();

    // invalid data
    if (!(data & (1 << OCF)) || data & (1 << COF) || __builtin_parity(data)) //__builtin_parity returns 1 if odd parity
        return magnetStatus::error;

    // magnetic field out of range
    if (data & (1 << MAGINC) && data & (1 << MAGDEC) && data & (1 << LIN))
        return magnetStatus::red;

    // magnetic field borderline out of range
    if (data & (1 << MAGINC) && data & (1 << MAGDEC))
        return magnetStatus::yellow;

    return magnetStatus::green;
}

/**
 * Return the raw sensor binary data
 * @return raw sensor data
 */
uint32_t AS5311::getRawData()
{
    return bitbang(true);
}

/**
 * Right shift the raw sensor data to isolate the absolute position component
 * @return 12-bit absolute postion value
 */
uint16_t AS5311::getPosition()
{
    return bitbang(true) >> DATAOFFSET;
}

/**
 * Right shift the raw sensor data to isolate the field strength component
 * @return 12-bit magnetic field strength value
 */
uint16_t AS5311::getFieldStrength()
{
    return bitbang(false) >> DATAOFFSET;
}

/**
 * Takes multiple position measurements and average them
 * @return averaged 12-bit absolute position value
 */
uint16_t AS5311::getFilteredPosition()
{
    uint16_t average = 0;
    for (int i = 0; i < AVERAGE_MEASUREMENTS; i++)
    {
        average += getPosition();
    }
    average /= AVERAGE_MEASUREMENTS;
    return average;
}

/**
 * Record the data from the magnet sensor, process it, and add it to the manager's packet.
 */
void AS5311::measure(Manager &manager)
{
    int filteredPosition = (int)getFilteredPosition();
    int rawPosition = (int)getPosition();

    recordMagnetStatus(manager);
    manager.addData("AS5311", "mag", getFieldStrength());
    manager.addData("AS5311", "pos_raw", rawPosition);
    manager.addData("AS5311", "pos_avg", filteredPosition);
    manager.addData("displacement", "um", measureDisplacement(rawPosition));
}

/**
 * Calculate the displacement of the magnet given a position.
 * Keeps a persistent count of sensor range overflows
 * Moving the sensor too much (about 1mm) in between calls to this function will result in invalid data.
 */
float AS5311::measureDisplacement(int pos)
{
    static const int WRAP_THRESHOLD = 2048;
    static const int TICKS = 4096;                   // 2^12 == 4096   see datasheet page 10
    static const float POLE_PAIR_LENGTH_UM = 2000.0; // 2mm == 2000um
    static const float UM_PER_TICK = POLE_PAIR_LENGTH_UM / TICKS;

    if (initialPosition == -1) { // initial position has not been measured
        initialPosition = pos;
        lastPosition = pos;
    }
    int magnetPosition = pos;

    int difference = magnetPosition - lastPosition;
    if (abs(difference) > WRAP_THRESHOLD)
    {
        if (difference < 0) // high to low overflow
            overflows += 1;
        else // low to high overflow
            overflows -= 1;
    }
    lastPosition = magnetPosition;

    return ((magnetPosition - initialPosition) * UM_PER_TICK) + overflows * POLE_PAIR_LENGTH_UM;
}

/**
 * Record the alignment status of the magnet sensor
 */
void AS5311::recordMagnetStatus(Manager &manager)
{
    magnetStatus status = getMagnetStatus();
    switch (status)
    {
    case magnetStatus::red:
        manager.addData("AS5311", "Alignment", "Red");
        break;
    case magnetStatus::yellow:
        manager.addData("AS5311", "Alignment", "Yellow");
        break;
    case magnetStatus::green:
        manager.addData("AS5311", "Alignment", "Green");
        break;
    case magnetStatus::error: // fall through
    default:
        manager.addData("AS5311", "Alignment", "Error");
        break;
    }
}
WL-Richards commented 8 months ago

Can you upload a screen shot of the full packet in question on both the SD card and on MongoDB

nicholasqle commented 8 months ago

For the spiky graph above, the packet that shows in MongoDB has a slightly different time and dramatically different displacement value (second to last column. image

image

As for the undefined null field, I do not have that exact one from SD card but here is two more I found. The undefined will occasionally appear in different fields. Sometimes the values are incorrect but in this case it is close image

image

WL-Richards commented 8 months ago

I'd recommend turning on SD_DEBUG logging if it's not already on. https://github.com/OPEnSLab-OSU/Loom-V4/wiki/Utilizing-the-Loom-Logger There is the link to how to enable it, if it is already on could you send me the file that has the same packet numbers as the broken ones I wanna see whats happening on the device

nicholasqle commented 7 months ago

I set up multiple devices to upload at the same time, and it does look like packet from multiple devices at the same time are causing the problems. SD Debug from LTE hub:

[2024.04.14 17:49:57] [DEBUG] [Loom_LoRa.cpp:receiveBatch:340] Received packet!
[2024.04.14 17:49:57] [DEBUG] [Loom_Manager.cpp:display_data:198] Data Json: 

{
  "type": "data",
  "id": {
    "name": "DendrometerV4_",
    "instance": 29
  },
  "contents": [
    {
      "module": "Packet",
      "data": {
        "Number": 411
      }
    },
    {
      "type": null,
      "id": {
        "name": null,
        "instance": 0
      },
      "numPackets": 0,
      "contents": []
    },
    {
      "type": "data",
      "id": {
        "name": "DendrometerV4_",
        "instance": 27
      },
      "numPackets": 7,
      "contents": [],
      "timestamp": {
        "time_utc": "2024-04-14T22:4:50Z",
        "time_local": "2024-04-14T15:4:50Z"
      }
    },
    {
      "module": "Packet",
      "data": {
        "Number": 401
      }
    },
    {
      "module": "Analog",
      "data": {
        "Vbat": 4.165283203,
        "Vbat_MV": 4162.060547
      }
    },
    {
      "module": "SHT31",
      "data": {
        "Temperature": 20.12000084,
        "Humidity": 52.11000061,
        "VPD": 1.128057599
      }
    },
    {
      "module": "LoRa",
      "data": {
        "RSSI": -79
      }
    }
  ],
  "timestamp": {
    "time_utc": "2024-04-15T0:33:24Z",
    "time_local": "2024-04-14T17:33:24Z"
  }
}
[2024.04.14 17:49:57] [DEBUG] [SDManager.cpp:log:159] Successfully logged data to Hub2.csv
[2024.04.14 17:49:57] [DEBUG] [Loom_MongoDB.cpp:publish:148] Batch not ready to publish: 10/16
[2024.04.14 17:49:57] [DEBUG] [Loom_LoRa.cpp:recv:146] Waiting for packet...
[2024.04.14 17:50:00] [DEBUG] [Loom_LoRa.cpp:receiveBatch:312] Packet Received!
[2024.04.14 17:50:00] [ERROR] [Loom_LoRa.cpp:receiveBatch:336] Failed to receive packet!
[2024.04.14 17:50:00] [DEBUG] [Loom_LoRa.cpp:recv:146] Waiting for packet...
[2024.04.14 17:50:01] [DEBUG] [Loom_LoRa.cpp:receiveBatch:312] Packet Received!
[2024.04.14 17:50:01] [ERROR] [Loom_LoRa.cpp:receiveBatch:336] Failed to receive packet!
[2024.04.14 17:50:01] [DEBUG] [Loom_LoRa.cpp:recv:146] Waiting for packet...
[2024.04.14 17:50:03] [DEBUG] [Loom_LoRa.cpp:receiveBatch:312] Packet Received!
[2024.04.14 17:50:03] [ERROR] [Loom_LoRa.cpp:receiveBatch:336] Failed to receive packet!
[2024.04.14 17:50:03] [DEBUG] [Loom_LoRa.cpp:recv:146] Waiting for packet...
[2024.04.14 17:50:05] [DEBUG] [Loom_LoRa.cpp:receiveBatch:312] Packet Received!
[2024.04.14 17:50:05] [DEBUG] [Loom_LoRa.cpp:receivePartial:372] Waiting for packet 1 / 7
[2024.04.14 17:50:06] [DEBUG] [Loom_LoRa.cpp:recv:146] Waiting for packet...
[2024.04.14 17:50:06] [DEBUG] [Loom_LoRa.cpp:receivePartial:377] Fragment received 1 / 7
[2024.04.14 17:50:07] [DEBUG] [Loom_LoRa.cpp:receivePartial:372] Waiting for packet 2 / 7
[2024.04.14 17:50:07] [DEBUG] [Loom_LoRa.cpp:recv:146] Waiting for packet...
[2024.04.14 17:50:08] [DEBUG] [Loom_LoRa.cpp:receivePartial:377] Fragment received 2 / 7
[2024.04.14 17:50:08] [DEBUG] [Loom_LoRa.cpp:receivePartial:372] Wa

The full file is too big to upload but I think you can get the idea, I can send it if you need it.

nicholasqle commented 7 months ago

Chet wanted to check in on this to make sure the packet gets pushed to the correct device

udellc commented 4 months ago

@WL-Richards , can we look into LoRa Radiohead library channel activity functionality to see if we can avoid collisions?