New test release, changed gyro read
This commit is contained in:
parent
8d1048adeb
commit
d0cd50dcd1
12
README.md
12
README.md
@ -1,10 +1,11 @@
|
||||
# Gravity Monitor for Beer Brewing
|
||||
|
||||
I started this project out of curiosity for how a motion sensor is working and since I like to brew beer this was the result. This software can be used with iSpindle hardware and utilizes the same hardware configuration. No code has been reused from the iSpindle project.
|
||||
This software can be used with iSpindle hardware and utilizes the same hardware configuration. No code has been reused from the iSpindle project.
|
||||
|
||||
I started this project out of curiosity for how a motion sensor is working and since I like to brew beer this was the result.
|
||||
|
||||
## TODO
|
||||
|
||||
* Add iSpindle 3D print cradle + small PCB (what I use for my builds)
|
||||
* Validate the power consumption of the device using amp meter (integrated and/or separate)
|
||||
* Testing, Testing and more testing......
|
||||
|
||||
@ -14,7 +15,7 @@ Lower priority
|
||||
* Add support for Blynk as endpoint
|
||||
* Add support for https connections (push) - [need to reduce memory usage for this to work, gets out of memory error]
|
||||
* Add support for https web server (will require certificates to be created as part of build process)
|
||||
* Add support for WifiManager Secure access.
|
||||
* Add support for WifiManager Secure access, depends on support in library.
|
||||
|
||||
# Functionallity
|
||||
|
||||
@ -133,6 +134,11 @@ Contents version.json
|
||||
|
||||
See the iSpindle documentation for building a device.
|
||||
|
||||
I've included my 3d sled that I use for my builds that allows for easy adjustment of the default angle. The stl files can be found under the stl directory.
|
||||
|
||||

|
||||

|
||||
|
||||
# Compiling the software
|
||||
|
||||
I recommend that VSCODE with PlatformIO and Minfy extensions are used. Minify is used to reduce the size of the HTML files which are embedded into the firmware or uploaded to the file system. When using minify on a file, for example index.htm the output will be called index.min.htm. This is the file that will be used when buildning the image.
|
||||
|
Binary file not shown.
BIN
bin/firmware.bin
BIN
bin/firmware.bin
Binary file not shown.
@ -1 +1 @@
|
||||
{ "project":"gravmon", "version":"0.3.5", "html": [ "index.min.htm", "device.min.htm", "config.min.htm", "about.min.htm" ] }
|
||||
{ "project":"gravmon", "version":"0.3.8", "html": [ "index.min.htm", "device.min.htm", "config.min.htm", "about.min.htm" ] }
|
BIN
img/build-1.png
Normal file
BIN
img/build-1.png
Normal file
Binary file not shown.
After Width: | Height: | Size: 112 KiB |
BIN
img/build-2.png
Normal file
BIN
img/build-2.png
Normal file
Binary file not shown.
After Width: | Height: | Size: 110 KiB |
BIN
img/spindle-weight.png
Normal file
BIN
img/spindle-weight.png
Normal file
Binary file not shown.
After Width: | Height: | Size: 115 KiB |
BIN
img/spindle.png
Normal file
BIN
img/spindle.png
Normal file
Binary file not shown.
After Width: | Height: | Size: 114 KiB |
@ -22,7 +22,7 @@ build_unflags =
|
||||
build_flags = #-O0 -Wl,-Map,output.map
|
||||
-D BAUD=${common_env_data.monitor_speed}
|
||||
-D ACTIVATE_OTA
|
||||
-D USE_GYRO_TEMP # If this is enabled the DS18 will not be used, temp is read from the gyro.
|
||||
#-D USE_GYRO_TEMP # If this is enabled the DS18 will not be used, temp is read from the gyro.
|
||||
#-D DEBUG_ESP_HTTP_CLIENT
|
||||
#-D DEBUG_ESP_HTTP_SERVER
|
||||
#-D DEBUG_ESP_PORT=Serial
|
||||
@ -32,7 +32,7 @@ build_flags = #-O0 -Wl,-Map,output.map
|
||||
-D EMBED_HTML # If this is not used the html files needs to be on the file system (can be uploaded)
|
||||
-D USER_SSID=\""\"" # =\""myssid\""
|
||||
-D USER_SSID_PWD=\""\"" # =\""mypwd\""
|
||||
-D CFG_APPVER="\"0.3.5\""
|
||||
-D CFG_APPVER="\"0.3.8\""
|
||||
lib_deps =
|
||||
# https://github.com/jrowberg/i2cdevlib.git # Using local copy of this library
|
||||
https://github.com/codeplea/tinyexpr
|
||||
@ -43,7 +43,6 @@ lib_deps =
|
||||
https://github.com/bblanchon/ArduinoJson
|
||||
https://github.com/PaulStoffregen/OneWire
|
||||
https://github.com/milesburton/Arduino-Temperature-Control-Library
|
||||
https://github.com/wollewald/INA219_WE # For measuring power consumption
|
||||
|
||||
[env:gravity-debug]
|
||||
upload_speed = ${common_env_data.upload_speed}
|
||||
|
59
src/gyro.cpp
59
src/gyro.cpp
@ -26,11 +26,12 @@ SOFTWARE.
|
||||
|
||||
GyroSensor myGyro;
|
||||
|
||||
#define GYRO_USE_INTERRUPT // Use interrupt to detect when new sample is ready
|
||||
#define SENSOR_MOVING_THREASHOLD 500
|
||||
#define SENSOR_READ_COUNT 50
|
||||
#define SENSOR_READ_DELAY 3150 // us, empirical, to hold sampling to 200 Hz
|
||||
|
||||
//#define GYRO_SHOW_MINMAX // Will calculate the min/max values when doing calibration
|
||||
#define GYRO_SHOW_MINMAX // Will calculate the min/max values when doing calibration
|
||||
//#define GYRO_CALIBRATE_STARTUP // Will calibrate sensor at startup
|
||||
|
||||
//
|
||||
@ -54,15 +55,22 @@ bool GyroSensor::setup() {
|
||||
|
||||
// Configure the sensor
|
||||
accelgyro.setTempSensorEnabled(true);
|
||||
accelgyro.setFullScaleAccelRange(MPU6050_ACCEL_FS_2);
|
||||
accelgyro.setFullScaleGyroRange(MPU6050_GYRO_FS_250);
|
||||
//accelgyro.setFullScaleAccelRange(MPU6050_ACCEL_FS_2); // Set in .initalize()
|
||||
//accelgyro.setFullScaleGyroRange(MPU6050_GYRO_FS_250); // Set in .initalize()
|
||||
accelgyro.setDLPFMode(MPU6050_DLPF_BW_5);
|
||||
#if defined( GYRO_USE_INTERRUPT )
|
||||
// Alternative method to read data, let the MPU signal when sampling is done.
|
||||
accelgyro.setRate(17);
|
||||
|
||||
// For now we run the calibration at start.
|
||||
#if defined ( GYRO_CALIBRATE_STARTUP )
|
||||
accelgyro.setInterruptDrive(1);
|
||||
accelgyro.setInterruptMode(1);
|
||||
accelgyro.setInterruptLatch(0);
|
||||
accelgyro.setIntDataReadyEnabled(true);
|
||||
#endif
|
||||
|
||||
#if defined ( GYRO_CALIBRATE_STARTUP )
|
||||
// Run the calibration at start, useful for testing.
|
||||
calibrateSensor();
|
||||
#endif
|
||||
#endif
|
||||
|
||||
// Once we have calibration values stored we just apply them from the config.
|
||||
calibrationOffset = myConfig.getGyroCalibration();
|
||||
@ -101,8 +109,16 @@ void GyroSensor::readSensor(RawGyroData &raw, const int noIterations, const int
|
||||
max = min;
|
||||
#endif
|
||||
for(int cnt = 0; cnt < noIterations ; cnt ++) {
|
||||
accelgyro.getRotation( &raw.gx, &raw.gy, &raw.gz );
|
||||
accelgyro.getAcceleration( &raw.ax, &raw.ay, &raw.az );
|
||||
|
||||
#if defined( GYRO_USE_INTERRUPT )
|
||||
while( accelgyro.getIntDataReadyStatus() == 0) {
|
||||
delayMicroseconds( 1 );
|
||||
}
|
||||
#endif
|
||||
|
||||
//accelgyro.getRotation( &raw.gx, &raw.gy, &raw.gz );
|
||||
//accelgyro.getAcceleration( &raw.ax, &raw.ay, &raw.az );
|
||||
accelgyro.getMotion6(&raw.ax, &raw.ay, &raw.az, &raw.gx, &raw.gy, &raw.gz);
|
||||
raw.temp = accelgyro.getTemperature();
|
||||
|
||||
average.ax += raw.ax;
|
||||
@ -133,7 +149,9 @@ void GyroSensor::readSensor(RawGyroData &raw, const int noIterations, const int
|
||||
if( raw.temp > max.temp ) max.temp = raw.temp;
|
||||
#endif
|
||||
|
||||
#if !defined( GYRO_USE_INTERRUPT )
|
||||
delayMicroseconds( delayTime );
|
||||
#endif
|
||||
}
|
||||
|
||||
raw.ax = average.ax/noIterations;
|
||||
@ -158,13 +176,21 @@ void GyroSensor::readSensor(RawGyroData &raw, const int noIterations, const int
|
||||
//
|
||||
// Calcuate the angles (tilt)
|
||||
//
|
||||
double GyroSensor::calculateAngle(RawGyroData &raw) {
|
||||
float GyroSensor::calculateAngle(RawGyroData &raw) {
|
||||
#if LOG_LEVEL==6
|
||||
Log.verbose(F("GYRO: Calculating the angle." CR) );
|
||||
#endif
|
||||
|
||||
// Smooth out the readings to we can have a more stable angle/tilt.
|
||||
// ------------------------------------------------------------------------------------------------------------
|
||||
// Accelerometer full scale range of +/- 2g with Sensitivity Scale Factor of 16,384 LSB(Count)/g.
|
||||
// Gyroscope full scale range of +/- 250 °/s with Sensitivity Scale Factor of 131 LSB (Count)/°/s.
|
||||
float ax = ((float) raw.ax)/16384,
|
||||
ay = ((float) raw.ay)/16384,
|
||||
az = ((float) raw.az)/16384;
|
||||
|
||||
// Source: https://www.nxp.com/docs/en/application-note/AN3461.pdf
|
||||
double v = (acos( raw.ay / sqrt( raw.ax*raw.ax + raw.ay*raw.ay + raw.az*raw.az ) ) *180.0 / PI);
|
||||
float v = (acos( ay / sqrt( ax*ax + ay*ay + az*az ) ) *180.0 / PI);
|
||||
//Log.notice(F("GYRO: angle = %F." CR), v );
|
||||
//double v = (acos( raw.az / sqrt( raw.ax*raw.ax + raw.ay*raw.ay + raw.az*raw.az ) ) *180.0 / PI);
|
||||
//Log.notice(F("GYRO: angle = %F." CR), v );
|
||||
@ -201,20 +227,19 @@ bool GyroSensor::read() {
|
||||
Log.verbose(F("GYRO: Getting new gyro position." CR) );
|
||||
#endif
|
||||
|
||||
RawGyroData raw;
|
||||
readSensor( raw, SENSOR_READ_COUNT, SENSOR_READ_DELAY );
|
||||
readSensor( lastGyroData, SENSOR_READ_COUNT, SENSOR_READ_DELAY ); // Last param is unused if GYRO_USE_INTERRUPT is defined.
|
||||
|
||||
// If the sensor is unstable we return false to signal we dont have valid value
|
||||
if( isSensorMoving(raw) ) {
|
||||
if( isSensorMoving(lastGyroData) ) {
|
||||
Log.notice(F("GYRO: Sensor is moving." CR) );
|
||||
validValue = false;
|
||||
} else {
|
||||
validValue = true;
|
||||
angle = calculateAngle( raw );
|
||||
//Log.notice(F("GYRO: Calculated angle %F" CR), angle );
|
||||
angle = calculateAngle( lastGyroData );
|
||||
//Log.notice(F("GYRO: Sensor values %d,%d,%d\t%F" CR), raw.ax, raw.ay, raw.az, angle );
|
||||
}
|
||||
|
||||
sensorTemp = ((float) raw.temp) / 340 + 36.53;
|
||||
sensorTemp = ((float) lastGyroData.temp) / 340 + 36.53;
|
||||
|
||||
// The first read value is close to the DS18 value according to my tests, if more reads are
|
||||
// done then the gyro temp will increase to much
|
||||
|
18
src/gyro.h
18
src/gyro.h
@ -52,29 +52,31 @@ class GyroSensor {
|
||||
MPU6050 accelgyro;
|
||||
bool sensorConnected = false;
|
||||
bool validValue = false;
|
||||
double angle = 0;
|
||||
float angle = 0;
|
||||
float sensorTemp = 0;
|
||||
float initialSensorTemp = INVALID_TEMPERATURE;
|
||||
RawGyroData calibrationOffset;
|
||||
RawGyroData lastGyroData;
|
||||
|
||||
void debug();
|
||||
void applyCalibration();
|
||||
void dumpCalibration();
|
||||
void readSensor(RawGyroData &raw, const int noIterations = 100, const int delayTime = 1);
|
||||
bool isSensorMoving(RawGyroData &raw);
|
||||
double calculateAngle(RawGyroData &raw);
|
||||
float calculateAngle(RawGyroData &raw);
|
||||
|
||||
public:
|
||||
bool setup();
|
||||
bool read();
|
||||
void calibrateSensor();
|
||||
|
||||
double getAngle() { return angle; };
|
||||
float getSensorTempC() { return sensorTemp; };
|
||||
float getInitialSensorTempC() { return initialSensorTemp; };
|
||||
bool isConnected() { return sensorConnected; };
|
||||
bool hasValue() { return validValue; };
|
||||
void enterSleep();
|
||||
const RawGyroData& getLastGyroData() { return lastGyroData; }
|
||||
float getAngle() { return angle; };
|
||||
float getSensorTempC() { return sensorTemp; };
|
||||
float getInitialSensorTempC() { return initialSensorTemp; };
|
||||
bool isConnected() { return sensorConnected; };
|
||||
bool hasValue() { return validValue; };
|
||||
void enterSleep();
|
||||
};
|
||||
|
||||
// Global instance created
|
||||
|
@ -23,13 +23,11 @@ SOFTWARE.
|
||||
*/
|
||||
#include "helper.h"
|
||||
#include "config.h"
|
||||
#include "gyro.h"
|
||||
#include "tempsensor.h"
|
||||
#include <ESP8266WiFi.h>
|
||||
#include <ESP8266HTTPClient.h>
|
||||
|
||||
#if defined( COLLECT_PERFDATA )
|
||||
#include <INA219_WE.h> // For measuring power consumption
|
||||
#endif
|
||||
|
||||
SerialDebug mySerial;
|
||||
BatteryVoltage myBatteryVoltage;
|
||||
|
||||
@ -105,42 +103,6 @@ void BatteryVoltage::read() {
|
||||
#if defined( COLLECT_PERFDATA )
|
||||
|
||||
PerfLogging myPerfLogging;
|
||||
INA219_WE ina219(0x40); // For measuring power consumption
|
||||
|
||||
//
|
||||
// Initialize
|
||||
//
|
||||
PerfLogging::PerfLogging() {
|
||||
if( ina219.init() )
|
||||
measurePower = true;
|
||||
|
||||
Log.notice( F("PERF: Performance logging enabled. Power sensor %s" CR), measurePower?"found":"not found");
|
||||
}
|
||||
|
||||
//
|
||||
// Initialize
|
||||
//
|
||||
void PerfLogging::readPowerSensor(PerfEntry *pe) {
|
||||
pe->mA = 0;
|
||||
pe->V = 0;
|
||||
|
||||
if( !measurePower )
|
||||
return;
|
||||
|
||||
if( ina219.getOverflow() )
|
||||
Log.error( F("PERF: Voltage sensor overflow detected." CR));
|
||||
|
||||
/*
|
||||
shuntVoltage_mV = ina219.getShuntVoltage_mV();
|
||||
busVoltage_V = ina219.getBusVoltage_V();
|
||||
current_mA = ina219.getCurrent_mA();
|
||||
power_mW = ina219.getBusPower();
|
||||
loadVoltage_V = busVoltage_V + (shuntVoltage_mV/1000);
|
||||
*/
|
||||
|
||||
pe->mA = ina219.getCurrent_mA();
|
||||
pe->V = ina219.getBusVoltage_V() + (ina219.getShuntVoltage_mV()/1000);
|
||||
}
|
||||
|
||||
//
|
||||
// Clear the current cache
|
||||
@ -183,8 +145,6 @@ void PerfLogging::stop( const char* key ) {
|
||||
|
||||
if( t > pe->max )
|
||||
pe->max = t;
|
||||
|
||||
readPowerSensor( pe );
|
||||
}
|
||||
}
|
||||
|
||||
@ -220,6 +180,8 @@ void PerfLogging::pushInflux() {
|
||||
// key,host=mdns value=0.0
|
||||
String body;
|
||||
|
||||
// Create the payload with performance data.
|
||||
// ------------------------------------------------------------------------------------------
|
||||
PerfEntry* pe = first;
|
||||
char buf[100];
|
||||
sprintf( &buf[0], "perf,host=%s,device=%s ", myConfig.getMDNS(), myConfig.getID() );
|
||||
@ -237,6 +199,16 @@ void PerfLogging::pushInflux() {
|
||||
pe = pe->next;
|
||||
}
|
||||
|
||||
// Create the payload with debug data for validating sensor stability
|
||||
// ------------------------------------------------------------------------------------------
|
||||
sprintf( &buf[0], "\ndebug,host=%s,device=%s ", myConfig.getMDNS(), myConfig.getID() );
|
||||
body += &buf[0];
|
||||
sprintf( &buf[0], "angle=%.4f,gyro-ax=%d,gyro-ay=%d,gyro-az=%d,gyro-temp=%.2f,ds-temp=%.2f", myGyro.getAngle(), myGyro.getLastGyroData().ax,
|
||||
myGyro.getLastGyroData().ay, myGyro.getLastGyroData().az, myGyro.getSensorTempC(), myTempSensor.getTempC() );
|
||||
body += &buf[0];
|
||||
|
||||
// Log.notice(F("PERF: data %s." CR), body.c_str() );
|
||||
|
||||
#if LOG_LEVEL==6
|
||||
Log.verbose(F("PERF: url %s." CR), serverPath.c_str());
|
||||
Log.verbose(F("PERF: data %s." CR), body.c_str() );
|
||||
|
@ -117,10 +117,7 @@ class PerfLogging {
|
||||
return pe;
|
||||
};
|
||||
|
||||
void readPowerSensor(PerfEntry* pe);
|
||||
|
||||
public:
|
||||
PerfLogging();
|
||||
void clear();
|
||||
void start( const char* key );
|
||||
void stop( const char* key );
|
||||
|
@ -184,7 +184,7 @@ void loop() {
|
||||
stableGyroMillis = millis(); // Reset timer
|
||||
|
||||
LOG_PERF_START("loop-temp-read");
|
||||
float temp = myTempSensor.getValueCelcius();
|
||||
float temp = myTempSensor.getTempC();
|
||||
LOG_PERF_STOP("loop-temp-read");
|
||||
|
||||
//LOG_PERF_START("loop-gravity-calc"); // Takes less than 2ms , so skip this measurment
|
||||
|
@ -67,7 +67,7 @@ void TempSensor::setup() {
|
||||
mySensors.begin();
|
||||
|
||||
if( mySensors.getDS18Count() ) {
|
||||
Log.notice(F("TSEN: Found %d sensors." CR), mySensors.getDS18Count());
|
||||
Log.notice(F("TSEN: Found %d temperature sensor(s)." CR), mySensors.getDS18Count());
|
||||
mySensors.setResolution(TEMPERATURE_PRECISION);
|
||||
}
|
||||
#endif
|
||||
|
@ -38,8 +38,8 @@ class TempSensor {
|
||||
public:
|
||||
void setup();
|
||||
bool isSensorAttached() { return hasSensor; };
|
||||
float getValueCelcius() { return getValue() + tempSensorAdjC; }
|
||||
float getValueFarenheight() { return convertCtoF(getValue()) + tempSensorAdjF; };
|
||||
float getTempC() { return getValue() + tempSensorAdjC; }
|
||||
float getTempF() { return convertCtoF(getValue()) + tempSensorAdjF; };
|
||||
};
|
||||
|
||||
// Global instance created
|
||||
|
@ -85,7 +85,7 @@ void webHandleConfig() {
|
||||
myConfig.createJson( doc );
|
||||
|
||||
double angle = myGyro.getAngle();
|
||||
double temp = myTempSensor.getValueCelcius();
|
||||
double temp = myTempSensor.getTempC();
|
||||
double gravity = calculateGravity( angle, temp );
|
||||
|
||||
doc[ CFG_PARAM_ANGLE ] = reduceFloatPrecision( angle);
|
||||
@ -224,7 +224,7 @@ void webHandleStatus() {
|
||||
DynamicJsonDocument doc(256);
|
||||
|
||||
double angle = myGyro.getAngle();
|
||||
double temp = myTempSensor.getValueCelcius();
|
||||
double temp = myTempSensor.getTempC();
|
||||
double gravity = calculateGravity( angle, temp );
|
||||
|
||||
doc[ CFG_PARAM_ID ] = myConfig.getID();
|
||||
@ -234,7 +234,7 @@ void webHandleStatus() {
|
||||
else
|
||||
doc[ CFG_PARAM_GRAVITY ] = reduceFloatPrecision( gravity, 4);
|
||||
doc[ CFG_PARAM_TEMP_C ] = reduceFloatPrecision( temp, 1);
|
||||
doc[ CFG_PARAM_TEMP_F ] = reduceFloatPrecision( myTempSensor.getValueFarenheight(), 1);
|
||||
doc[ CFG_PARAM_TEMP_F ] = reduceFloatPrecision( myTempSensor.getTempF(), 1);
|
||||
doc[ CFG_PARAM_BATTERY ] = reduceFloatPrecision( myBatteryVoltage.getVoltage());
|
||||
doc[ CFG_PARAM_TEMPFORMAT ] = String( myConfig.getTempFormat() );
|
||||
doc[ CFG_PARAM_SLEEP_MODE ] = sleepModeAlwaysSkip;
|
||||
|
BIN
stl/sled.stl
Normal file
BIN
stl/sled.stl
Normal file
Binary file not shown.
BIN
stl/spacer.stl
Normal file
BIN
stl/spacer.stl
Normal file
Binary file not shown.
Loading…
Reference in New Issue
Block a user