Open nicholasqle opened 8 months ago
Can you paste your code for how you are measuring your magnet sensor here too
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;
}
}
Can you upload a screen shot of the full packet in question on both the SD card and on MongoDB
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.
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
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
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.
Chet wanted to check in on this to make sure the packet gets pushed to the correct device
@WL-Richards , can we look into LoRa Radiohead library channel activity functionality to see if we can avoid collisions?
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. 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.
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:
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:
Sending node:
Output Copy and paste the serial output here if possible wrapped in ``` ```
Additional context This is different than the previous null packet issue