Skip to content

Commit

Permalink
Add scaling, add 1euro filter, force floats for esp8266
Browse files Browse the repository at this point in the history
  • Loading branch information
deiteris committed Oct 8, 2022
1 parent 1e7dd25 commit 5512bee
Show file tree
Hide file tree
Showing 7 changed files with 247 additions and 22 deletions.
188 changes: 188 additions & 0 deletions lib/1efilter/1efilter.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,188 @@
/* -*- coding: utf-8 -*-
*
* OneEuroFilter.cc -
*
* Author: Nicolas Roussel ([email protected])
*
* Copyright 2019 Inria
*
* BSD License https://opensource.org/licenses/BSD-3-Clause
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* 1. Redistributions of source code must retain the above copyright notice, this list of conditions
* and the following disclaimer.
*
* 2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions
* and the following disclaimer in the documentation and/or other materials provided with the distribution.
*
* 3. Neither the name of the copyright holder nor the names of its contributors may be used to endorse or
* promote products derived from this software without specific prior written permission.
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES,
* INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
* SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
* CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
*/

#include <iostream>
#include <cmath>
#include <ctime>

#define M_PI_FLOAT 3.1415926f

// -----------------------------------------------------------------
// Utilities

typedef uint32_t TimeStamp; // in millis

static const TimeStamp UndefinedTime = 0;

// -----------------------------------------------------------------

class LowPassFilter
{

float y, a, s;
bool initialized;

void setAlpha(float alpha)
{
if (alpha <= 0.0f || alpha > 1.0f) {
alpha = 0.1f;
return;
}
a = alpha;
}

public:
LowPassFilter(float alpha, float initval = 0.0)
{
y = s = initval;
setAlpha(alpha);
initialized = false;
}

float filter(float value)
{
float result;
if (initialized)
result = a * value + (1.0f - a) * s;
else
{
result = value;
initialized = true;
}
y = value;
s = result;
return result;
}

float filterWithAlpha(float value, float alpha)
{
setAlpha(alpha);
return filter(value);
}

bool hasLastRawValue(void)
{
return initialized;
}

float lastRawValue(void)
{
return y;
}
};

// -----------------------------------------------------------------

class OneEuroFilter
{

float freq;
float mincutoff;
float beta_;
float dcutoff;
LowPassFilter *x;
LowPassFilter *dx;
TimeStamp lasttime;

float alpha(float cutoff)
{
float te = 1.0f / freq;
float tau = 1.0f / (2 * M_PI_FLOAT * cutoff);
return 1.0f / (1.0f + tau / te);
}

void setFrequency(float f)
{
if (f <= 0) {
f = 0.1f;
return;
}
freq = f;
}

void setMinCutoff(float mc)
{
if (mc <= 0) {
mc = 0.1f;
return;
}
mincutoff = mc;
}

void setBeta(float b)
{
beta_ = b;
}

void setDerivateCutoff(float dc)
{
if (dc <= 0) {
dc = 0.1f;
return;
}
dcutoff = dc;
}

public:
OneEuroFilter(float freq,
float mincutoff = 1.0f, float beta_ = 0.0, float dcutoff = 1.0f)
{
setFrequency(freq);
setMinCutoff(mincutoff);
setBeta(beta_);
setDerivateCutoff(dcutoff);
x = new LowPassFilter(alpha(mincutoff));
dx = new LowPassFilter(alpha(dcutoff));
lasttime = UndefinedTime;
}

float filter(float value, uint32_t timestamp = UndefinedTime)
{
// update the sampling frequency based on timestamps
if (lasttime != UndefinedTime && timestamp != UndefinedTime)
freq = 1000000.f / (timestamp - lasttime);
lasttime = timestamp;
// estimate the current variation per second
float dvalue = x->hasLastRawValue() ? (value - x->lastRawValue()) * freq : 0.0; // FIXME: 0.0 or value?
float edvalue = dx->filterWithAlpha(dvalue, alpha(dcutoff));
// use it to update the cutoff frequency
float cutoff = mincutoff + beta_ * fabs(edvalue);
// filter the given value
return x->filterWithAlpha(value, alpha(cutoff));
}

~OneEuroFilter(void)
{
delete x;
delete dx;
}
};
6 changes: 5 additions & 1 deletion lib/magneto/mahony.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,9 @@ static float ix = 0.0f, iy = 0.0f, iz = 0.0f; //integral feedback terms
// Modified from Madgwick version to remove Z component of magnetometer:
// reference vectors are Up (Acc) and West (Acc cross Mag)
// sjr 12/2020
// gx, gy, gz must be in units of radians/second
// gx, gy, gz must be in radians/second
// ax, ay, az must be in meters/second^2
// mx, my, mz must be in microteslas (µT)
void mahonyQuaternionUpdate(float q[4], float ax, float ay, float az, float gx, float gy, float gz, float mx, float my, float mz, float deltat)
{
// short name local variable for readability
Expand Down Expand Up @@ -144,6 +146,8 @@ void mahonyQuaternionUpdate(float q[4], float ax, float ay, float az, float gx,
q[3] = q4 * norm;
}

// gx, gy, gz must be in radians/second
// ax, ay, az must be in meters/second^2
void mahonyQuaternionUpdate(float q[4], float ax, float ay, float az, float gx, float gy, float gz, float deltat)
{
// short name local variable for readability
Expand Down
2 changes: 1 addition & 1 deletion lib/mpu9250/MPU9250.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -3338,7 +3338,7 @@ void MPU9250_Base::initilaizeMagnetometer() {
I2Cdev::writeByte(devAddr, MPU9250_RA_I2C_SLV0_ADDR, 0x0D);
// I2C slave 0 register address from where to begin data transfer
I2Cdev::writeByte(devAddr, MPU9250_RA_I2C_SLV0_REG, 0x09);
// Start measurements in continuous mode 200hz
// Start measurements in continuous mode 200hz at 8G scale
I2Cdev::writeByte(devAddr, MPU9250_RA_I2C_SLV0_DO, 0x1D);
// Enable I2C and write 1 byte
I2Cdev::writeByte(devAddr, MPU9250_RA_I2C_SLV0_CTRL, 0x81);
Expand Down
1 change: 1 addition & 0 deletions platformio.ini
Original file line number Diff line number Diff line change
Expand Up @@ -51,6 +51,7 @@ build_unflags = -Os
[env:esp12e]
platform = espressif8266
board = esp12e
build_flags = ${env.build_flags} -fsingle-precision-constant
; Comment out this line below if you have any trouble uploading the firmware
; and if it has a CP2102 on it (a square chip next to the usb port): change to 3000000 (3 million) for even faster upload speed
upload_speed = 921600
Expand Down
20 changes: 12 additions & 8 deletions src/sensors/bmi160sensor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -28,10 +28,14 @@
// Typical sensitivity at 25C
// See p. 9 of https://www.mouser.com/datasheet/2/783/BST-BMI160-DS000-1509569.pdf
// 65.6 LSB/deg/s = 500 deg/s
#define TYPICAL_SENSITIVITY_LSB 65.6
#define TYPICAL_GYRO_SENSITIVITY 65.6
// 8192 LSB/G = 4G
#define TYPICAL_ACCEL_SENSITIVITY 8192.

// Scale conversion steps: LSB/°/s -> °/s -> step/°/s -> step/rad/s
constexpr float GSCALE = ((32768. / TYPICAL_SENSITIVITY_LSB) / 32768.) * (PI / 180.0);
// Gyro scale conversion steps: LSB/°/s -> °/s -> step/°/s -> step/rad/s
constexpr float GSCALE = ((32768. / TYPICAL_GYRO_SENSITIVITY) / 32768.) * (PI / 180.0);
// Accel scale conversion steps: LSB/G -> G -> m/s^2
constexpr float ASCALE = ((32768. / TYPICAL_ACCEL_SENSITIVITY) / 32768.) * EARTH_GRAVITY;

#define ACCEL_SENSITIVITY_4G 8192.0f

Expand Down Expand Up @@ -73,14 +77,14 @@ void BMI160Sensor::motionSetup() {

int16_t ax, ay, az;
imu.getAcceleration(&ax, &ay, &az);
float g_az = (float)az / 8192; // For 4G sensitivity
float g_az = (float)az / TYPICAL_ACCEL_SENSITIVITY; // For 4G sensitivity
if(g_az < -0.75f) {
ledManager.on();

m_Logger.info("Flip front to confirm start calibration");
delay(5000);
imu.getAcceleration(&ax, &ay, &az);
g_az = (float)az / 8192;
g_az = (float)az / TYPICAL_ACCEL_SENSITIVITY;
if(g_az > 0.75f)
{
m_Logger.debug("Starting calibration...");
Expand Down Expand Up @@ -226,9 +230,9 @@ void BMI160Sensor::getScaledValues(float Gxyz[3], float Axyz[3], float Mxyz[3])
float temp[3];
for (uint8_t i = 0; i < 3; i++)
temp[i] = (Axyz[i] - m_Calibration.A_B[i]);
Axyz[0] = m_Calibration.A_Ainv[0][0] * temp[0] + m_Calibration.A_Ainv[0][1] * temp[1] + m_Calibration.A_Ainv[0][2] * temp[2];
Axyz[1] = m_Calibration.A_Ainv[1][0] * temp[0] + m_Calibration.A_Ainv[1][1] * temp[1] + m_Calibration.A_Ainv[1][2] * temp[2];
Axyz[2] = m_Calibration.A_Ainv[2][0] * temp[0] + m_Calibration.A_Ainv[2][1] * temp[1] + m_Calibration.A_Ainv[2][2] * temp[2];
Axyz[0] = (m_Calibration.A_Ainv[0][0] * temp[0] + m_Calibration.A_Ainv[0][1] * temp[1] + m_Calibration.A_Ainv[0][2] * temp[2]) * ASCALE;
Axyz[1] = (m_Calibration.A_Ainv[1][0] * temp[0] + m_Calibration.A_Ainv[1][1] * temp[1] + m_Calibration.A_Ainv[1][2] * temp[2]) * ASCALE;
Axyz[2] = (m_Calibration.A_Ainv[2][0] * temp[0] + m_Calibration.A_Ainv[2][1] * temp[1] + m_Calibration.A_Ainv[2][2] * temp[2]) * ASCALE;
#else
for (uint8_t i = 0; i < 3; i++)
Axyz[i] = (Axyz[i] - calibration->A_B[i]);
Expand Down
42 changes: 30 additions & 12 deletions src/sensors/mpu9250sensor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,8 +33,21 @@
#include "dmpmag.h"
#endif

// See AK8693 datasheet for sensitivity scales in different mode
// We use 16-bit continuous reading mode
#define MAG_LSB_TO_MG_8G .333f
//#define MAG_UT_LSB_16_BIT 0.15f

// 131 LSB/deg/s = 250 deg/s
#define TYPICAL_GYRO_SENSITIVITY 131
// 16384 LSB/G = 2G
#define TYPICAL_ACCEL_SENSITIVITY 16384.

#if defined(_MAHONY_H_) || defined(_MADGWICK_H_)
constexpr float gscale = (250. / 32768.0) * (PI / 180.0); //gyro default 250 LSB per d/s -> rad/s
// Gyro scale conversion steps: LSB/°/s -> °/s -> step/°/s -> step/rad/s
constexpr float GSCALE = ((32768. / TYPICAL_GYRO_SENSITIVITY) / 32768.) * (PI / 180.0);
// Accel scale conversion steps: LSB/G -> G -> m/s^2
constexpr float ASCALE = ((32768. / TYPICAL_ACCEL_SENSITIVITY) / 32768.) * EARTH_GRAVITY;
#endif

#define MAG_CORR_RATIO 0.02
Expand Down Expand Up @@ -66,15 +79,15 @@ void MPU9250Sensor::motionSetup() {
// turn on while flip back to calibrate. then, flip again after 5 seconds.
// TODO: Move calibration invoke after calibrate button on slimeVR server available
imu.getAcceleration(&ax, &ay, &az);
float g_az = (float)az / 16384; // For 2G sensitivity
float g_az = (float)az / TYPICAL_ACCEL_SENSITIVITY; // For 2G sensitivity
if(g_az < -0.75f) {
ledManager.on();
m_Logger.info("Flip front to confirm start calibration");
delay(5000);
ledManager.off();

imu.getAcceleration(&ax, &ay, &az);
g_az = (float)az / 16384;
g_az = (float)az / TYPICAL_ACCEL_SENSITIVITY;
if(g_az > 0.75f) {
m_Logger.debug("Starting calibration...");
startCalibration(0);
Expand Down Expand Up @@ -232,9 +245,9 @@ void MPU9250Sensor::getMPUScaled()
#if defined(_MAHONY_H_) || defined(_MADGWICK_H_)
int16_t ax, ay, az, gx, gy, gz, mx, my, mz;
imu.getMotion9(&ax, &ay, &az, &gx, &gy, &gz, &mx, &my, &mz);
Gxyz[0] = ((float)gx - m_Calibration.G_off[0]) * gscale; //250 LSB(d/s) default to radians/s
Gxyz[1] = ((float)gy - m_Calibration.G_off[1]) * gscale;
Gxyz[2] = ((float)gz - m_Calibration.G_off[2]) * gscale;
Gxyz[0] = ((float)gx - m_Calibration.G_off[0]) * GSCALE;
Gxyz[1] = ((float)gy - m_Calibration.G_off[1]) * GSCALE;
Gxyz[2] = ((float)gz - m_Calibration.G_off[2]) * GSCALE;

Axyz[0] = (float)ax;
Axyz[1] = (float)ay;
Expand All @@ -244,9 +257,9 @@ void MPU9250Sensor::getMPUScaled()
#if useFullCalibrationMatrix == true
for (i = 0; i < 3; i++)
temp[i] = (Axyz[i] - m_Calibration.A_B[i]);
Axyz[0] = m_Calibration.A_Ainv[0][0] * temp[0] + m_Calibration.A_Ainv[0][1] * temp[1] + m_Calibration.A_Ainv[0][2] * temp[2];
Axyz[1] = m_Calibration.A_Ainv[1][0] * temp[0] + m_Calibration.A_Ainv[1][1] * temp[1] + m_Calibration.A_Ainv[1][2] * temp[2];
Axyz[2] = m_Calibration.A_Ainv[2][0] * temp[0] + m_Calibration.A_Ainv[2][1] * temp[1] + m_Calibration.A_Ainv[2][2] * temp[2];
Axyz[0] = (m_Calibration.A_Ainv[0][0] * temp[0] + m_Calibration.A_Ainv[0][1] * temp[1] + m_Calibration.A_Ainv[0][2] * temp[2]) * ASCALE;
Axyz[1] = (m_Calibration.A_Ainv[1][0] * temp[0] + m_Calibration.A_Ainv[1][1] * temp[1] + m_Calibration.A_Ainv[1][2] * temp[2]) * ASCALE;
Axyz[2] = (m_Calibration.A_Ainv[2][0] * temp[0] + m_Calibration.A_Ainv[2][1] * temp[1] + m_Calibration.A_Ainv[2][2] * temp[2]) * ASCALE;
#else
for (i = 0; i < 3; i++)
Axyz[i] = (Axyz[i] - m-Calibration.A_B[i]);
Expand All @@ -268,13 +281,18 @@ void MPU9250Sensor::getMPUScaled()
#if useFullCalibrationMatrix == true
for (i = 0; i < 3; i++)
temp[i] = (Mxyz[i] - m_Calibration.M_B[i]);
Mxyz[0] = m_Calibration.M_Ainv[0][0] * temp[0] + m_Calibration.M_Ainv[0][1] * temp[1] + m_Calibration.M_Ainv[0][2] * temp[2];
Mxyz[1] = m_Calibration.M_Ainv[1][0] * temp[0] + m_Calibration.M_Ainv[1][1] * temp[1] + m_Calibration.M_Ainv[1][2] * temp[2];
Mxyz[2] = m_Calibration.M_Ainv[2][0] * temp[0] + m_Calibration.M_Ainv[2][1] * temp[1] + m_Calibration.M_Ainv[2][2] * temp[2];
Mxyz[0] = (m_Calibration.M_Ainv[0][0] * temp[0] + m_Calibration.M_Ainv[0][1] * temp[1] + m_Calibration.M_Ainv[0][2] * temp[2]) * MAG_LSB_TO_MG_8G * .1f;
Mxyz[1] = (m_Calibration.M_Ainv[1][0] * temp[0] + m_Calibration.M_Ainv[1][1] * temp[1] + m_Calibration.M_Ainv[1][2] * temp[2]) * MAG_LSB_TO_MG_8G * .1f;
Mxyz[2] = (m_Calibration.M_Ainv[2][0] * temp[0] + m_Calibration.M_Ainv[2][1] * temp[1] + m_Calibration.M_Ainv[2][2] * temp[2]) * MAG_LSB_TO_MG_8G * .1f;
#else
for (i = 0; i < 3; i++)
Mxyz[i] = (Mxyz[i] - m_Calibration.M_B[i]);
#endif

uint32_t t = micros();
Mxyz[0] = f_mag_y.filter(Mxyz[0], t);
Mxyz[1] = f_mag_x.filter(Mxyz[1], t);
Mxyz[2] = f_mag_z.filter(Mxyz[2], t);
}

void MPU9250Sensor::startCalibration(int calibrationType) {
Expand Down
10 changes: 10 additions & 0 deletions src/sensors/mpu9250sensor.h
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,7 @@
#include "sensor.h"
#include "logging/Logger.h"

#include <1efilter.cc>
#include <MPU9250_6Axis_MotionApps_V6_12.h>

class MPU9250Sensor : public Sensor
Expand Down Expand Up @@ -59,6 +60,15 @@ class MPU9250Sensor : public Sensor
unsigned long now = 0, last = 0; // micros() timers
float deltat = 0; // loop time in seconds

float mag_frequency = 200.f;
float beta = 0.02f;
float mincutoff = 0.005f;
float d_cutoff = 1.0f;

OneEuroFilter f_mag_x{mag_frequency, mincutoff, beta, d_cutoff};
OneEuroFilter f_mag_y{mag_frequency, mincutoff, beta, d_cutoff};
OneEuroFilter f_mag_z{mag_frequency, mincutoff, beta, d_cutoff};

SlimeVR::Configuration::MPU9250CalibrationConfig m_Calibration;
};

Expand Down

0 comments on commit 5512bee

Please sign in to comment.