Skip to content

Commit

Permalink
Work on new sensor interface to abstract I2C hardware
Browse files Browse the repository at this point in the history
  • Loading branch information
Eirenliel committed Aug 6, 2024
1 parent 969ba13 commit 93b5a07
Show file tree
Hide file tree
Showing 12 changed files with 167 additions and 76 deletions.
89 changes: 89 additions & 0 deletions src/sensorinterface/I2CWireSensorInterface.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,89 @@
/*
SlimeVR Code is placed under the MIT license
Copyright (c) 2024 Eiren & SlimeVR Contributors
Permission is hereby granted, free of charge, to any person obtaining a copy
of this software and associated documentation files (the "Software"), to deal
in the Software without restriction, including without limitation the rights
to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
copies of the Software, and to permit persons to whom the Software is
furnished to do so, subject to the following conditions:
The above copyright notice and this permission notice shall be included in
all copies or substantial portions of the Software.
THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
THE SOFTWARE.
*/

#ifndef SENSORINTERFACE_I2CWIRE_H
#define SENSORINTERFACE_I2CWIRE_H

#include <Wire.h>
#include "sensorinterface.h"
#include <i2cscan.h>

uint8_t activeSCLPin;
uint8_t activeSDAPin;
bool isI2CActive = false;

namespace SlimeVR
{
void swapI2C(uint8_t sclPin, uint8_t sdaPin)
{
if (sclPin != activeSCLPin || sdaPin != activeSDAPin || !isI2CActive) {
Wire.flush();
#if ESP32
if (running) {}
else {
// Reset HWI2C to avoid being affected by I2CBUS reset
Wire.end();
}
// Disconnect pins from HWI2C
gpio_set_direction((gpio_num_t)activeSCLPin, GPIO_MODE_INPUT);
gpio_set_direction((gpio_num_t)activeSDAPin, GPIO_MODE_INPUT);

if (running) {
i2c_set_pin(I2C_NUM_0, sdaPin, sclPin, false, false, I2C_MODE_MASTER);
} else {
Wire.begin(static_cast<int>(sdaPin), static_cast<int>(sclPin), I2C_SPEED);
Wire.setTimeOut(150);
}
#else
Wire.begin(static_cast<int>(sdaPin), static_cast<int>(sclPin));
#endif

activeSCLPin = sclPin;
activeSDAPin = sdaPin;
isI2CActive = true;
}
}

class I2CWireSensorInterface : public SensorInterface {
public:
I2CWireSensorInterface(uint8_t sdapin, uint8_t sclpin) :
sdaPin(sdapin), sclPin(sclpin){};
~I2CWireSensorInterface(){};

void init() override final {
I2CSCAN::clearBus(sdaPin, sclPin);
}
void swapIn() override final {
swapI2C(sclPin, sdaPin);
}
protected:
uint8_t sdaPin;
uint8_t sclPin;
};


}



#endif // SENSORINTERFACE_I2CWIRE_H
38 changes: 38 additions & 0 deletions src/sensorinterface/SensorInterface.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,38 @@
/*
SlimeVR Code is placed under the MIT license
Copyright (c) 2024 Eiren & SlimeVR Contributors
Permission is hereby granted, free of charge, to any person obtaining a copy
of this software and associated documentation files (the "Software"), to deal
in the Software without restriction, including without limitation the rights
to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
copies of the Software, and to permit persons to whom the Software is
furnished to do so, subject to the following conditions:
The above copyright notice and this permission notice shall be included in
all copies or substantial portions of the Software.
THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
THE SOFTWARE.
*/

#ifndef SENSORINTERFACE_H
#define SENSORINTERFACE_H

namespace SlimeVR
{
class SensorInterface
{
public:

virtual void init();
virtual void swapIn();
};
}

#endif // SENSORINTERFACE_H
40 changes: 3 additions & 37 deletions src/sensors/SensorManager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -57,41 +57,8 @@ namespace SlimeVR
using SoftFusionLSM6DSR = SoftFusionSensor<SoftFusion::Drivers::LSM6DSR, SoftFusion::I2CImpl>;
using SoftFusionMPU6050 = SoftFusionSensor<SoftFusion::Drivers::MPU6050, SoftFusion::I2CImpl>;

// TODO Make it more generic in the future and move another place (abstract sensor interface)
void SensorManager::swapI2C(uint8_t sclPin, uint8_t sdaPin)
{
if (sclPin != activeSCL || sdaPin != activeSDA || !running) {
Wire.flush();
#if ESP32
if (running) {}
else {
// Reset HWI2C to avoid being affected by I2CBUS reset
Wire.end();
}
// Disconnect pins from HWI2C
gpio_set_direction((gpio_num_t)activeSCL, GPIO_MODE_INPUT);
gpio_set_direction((gpio_num_t)activeSDA, GPIO_MODE_INPUT);

if (running) {
i2c_set_pin(I2C_NUM_0, sdaPin, sclPin, false, false, I2C_MODE_MASTER);
} else {
Wire.begin(static_cast<int>(sdaPin), static_cast<int>(sclPin), I2C_SPEED);
Wire.setTimeOut(150);
}
#else
Wire.begin(static_cast<int>(sdaPin), static_cast<int>(sclPin));
#endif

activeSCL = sclPin;
activeSDA = sdaPin;
}
}

void SensorManager::setup()
{
running = false;
activeSCL = PIN_IMU_SCL;
activeSDA = PIN_IMU_SDA;

uint8_t sensorID = 0;
uint8_t activeSensorCount = 0;
Expand Down Expand Up @@ -119,10 +86,9 @@ namespace SlimeVR

void SensorManager::postSetup()
{
running = true;
for (auto &sensor : m_Sensors) {
if (sensor->isWorking()) {
swapI2C(sensor->sclPin, sensor->sdaPin);
sensor->hwInterface->swapIn();
sensor->postSetup();
}
}
Expand All @@ -134,7 +100,7 @@ namespace SlimeVR
bool allIMUGood = true;
for (auto &sensor : m_Sensors) {
if (sensor->isWorking()) {
swapI2C(sensor->sclPin, sensor->sdaPin);
sensor->hwInterface->swapIn();
sensor->motionLoop();
}
if (sensor->getSensorState() == SensorStatus::SENSOR_ERROR)
Expand Down Expand Up @@ -172,7 +138,7 @@ namespace SlimeVR

m_LastBundleSentAtMicros = now;
#endif

#if PACKET_BUNDLING != PACKET_BUNDLING_DISABLED
networkConnection.beginBundle();
#endif
Expand Down
20 changes: 8 additions & 12 deletions src/sensors/SensorManager.h
Original file line number Diff line number Diff line change
Expand Up @@ -29,8 +29,7 @@
#include "EmptySensor.h"
#include "ErroneousSensor.h"
#include "logging/Logger.h"

#include <i2cscan.h>
#include "sensorinterface/I2CWireSensorInterface.h"

#include <memory>

Expand All @@ -48,7 +47,7 @@ namespace SlimeVR
void postSetup();

void update();

std::vector<std::unique_ptr<Sensor>> & getSensors() { return m_Sensors; };
ImuID getSensorType(size_t id) {
if(id < m_Sensors.size()) {
Expand Down Expand Up @@ -76,8 +75,9 @@ namespace SlimeVR
std::unique_ptr<Sensor> sensor;

// Clear and reset I2C bus for each sensor upon startup
I2CSCAN::clearBus(sdaPin, sclPin);
swapI2C(sclPin, sdaPin);
std::shared_ptr<SensorInterface> sensorInterface = std::make_shared<I2CWireSensorInterface>(sclPin, sdaPin);
sensorInterface->init();
sensorInterface->swapIn();

if (I2CSCAN::hasDevOnBus(address)) {
m_Logger.trace("Sensor %d found at address 0x%02X", sensorID + 1, address);
Expand All @@ -94,16 +94,12 @@ namespace SlimeVR
}

uint8_t intPin = extraParam;
sensor = std::make_unique<ImuType>(sensorID, addrSuppl, rotation, sclPin, sdaPin, intPin);
sensor = std::make_unique<ImuType>(sensorID, addrSuppl, rotation, std::move(sensorInterface), intPin);

sensor->motionSetup();
return sensor;
}
uint8_t activeSCL = 0;
uint8_t activeSDA = 0;
bool running = false;
void swapI2C(uint8_t scl, uint8_t sda);

}

uint32_t m_LastBundleSentAtMicros = micros();
};
}
Expand Down
8 changes: 4 additions & 4 deletions src/sensors/bmi160sensor.h
Original file line number Diff line number Diff line change
Expand Up @@ -97,7 +97,7 @@ constexpr uint16_t BMI160_FIFO_READ_BUFFER_SIZE_BYTES = min(
// #define BMI160_GYRO_TYPICAL_SENSITIVITY_LSB 16.4f // 2000 deg 0
// #define BMI160_GYRO_TYPICAL_SENSITIVITY_LSB 32.8f // 1000 deg 1
// #define BMI160_GYRO_TYPICAL_SENSITIVITY_LSB 65.6f // 500 deg 2
// #define BMI160_GYRO_TYPICAL_SENSITIVITY_LSB 131.2f // 250 deg 3
// #define BMI160_GYRO_TYPICAL_SENSITIVITY_LSB 131.2f // 250 deg 3
// #define BMI160_GYRO_TYPICAL_SENSITIVITY_LSB 262.4f // 125 deg 4
constexpr double BMI160_GYRO_TYPICAL_SENSITIVITY_LSB = (16.4f * (1 << BMI160_GYRO_RANGE));

Expand Down Expand Up @@ -125,8 +125,8 @@ class BMI160Sensor : public Sensor {
static constexpr uint8_t Address = 0x68;
static constexpr auto TypeID = ImuID::BMI160;

BMI160Sensor(uint8_t id, uint8_t addrSuppl, float rotation, uint8_t sclPin, uint8_t sdaPin, int axisRemapParam) :
Sensor("BMI160Sensor", ImuID::BMI160, id, Address+addrSuppl, rotation, sclPin, sdaPin),
BMI160Sensor(uint8_t id, uint8_t addrSuppl, float rotation, std::shared_ptr<SlimeVR::SensorInterface> sensorInterface, int axisRemapParam) :
Sensor("BMI160Sensor", ImuID::BMI160, id, Address+addrSuppl, rotation, sensorInterface),
sfusion(BMI160_ODR_GYR_MICROS / 1e6f, BMI160_ODR_ACC_MICROS / 1e6f, BMI160_ODR_MAG_MICROS / 1e6f)
{
if (axisRemapParam < 256) {
Expand All @@ -146,7 +146,7 @@ class BMI160Sensor : public Sensor {
void maybeCalibrateGyro();
void maybeCalibrateAccel();
void maybeCalibrateMag();

void printTemperatureCalibrationState() override final;
void printDebugTemperatureCalibrationState() override final;
void resetTemperatureCalibrationState() override final {
Expand Down
4 changes: 2 additions & 2 deletions src/sensors/bno055sensor.h
Original file line number Diff line number Diff line change
Expand Up @@ -34,8 +34,8 @@ class BNO055Sensor : public Sensor
static constexpr auto TypeID = ImuID::BNO055;
static constexpr uint8_t Address = 0x28;

BNO055Sensor(uint8_t id, uint8_t addrSuppl, float rotation, uint8_t sclPin, uint8_t sdaPin, uint8_t)
: Sensor("BNO055Sensor", ImuID::BNO055, id, Address+addrSuppl, rotation, sclPin, sdaPin){};
BNO055Sensor(uint8_t id, uint8_t addrSuppl, float rotation, std::shared_ptr<SlimeVR::SensorInterface> sensorInterface, uint8_t)
: Sensor("BNO055Sensor", ImuID::BNO055, id, Address+addrSuppl, rotation, sensorInterface){};
~BNO055Sensor(){};
void motionSetup() override final;
void motionLoop() override final;
Expand Down
4 changes: 3 additions & 1 deletion src/sensors/bno080sensor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -81,10 +81,12 @@ void BNO080Sensor::motionSetup()
imu.saveCalibrationPeriodically(true);
imu.requestCalibrationStatus();
// EXPERIMENTAL Disable accelerometer calibration after 1 minute to prevent "stomping" bug
// WARNING : Executing IMU commands outside of the update loop is not allowed
// since the address might have changed when the timer is executed!
if(sensorType == ImuID::BNO085) {
// For BNO085, disable accel calibration
globalTimer.in(60000, [](void *sensor) {((BNO080*) sensor)->sendCalibrateCommand(SH2_CAL_MAG | SH2_CAL_ON_TABLE); return true;}, &imu);
} else if(sensorType == ImuID::BNO085) {
} else if(sensorType == ImuID::BNO086) {
// For BNO086, disable accel calibration
// TODO: Find default flags for BNO086
globalTimer.in(60000, [](void *sensor) {((BNO080*) sensor)->sendCalibrateCommand(SH2_CAL_MAG | SH2_CAL_ON_TABLE); return true;}, &imu);
Expand Down
16 changes: 8 additions & 8 deletions src/sensors/bno080sensor.h
Original file line number Diff line number Diff line change
Expand Up @@ -33,8 +33,8 @@ class BNO080Sensor : public Sensor
static constexpr auto TypeID = ImuID::BNO080;
static constexpr uint8_t Address = 0x4a;

BNO080Sensor(uint8_t id, uint8_t addrSuppl, float rotation, uint8_t sclPin, uint8_t sdaPin, uint8_t intPin)
: Sensor("BNO080Sensor", ImuID::BNO080, id, Address+addrSuppl, rotation, sclPin, sdaPin), m_IntPin(intPin) {};
BNO080Sensor(uint8_t id, uint8_t addrSuppl, float rotation, std::shared_ptr<SlimeVR::SensorInterface> sensorInterface, uint8_t intPin)
: Sensor("BNO080Sensor", ImuID::BNO080, id, Address+addrSuppl, rotation, sensorInterface), m_IntPin(intPin) {};
~BNO080Sensor(){};
void motionSetup() override final;
void postSetup() override {
Expand All @@ -48,8 +48,8 @@ class BNO080Sensor : public Sensor

protected:
// forwarding constructor
BNO080Sensor(const char* sensorName, ImuID imuId, uint8_t id, uint8_t addrSuppl, float rotation, uint8_t sclPin, uint8_t sdaPin, uint8_t intPin)
: Sensor(sensorName, imuId, id, Address+addrSuppl, rotation, sclPin, sdaPin), m_IntPin(intPin) {};
BNO080Sensor(const char* sensorName, ImuID imuId, uint8_t id, uint8_t addrSuppl, float rotation, std::shared_ptr<SlimeVR::SensorInterface> sensorInterface, uint8_t intPin)
: Sensor(sensorName, imuId, id, Address+addrSuppl, rotation, sensorInterface), m_IntPin(intPin) {};
private:
BNO080 imu{};

Expand All @@ -72,16 +72,16 @@ class BNO085Sensor : public BNO080Sensor
{
public:
static constexpr auto TypeID = ImuID::BNO085;
BNO085Sensor(uint8_t id, uint8_t address, float rotation, uint8_t sclPin, uint8_t sdaPin, uint8_t intPin)
: BNO080Sensor("BNO085Sensor", ImuID::BNO085, id, address, rotation, sclPin, sdaPin, intPin) {};
BNO085Sensor(uint8_t id, uint8_t address, float rotation, std::shared_ptr<SlimeVR::SensorInterface> sensorInterface, uint8_t intPin)
: BNO080Sensor("BNO085Sensor", ImuID::BNO085, id, address, rotation, sensorInterface, intPin) {};
};

class BNO086Sensor : public BNO080Sensor
{
public:
static constexpr auto TypeID = ImuID::BNO086;
BNO086Sensor(uint8_t id, uint8_t address, float rotation, uint8_t sclPin, uint8_t sdaPin, uint8_t intPin)
: BNO080Sensor("BNO086Sensor", ImuID::BNO086, id, address, rotation, sclPin, sdaPin, intPin) {};
BNO086Sensor(uint8_t id, uint8_t address, float rotation, std::shared_ptr<SlimeVR::SensorInterface> sensorInterface, uint8_t intPin)
: BNO080Sensor("BNO086Sensor", ImuID::BNO086, id, address, rotation, sensorInterface, intPin) {};
};

#endif
4 changes: 2 additions & 2 deletions src/sensors/icm20948sensor.h
Original file line number Diff line number Diff line change
Expand Up @@ -33,8 +33,8 @@ class ICM20948Sensor : public Sensor
static constexpr auto TypeID = ImuID::ICM20948;
static constexpr uint8_t Address = 0x68;

ICM20948Sensor(uint8_t id, uint8_t addrSuppl, float rotation, uint8_t sclPin, uint8_t sdaPin, uint8_t)
: Sensor("ICM20948Sensor", ImuID::ICM20948, id, Address+addrSuppl, rotation, sclPin, sdaPin) {}
ICM20948Sensor(uint8_t id, uint8_t addrSuppl, float rotation, std::shared_ptr<SlimeVR::SensorInterface> sensorInterface, uint8_t)
: Sensor("ICM20948Sensor", ImuID::ICM20948, id, Address+addrSuppl, rotation, sensorInterface) {}
~ICM20948Sensor() override = default;
void motionSetup() override final;
void postSetup() override {
Expand Down
4 changes: 2 additions & 2 deletions src/sensors/mpu6050sensor.h
Original file line number Diff line number Diff line change
Expand Up @@ -34,8 +34,8 @@ class MPU6050Sensor : public Sensor
static constexpr auto TypeID = ImuID::MPU6050;
static constexpr uint8_t Address = 0x68;

MPU6050Sensor(uint8_t id, uint8_t addrSuppl, float rotation, uint8_t sclPin, uint8_t sdaPin, uint8_t)
: Sensor("MPU6050Sensor", ImuID::MPU6050, id, Address+addrSuppl, rotation, sclPin, sdaPin){};
MPU6050Sensor(uint8_t id, uint8_t addrSuppl, float rotation, std::shared_ptr<SlimeVR::SensorInterface> sensorInterface, uint8_t)
: Sensor("MPU6050Sensor", ImuID::MPU6050, id, Address+addrSuppl, rotation, sensorInterface){};
~MPU6050Sensor(){};
void motionSetup() override final;
void motionLoop() override final;
Expand Down
4 changes: 2 additions & 2 deletions src/sensors/mpu9250sensor.h
Original file line number Diff line number Diff line change
Expand Up @@ -47,8 +47,8 @@ class MPU9250Sensor : public Sensor
static constexpr auto TypeID = ImuID::MPU9250;
static constexpr uint8_t Address = 0x68;

MPU9250Sensor(uint8_t id, uint8_t addrSuppl, float rotation, uint8_t sclPin, uint8_t sdaPin, uint8_t)
: Sensor("MPU9250Sensor", ImuID::MPU9250, id, Address+addrSuppl, rotation, sclPin, sdaPin)
MPU9250Sensor(uint8_t id, uint8_t addrSuppl, float rotation, std::shared_ptr<SlimeVR::SensorInterface> sensorInterface, uint8_t)
: Sensor("MPU9250Sensor", ImuID::MPU9250, id, Address+addrSuppl, rotation, sensorInterface)
#if !MPU_USE_DMPMAG
, sfusion(MPU9250_ODR_TS)
#endif
Expand Down
Loading

0 comments on commit 93b5a07

Please sign in to comment.