mirror of
https://github.com/SlimeVR/SlimeVR-Tracker-ESP.git
synced 2026-04-05 17:51:57 +02:00
Merge branch 'main' into add-id-command
This commit is contained in:
1
.github/workflows/actions.yml
vendored
1
.github/workflows/actions.yml
vendored
@@ -71,3 +71,4 @@ jobs:
|
||||
generate_release_notes: true
|
||||
files: |
|
||||
./build/BOARD_SLIMEVR-firmware.bin
|
||||
./build/BOARD_SLIMEVR_V1_2-firmware.bin
|
||||
|
||||
@@ -95,7 +95,7 @@ def build() -> int:
|
||||
status = build_for_device(device)
|
||||
|
||||
if not status:
|
||||
failed_builds.append(device.platformio_board)
|
||||
failed_builds.append(device.board)
|
||||
|
||||
if len(failed_builds) > 0:
|
||||
print(f" 🡢 {COLOR_RED}Failed!{COLOR_RESET}")
|
||||
|
||||
@@ -12,7 +12,6 @@
|
||||
|
||||
This library handles the initialization of the BNO080 and is able to query the sensor
|
||||
for different readings.
|
||||
|
||||
https://github.com/sparkfun/SparkFun_BNO080_Arduino_Library
|
||||
|
||||
Development environment specifics:
|
||||
@@ -688,6 +687,16 @@ void BNO080::getAccel(float &x, float &y, float &z, uint8_t &accuracy)
|
||||
hasNewAccel_ = false;
|
||||
}
|
||||
|
||||
bool BNO080::getNewAccel(float &x, float &y, float &z, uint8_t &accuracy)
|
||||
{
|
||||
if (hasNewAccel_)
|
||||
{
|
||||
getAccel(x, y, z, accuracy);
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
//Return the acceleration component
|
||||
float BNO080::getAccelX()
|
||||
{
|
||||
|
||||
@@ -214,6 +214,7 @@ public:
|
||||
uint8_t getQuatAccuracy();
|
||||
|
||||
void getAccel(float &x, float &y, float &z, uint8_t &accuracy);
|
||||
bool getNewAccel(float &x, float &y, float &z, uint8_t &accuracy);
|
||||
float getAccelX();
|
||||
float getAccelY();
|
||||
float getAccelZ();
|
||||
|
||||
@@ -17,26 +17,62 @@ build_unflags =
|
||||
[env:BOARD_SLIMEVR]
|
||||
platform = espressif8266 @ 4.2.1
|
||||
board = esp12e
|
||||
build_flags =
|
||||
${env.build_flags}
|
||||
-D BOARD=BOARD_SLIMEVR
|
||||
|
||||
[env:BOARD_SLIMEVR_V1_2]
|
||||
platform = espressif8266 @ 4.2.1
|
||||
board = esp12e
|
||||
build_flags =
|
||||
${env.build_flags}
|
||||
-D BOARD=BOARD_SLIMEVR_V1_2
|
||||
|
||||
[env:BOARD_SLIMEVR_DEV]
|
||||
platform = espressif8266 @ 4.2.1
|
||||
board = esp12e
|
||||
build_flags =
|
||||
${env.build_flags}
|
||||
-D BOARD=BOARD_SLIMEVR_DEV
|
||||
|
||||
[env:BOARD_GLOVE_IMU_SLIMEVR_DEV]
|
||||
platform = espressif32 @ 6.7.0
|
||||
platform_packages =
|
||||
framework-arduinoespressif32 @ https://github.com/espressif/arduino-esp32.git#3.0.1
|
||||
framework-arduinoespressif32-libs @ https://github.com/espressif/arduino-esp32/releases/download/3.0.1/esp32-arduino-libs-3.0.1.zip
|
||||
build_flags =
|
||||
${env.build_flags}
|
||||
-DESP32C3
|
||||
-D BOARD=BOARD_GLOVE_IMU_SLIMEVR_DEV
|
||||
board = lolin_c3_mini
|
||||
|
||||
[env:BOARD_NODEMCU]
|
||||
platform = espressif8266 @ 4.2.1
|
||||
board = esp12e
|
||||
build_flags =
|
||||
${env.build_flags}
|
||||
-D BOARD=BOARD_NODEMCU
|
||||
|
||||
[env:BOARD_WEMOSD1MINI]
|
||||
platform = espressif8266 @ 4.2.1
|
||||
board = esp12e
|
||||
build_flags =
|
||||
${env.build_flags}
|
||||
-D BOARD=BOARD_WEMOSD1MINI
|
||||
|
||||
[env:BOARD_TTGO_TBASE]
|
||||
platform = espressif8266 @ 4.2.1
|
||||
board = esp12e
|
||||
build_flags =
|
||||
${env.build_flags}
|
||||
-D BOARD=BOARD_TTGO_TBASE
|
||||
|
||||
[env:BOARD_WEMOSWROOM02]
|
||||
platform = espressif8266 @ 4.2.1
|
||||
board = esp12e
|
||||
build_flags =
|
||||
${env.build_flags}
|
||||
-D BOARD=BOARD_NODEMCU
|
||||
|
||||
[env:BOARD_WROOM32]
|
||||
platform = espressif32 @ 6.7.0
|
||||
@@ -44,6 +80,9 @@ platform_packages =
|
||||
framework-arduinoespressif32 @ https://github.com/espressif/arduino-esp32.git#3.0.1
|
||||
framework-arduinoespressif32-libs @ https://github.com/espressif/arduino-esp32/releases/download/3.0.1/esp32-arduino-libs-3.0.1.zip
|
||||
board = esp32dev
|
||||
build_flags =
|
||||
${env.build_flags}
|
||||
-D BOARD=BOARD_WROOM32
|
||||
|
||||
[env:BOARD_ESP01]
|
||||
platform = espressif32 @ 6.7.0
|
||||
@@ -51,6 +90,9 @@ platform_packages =
|
||||
framework-arduinoespressif32 @ https://github.com/espressif/arduino-esp32.git#3.0.1
|
||||
framework-arduinoespressif32-libs @ https://github.com/espressif/arduino-esp32/releases/download/3.0.1/esp32-arduino-libs-3.0.1.zip
|
||||
board = esp32dev
|
||||
build_flags =
|
||||
${env.build_flags}
|
||||
-D BOARD=BOARD_ESP01
|
||||
|
||||
[env:BOARD_LOLIN_C3_MINI]
|
||||
platform = espressif32 @ 6.7.0
|
||||
@@ -60,6 +102,7 @@ platform_packages =
|
||||
build_flags =
|
||||
${env.build_flags}
|
||||
-DESP32C3
|
||||
-D BOARD=BOARD_LOLIN_C3_MINI
|
||||
board = lolin_c3_mini
|
||||
|
||||
[env:BOARD_BEETLE32C3]
|
||||
@@ -70,6 +113,7 @@ platform_packages =
|
||||
build_flags =
|
||||
${env.build_flags}
|
||||
-DESP32C3
|
||||
-D BOARD=BOARD_BEETLE32C3
|
||||
board = dfrobot_beetle_esp32c3
|
||||
|
||||
[env:BOARD_ESP32C3DEVKITM1]
|
||||
@@ -80,6 +124,7 @@ platform_packages =
|
||||
build_flags =
|
||||
${env.build_flags}
|
||||
-DESP32C3
|
||||
-D BOARD=BOARD_ESP32C3DEVKITM1
|
||||
board = esp32-c3-devkitm-1
|
||||
|
||||
[env:BOARD_ESP32C6DEVKITC1]
|
||||
@@ -87,6 +132,7 @@ platform = https://github.com/tasmota/platform-espressif32/releases/download/202
|
||||
build_flags =
|
||||
${env.build_flags}
|
||||
-DESP32C6
|
||||
-D BOARD=BOARD_ESP32C6DEVKITC1
|
||||
board = esp32-c6-devkitc-1
|
||||
|
||||
[env:BOARD_XIAO_ESP32C3]
|
||||
@@ -97,4 +143,5 @@ platform_packages =
|
||||
build_flags =
|
||||
${env.build_flags}
|
||||
-DESP32C3
|
||||
-D BOARD=BOARD_XIAO_ESP32C3
|
||||
board = seeed_xiao_esp32c3
|
||||
|
||||
@@ -25,8 +25,7 @@
|
||||
|
||||
#include <functional>
|
||||
|
||||
namespace SlimeVR {
|
||||
namespace Utils {
|
||||
namespace SlimeVR::Utils {
|
||||
SlimeVR::Logging::Logger m_Logger("FSHelper");
|
||||
|
||||
bool ensureDirectory(const char* directory) {
|
||||
@@ -88,5 +87,4 @@ void forEachFile(const char* directory, std::function<void(File file)> callback)
|
||||
}
|
||||
#endif
|
||||
}
|
||||
} // namespace Utils
|
||||
} // namespace SlimeVR
|
||||
} // namespace SlimeVR::Utils
|
||||
|
||||
@@ -29,8 +29,7 @@
|
||||
|
||||
#include <functional>
|
||||
|
||||
namespace SlimeVR {
|
||||
namespace Utils {
|
||||
namespace SlimeVR::Utils {
|
||||
|
||||
class File {
|
||||
public:
|
||||
@@ -62,7 +61,6 @@ bool ensureDirectory(const char* directory);
|
||||
File openFile(const char* path, const char* mode);
|
||||
|
||||
void forEachFile(const char* directory, std::function<void(File file)> callback);
|
||||
} // namespace Utils
|
||||
} // namespace SlimeVR
|
||||
} // namespace SlimeVR::Utils
|
||||
|
||||
#endif
|
||||
|
||||
@@ -20,18 +20,16 @@
|
||||
OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
|
||||
THE SOFTWARE.
|
||||
*/
|
||||
|
||||
#ifndef GLOBALVARS_H
|
||||
#define GLOBALVARS_H
|
||||
#pragma once
|
||||
|
||||
#include <arduino-timer.h>
|
||||
|
||||
#include "LEDManager.h"
|
||||
#include "batterymonitor.h"
|
||||
#include "configuration/Configuration.h"
|
||||
#include "network/connection.h"
|
||||
#include "network/manager.h"
|
||||
#include "sensors/SensorManager.h"
|
||||
#include "status/LEDManager.h"
|
||||
#include "status/StatusManager.h"
|
||||
|
||||
extern Timer<> globalTimer;
|
||||
@@ -42,5 +40,3 @@ extern SlimeVR::Sensors::SensorManager sensorManager;
|
||||
extern SlimeVR::Network::Manager networkManager;
|
||||
extern SlimeVR::Network::Connection networkConnection;
|
||||
extern BatteryMonitor battery;
|
||||
|
||||
#endif
|
||||
|
||||
@@ -174,3 +174,73 @@ BATTERY_R1(10)
|
||||
BATTERY_R2(40.2)
|
||||
|
||||
#endif
|
||||
|
||||
// Default IMU pinouts and definitions for default tracker types
|
||||
|
||||
#if BOARD != BOARD_GLOVE_IMU_SLIMEVR_DEV
|
||||
// Defaunlt definitions for normal 2-sensor trackers
|
||||
#ifndef MAX_SENSORS_COUNT
|
||||
#define MAX_SENSORS_COUNT 2
|
||||
#endif
|
||||
#ifndef TRACKER_TYPE
|
||||
#define TRACKER_TYPE TrackerType::TRACKER_TYPE_SVR_ROTATION
|
||||
#endif
|
||||
|
||||
// Axis mapping example
|
||||
/*
|
||||
#include "sensors/axisremap.h"
|
||||
#define BMI160_QMC_REMAP AXIS_REMAP_BUILD(AXIS_REMAP_USE_Y, AXIS_REMAP_USE_XN,
|
||||
AXIS_REMAP_USE_Z, \ AXIS_REMAP_USE_YN, AXIS_REMAP_USE_X, AXIS_REMAP_USE_Z)
|
||||
|
||||
SENSOR_DESC_ENTRY(IMU_BMP160, PRIMARY_IMU_ADDRESS_ONE, IMU_ROTATION, PIN_IMU_SCL,
|
||||
PIN_IMU_SDA, PRIMARY_IMU_OPTIONAL, BMI160_QMC_REMAP) \
|
||||
*/
|
||||
|
||||
#ifndef SENSOR_DESC_LIST
|
||||
#if BOARD == BOARD_SLIMEVR_V1_2
|
||||
#define SENSOR_DESC_LIST \
|
||||
SENSOR_DESC_ENTRY( \
|
||||
IMU, \
|
||||
DIRECT_PIN(15), \
|
||||
IMU_ROTATION, \
|
||||
DIRECT_SPI(24'000'000, MSBFIRST, SPI_MODE3), \
|
||||
PRIMARY_IMU_OPTIONAL, \
|
||||
DIRECT_PIN(PIN_IMU_INT), \
|
||||
0 \
|
||||
) \
|
||||
SENSOR_DESC_ENTRY( \
|
||||
SECOND_IMU, \
|
||||
SECONDARY_IMU_ADDRESS_TWO, \
|
||||
SECOND_IMU_ROTATION, \
|
||||
DIRECT_WIRE(PIN_IMU_SCL, PIN_IMU_SDA), \
|
||||
SECONDARY_IMU_OPTIONAL, \
|
||||
DIRECT_PIN(PIN_IMU_INT_2), \
|
||||
0 \
|
||||
)
|
||||
#else
|
||||
#define SENSOR_DESC_LIST \
|
||||
SENSOR_DESC_ENTRY( \
|
||||
IMU, \
|
||||
PRIMARY_IMU_ADDRESS_ONE, \
|
||||
IMU_ROTATION, \
|
||||
DIRECT_WIRE(PIN_IMU_SCL, PIN_IMU_SDA), \
|
||||
PRIMARY_IMU_OPTIONAL, \
|
||||
DIRECT_PIN(PIN_IMU_INT), \
|
||||
0 \
|
||||
) \
|
||||
SENSOR_DESC_ENTRY( \
|
||||
SECOND_IMU, \
|
||||
SECONDARY_IMU_ADDRESS_TWO, \
|
||||
SECOND_IMU_ROTATION, \
|
||||
DIRECT_WIRE(PIN_IMU_SCL, PIN_IMU_SDA), \
|
||||
SECONDARY_IMU_OPTIONAL, \
|
||||
DIRECT_PIN(PIN_IMU_INT_2), \
|
||||
0 \
|
||||
)
|
||||
#endif
|
||||
#endif
|
||||
#else // BOARD == BOARD_GLOVE_IMU_SLIMEVR_DEV
|
||||
|
||||
#include "glove_default.h"
|
||||
|
||||
#endif // BOARD != BOARD_GLOVE_IMU_SLIMEVR_DEV
|
||||
@@ -23,7 +23,7 @@
|
||||
|
||||
#include "defines_helpers.h"
|
||||
|
||||
#include "consts.h"
|
||||
#include "../consts.h"
|
||||
|
||||
#ifndef LED_BUILTIN
|
||||
#define LED_BUILTIN LED_OFF
|
||||
@@ -63,7 +63,9 @@
|
||||
#define LED(pin)
|
||||
#endif
|
||||
|
||||
extern const bool __attribute__((weak)) LED_INVERTED;
|
||||
#ifndef LED_PIN
|
||||
extern const uint8_t __attribute__((weak)) LED_PIN;
|
||||
#endif
|
||||
|
||||
#ifndef BATTERY_SHIELD_RESISTANCE
|
||||
#define BATTERY_SHIELD_R(value) constexpr float BATTERY_SHIELD_RESISTANCE = value;
|
||||
@@ -89,4 +91,6 @@ extern const bool __attribute__((weak)) LED_INVERTED;
|
||||
#define INVERTED_LED(value)
|
||||
#endif
|
||||
|
||||
extern const uint8_t __attribute__((weak)) LED_PIN;
|
||||
#ifndef LED_INVERTED
|
||||
extern const bool __attribute__((weak)) LED_INVERTED;
|
||||
#endif
|
||||
140
src/boards/glove_default.h
Normal file
140
src/boards/glove_default.h
Normal file
@@ -0,0 +1,140 @@
|
||||
// default definitions for the GLOVE
|
||||
#ifndef MAX_SENSORS_COUNT
|
||||
#define MAX_SENSORS_COUNT 10
|
||||
#endif
|
||||
#ifndef TRACKER_TYPE
|
||||
#define TRACKER_TYPE TrackerType::TRACKER_TYPE_SVR_GLOVE_LEFT
|
||||
#endif
|
||||
#ifndef GLOVE_SIDE
|
||||
#define GLOVE_SIDE GLOVE_LEFT
|
||||
#endif
|
||||
#ifndef PRIMARY_IMU_ADDRESS_ONE
|
||||
#define PRIMARY_IMU_ADDRESS_ONE 0x4a
|
||||
#endif
|
||||
#ifndef SECONDARY_IMU_ADDRESS_TWO
|
||||
#define SECONDARY_IMU_ADDRESS_TWO 0x4b
|
||||
#endif
|
||||
|
||||
#ifndef SENSOR_DESC_LIST
|
||||
#define SENSOR_DESC_LIST \
|
||||
SENSOR_DESC_ENTRY( \
|
||||
IMU, \
|
||||
(PRIMARY_IMU_ADDRESS_ONE ^ 0x02), \
|
||||
IMU_ROTATION, \
|
||||
DIRECT_WIRE(PIN_IMU_SCL, PIN_IMU_SDA), \
|
||||
false, \
|
||||
MCP_PIN(MCP_GPA6), \
|
||||
0 \
|
||||
) \
|
||||
SENSOR_DESC_ENTRY( \
|
||||
IMU, \
|
||||
(SECONDARY_IMU_ADDRESS_TWO ^ 0x02), \
|
||||
IMU_ROTATION, \
|
||||
DIRECT_WIRE(PIN_IMU_SCL, PIN_IMU_SDA), \
|
||||
true, \
|
||||
MCP_PIN(MCP_GPA5), \
|
||||
0 \
|
||||
) \
|
||||
SENSOR_DESC_ENTRY( \
|
||||
IMU, \
|
||||
PRIMARY_IMU_ADDRESS_ONE, \
|
||||
IMU_ROTATION, \
|
||||
PCA_WIRE(PIN_IMU_SCL, PIN_IMU_SDA, PCA_ADDR, 0), \
|
||||
true, \
|
||||
MCP_PIN(MCP_GPB0), \
|
||||
0 \
|
||||
) \
|
||||
SENSOR_DESC_ENTRY( \
|
||||
IMU, \
|
||||
SECONDARY_IMU_ADDRESS_TWO, \
|
||||
IMU_ROTATION, \
|
||||
PCA_WIRE(PIN_IMU_SCL, PIN_IMU_SDA, PCA_ADDR, 0), \
|
||||
true, \
|
||||
MCP_PIN(MCP_GPB1), \
|
||||
0 \
|
||||
) \
|
||||
SENSOR_DESC_ENTRY( \
|
||||
IMU, \
|
||||
PRIMARY_IMU_ADDRESS_ONE, \
|
||||
IMU_ROTATION, \
|
||||
PCA_WIRE(PIN_IMU_SCL, PIN_IMU_SDA, PCA_ADDR, 1), \
|
||||
true, \
|
||||
MCP_PIN(MCP_GPB2), \
|
||||
0 \
|
||||
) \
|
||||
SENSOR_DESC_ENTRY( \
|
||||
IMU, \
|
||||
SECONDARY_IMU_ADDRESS_TWO, \
|
||||
IMU_ROTATION, \
|
||||
PCA_WIRE(PIN_IMU_SCL, PIN_IMU_SDA, PCA_ADDR, 1), \
|
||||
true, \
|
||||
MCP_PIN(MCP_GPB3), \
|
||||
0 \
|
||||
) \
|
||||
SENSOR_DESC_ENTRY( \
|
||||
IMU, \
|
||||
PRIMARY_IMU_ADDRESS_ONE, \
|
||||
IMU_ROTATION, \
|
||||
PCA_WIRE(PIN_IMU_SCL, PIN_IMU_SDA, PCA_ADDR, 2), \
|
||||
true, \
|
||||
MCP_PIN(MCP_GPB4), \
|
||||
0 \
|
||||
) \
|
||||
SENSOR_DESC_ENTRY( \
|
||||
IMU, \
|
||||
SECONDARY_IMU_ADDRESS_TWO, \
|
||||
IMU_ROTATION, \
|
||||
PCA_WIRE(PIN_IMU_SCL, PIN_IMU_SDA, PCA_ADDR, 2), \
|
||||
true, \
|
||||
MCP_PIN(MCP_GPB5), \
|
||||
0 \
|
||||
) \
|
||||
SENSOR_DESC_ENTRY( \
|
||||
IMU, \
|
||||
PRIMARY_IMU_ADDRESS_ONE, \
|
||||
IMU_ROTATION, \
|
||||
PCA_WIRE(PIN_IMU_SCL, PIN_IMU_SDA, PCA_ADDR, 3), \
|
||||
true, \
|
||||
MCP_PIN(MCP_GPB6), \
|
||||
0 \
|
||||
) \
|
||||
SENSOR_DESC_ENTRY( \
|
||||
IMU, \
|
||||
SECONDARY_IMU_ADDRESS_TWO, \
|
||||
IMU_ROTATION, \
|
||||
PCA_WIRE(PIN_IMU_SCL, PIN_IMU_SDA, PCA_ADDR, 3), \
|
||||
true, \
|
||||
MCP_PIN(MCP_GPA1), \
|
||||
0 \
|
||||
)
|
||||
#endif
|
||||
|
||||
#ifndef SENSOR_INFO_LIST
|
||||
#if GLOVE_SIDE == GLOVE_LEFT
|
||||
#define SENSOR_INFO_LIST \
|
||||
SENSOR_INFO_ENTRY(0, SensorPosition::POSITION_LEFT_HAND) \
|
||||
SENSOR_INFO_ENTRY(1, SensorPosition::POSITION_LEFT_LITTLE_INTERMEDIATE) \
|
||||
SENSOR_INFO_ENTRY(2, SensorPosition::POSITION_LEFT_RING_INTERMEDIATE) \
|
||||
SENSOR_INFO_ENTRY(3, SensorPosition::POSITION_LEFT_RING_DISTAL) \
|
||||
SENSOR_INFO_ENTRY(4, SensorPosition::POSITION_LEFT_MIDDLE_INTERMEDIATE) \
|
||||
SENSOR_INFO_ENTRY(5, SensorPosition::POSITION_LEFT_MIDDLE_DISTAL) \
|
||||
SENSOR_INFO_ENTRY(6, SensorPosition::POSITION_LEFT_INDEX_INTERMEDIATE) \
|
||||
SENSOR_INFO_ENTRY(7, SensorPosition::POSITION_LEFT_INDEX_DISTAL) \
|
||||
SENSOR_INFO_ENTRY(8, SensorPosition::POSITION_LEFT_THUMB_PROXIMAL) \
|
||||
SENSOR_INFO_ENTRY(9, SensorPosition::POSITION_LEFT_THUMB_DISTAL)
|
||||
#elif GLOVE_SDIE == GLOVE_RIGHT
|
||||
#define SENSOR_INFO_LIST \
|
||||
SENSOR_INFO_ENTRY(0, SensorPosition::POSITION_RIGHT_HAND) \
|
||||
SENSOR_INFO_ENTRY(1, SensorPosition::POSITION_RIGHT_LITTLE_INTERMEDIATE) \
|
||||
SENSOR_INFO_ENTRY(2, SensorPosition::POSITION_RIGHT_RING_INTERMEDIATE) \
|
||||
SENSOR_INFO_ENTRY(3, SensorPosition::POSITION_RIGHT_RING_DISTAL) \
|
||||
SENSOR_INFO_ENTRY(4, SensorPosition::POSITION_RIGHT_MIDDLE_INTERMEDIATE) \
|
||||
SENSOR_INFO_ENTRY(5, SensorPosition::POSITION_RIGHT_MIDDLE_DISTAL) \
|
||||
SENSOR_INFO_ENTRY(6, SensorPosition::POSITION_RIGHT_INDEX_INTERMEDIATE) \
|
||||
SENSOR_INFO_ENTRY(7, SensorPosition::POSITION_RIGHT_INDEX_DISTAL) \
|
||||
SENSOR_INFO_ENTRY(8, SensorPosition::POSITION_RIGHT_THUMB_PROXIMAL) \
|
||||
SENSOR_INFO_ENTRY(9, SensorPosition::POSITION_RIGHT_THUMB_DISTAL)
|
||||
#else // GLOVE_SIDE
|
||||
#error "Glove side not defined"
|
||||
#endif // GLOVE_SIDE
|
||||
#endif
|
||||
@@ -33,8 +33,7 @@
|
||||
#define DIR_TEMPERATURE_CALIBRATIONS "/tempcalibrations"
|
||||
#define DIR_TOGGLES "/toggles"
|
||||
|
||||
namespace SlimeVR {
|
||||
namespace Configuration {
|
||||
namespace SlimeVR::Configuration {
|
||||
void Configuration::setup() {
|
||||
if (m_Loaded) {
|
||||
return;
|
||||
@@ -442,5 +441,4 @@ void Configuration::print() {
|
||||
}
|
||||
}
|
||||
}
|
||||
} // namespace Configuration
|
||||
} // namespace SlimeVR
|
||||
} // namespace SlimeVR::Configuration
|
||||
|
||||
@@ -31,8 +31,7 @@
|
||||
#include "DeviceConfig.h"
|
||||
#include "logging/Logger.h"
|
||||
|
||||
namespace SlimeVR {
|
||||
namespace Configuration {
|
||||
namespace SlimeVR::Configuration {
|
||||
class Configuration {
|
||||
public:
|
||||
void setup();
|
||||
@@ -72,7 +71,6 @@ private:
|
||||
|
||||
Logging::Logger m_Logger = Logging::Logger("Configuration");
|
||||
};
|
||||
} // namespace Configuration
|
||||
} // namespace SlimeVR
|
||||
} // namespace SlimeVR::Configuration
|
||||
|
||||
#endif
|
||||
|
||||
@@ -23,8 +23,7 @@
|
||||
|
||||
#include "SensorConfig.h"
|
||||
|
||||
namespace SlimeVR {
|
||||
namespace Configuration {
|
||||
namespace SlimeVR::Configuration {
|
||||
const char* calibrationConfigTypeToString(SensorConfigType type) {
|
||||
switch (type) {
|
||||
case SensorConfigType::NONE:
|
||||
@@ -60,5 +59,4 @@ bool SensorConfigBits::operator!=(const SensorConfigBits& rhs) const {
|
||||
return !(*this == rhs);
|
||||
}
|
||||
|
||||
} // namespace Configuration
|
||||
} // namespace SlimeVR
|
||||
} // namespace SlimeVR::Configuration
|
||||
|
||||
@@ -28,8 +28,7 @@
|
||||
|
||||
#include "consts.h"
|
||||
|
||||
namespace SlimeVR {
|
||||
namespace Configuration {
|
||||
namespace SlimeVR::Configuration {
|
||||
struct BMI160SensorConfig {
|
||||
// accelerometer offsets and correction matrix
|
||||
float A_B[3];
|
||||
@@ -196,7 +195,6 @@ struct SensorConfigBits {
|
||||
// If this fails, you forgot to do the above
|
||||
static_assert(sizeof(SensorConfigBits) == 2);
|
||||
|
||||
} // namespace Configuration
|
||||
} // namespace SlimeVR
|
||||
} // namespace SlimeVR::Configuration
|
||||
|
||||
#endif
|
||||
|
||||
205
src/defines.h
205
src/defines.h
@@ -26,214 +26,41 @@
|
||||
// ================================================
|
||||
|
||||
// Set parameters of IMU and board used
|
||||
#ifndef IMU
|
||||
#define IMU IMU_AUTO
|
||||
#endif
|
||||
#ifndef SECOND_IMU
|
||||
#define SECOND_IMU IMU_AUTO
|
||||
#endif
|
||||
#ifndef BOARD
|
||||
#define BOARD BOARD_SLIMEVR_V1_2
|
||||
#endif
|
||||
#ifndef IMU_ROTATION
|
||||
#define IMU_ROTATION DEG_270
|
||||
#endif
|
||||
#ifndef SECOND_IMU_ROTATION
|
||||
#define SECOND_IMU_ROTATION DEG_270
|
||||
#endif
|
||||
|
||||
#ifndef PRIMARY_IMU_OPTIONAL
|
||||
#define PRIMARY_IMU_OPTIONAL false
|
||||
#endif
|
||||
#ifndef SECONDARY_IMU_OPTIONAL
|
||||
#define SECONDARY_IMU_OPTIONAL true
|
||||
#endif
|
||||
|
||||
#if BOARD != BOARD_GLOVE_IMU_SLIMEVR_DEV
|
||||
#define MAX_SENSORS_COUNT 2
|
||||
#define TRACKER_TYPE TrackerType::TRACKER_TYPE_SVR_ROTATION
|
||||
// Set I2C address here or directly in IMU_DESC_ENTRY for each IMU used
|
||||
// If not set, default address is used based on the IMU and Sensor ID
|
||||
// #define PRIMARY_IMU_ADDRESS_ONE 0x4a
|
||||
// #define SECONDARY_IMU_ADDRESS_TWO 0x4b
|
||||
|
||||
// Axis mapping example
|
||||
/*
|
||||
#include "sensors/axisremap.h"
|
||||
#define BMI160_QMC_REMAP AXIS_REMAP_BUILD(AXIS_REMAP_USE_Y, AXIS_REMAP_USE_XN,
|
||||
AXIS_REMAP_USE_Z, \ AXIS_REMAP_USE_YN, AXIS_REMAP_USE_X, AXIS_REMAP_USE_Z)
|
||||
|
||||
SENSOR_DESC_ENTRY(IMU_BMP160, PRIMARY_IMU_ADDRESS_ONE, IMU_ROTATION, PIN_IMU_SCL,
|
||||
PIN_IMU_SDA, PRIMARY_IMU_OPTIONAL, BMI160_QMC_REMAP) \
|
||||
*/
|
||||
|
||||
#ifndef SENSOR_DESC_LIST
|
||||
#if BOARD == BOARD_SLIMEVR_V1_2
|
||||
#define SENSOR_DESC_LIST \
|
||||
SENSOR_DESC_ENTRY( \
|
||||
IMU, \
|
||||
DIRECT_SPI(24'000'000, MSBFIRST, SPI_MODE3, DIRECT_PIN(15)), \
|
||||
IMU_ROTATION, \
|
||||
NO_WIRE, \
|
||||
PRIMARY_IMU_OPTIONAL, \
|
||||
DIRECT_PIN(PIN_IMU_INT), \
|
||||
0 \
|
||||
) \
|
||||
SENSOR_DESC_ENTRY( \
|
||||
SECOND_IMU, \
|
||||
SECONDARY_IMU_ADDRESS_TWO, \
|
||||
SECOND_IMU_ROTATION, \
|
||||
DIRECT_WIRE(PIN_IMU_SCL, PIN_IMU_SDA), \
|
||||
SECONDARY_IMU_OPTIONAL, \
|
||||
DIRECT_PIN(PIN_IMU_INT_2), \
|
||||
0 \
|
||||
)
|
||||
#else
|
||||
#define SENSOR_DESC_LIST \
|
||||
SENSOR_DESC_ENTRY( \
|
||||
IMU, \
|
||||
PRIMARY_IMU_ADDRESS_ONE, \
|
||||
IMU_ROTATION, \
|
||||
DIRECT_WIRE(PIN_IMU_SCL, PIN_IMU_SDA), \
|
||||
PRIMARY_IMU_OPTIONAL, \
|
||||
DIRECT_PIN(PIN_IMU_INT), \
|
||||
0 \
|
||||
) \
|
||||
SENSOR_DESC_ENTRY( \
|
||||
SECOND_IMU, \
|
||||
SECONDARY_IMU_ADDRESS_TWO, \
|
||||
SECOND_IMU_ROTATION, \
|
||||
DIRECT_WIRE(PIN_IMU_SCL, PIN_IMU_SDA), \
|
||||
SECONDARY_IMU_OPTIONAL, \
|
||||
DIRECT_PIN(PIN_IMU_INT_2), \
|
||||
0 \
|
||||
)
|
||||
#endif
|
||||
#endif
|
||||
#else
|
||||
|
||||
// Predefines for the GLOVE
|
||||
#ifndef SENSOR_DESC_LIST
|
||||
#define MAX_SENSORS_COUNT 10
|
||||
#define TRACKER_TYPE TrackerType::TRACKER_TYPE_SVR_GLOVE_LEFT
|
||||
#define GLOVE_SIDE GLOVE_LEFT
|
||||
#define PRIMARY_IMU_ADDRESS_ONE 0x4a
|
||||
#define SECONDARY_IMU_ADDRESS_TWO 0x4b
|
||||
|
||||
#define SENSOR_DESC_LIST \
|
||||
SENSOR_DESC_ENTRY( \
|
||||
IMU, \
|
||||
(PRIMARY_IMU_ADDRESS_ONE ^ 0x02), \
|
||||
IMU_ROTATION, \
|
||||
DIRECT_WIRE(PIN_IMU_SCL, PIN_IMU_SDA), \
|
||||
false, \
|
||||
MCP_PIN(MCP_GPA6), \
|
||||
0 \
|
||||
) \
|
||||
SENSOR_DESC_ENTRY( \
|
||||
IMU, \
|
||||
(SECONDARY_IMU_ADDRESS_TWO ^ 0x02), \
|
||||
IMU_ROTATION, \
|
||||
DIRECT_WIRE(PIN_IMU_SCL, PIN_IMU_SDA), \
|
||||
true, \
|
||||
MCP_PIN(MCP_GPA5), \
|
||||
0 \
|
||||
) \
|
||||
SENSOR_DESC_ENTRY( \
|
||||
IMU, \
|
||||
PRIMARY_IMU_ADDRESS_ONE, \
|
||||
IMU_ROTATION, \
|
||||
PCA_WIRE(PIN_IMU_SCL, PIN_IMU_SDA, PCA_ADDR, 0), \
|
||||
true, \
|
||||
MCP_PIN(MCP_GPB0), \
|
||||
0 \
|
||||
) \
|
||||
SENSOR_DESC_ENTRY( \
|
||||
IMU, \
|
||||
SECONDARY_IMU_ADDRESS_TWO, \
|
||||
IMU_ROTATION, \
|
||||
PCA_WIRE(PIN_IMU_SCL, PIN_IMU_SDA, PCA_ADDR, 0), \
|
||||
true, \
|
||||
MCP_PIN(MCP_GPB1), \
|
||||
0 \
|
||||
) \
|
||||
SENSOR_DESC_ENTRY( \
|
||||
IMU, \
|
||||
PRIMARY_IMU_ADDRESS_ONE, \
|
||||
IMU_ROTATION, \
|
||||
PCA_WIRE(PIN_IMU_SCL, PIN_IMU_SDA, PCA_ADDR, 1), \
|
||||
true, \
|
||||
MCP_PIN(MCP_GPB2), \
|
||||
0 \
|
||||
) \
|
||||
SENSOR_DESC_ENTRY( \
|
||||
IMU, \
|
||||
SECONDARY_IMU_ADDRESS_TWO, \
|
||||
IMU_ROTATION, \
|
||||
PCA_WIRE(PIN_IMU_SCL, PIN_IMU_SDA, PCA_ADDR, 1), \
|
||||
true, \
|
||||
MCP_PIN(MCP_GPB3), \
|
||||
0 \
|
||||
) \
|
||||
SENSOR_DESC_ENTRY( \
|
||||
IMU, \
|
||||
PRIMARY_IMU_ADDRESS_ONE, \
|
||||
IMU_ROTATION, \
|
||||
PCA_WIRE(PIN_IMU_SCL, PIN_IMU_SDA, PCA_ADDR, 2), \
|
||||
true, \
|
||||
MCP_PIN(MCP_GPB4), \
|
||||
0 \
|
||||
) \
|
||||
SENSOR_DESC_ENTRY( \
|
||||
IMU, \
|
||||
SECONDARY_IMU_ADDRESS_TWO, \
|
||||
IMU_ROTATION, \
|
||||
PCA_WIRE(PIN_IMU_SCL, PIN_IMU_SDA, PCA_ADDR, 2), \
|
||||
true, \
|
||||
MCP_PIN(MCP_GPB5), \
|
||||
0 \
|
||||
) \
|
||||
SENSOR_DESC_ENTRY( \
|
||||
IMU, \
|
||||
PRIMARY_IMU_ADDRESS_ONE, \
|
||||
IMU_ROTATION, \
|
||||
PCA_WIRE(PIN_IMU_SCL, PIN_IMU_SDA, PCA_ADDR, 3), \
|
||||
true, \
|
||||
MCP_PIN(MCP_GPB6), \
|
||||
0 \
|
||||
) \
|
||||
SENSOR_DESC_ENTRY( \
|
||||
IMU, \
|
||||
SECONDARY_IMU_ADDRESS_TWO, \
|
||||
IMU_ROTATION, \
|
||||
PCA_WIRE(PIN_IMU_SCL, PIN_IMU_SDA, PCA_ADDR, 3), \
|
||||
true, \
|
||||
MCP_PIN(MCP_GPA1), \
|
||||
0 \
|
||||
)
|
||||
|
||||
#if GLOVE_SIDE == GLOVE_LEFT
|
||||
#define SENSOR_INFO_LIST \
|
||||
SENSOR_INFO_ENTRY(0, SensorPosition::POSITION_LEFT_HAND) \
|
||||
SENSOR_INFO_ENTRY(1, SensorPosition::POSITION_LEFT_LITTLE_INTERMEDIATE) \
|
||||
SENSOR_INFO_ENTRY(2, SensorPosition::POSITION_LEFT_RING_INTERMEDIATE) \
|
||||
SENSOR_INFO_ENTRY(3, SensorPosition::POSITION_LEFT_RING_DISTAL) \
|
||||
SENSOR_INFO_ENTRY(4, SensorPosition::POSITION_LEFT_MIDDLE_INTERMEDIATE) \
|
||||
SENSOR_INFO_ENTRY(5, SensorPosition::POSITION_LEFT_MIDDLE_DISTAL) \
|
||||
SENSOR_INFO_ENTRY(6, SensorPosition::POSITION_LEFT_INDEX_INTERMEDIATE) \
|
||||
SENSOR_INFO_ENTRY(7, SensorPosition::POSITION_LEFT_INDEX_DISTAL) \
|
||||
SENSOR_INFO_ENTRY(8, SensorPosition::POSITION_LEFT_THUMB_PROXIMAL) \
|
||||
SENSOR_INFO_ENTRY(9, SensorPosition::POSITION_LEFT_THUMB_DISTAL)
|
||||
#elif GLOVE_SDIE == GLOVE_RIGHT
|
||||
#define SENSOR_INFO_LIST \
|
||||
SENSOR_INFO_ENTRY(0, SensorPosition::POSITION_RIGHT_HAND) \
|
||||
SENSOR_INFO_ENTRY(1, SensorPosition::POSITION_RIGHT_LITTLE_INTERMEDIATE) \
|
||||
SENSOR_INFO_ENTRY(2, SensorPosition::POSITION_RIGHT_RING_INTERMEDIATE) \
|
||||
SENSOR_INFO_ENTRY(3, SensorPosition::POSITION_RIGHT_RING_DISTAL) \
|
||||
SENSOR_INFO_ENTRY(4, SensorPosition::POSITION_RIGHT_MIDDLE_INTERMEDIATE) \
|
||||
SENSOR_INFO_ENTRY(5, SensorPosition::POSITION_RIGHT_MIDDLE_DISTAL) \
|
||||
SENSOR_INFO_ENTRY(6, SensorPosition::POSITION_RIGHT_INDEX_INTERMEDIATE) \
|
||||
SENSOR_INFO_ENTRY(7, SensorPosition::POSITION_RIGHT_INDEX_DISTAL) \
|
||||
SENSOR_INFO_ENTRY(8, SensorPosition::POSITION_RIGHT_THUMB_PROXIMAL) \
|
||||
SENSOR_INFO_ENTRY(9, SensorPosition::POSITION_RIGHT_THUMB_DISTAL)
|
||||
#else // GLOVE_SDIE
|
||||
#error "Glove side not defined"
|
||||
#endif // GLOVE_SDIE
|
||||
|
||||
#endif // SENSOR_DESC_LIST
|
||||
#endif // BOARD != BOARD_GLOVE_IMU_SLIMEVR_DEV
|
||||
|
||||
#ifndef BATTERY_MONITOR
|
||||
// Battery monitoring options (comment to disable):
|
||||
// BAT_EXTERNAL for ADC pin,
|
||||
// BAT_INTERNAL for internal - can detect only low battery,
|
||||
// BAT_MCP3021 for external ADC connected over I2C
|
||||
#define BATTERY_MONITOR BAT_EXTERNAL
|
||||
#endif
|
||||
|
||||
// --- OVERRIDES FOR DEFAULT PINS
|
||||
|
||||
|
||||
@@ -20,8 +20,7 @@
|
||||
OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
|
||||
THE SOFTWARE.
|
||||
*/
|
||||
#ifndef SLIMEVR_GLOBALS_H_
|
||||
#define SLIMEVR_GLOBALS_H_
|
||||
#pragma once
|
||||
|
||||
#include <Arduino.h>
|
||||
|
||||
@@ -30,7 +29,7 @@
|
||||
#include "defines.h"
|
||||
|
||||
// clang-format off
|
||||
#include "board_default.h"
|
||||
#include "boards/boards_default.h"
|
||||
// clang-format on
|
||||
|
||||
#ifndef SECOND_IMU
|
||||
@@ -53,5 +52,3 @@
|
||||
#ifndef EXPERIMENTAL_BNO_DISABLE_ACCEL_CALIBRATION
|
||||
#define EXPERIMENTAL_BNO_DISABLE_ACCEL_CALIBRATION true
|
||||
#endif
|
||||
|
||||
#endif // SLIMEVR_GLOBALS_H_
|
||||
|
||||
@@ -1,7 +1,6 @@
|
||||
#include "Level.h"
|
||||
|
||||
namespace SlimeVR {
|
||||
namespace Logging {
|
||||
namespace SlimeVR::Logging {
|
||||
const char* levelToString(Level level) {
|
||||
switch (level) {
|
||||
case TRACE:
|
||||
@@ -20,5 +19,4 @@ const char* levelToString(Level level) {
|
||||
return "UNKNOWN";
|
||||
}
|
||||
}
|
||||
} // namespace Logging
|
||||
} // namespace SlimeVR
|
||||
} // namespace SlimeVR::Logging
|
||||
|
||||
@@ -7,8 +7,7 @@
|
||||
#define LOG_LEVEL_ERROR 4
|
||||
#define LOG_LEVEL_FATAL 5
|
||||
|
||||
namespace SlimeVR {
|
||||
namespace Logging {
|
||||
namespace SlimeVR::Logging {
|
||||
enum Level {
|
||||
TRACE = LOG_LEVEL_TRACE,
|
||||
DEBUG = LOG_LEVEL_DEBUG,
|
||||
@@ -19,8 +18,7 @@ enum Level {
|
||||
};
|
||||
|
||||
const char* levelToString(Level level);
|
||||
} // namespace Logging
|
||||
} // namespace SlimeVR
|
||||
} // namespace SlimeVR::Logging
|
||||
|
||||
#define LOGGING_LEVEL_H
|
||||
#endif
|
||||
|
||||
@@ -1,7 +1,6 @@
|
||||
#include "Logger.h"
|
||||
|
||||
namespace SlimeVR {
|
||||
namespace Logging {
|
||||
namespace SlimeVR::Logging {
|
||||
void Logger::setTag(const char* tag) {
|
||||
m_Tag = (char*)malloc(strlen(tag) + 1);
|
||||
strcpy(m_Tag, tag);
|
||||
@@ -66,5 +65,4 @@ void Logger::log(Level level, const char* format, va_list args) const {
|
||||
|
||||
Serial.printf("[%-5s] [%s] %s\n", levelToString(level), buf, buffer);
|
||||
}
|
||||
} // namespace Logging
|
||||
} // namespace SlimeVR
|
||||
} // namespace SlimeVR::Logging
|
||||
|
||||
@@ -6,8 +6,7 @@
|
||||
#include "Level.h"
|
||||
#include "debug.h"
|
||||
|
||||
namespace SlimeVR {
|
||||
namespace Logging {
|
||||
namespace SlimeVR::Logging {
|
||||
class Logger {
|
||||
public:
|
||||
Logger(const char* prefix)
|
||||
@@ -92,7 +91,6 @@ private:
|
||||
const char* const m_Prefix;
|
||||
char* m_Tag;
|
||||
};
|
||||
} // namespace Logging
|
||||
} // namespace SlimeVR
|
||||
} // namespace SlimeVR::Logging
|
||||
|
||||
#endif
|
||||
|
||||
@@ -227,7 +227,7 @@ bool GyroTemperatureCalibrator::loadConfig(float newSensitivity) {
|
||||
bool GyroTemperatureCalibrator::saveConfig() {
|
||||
if (configuration.saveTemperatureCalibration(sensorId, config)) {
|
||||
m_Logger.info(
|
||||
"Saved temperature calibration config (%0.1f%) for sensorId:%i",
|
||||
"Saved temperature calibration config (%0.1f%%) for sensorId:%i",
|
||||
config.getCalibrationDonePercent(),
|
||||
sensorId
|
||||
);
|
||||
|
||||
@@ -24,8 +24,7 @@
|
||||
|
||||
#include "GlobalVars.h"
|
||||
|
||||
namespace SlimeVR {
|
||||
namespace Network {
|
||||
namespace SlimeVR::Network {
|
||||
|
||||
void Manager::setup() { ::WiFiNetwork::setUp(); }
|
||||
|
||||
@@ -48,5 +47,4 @@ void Manager::update() {
|
||||
networkConnection.update();
|
||||
}
|
||||
|
||||
} // namespace Network
|
||||
} // namespace SlimeVR
|
||||
} // namespace SlimeVR::Network
|
||||
|
||||
@@ -28,8 +28,7 @@
|
||||
#include "wifihandler.h"
|
||||
#include "wifiprovisioning.h"
|
||||
|
||||
namespace SlimeVR {
|
||||
namespace Network {
|
||||
namespace SlimeVR::Network {
|
||||
|
||||
class Manager {
|
||||
public:
|
||||
@@ -40,7 +39,6 @@ private:
|
||||
bool m_IsConnected = false;
|
||||
};
|
||||
|
||||
} // namespace Network
|
||||
} // namespace SlimeVR
|
||||
} // namespace SlimeVR::Network
|
||||
|
||||
#endif // SLIMEVR_NETWORK_MANAGER_H_
|
||||
|
||||
54
src/sensorinterface/DirectSPIInterface.cpp
Normal file
54
src/sensorinterface/DirectSPIInterface.cpp
Normal file
@@ -0,0 +1,54 @@
|
||||
/*
|
||||
SlimeVR Code is placed under the MIT license
|
||||
Copyright (c) 2025 Gorbit99 & 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.
|
||||
*/
|
||||
|
||||
#include "DirectSPIInterface.h"
|
||||
|
||||
#include <Arduino.h>
|
||||
#include <PinInterface.h>
|
||||
|
||||
namespace SlimeVR {
|
||||
|
||||
DirectSPIInterface::DirectSPIInterface(SPIClass& spiClass, SPISettings spiSettings)
|
||||
: m_spiClass{spiClass}
|
||||
, m_spiSettings{spiSettings} {}
|
||||
|
||||
bool DirectSPIInterface::init() {
|
||||
m_spiClass.begin();
|
||||
return true;
|
||||
}
|
||||
|
||||
void DirectSPIInterface::swapIn() {}
|
||||
|
||||
void DirectSPIInterface::beginTransaction(PinInterface* csPin) {
|
||||
m_spiClass.beginTransaction(m_spiSettings);
|
||||
csPin->digitalWrite(LOW);
|
||||
}
|
||||
|
||||
void DirectSPIInterface::endTransaction(PinInterface* csPin) {
|
||||
csPin->digitalWrite(HIGH);
|
||||
m_spiClass.endTransaction();
|
||||
}
|
||||
|
||||
const SPISettings& DirectSPIInterface::getSpiSettings() { return m_spiSettings; }
|
||||
|
||||
} // namespace SlimeVR
|
||||
56
src/sensorinterface/DirectSPIInterface.h
Normal file
56
src/sensorinterface/DirectSPIInterface.h
Normal file
@@ -0,0 +1,56 @@
|
||||
/*
|
||||
SlimeVR Code is placed under the MIT license
|
||||
Copyright (c) 2025 Gorbit99 & 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.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <PinInterface.h>
|
||||
#include <SPI.h>
|
||||
|
||||
#include "SensorInterface.h"
|
||||
|
||||
namespace SlimeVR {
|
||||
|
||||
class DirectSPIInterface : public SensorInterface {
|
||||
public:
|
||||
DirectSPIInterface(SPIClass& spiClass, SPISettings spiSettings);
|
||||
bool init() final;
|
||||
void swapIn() final;
|
||||
|
||||
void beginTransaction(PinInterface* csPin);
|
||||
void endTransaction(PinInterface* csPin);
|
||||
|
||||
[[nodiscard]] std::string toString() const final { return std::string{"SPI"}; }
|
||||
|
||||
template <typename... Args>
|
||||
auto transfer(Args... args) {
|
||||
return m_spiClass.transfer(args...);
|
||||
}
|
||||
|
||||
const SPISettings& getSpiSettings();
|
||||
|
||||
private:
|
||||
SPIClass& m_spiClass;
|
||||
SPISettings m_spiSettings;
|
||||
};
|
||||
|
||||
} // namespace SlimeVR
|
||||
@@ -28,6 +28,7 @@
|
||||
#include <cstdint>
|
||||
|
||||
#include "../logging/Logger.h"
|
||||
#include "DirectSPIInterface.h"
|
||||
#include "RegisterInterface.h"
|
||||
|
||||
#define ICM_READ_FLAG 0x80
|
||||
@@ -35,10 +36,10 @@
|
||||
namespace SlimeVR::Sensors {
|
||||
|
||||
struct SPIImpl : public RegisterInterface {
|
||||
SPIImpl(SPIClass& spiClass, SPISettings spiSettings, PinInterface* csPin)
|
||||
: m_spiClass(spiClass)
|
||||
, m_spiSettings(spiSettings)
|
||||
SPIImpl(DirectSPIInterface* spi, PinInterface* csPin)
|
||||
: m_spi(spi)
|
||||
, m_csPin(csPin) {
|
||||
auto& spiSettings = spi->getSpiSettings();
|
||||
m_Logger.info(
|
||||
"SPI settings: clock: %d, bit order: 0x%02X, data mode: 0x%02X",
|
||||
spiSettings._clock,
|
||||
@@ -47,83 +48,69 @@ struct SPIImpl : public RegisterInterface {
|
||||
);
|
||||
csPin->pinMode(OUTPUT);
|
||||
csPin->digitalWrite(HIGH);
|
||||
spiClass.begin();
|
||||
}
|
||||
|
||||
uint8_t readReg(uint8_t regAddr) const override {
|
||||
m_spiClass.beginTransaction(m_spiSettings);
|
||||
m_csPin->digitalWrite(LOW);
|
||||
m_spi->beginTransaction(m_csPin);
|
||||
|
||||
m_spiClass.transfer(regAddr | ICM_READ_FLAG);
|
||||
uint8_t buffer = m_spiClass.transfer(0);
|
||||
m_spi->transfer(regAddr | ICM_READ_FLAG);
|
||||
uint8_t buffer = m_spi->transfer(0);
|
||||
|
||||
m_csPin->digitalWrite(HIGH);
|
||||
m_spiClass.endTransaction();
|
||||
m_spi->endTransaction(m_csPin);
|
||||
|
||||
return buffer;
|
||||
}
|
||||
|
||||
uint16_t readReg16(uint8_t regAddr) const override {
|
||||
m_spiClass.beginTransaction(m_spiSettings);
|
||||
m_csPin->digitalWrite(LOW);
|
||||
m_spi->beginTransaction(m_csPin);
|
||||
|
||||
m_spiClass.transfer(regAddr | ICM_READ_FLAG);
|
||||
uint8_t b1 = m_spiClass.transfer(0);
|
||||
uint8_t b2 = m_spiClass.transfer(0);
|
||||
m_spi->transfer(regAddr | ICM_READ_FLAG);
|
||||
uint8_t b1 = m_spi->transfer(0);
|
||||
uint8_t b2 = m_spi->transfer(0);
|
||||
|
||||
m_csPin->digitalWrite(HIGH);
|
||||
m_spiClass.endTransaction();
|
||||
m_spi->endTransaction(m_csPin);
|
||||
return b2 << 8 | b1;
|
||||
}
|
||||
|
||||
void writeReg(uint8_t regAddr, uint8_t value) const override {
|
||||
m_spiClass.beginTransaction(m_spiSettings);
|
||||
m_csPin->digitalWrite(LOW);
|
||||
m_spi->beginTransaction(m_csPin);
|
||||
|
||||
m_spiClass.transfer(regAddr);
|
||||
m_spiClass.transfer(value);
|
||||
m_spi->transfer(regAddr);
|
||||
m_spi->transfer(value);
|
||||
|
||||
m_csPin->digitalWrite(HIGH);
|
||||
m_spiClass.endTransaction();
|
||||
m_spi->endTransaction(m_csPin);
|
||||
}
|
||||
|
||||
void writeReg16(uint8_t regAddr, uint16_t value) const override {
|
||||
m_spiClass.beginTransaction(m_spiSettings);
|
||||
m_csPin->digitalWrite(LOW);
|
||||
m_spi->beginTransaction(m_csPin);
|
||||
|
||||
m_spiClass.transfer(regAddr);
|
||||
m_spiClass.transfer(value & 0xFF);
|
||||
m_spiClass.transfer(value >> 8);
|
||||
m_spi->transfer(regAddr);
|
||||
m_spi->transfer(value & 0xFF);
|
||||
m_spi->transfer(value >> 8);
|
||||
|
||||
m_csPin->digitalWrite(HIGH);
|
||||
m_spiClass.endTransaction();
|
||||
m_spi->endTransaction(m_csPin);
|
||||
}
|
||||
|
||||
void readBytes(uint8_t regAddr, uint8_t size, uint8_t* buffer) const override {
|
||||
m_spiClass.beginTransaction(m_spiSettings);
|
||||
m_csPin->digitalWrite(LOW);
|
||||
;
|
||||
m_spi->beginTransaction(m_csPin);
|
||||
|
||||
m_spiClass.transfer(regAddr | ICM_READ_FLAG);
|
||||
m_spi->transfer(regAddr | ICM_READ_FLAG);
|
||||
for (uint8_t i = 0; i < size; ++i) {
|
||||
buffer[i] = m_spiClass.transfer(0);
|
||||
buffer[i] = m_spi->transfer(0);
|
||||
}
|
||||
|
||||
m_csPin->digitalWrite(HIGH);
|
||||
m_spiClass.endTransaction();
|
||||
m_spi->endTransaction(m_csPin);
|
||||
}
|
||||
|
||||
void writeBytes(uint8_t regAddr, uint8_t size, uint8_t* buffer) const override {
|
||||
m_spiClass.beginTransaction(m_spiSettings);
|
||||
m_csPin->digitalWrite(LOW);
|
||||
m_spi->beginTransaction(m_csPin);
|
||||
|
||||
m_spiClass.transfer(regAddr);
|
||||
m_spi->transfer(regAddr);
|
||||
for (uint8_t i = 0; i < size; ++i) {
|
||||
m_spiClass.transfer(buffer[i]);
|
||||
m_spi->transfer(buffer[i]);
|
||||
}
|
||||
|
||||
m_csPin->digitalWrite(HIGH);
|
||||
m_spiClass.endTransaction();
|
||||
m_spi->endTransaction(m_csPin);
|
||||
}
|
||||
|
||||
bool hasSensorOnBus() override {
|
||||
@@ -135,8 +122,7 @@ struct SPIImpl : public RegisterInterface {
|
||||
std::string toString() const override { return std::string("SPI"); }
|
||||
|
||||
private:
|
||||
SPIClass& m_spiClass;
|
||||
SPISettings m_spiSettings;
|
||||
DirectSPIInterface* m_spi;
|
||||
PinInterface* m_csPin;
|
||||
SlimeVR::Logging::Logger m_Logger = SlimeVR::Logging::Logger("SPI");
|
||||
};
|
||||
|
||||
30
src/sensorinterface/SensorInterface.cpp
Normal file
30
src/sensorinterface/SensorInterface.cpp
Normal file
@@ -0,0 +1,30 @@
|
||||
/*
|
||||
SlimeVR Code is placed under the MIT license
|
||||
Copyright (c) 2025 Gorbit99 & 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.
|
||||
*/
|
||||
|
||||
#include "SensorInterface.h"
|
||||
|
||||
namespace SlimeVR {
|
||||
|
||||
EmptySensorInterface EmptySensorInterface::instance;
|
||||
|
||||
}
|
||||
@@ -39,8 +39,9 @@ public:
|
||||
EmptySensorInterface(){};
|
||||
bool init() override final { return true; };
|
||||
void swapIn() override final{};
|
||||
|
||||
[[nodiscard]] std::string toString() const final { return "None"; }
|
||||
|
||||
static EmptySensorInterface instance;
|
||||
};
|
||||
} // namespace SlimeVR
|
||||
|
||||
|
||||
46
src/sensorinterface/SensorInterfaceManager.cpp
Normal file
46
src/sensorinterface/SensorInterfaceManager.cpp
Normal file
@@ -0,0 +1,46 @@
|
||||
/*
|
||||
SlimeVR Code is placed under the MIT license
|
||||
Copyright (c) 2025 Gorbit99 & 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.
|
||||
*/
|
||||
|
||||
#include "SensorInterfaceManager.h"
|
||||
|
||||
template <typename T>
|
||||
bool byteCompare(const T& lhs, const T& rhs) {
|
||||
const auto* lhsBytes = reinterpret_cast<const uint8_t*>(&lhs);
|
||||
const auto* rhsBytes = reinterpret_cast<const uint8_t*>(&rhs);
|
||||
|
||||
for (size_t i = 0; i < sizeof(T); i++) {
|
||||
if (lhsBytes[i] < rhsBytes[i]) {
|
||||
return true;
|
||||
}
|
||||
}
|
||||
|
||||
return false;
|
||||
}
|
||||
|
||||
bool operator<(const SPISettings& lhs, const SPISettings& rhs) {
|
||||
return byteCompare(lhs, rhs);
|
||||
}
|
||||
|
||||
bool operator<(const SPIClass& lhs, const SPIClass& rhs) {
|
||||
return byteCompare(lhs, rhs);
|
||||
}
|
||||
@@ -23,6 +23,9 @@
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <PinInterface.h>
|
||||
#include <SPI.h>
|
||||
|
||||
#include <functional>
|
||||
#include <map>
|
||||
#include <optional>
|
||||
@@ -31,8 +34,17 @@
|
||||
#include "I2CPCAInterface.h"
|
||||
#include "I2CWireSensorInterface.h"
|
||||
#include "MCP23X17PinInterface.h"
|
||||
#include "SPIImpl.h"
|
||||
#include "SensorInterface.h"
|
||||
#include "i2cimpl.h"
|
||||
#include "sensorinterface/DirectSPIInterface.h"
|
||||
#include "sensorinterface/SPIImpl.h"
|
||||
|
||||
bool operator<(const SPISettings& lhs, const SPISettings& rhs);
|
||||
bool operator<(const SPIClass& lhs, const SPIClass& rhs);
|
||||
|
||||
bool operator<(const SPISettings& lhs, const SPISettings& rhs);
|
||||
bool operator<(const SPIClass& lhs, const SPIClass& rhs);
|
||||
|
||||
namespace SlimeVR {
|
||||
|
||||
@@ -54,7 +66,15 @@ private:
|
||||
|
||||
if (!cache.contains(key)) {
|
||||
auto ptr = new InterfaceClass(args...);
|
||||
if (!ptr->init()) {
|
||||
|
||||
bool success;
|
||||
if constexpr (requires { ptr->init(); }) {
|
||||
success = ptr->init();
|
||||
} else {
|
||||
success = true;
|
||||
}
|
||||
|
||||
if (!success) {
|
||||
cache[key] = nullptr;
|
||||
return nullptr;
|
||||
}
|
||||
@@ -74,6 +94,9 @@ public:
|
||||
inline auto& mcpPinInterface() { return mcpPinInterfaces; }
|
||||
inline auto& i2cWireInterface() { return i2cWireInterfaces; }
|
||||
inline auto& pcaWireInterface() { return pcaWireInterfaces; }
|
||||
inline auto& i2cImpl() { return i2cImpls; }
|
||||
inline auto& directSPIInterface() { return directSPIInterfaces; }
|
||||
inline auto& spiImpl() { return spiImpls; }
|
||||
|
||||
private:
|
||||
SensorInterface<DirectPinInterface, int> directPinInterfaces{[](int pin) {
|
||||
@@ -82,6 +105,9 @@ private:
|
||||
SensorInterface<MCP23X17PinInterface, Adafruit_MCP23X17*, int> mcpPinInterfaces;
|
||||
SensorInterface<I2CWireSensorInterface, int, int> i2cWireInterfaces;
|
||||
SensorInterface<I2CPCASensorInterface, int, int, int, int> pcaWireInterfaces;
|
||||
SensorInterface<Sensors::I2CImpl, uint8_t> i2cImpls;
|
||||
SensorInterface<DirectSPIInterface, SPIClass, SPISettings> directSPIInterfaces;
|
||||
SensorInterface<Sensors::SPIImpl, DirectSPIInterface*, PinInterface*> spiImpls;
|
||||
};
|
||||
|
||||
} // namespace SlimeVR
|
||||
|
||||
@@ -74,12 +74,17 @@ struct I2CImpl : public RegisterInterface {
|
||||
I2Cdev::writeBytes(m_devAddr, regAddr, size, buffer);
|
||||
}
|
||||
|
||||
bool hasSensorOnBus() { return I2CSCAN::hasDevOnBus(m_devAddr); }
|
||||
bool hasSensorOnBus() {
|
||||
// Ask twice, because we're nice like this
|
||||
return I2CSCAN::hasDevOnBus(m_devAddr) || I2CSCAN::hasDevOnBus(m_devAddr);
|
||||
}
|
||||
|
||||
uint8_t getAddress() const override { return m_devAddr; }
|
||||
|
||||
std::string toString() const {
|
||||
return std::string("I2C(") + std::to_string(m_devAddr) + std::string(")");
|
||||
char buf[16];
|
||||
std::snprintf(buf, sizeof(buf), "I2C(0x%02x)", m_devAddr);
|
||||
return std::string(buf);
|
||||
}
|
||||
|
||||
private:
|
||||
|
||||
@@ -25,8 +25,7 @@
|
||||
|
||||
#include "GlobalVars.h"
|
||||
|
||||
namespace SlimeVR {
|
||||
namespace Sensors {
|
||||
namespace SlimeVR::Sensors {
|
||||
void ErroneousSensor::motionSetup() {
|
||||
m_Logger.error(
|
||||
"IMU of type %s failed to initialize",
|
||||
@@ -37,5 +36,4 @@ void ErroneousSensor::motionSetup() {
|
||||
}
|
||||
|
||||
SensorStatus ErroneousSensor::getSensorState() { return SensorStatus::SENSOR_ERROR; };
|
||||
} // namespace Sensors
|
||||
} // namespace SlimeVR
|
||||
} // namespace SlimeVR::Sensors
|
||||
|
||||
@@ -28,284 +28,99 @@ namespace SlimeVR::Sensors {
|
||||
SensorBuilder::SensorBuilder(SensorManager* sensorManager)
|
||||
: m_Manager(sensorManager) {}
|
||||
|
||||
uint8_t SensorBuilder::buildAllSensors() {
|
||||
SensorInterfaceManager interfaceManager;
|
||||
#define SENSOR_DESC_ENTRY(ImuType, ...) \
|
||||
activeSensorCount += sensorDescEntry<ImuType>(sensorID, __VA_ARGS__) ? 1 : 0; \
|
||||
sensorID++;
|
||||
|
||||
#define SENSOR_INFO_ENTRY(ImuID, SensorPosition) \
|
||||
m_Manager->m_Sensors[ImuID]->setSensorInfo(SensorPosition);
|
||||
|
||||
uint8_t SensorBuilder::buildAllSensors() {
|
||||
uint8_t sensorID = 0;
|
||||
uint8_t activeSensorCount = 0;
|
||||
|
||||
#define NO_PIN nullptr
|
||||
#define NO_WIRE new EmptySensorInterface
|
||||
#define DIRECT_PIN(pin) interfaceManager.directPinInterface().get(pin)
|
||||
#define DIRECT_WIRE(scl, sda) interfaceManager.i2cWireInterface().get(scl, sda)
|
||||
#define MCP_PIN(pin) interfaceManager.mcpPinInterface().get(&m_Manager->m_MCP, pin)
|
||||
#define PCA_WIRE(scl, sda, addr, ch) \
|
||||
interfaceManager.pcaWireInterface().get(scl, sda, addr, ch)
|
||||
#define DIRECT_SPI(clockfreq, bitorder, datamode, CS_PIN) \
|
||||
*(new SPIImpl(SPI, SPISettings(clockfreq, bitorder, datamode), CS_PIN))
|
||||
|
||||
#define SENSOR_DESC_ENTRY(ImuType, ...) \
|
||||
{ \
|
||||
do { \
|
||||
std::unique_ptr<::Sensor> sensor; \
|
||||
if constexpr (std::is_same<ImuType, SensorAuto>::value) { \
|
||||
auto sensorType = findSensorType(sensorID, __VA_ARGS__); \
|
||||
if (sensorType == SensorTypeID::Unknown) { \
|
||||
m_Manager->m_Logger.error( \
|
||||
"Can't find sensor type for sensor %d", \
|
||||
sensorID \
|
||||
); \
|
||||
break; \
|
||||
} else { \
|
||||
m_Manager->m_Logger.info( \
|
||||
"Sensor %d automatically detected with %s", \
|
||||
sensorID, \
|
||||
getIMUNameByType(sensorType) \
|
||||
); \
|
||||
sensor \
|
||||
= buildSensorDynamically(sensorType, sensorID, __VA_ARGS__); \
|
||||
} \
|
||||
} else { \
|
||||
sensor = buildSensor<ImuType>(sensorID, __VA_ARGS__); \
|
||||
} \
|
||||
if (sensor->isWorking()) { \
|
||||
m_Manager->m_Logger.info("Sensor %d configured", sensorID); \
|
||||
activeSensorCount++; \
|
||||
} \
|
||||
m_Manager->m_Sensors.push_back(std::move(sensor)); \
|
||||
} while (false); \
|
||||
sensorID++; \
|
||||
}
|
||||
[[maybe_unused]] const auto NO_PIN = nullptr;
|
||||
[[maybe_unused]] const auto NO_WIRE = &EmptySensorInterface::instance;
|
||||
[[maybe_unused]] const auto DIRECT_PIN
|
||||
= [&](uint8_t pin) { return interfaceManager.directPinInterface().get(pin); };
|
||||
[[maybe_unused]] const auto DIRECT_WIRE = [&](uint8_t scl, uint8_t sda) {
|
||||
return interfaceManager.i2cWireInterface().get(scl, sda);
|
||||
};
|
||||
[[maybe_unused]] const auto MCP_PIN = [&](uint8_t pin) {
|
||||
return interfaceManager.mcpPinInterface().get(&m_Manager->m_MCP, pin);
|
||||
};
|
||||
[[maybe_unused]] const auto PCA_WIRE
|
||||
= [&](uint8_t scl, uint8_t sda, uint8_t addr, uint8_t ch) {
|
||||
return interfaceManager.pcaWireInterface().get(scl, sda, addr, ch);
|
||||
};
|
||||
[[maybe_unused]] const auto DIRECT_SPI
|
||||
= [&](uint32_t clockFreq, uint8_t bitOrder, uint8_t dataMode) {
|
||||
return interfaceManager.directSPIInterface().get(
|
||||
SPI,
|
||||
SPISettings(clockFreq, bitOrder, dataMode)
|
||||
);
|
||||
};
|
||||
|
||||
// Apply descriptor list and expand to entries
|
||||
SENSOR_DESC_LIST;
|
||||
SENSOR_DESC_LIST
|
||||
|
||||
#define SENSOR_INFO_ENTRY(ImuID, ...) \
|
||||
{ m_Manager->m_Sensors[ImuID]->setSensorInfo(__VA_ARGS__); }
|
||||
|
||||
// Apply sensor info list
|
||||
SENSOR_INFO_LIST;
|
||||
// Apply sensor info list and expand to entries
|
||||
SENSOR_INFO_LIST
|
||||
|
||||
return activeSensorCount;
|
||||
}
|
||||
|
||||
#define BUILD_SENSOR_ARGS \
|
||||
sensorID, imuInterface, rotation, sensorInterface, optional, intPin, extraParam
|
||||
|
||||
std::unique_ptr<::Sensor> SensorBuilder::buildSensorDynamically(
|
||||
SensorTypeID type,
|
||||
uint8_t sensorID,
|
||||
RegisterInterface& imuInterface,
|
||||
float rotation,
|
||||
SensorInterface* sensorInterface,
|
||||
bool optional,
|
||||
PinInterface* intPin,
|
||||
int extraParam
|
||||
) {
|
||||
std::unique_ptr<::Sensor>
|
||||
SensorBuilder::buildSensorDynamically(SensorTypeID type, SensorDefinition sensorDef) {
|
||||
switch (type) {
|
||||
// case SensorTypeID::MPU9250:
|
||||
// return buildSensor<MPU9250Sensor>(BUILD_SENSOR_ARGS);
|
||||
// return buildSensor<MPU9250Sensor>(sensorDef);
|
||||
// case SensorTypeID::BNO080:
|
||||
// return buildSensor<BNO080Sensor>(BUILD_SENSOR_ARGS);
|
||||
// return buildSensor<BNO080Sensor>(sensorDef);
|
||||
case SensorTypeID::BNO085:
|
||||
return buildSensor<BNO085Sensor>(BUILD_SENSOR_ARGS);
|
||||
return buildSensor<BNO085Sensor>(sensorDef);
|
||||
// case SensorTypeID::BNO055:
|
||||
// return buildSensor<BNO055Sensor>(BUILD_SENSOR_ARGS);
|
||||
// return buildSensor<BNO055Sensor>(sensorDef);
|
||||
// case SensorTypeID::MPU6050:
|
||||
// return buildSensor<SoftFusionMPU6050>(
|
||||
// BUILD_SENSOR_ARGS
|
||||
// sensorDef
|
||||
// );
|
||||
// case SensorTypeID::BNO086:
|
||||
// return buildSensor<BNO086Sensor>(BUILD_SENSOR_ARGS);
|
||||
// return buildSensor<BNO086Sensor>(sensorDef);
|
||||
// case SensorTypeID::BMI160:
|
||||
// return buildSensor<BMI160Sensor>(BUILD_SENSOR_ARGS);
|
||||
// return buildSensor<BMI160Sensor>(sensorDef);
|
||||
// case SensorTypeID::ICM20948:
|
||||
// return buildSensor<ICM20948Sensor>(BUILD_SENSOR_ARGS);
|
||||
// return buildSensor<ICM20948Sensor>(sensorDef);
|
||||
// case SensorTypeID::ICM42688:
|
||||
// return buildSensor<SoftFusionICM42688>(
|
||||
// BUILD_SENSOR_ARGS
|
||||
// sensorDef
|
||||
// );
|
||||
case SensorTypeID::BMI270:
|
||||
return buildSensor<SoftFusionBMI270>(BUILD_SENSOR_ARGS);
|
||||
return buildSensor<SoftFusionBMI270>(sensorDef);
|
||||
// case SensorTypeID::LSM6DS3TRC:
|
||||
// return buildSensor<SoftFusionLSM6DS3TRC>(
|
||||
// BUILD_SENSOR_ARGS
|
||||
// sensorDef
|
||||
// );
|
||||
case SensorTypeID::LSM6DSV:
|
||||
return buildSensor<SoftFusionLSM6DSV>(BUILD_SENSOR_ARGS);
|
||||
// case SensorTypeID::LSM6DSO:
|
||||
// return buildSensor<SoftFusionLSM6DSO>(
|
||||
// BUILD_SENSOR_ARGS
|
||||
// );
|
||||
// case SensorTypeID::LSM6DSR:
|
||||
// return buildSensor<SoftFusionLSM6DSR>(
|
||||
// BUILD_SENSOR_ARGS
|
||||
// );
|
||||
return buildSensor<SoftFusionLSM6DSV>(sensorDef);
|
||||
case SensorTypeID::LSM6DSO:
|
||||
return buildSensor<SoftFusionLSM6DSO>(sensorDef);
|
||||
case SensorTypeID::LSM6DSR:
|
||||
return buildSensor<SoftFusionLSM6DSR>(sensorDef);
|
||||
case SensorTypeID::ICM45686:
|
||||
return buildSensor<SoftFusionICM45686>(BUILD_SENSOR_ARGS);
|
||||
return buildSensor<SoftFusionICM45686>(sensorDef);
|
||||
// case SensorTypeID::ICM45605:
|
||||
// return buildSensor<SoftFusionICM45605>(
|
||||
// BUILD_SENSOR_ARGS
|
||||
// sensorDef
|
||||
// );
|
||||
default:
|
||||
m_Manager->m_Logger.error(
|
||||
"Unable to create sensor with type %s (%d)",
|
||||
getIMUNameByType(type),
|
||||
type
|
||||
static_cast<int>(type)
|
||||
);
|
||||
}
|
||||
return std::make_unique<EmptySensor>(sensorID);
|
||||
}
|
||||
|
||||
std::unique_ptr<::Sensor> SensorBuilder::buildSensorDynamically(
|
||||
SensorTypeID type,
|
||||
uint8_t sensorID,
|
||||
uint8_t imuInterface,
|
||||
float rotation,
|
||||
SensorInterface* sensorInterface,
|
||||
bool optional,
|
||||
PinInterface* intPin,
|
||||
int extraParam
|
||||
) {
|
||||
switch (type) {
|
||||
// case SensorTypeID::MPU9250:
|
||||
// return buildSensor<MPU9250Sensor>(BUILD_SENSOR_ARGS);
|
||||
// case SensorTypeID::BNO080:
|
||||
// return buildSensor<BNO080Sensor>(BUILD_SENSOR_ARGS);
|
||||
case SensorTypeID::BNO085:
|
||||
return buildSensor<BNO085Sensor>(BUILD_SENSOR_ARGS);
|
||||
// case SensorTypeID::BNO055:
|
||||
// return buildSensor<BNO055Sensor>(BUILD_SENSOR_ARGS);
|
||||
// case SensorTypeID::MPU6050:
|
||||
// return buildSensor<SoftFusionMPU6050>(
|
||||
// BUILD_SENSOR_ARGS
|
||||
// );
|
||||
// case SensorTypeID::BNO086:
|
||||
// return buildSensor<BNO086Sensor>(BUILD_SENSOR_ARGS);
|
||||
// case SensorTypeID::BMI160:
|
||||
// return buildSensor<BMI160Sensor>(BUILD_SENSOR_ARGS);
|
||||
// case SensorTypeID::ICM20948:
|
||||
// return buildSensor<ICM20948Sensor>(BUILD_SENSOR_ARGS);
|
||||
// case SensorTypeID::ICM42688:
|
||||
// return buildSensor<SoftFusionICM42688>(
|
||||
// BUILD_SENSOR_ARGS
|
||||
// );
|
||||
case SensorTypeID::BMI270:
|
||||
return buildSensor<SoftFusionBMI270>(BUILD_SENSOR_ARGS);
|
||||
// case SensorTypeID::LSM6DS3TRC:
|
||||
// return buildSensor<SoftFusionLSM6DS3TRC>(
|
||||
// BUILD_SENSOR_ARGS
|
||||
// );
|
||||
case SensorTypeID::LSM6DSV:
|
||||
return buildSensor<SoftFusionLSM6DSV>(BUILD_SENSOR_ARGS);
|
||||
// case SensorTypeID::LSM6DSO:
|
||||
// return buildSensor<SoftFusionLSM6DSO>(
|
||||
// BUILD_SENSOR_ARGS
|
||||
// );
|
||||
// case SensorTypeID::LSM6DSR:
|
||||
// return buildSensor<SoftFusionLSM6DSR>(
|
||||
// BUILD_SENSOR_ARGS
|
||||
// );
|
||||
case SensorTypeID::ICM45686:
|
||||
return buildSensor<SoftFusionICM45686>(BUILD_SENSOR_ARGS);
|
||||
// case SensorTypeID::ICM45605:
|
||||
// return buildSensor<SoftFusionICM45605>(
|
||||
// BUILD_SENSOR_ARGS
|
||||
// );
|
||||
default:
|
||||
m_Manager->m_Logger.error(
|
||||
"Unable to create sensor with type %s (%d)",
|
||||
getIMUNameByType(type),
|
||||
type
|
||||
);
|
||||
}
|
||||
return std::make_unique<EmptySensor>(sensorID);
|
||||
}
|
||||
|
||||
SensorTypeID SensorBuilder::findSensorType(
|
||||
uint8_t sensorID,
|
||||
uint8_t imuAddress,
|
||||
float rotation,
|
||||
SensorInterface* sensorInterface,
|
||||
bool optional,
|
||||
PinInterface* intPin,
|
||||
int extraParam
|
||||
) {
|
||||
sensorInterface->init();
|
||||
sensorInterface->swapIn();
|
||||
// if (SoftFusionLSM6DS3TRC::checkPresent(sensorID, imuAddress))
|
||||
// { return SensorTypeID::LSM6DS3TRC;
|
||||
// }
|
||||
// if (SoftFusionICM42688::checkPresent(sensorID, imuAddress)) {
|
||||
// return SensorTypeID::ICM42688;
|
||||
//}
|
||||
if (SoftFusionBMI270::checkPresent(sensorID, imuAddress)) {
|
||||
return SensorTypeID::BMI270;
|
||||
}
|
||||
if (SoftFusionLSM6DSV::checkPresent(sensorID, imuAddress)) {
|
||||
return SensorTypeID::LSM6DSV;
|
||||
}
|
||||
// if (SoftFusionLSM6DSO::checkPresent(sensorID, imuAddress)) {
|
||||
// return SensorTypeID::LSM6DSO;
|
||||
// }
|
||||
// if (SoftFusionLSM6DSR::checkPresent(sensorID, imuAddress)) {
|
||||
// return SensorTypeID::LSM6DSR;
|
||||
// }
|
||||
// if (SoftFusionMPU6050::checkPresent(sensorID, imuAddress)) {
|
||||
// return SensorTypeID::MPU6050;
|
||||
// }
|
||||
if (SoftFusionICM45686::checkPresent(sensorID, imuAddress)) {
|
||||
return SensorTypeID::ICM45686;
|
||||
}
|
||||
return BNO080Sensor::checkPresent(sensorID, imuAddress, intPin);
|
||||
// if (SoftFusionICM45605::checkPresent(sensorID, imuAddress)) {
|
||||
// return SensorTypeID::ICM45605;
|
||||
// }
|
||||
|
||||
return SensorTypeID::Unknown;
|
||||
}
|
||||
|
||||
SensorTypeID SensorBuilder::findSensorType(
|
||||
uint8_t sensorID,
|
||||
RegisterInterface& imuInterface,
|
||||
float rotation,
|
||||
SensorInterface* sensorInterface,
|
||||
bool optional,
|
||||
PinInterface* intPin,
|
||||
int extraParam
|
||||
) {
|
||||
sensorInterface->init();
|
||||
sensorInterface->swapIn();
|
||||
// if (SoftFusionLSM6DS3TRC::checkPresent(sensorID, imuInterface))
|
||||
// { return SensorTypeID::LSM6DS3TRC;
|
||||
// }
|
||||
// if (SoftFusionICM42688::checkPresent(sensorID, imuInterface)) {
|
||||
// return SensorTypeID::ICM42688;
|
||||
//}
|
||||
if (SoftFusionBMI270::checkPresent(sensorID, imuInterface)) {
|
||||
return SensorTypeID::BMI270;
|
||||
}
|
||||
if (SoftFusionLSM6DSV::checkPresent(sensorID, imuInterface)) {
|
||||
return SensorTypeID::LSM6DSV;
|
||||
}
|
||||
// if (SoftFusionLSM6DSO::checkPresent(sensorID, imuInterface)) {
|
||||
// return SensorTypeID::LSM6DSO;
|
||||
// }
|
||||
// if (SoftFusionLSM6DSR::checkPresent(sensorID, imuInterface)) {
|
||||
// return SensorTypeID::LSM6DSR;
|
||||
// }
|
||||
// if (SoftFusionMPU6050::checkPresent(sensorID, imuInterface)) {
|
||||
// return SensorTypeID::MPU6050;
|
||||
// }
|
||||
if (SoftFusionICM45686::checkPresent(sensorID, imuInterface)) {
|
||||
return SensorTypeID::ICM45686;
|
||||
}
|
||||
return BNO080Sensor::checkPresent(sensorID, sensorInterface, intPin);
|
||||
// if (SoftFusionICM45605::checkPresent(sensorID, imuInterface)) {
|
||||
// return SensorTypeID::ICM45605;
|
||||
// }
|
||||
|
||||
// return SensorTypeID::Unknown;
|
||||
return std::make_unique<EmptySensor>(sensorDef.sensorID);
|
||||
}
|
||||
|
||||
} // namespace SlimeVR::Sensors
|
||||
|
||||
@@ -29,9 +29,11 @@
|
||||
|
||||
#include "EmptySensor.h"
|
||||
#include "ErroneousSensor.h"
|
||||
#include "PinInterface.h"
|
||||
#include "SensorManager.h"
|
||||
#include "bno055sensor.h"
|
||||
#include "bno080sensor.h"
|
||||
#include "consts.h"
|
||||
#include "globals.h"
|
||||
#include "icm20948sensor.h"
|
||||
#include "logging/Logger.h"
|
||||
@@ -39,11 +41,13 @@
|
||||
#include "mpu9250sensor.h"
|
||||
#include "sensor.h"
|
||||
#include "sensorinterface/DirectPinInterface.h"
|
||||
#include "sensorinterface/DirectSPIInterface.h"
|
||||
#include "sensorinterface/I2CPCAInterface.h"
|
||||
#include "sensorinterface/I2CWireSensorInterface.h"
|
||||
#include "sensorinterface/MCP23X17PinInterface.h"
|
||||
#include "sensorinterface/RegisterInterface.h"
|
||||
#include "sensorinterface/SPIImpl.h"
|
||||
#include "sensorinterface/SensorInterface.h"
|
||||
#include "sensorinterface/SensorInterfaceManager.h"
|
||||
#include "sensorinterface/i2cimpl.h"
|
||||
#include "softfusion/drivers/bmi160.h"
|
||||
@@ -59,11 +63,11 @@
|
||||
#include "softfusion/softfusionsensor.h"
|
||||
|
||||
#ifndef PRIMARY_IMU_ADDRESS_ONE
|
||||
#define PRIMARY_IMU_ADDRESS_ONE 0
|
||||
#define PRIMARY_IMU_ADDRESS_ONE false
|
||||
#endif
|
||||
|
||||
#ifndef SECONDARY_IMU_ADDRESS_TWO
|
||||
#define SECONDARY_IMU_ADDRESS_TWO 0
|
||||
#define SECONDARY_IMU_ADDRESS_TWO true
|
||||
#endif
|
||||
|
||||
#if USE_RUNTIME_CALIBRATION
|
||||
@@ -96,141 +100,263 @@ using SoftFusionBMI160 = SoftFusionSensor<SoftFusion::Drivers::BMI160, SFCALIBRA
|
||||
class SensorAuto {};
|
||||
|
||||
struct SensorBuilder {
|
||||
private:
|
||||
struct SensorDefinition {
|
||||
uint8_t sensorID;
|
||||
RegisterInterface& imuInterface;
|
||||
float rotation;
|
||||
SensorInterface* sensorInterface;
|
||||
bool optional;
|
||||
PinInterface* intPin;
|
||||
int extraParam;
|
||||
};
|
||||
|
||||
public:
|
||||
SensorManager* m_Manager;
|
||||
SensorBuilder(SensorManager* sensorManager);
|
||||
explicit SensorBuilder(SensorManager* sensorManager);
|
||||
|
||||
uint8_t buildAllSensors();
|
||||
|
||||
std::unique_ptr<::Sensor> buildSensorDynamically(
|
||||
SensorTypeID type,
|
||||
uint8_t sensorID,
|
||||
RegisterInterface& imuInterface,
|
||||
float rotation,
|
||||
SensorInterface* sensorInterface,
|
||||
bool optional,
|
||||
PinInterface* intPin,
|
||||
int extraParam = 0
|
||||
);
|
||||
std::unique_ptr<::Sensor>
|
||||
buildSensorDynamically(SensorTypeID type, SensorDefinition sensorDef);
|
||||
|
||||
std::unique_ptr<::Sensor> buildSensorDynamically(
|
||||
SensorTypeID type,
|
||||
uint8_t sensorID,
|
||||
uint8_t imuInterface,
|
||||
float rotation,
|
||||
template <typename Sensor, typename AccessInterface>
|
||||
std::optional<std::pair<SensorTypeID, RegisterInterface*>> checkSensorPresent(
|
||||
uint8_t sensorId,
|
||||
SensorInterface* sensorInterface,
|
||||
bool optional,
|
||||
PinInterface* intPin,
|
||||
int extraParam = 0
|
||||
);
|
||||
AccessInterface accessInterface
|
||||
) {
|
||||
auto* registerInterface
|
||||
= getRegisterInterface<Sensor>(sensorId, sensorInterface, accessInterface);
|
||||
|
||||
SensorTypeID findSensorType(
|
||||
uint8_t sensorID,
|
||||
uint8_t imuAddress,
|
||||
float rotation,
|
||||
if (!registerInterface->hasSensorOnBus()) {
|
||||
return {};
|
||||
}
|
||||
|
||||
if constexpr (requires {
|
||||
{
|
||||
Sensor::checkPresent(*registerInterface)
|
||||
} -> std::same_as<SensorTypeID>;
|
||||
}) {
|
||||
auto type = Sensor::checkPresent(*registerInterface);
|
||||
|
||||
if (type == SensorTypeID::Unknown) {
|
||||
return {};
|
||||
}
|
||||
|
||||
return std::make_pair(type, registerInterface);
|
||||
} else {
|
||||
if (!Sensor::checkPresent(*registerInterface)) {
|
||||
return {};
|
||||
}
|
||||
}
|
||||
|
||||
return std::make_pair(Sensor::TypeID, registerInterface);
|
||||
}
|
||||
|
||||
template <typename AccessInterface>
|
||||
inline std::optional<std::pair<SensorTypeID, RegisterInterface*>>
|
||||
checkSensorsPresent(uint8_t, SensorInterface*, AccessInterface) {
|
||||
return std::nullopt;
|
||||
}
|
||||
|
||||
template <typename AccessInterface, typename Sensor, typename... Rest>
|
||||
inline std::optional<std::pair<SensorTypeID, RegisterInterface*>>
|
||||
checkSensorsPresent(
|
||||
uint8_t sensorId,
|
||||
SensorInterface* sensorInterface,
|
||||
bool optional,
|
||||
PinInterface* intPin,
|
||||
int extraParam = 0
|
||||
);
|
||||
AccessInterface accessInterface
|
||||
) {
|
||||
auto result
|
||||
= checkSensorPresent<Sensor>(sensorId, sensorInterface, accessInterface);
|
||||
if (result) {
|
||||
return result;
|
||||
}
|
||||
|
||||
SensorTypeID findSensorType(
|
||||
return checkSensorsPresent<AccessInterface, Rest...>(
|
||||
sensorId,
|
||||
sensorInterface,
|
||||
accessInterface
|
||||
);
|
||||
}
|
||||
|
||||
template <typename Sensor, typename AccessInterface>
|
||||
RegisterInterface* getRegisterInterface(
|
||||
uint8_t sensorId,
|
||||
SensorInterface* interface,
|
||||
AccessInterface access
|
||||
) {
|
||||
if constexpr (std::is_base_of_v<
|
||||
PinInterface,
|
||||
std::remove_pointer_t<AccessInterface>>) {
|
||||
return interfaceManager.spiImpl().get(
|
||||
static_cast<DirectSPIInterface*>(interface),
|
||||
access
|
||||
);
|
||||
} else if constexpr (std::is_same_v<AccessInterface, bool>) {
|
||||
uint8_t addressIncrement = access ? 1 : 0;
|
||||
return interfaceManager.i2cImpl().get(Sensor::Address + addressIncrement);
|
||||
} else if constexpr (std::is_integral_v<AccessInterface>) {
|
||||
return interfaceManager.i2cImpl().get(access);
|
||||
}
|
||||
|
||||
return &EmptyRegisterInterface::instance;
|
||||
}
|
||||
|
||||
template <typename AccessInterface>
|
||||
std::optional<std::pair<SensorTypeID, RegisterInterface*>> findSensorType(
|
||||
uint8_t sensorID,
|
||||
RegisterInterface& imuInterface,
|
||||
float rotation,
|
||||
SensorInterface* sensorInterface,
|
||||
bool optional,
|
||||
PinInterface* intPin,
|
||||
int extraParam = 0
|
||||
);
|
||||
AccessInterface accessInterface
|
||||
) {
|
||||
sensorInterface->init();
|
||||
sensorInterface->swapIn();
|
||||
|
||||
template <typename ImuType>
|
||||
std::unique_ptr<::Sensor> buildSensor(
|
||||
return checkSensorsPresent<
|
||||
AccessInterface,
|
||||
// SoftFusionLSM6DS3TRC,
|
||||
// SoftFusionICM42688,
|
||||
SoftFusionBMI270,
|
||||
SoftFusionLSM6DSV,
|
||||
SoftFusionLSM6DSO,
|
||||
SoftFusionLSM6DSR,
|
||||
// SoftFusionMPU6050,
|
||||
SoftFusionICM45686,
|
||||
// SoftFusionICM45605
|
||||
BNO085Sensor>(sensorID, sensorInterface, accessInterface);
|
||||
}
|
||||
|
||||
template <typename SensorType, typename AccessInterface>
|
||||
bool sensorDescEntry(
|
||||
uint8_t sensorID,
|
||||
RegisterInterface& imuInterface,
|
||||
AccessInterface accessInterface,
|
||||
float rotation,
|
||||
SensorInterface* sensorInterface,
|
||||
bool optional = false,
|
||||
PinInterface* intPin = nullptr,
|
||||
int extraParam = 0
|
||||
) {
|
||||
std::unique_ptr<::Sensor> sensor;
|
||||
if constexpr (std::is_same<SensorType, SensorAuto>::value) {
|
||||
auto result = findSensorType(sensorID, sensorInterface, accessInterface);
|
||||
|
||||
if (!result) {
|
||||
m_Manager->m_Logger.error(
|
||||
"Can't find sensor type for sensor %d",
|
||||
sensorID
|
||||
);
|
||||
return false;
|
||||
}
|
||||
|
||||
auto sensorType = result->first;
|
||||
auto& regInterface = *(result->second);
|
||||
|
||||
m_Manager->m_Logger.info(
|
||||
"Sensor %d automatically detected with %s",
|
||||
sensorID,
|
||||
getIMUNameByType(sensorType)
|
||||
);
|
||||
sensor = buildSensorDynamically(
|
||||
sensorType,
|
||||
{
|
||||
sensorID,
|
||||
regInterface,
|
||||
rotation,
|
||||
sensorInterface,
|
||||
optional,
|
||||
intPin,
|
||||
extraParam,
|
||||
}
|
||||
);
|
||||
} else {
|
||||
auto& regInterface = *getRegisterInterface<SensorType>(
|
||||
sensorID,
|
||||
sensorInterface,
|
||||
accessInterface
|
||||
);
|
||||
|
||||
sensor = buildSensor<SensorType>({
|
||||
sensorID,
|
||||
regInterface,
|
||||
rotation,
|
||||
sensorInterface,
|
||||
optional,
|
||||
intPin,
|
||||
extraParam,
|
||||
});
|
||||
}
|
||||
if (sensor->isWorking()) {
|
||||
m_Manager->m_Logger.info("Sensor %d configured", sensorID);
|
||||
}
|
||||
m_Manager->m_Sensors.push_back(std::move(sensor));
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
template <typename ImuType>
|
||||
std::unique_ptr<::Sensor> buildSensor(SensorDefinition sensorDef) {
|
||||
m_Manager->m_Logger.trace(
|
||||
"Building IMU with: id=%d,\n\
|
||||
address=%s, rotation=%f,\n\
|
||||
interface=%s, int=%s, extraParam=%d, optional=%d",
|
||||
sensorID,
|
||||
imuInterface.toString().c_str(),
|
||||
rotation,
|
||||
sensorInterface->toString().c_str(),
|
||||
intPin->toString().c_str(),
|
||||
extraParam,
|
||||
optional
|
||||
sensorDef.sensorID,
|
||||
sensorDef.imuInterface.toString().c_str(),
|
||||
sensorDef.rotation,
|
||||
sensorDef.sensorInterface->toString().c_str(),
|
||||
sensorDef.intPin ? sensorDef.intPin->toString().c_str() : "None",
|
||||
sensorDef.extraParam,
|
||||
sensorDef.optional
|
||||
);
|
||||
|
||||
// Now start detecting and building the IMU
|
||||
std::unique_ptr<::Sensor> sensor;
|
||||
|
||||
// Init I2C bus for each sensor upon startup
|
||||
sensorInterface->init();
|
||||
sensorInterface->swapIn();
|
||||
sensorDef.sensorInterface->init();
|
||||
sensorDef.sensorInterface->swapIn();
|
||||
|
||||
if (!imuInterface.hasSensorOnBus()) {
|
||||
if (!optional) {
|
||||
if (!sensorDef.imuInterface.hasSensorOnBus()) {
|
||||
if (!sensorDef.optional) {
|
||||
m_Manager->m_Logger.error(
|
||||
"Mandatory sensor %d not found at address %s",
|
||||
sensorID + 1,
|
||||
imuInterface.toString().c_str()
|
||||
sensorDef.sensorID + 1,
|
||||
sensorDef.imuInterface.toString().c_str()
|
||||
);
|
||||
return std::make_unique<ErroneousSensor>(
|
||||
sensorDef.sensorID,
|
||||
ImuType::TypeID
|
||||
);
|
||||
return std::make_unique<ErroneousSensor>(sensorID, ImuType::TypeID);
|
||||
} else {
|
||||
m_Manager->m_Logger.debug(
|
||||
"Optional sensor %d not found at address %s",
|
||||
sensorID + 1,
|
||||
imuInterface.toString().c_str()
|
||||
sensorDef.sensorID + 1,
|
||||
sensorDef.imuInterface.toString().c_str()
|
||||
);
|
||||
return std::make_unique<EmptySensor>(sensorID);
|
||||
return std::make_unique<EmptySensor>(sensorDef.sensorID);
|
||||
}
|
||||
}
|
||||
|
||||
m_Manager->m_Logger.trace(
|
||||
"Sensor %d found at address %s",
|
||||
sensorID + 1,
|
||||
imuInterface.toString().c_str()
|
||||
sensorDef.sensorID + 1,
|
||||
sensorDef.imuInterface.toString().c_str()
|
||||
);
|
||||
|
||||
sensor = std::make_unique<ImuType>(
|
||||
sensorID,
|
||||
imuInterface,
|
||||
rotation,
|
||||
sensorInterface,
|
||||
intPin,
|
||||
extraParam
|
||||
sensorDef.sensorID,
|
||||
sensorDef.imuInterface,
|
||||
sensorDef.rotation,
|
||||
sensorDef.sensorInterface,
|
||||
sensorDef.intPin,
|
||||
sensorDef.extraParam
|
||||
);
|
||||
|
||||
sensor->motionSetup();
|
||||
return sensor;
|
||||
}
|
||||
|
||||
template <typename ImuType>
|
||||
std::unique_ptr<::Sensor> buildSensor(
|
||||
uint8_t sensorID,
|
||||
uint8_t imuAddress,
|
||||
float rotation,
|
||||
SensorInterface* sensorInterface,
|
||||
bool optional = false,
|
||||
PinInterface* intPin = nullptr,
|
||||
int extraParam = 0
|
||||
) {
|
||||
uint8_t address = imuAddress > 0 ? imuAddress : ImuType::Address + sensorID;
|
||||
return buildSensor<ImuType>(
|
||||
sensorID,
|
||||
*(new I2CImpl(address)),
|
||||
rotation,
|
||||
sensorInterface,
|
||||
optional,
|
||||
intPin,
|
||||
extraParam
|
||||
);
|
||||
}
|
||||
private:
|
||||
SensorInterfaceManager interfaceManager;
|
||||
};
|
||||
|
||||
} // namespace SlimeVR::Sensors
|
||||
|
||||
@@ -1,7 +1,6 @@
|
||||
#include "SensorFusion.h"
|
||||
|
||||
namespace SlimeVR {
|
||||
namespace Sensors {
|
||||
namespace SlimeVR::Sensors {
|
||||
|
||||
void SensorFusion::update6D(
|
||||
sensor_real_t Axyz[3],
|
||||
@@ -218,5 +217,4 @@ void SensorFusion::updateBiasForgettingTime(float biasForgettingTime) {
|
||||
}
|
||||
#endif
|
||||
|
||||
} // namespace Sensors
|
||||
} // namespace SlimeVR
|
||||
} // namespace SlimeVR::Sensors
|
||||
|
||||
@@ -35,8 +35,7 @@
|
||||
#include "madgwick.h"
|
||||
#include "mahony.h"
|
||||
|
||||
namespace SlimeVR {
|
||||
namespace Sensors {
|
||||
namespace SlimeVR::Sensors {
|
||||
#if SENSOR_USE_VQF
|
||||
constexpr VQFParams DefaultVQFParams = VQFParams{
|
||||
.tauAcc = 2.0f,
|
||||
@@ -150,7 +149,6 @@ protected:
|
||||
sensor_real_t linAccel_guard; // Temporary patch for some weird ESP32 bug
|
||||
#endif
|
||||
};
|
||||
} // namespace Sensors
|
||||
} // namespace SlimeVR
|
||||
} // namespace SlimeVR::Sensors
|
||||
|
||||
#endif // SLIMEVR_SENSORFUSION_H
|
||||
|
||||
@@ -1,7 +1,6 @@
|
||||
#include "SensorFusionDMP.h"
|
||||
|
||||
namespace SlimeVR {
|
||||
namespace Sensors {
|
||||
namespace SlimeVR::Sensors {
|
||||
void SensorFusionDMP::updateAcc(sensor_real_t Axyz[3]) {
|
||||
std::copy(Axyz, Axyz + 3, bAxyz);
|
||||
}
|
||||
@@ -96,5 +95,4 @@ Vector3 SensorFusionDMP::getLinearAccVec() {
|
||||
getLinearAcc();
|
||||
return Vector3(linAccel[0], linAccel[1], linAccel[2]);
|
||||
}
|
||||
} // namespace Sensors
|
||||
} // namespace SlimeVR
|
||||
} // namespace SlimeVR::Sensors
|
||||
|
||||
@@ -4,8 +4,7 @@
|
||||
#include "SensorFusion.h"
|
||||
#include "dmpmag.h"
|
||||
|
||||
namespace SlimeVR {
|
||||
namespace Sensors {
|
||||
namespace SlimeVR::Sensors {
|
||||
class SensorFusionDMP {
|
||||
public:
|
||||
void updateQuaternion(sensor_real_t nqwxyz[4]);
|
||||
@@ -41,7 +40,6 @@ protected:
|
||||
sensor_real_t linAccel_guard; // Temporary patch for some weird ESP32 bug
|
||||
#endif
|
||||
};
|
||||
} // namespace Sensors
|
||||
} // namespace SlimeVR
|
||||
} // namespace SlimeVR::Sensors
|
||||
|
||||
#endif // SLIMEVR_SENSORFUSIONDMP_H
|
||||
|
||||
@@ -1,7 +1,6 @@
|
||||
#include "SensorFusionRestDetect.h"
|
||||
|
||||
namespace SlimeVR {
|
||||
namespace Sensors {
|
||||
namespace SlimeVR::Sensors {
|
||||
#if !SENSOR_FUSION_WITH_RESTDETECT
|
||||
void SensorFusionRestDetect::updateAcc(
|
||||
const sensor_real_t Axyz[3],
|
||||
@@ -33,5 +32,4 @@ bool SensorFusionRestDetect::getRestDetected() {
|
||||
return vqf.getRestDetected();
|
||||
#endif
|
||||
}
|
||||
} // namespace Sensors
|
||||
} // namespace SlimeVR
|
||||
} // namespace SlimeVR::Sensors
|
||||
|
||||
@@ -10,8 +10,7 @@
|
||||
#define SENSOR_FUSION_WITH_RESTDETECT 0
|
||||
#endif
|
||||
|
||||
namespace SlimeVR {
|
||||
namespace Sensors {
|
||||
namespace SlimeVR::Sensors {
|
||||
#if !SENSOR_FUSION_WITH_RESTDETECT
|
||||
struct SensorRestDetectionParams : RestDetectionParams {
|
||||
SensorRestDetectionParams()
|
||||
@@ -60,7 +59,6 @@ protected:
|
||||
RestDetection restDetection;
|
||||
#endif
|
||||
};
|
||||
} // namespace Sensors
|
||||
} // namespace SlimeVR
|
||||
} // namespace SlimeVR::Sensors
|
||||
|
||||
#endif // SLIMEVR_SENSORFUSIONRESTDETECT_H_
|
||||
|
||||
@@ -28,6 +28,7 @@
|
||||
#include <i2cscan.h>
|
||||
|
||||
#include "sensor.h"
|
||||
#include "sensorinterface/RegisterInterface.h"
|
||||
|
||||
#define FLAG_SENSOR_BNO0XX_MAG_ENABLED 1
|
||||
|
||||
@@ -65,27 +66,10 @@ public:
|
||||
void sendTempIfNeeded();
|
||||
|
||||
static SensorTypeID checkPresent(
|
||||
uint8_t sensorID,
|
||||
SlimeVR::SensorInterface* sensorInterface,
|
||||
PinInterface* intPin
|
||||
SlimeVR::Sensors::RegisterInterface& registerInterface
|
||||
) {
|
||||
// Lazy check for if BNO is present, we only check if I2C has an address here
|
||||
if (I2CSCAN::hasDevOnBus(Address + sensorID)) {
|
||||
return SensorTypeID::BNO085; // Assume it's 085, more precise diff will
|
||||
// require talking to it
|
||||
}
|
||||
return SensorTypeID::Unknown;
|
||||
}
|
||||
|
||||
static SensorTypeID
|
||||
checkPresent(uint8_t sensorID, uint8_t imuAddress, PinInterface* intPin) {
|
||||
uint8_t address = imuAddress > 0 ? imuAddress : Address + sensorID;
|
||||
// Lazy check for if BNO is present, we only check if I2C has an address here
|
||||
if (I2CSCAN::hasDevOnBus(address)) {
|
||||
return SensorTypeID::BNO085; // Assume it's 085, more precise diff will
|
||||
// require talking to it
|
||||
}
|
||||
return SensorTypeID::Unknown;
|
||||
// For BNO, just assume it's there if the sensorOnBus check succeeded
|
||||
return SensorTypeID::BNO085;
|
||||
}
|
||||
|
||||
protected:
|
||||
|
||||
@@ -328,7 +328,7 @@ void ICM20948Sensor::checkSensorTimeout() {
|
||||
if (lastData + 2000 < currenttime) {
|
||||
working = false;
|
||||
m_Logger.error(
|
||||
"Sensor timeout I2C Address 0x%02x delaytime: %d ms",
|
||||
"Sensor timeout I2C Address 0x%02x delaytime: %ld ms",
|
||||
addr,
|
||||
currenttime - lastData
|
||||
);
|
||||
|
||||
@@ -92,8 +92,6 @@ void Sensor::resetTemperatureCalibrationState() {
|
||||
};
|
||||
|
||||
SlimeVR::Configuration::SensorConfigBits Sensor::getSensorConfigData() {
|
||||
SlimeVR::Configuration::SensorConfig sensorConfig
|
||||
= configuration.getSensor(sensorId);
|
||||
return SlimeVR::Configuration::SensorConfigBits{
|
||||
.magEnabled = toggles.getToggle(SensorToggles::MagEnabled),
|
||||
.magSupported = isFlagSupported(SensorToggles::MagEnabled),
|
||||
@@ -142,6 +140,8 @@ const char* getIMUNameByType(SensorTypeID imuType) {
|
||||
return "ICM45686";
|
||||
case SensorTypeID::ICM45605:
|
||||
return "ICM45605";
|
||||
case SensorTypeID::ADC_RESISTANCE:
|
||||
return "ADC Resistance";
|
||||
case SensorTypeID::Unknown:
|
||||
case SensorTypeID::Empty:
|
||||
return "UNKNOWN";
|
||||
|
||||
@@ -122,6 +122,10 @@ protected:
|
||||
bool working = false;
|
||||
bool hadData = false;
|
||||
uint8_t calibrationAccuracy = 0;
|
||||
/**
|
||||
* Apply sensor offset to align it with tracker's axises
|
||||
* (Y to top of the tracker, Z to front, X to left)
|
||||
*/
|
||||
Quat sensorOffset;
|
||||
|
||||
bool newFusedRotation = false;
|
||||
|
||||
@@ -24,8 +24,7 @@
|
||||
#pragma once
|
||||
#include <memory>
|
||||
|
||||
namespace SlimeVR {
|
||||
namespace Sensors {
|
||||
namespace SlimeVR::Sensors {
|
||||
class ImuAddress {
|
||||
public:
|
||||
ImuAddress(bool isPrimary)
|
||||
@@ -49,5 +48,4 @@ public:
|
||||
return imuDefaultAddress + 1;
|
||||
}
|
||||
};
|
||||
} // namespace Sensors
|
||||
} // namespace SlimeVR
|
||||
} // namespace SlimeVR::Sensors
|
||||
|
||||
@@ -76,7 +76,8 @@ struct BMI160 {
|
||||
struct Regs {
|
||||
struct WhoAmI {
|
||||
static constexpr uint8_t reg = 0x00;
|
||||
static constexpr uint8_t value = 0xD1;
|
||||
static constexpr std::array<uint8_t, 2> values
|
||||
= {0xD1, 0xD3}; // 0xD3 for rev3 (thanks bosch)
|
||||
};
|
||||
static constexpr uint8_t TempData = 0x20;
|
||||
|
||||
|
||||
@@ -39,7 +39,7 @@
|
||||
|
||||
namespace SlimeVR::Sensors::SoftFusion::Drivers {
|
||||
|
||||
const uint8_t bmi270_firmware[] = {
|
||||
const uint8_t PROGMEM bmi270_firmware[] = {
|
||||
0xc8, 0x2e, 0x00, 0x2e, 0x80, 0x2e, 0x3d, 0xb1, 0xc8, 0x2e, 0x00, 0x2e, 0x80, 0x2e,
|
||||
0x91, 0x03, 0x80, 0x2e, 0xbc, 0xb0, 0x80, 0x2e, 0xa3, 0x03, 0xc8, 0x2e, 0x00, 0x2e,
|
||||
0x80, 0x2e, 0x00, 0xb0, 0x50, 0x30, 0x21, 0x2e, 0x59, 0xf5, 0x10, 0x30, 0x21, 0x2e,
|
||||
@@ -628,4 +628,4 @@ const uint8_t bmi270_firmware[] = {
|
||||
0x00, 0xc1
|
||||
};
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
@@ -73,7 +73,8 @@ struct LSM6DS3TRC {
|
||||
struct Regs {
|
||||
struct WhoAmI {
|
||||
static constexpr uint8_t reg = 0x0f;
|
||||
static constexpr uint8_t value = 0x6a;
|
||||
static constexpr std::array<uint8_t, 2> values
|
||||
= {0x6a, 0x69}; // 0x6a for LSM6DS3TR-C, 0x69 for LSM6DS3
|
||||
};
|
||||
struct Ctrl1XL {
|
||||
static constexpr uint8_t reg = 0x10;
|
||||
|
||||
@@ -32,6 +32,7 @@
|
||||
#include "../SensorFusionRestDetect.h"
|
||||
#include "../sensor.h"
|
||||
#include "GlobalVars.h"
|
||||
#include "PinInterface.h"
|
||||
#include "motionprocessing/types.h"
|
||||
#include "sensors/softfusion/TempGradientCalculator.h"
|
||||
|
||||
@@ -76,7 +77,26 @@ class SoftFusionSensor : public Sensor {
|
||||
bool detected() const {
|
||||
const auto value
|
||||
= m_sensor.m_RegisterInterface.readReg(SensorType::Regs::WhoAmI::reg);
|
||||
if (SensorType::Regs::WhoAmI::value != value) {
|
||||
if constexpr (requires { SensorType::Regs::WhoAmI::values.size(); }) {
|
||||
for (auto possible : SensorType::Regs::WhoAmI::values) {
|
||||
if (value == possible) {
|
||||
return true;
|
||||
}
|
||||
}
|
||||
// this assumes there are only 2 values in the array
|
||||
m_Logger.error(
|
||||
"Sensor not detected, expected reg 0x%02x = [0x%02x, 0x%02x] but got "
|
||||
"0x%02x",
|
||||
SensorType::Regs::WhoAmI::reg,
|
||||
SensorType::Regs::WhoAmI::values[0],
|
||||
SensorType::Regs::WhoAmI::values[1],
|
||||
value
|
||||
);
|
||||
return false;
|
||||
} else {
|
||||
if (value == SensorType::Regs::WhoAmI::value) {
|
||||
return true;
|
||||
}
|
||||
m_Logger.error(
|
||||
"Sensor not detected, expected reg 0x%02x = 0x%02x but got 0x%02x",
|
||||
SensorType::Regs::WhoAmI::reg,
|
||||
@@ -85,8 +105,6 @@ class SoftFusionSensor : public Sensor {
|
||||
);
|
||||
return false;
|
||||
}
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
void sendData() {
|
||||
@@ -441,24 +459,23 @@ public:
|
||||
|
||||
RestCalibrationDetector calibrationDetector;
|
||||
|
||||
static bool checkPresent(uint8_t sensorID, const RegisterInterface& imuInterface) {
|
||||
static bool checkPresent(const RegisterInterface& imuInterface) {
|
||||
I2Cdev::readTimeout = 100;
|
||||
auto value = imuInterface.readReg(SensorType::Regs::WhoAmI::reg);
|
||||
I2Cdev::readTimeout = I2CDEV_DEFAULT_READ_TIMEOUT;
|
||||
if (SensorType::Regs::WhoAmI::value == value) {
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
static bool checkPresent(uint8_t sensorID, uint8_t imuAddress) {
|
||||
uint8_t address = imuAddress > 0 ? imuAddress : Address + sensorID;
|
||||
// Ask twice, because we're nice like this
|
||||
if (!I2CSCAN::hasDevOnBus(address) && !I2CSCAN::hasDevOnBus(address)) {
|
||||
if constexpr (requires { SensorType::Regs::WhoAmI::values.size(); }) {
|
||||
for (auto possible : SensorType::Regs::WhoAmI::values) {
|
||||
if (value == possible) {
|
||||
return true;
|
||||
}
|
||||
}
|
||||
return false;
|
||||
} else {
|
||||
if (value == SensorType::Regs::WhoAmI::value) {
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
const I2CImpl& i2c = I2CImpl(address);
|
||||
return checkPresent(sensorID, i2c);
|
||||
}
|
||||
};
|
||||
|
||||
|
||||
@@ -23,8 +23,8 @@
|
||||
|
||||
#include "LEDManager.h"
|
||||
|
||||
#include "GlobalVars.h"
|
||||
#include "status/Status.h"
|
||||
#include "../GlobalVars.h"
|
||||
#include "Status.h"
|
||||
|
||||
namespace SlimeVR {
|
||||
void LEDManager::setup() {
|
||||
@@ -25,8 +25,8 @@
|
||||
|
||||
#include <Arduino.h>
|
||||
|
||||
#include "globals.h"
|
||||
#include "logging/Logger.h"
|
||||
#include "../globals.h"
|
||||
#include "../logging/Logger.h"
|
||||
|
||||
#define DEFAULT_LENGTH 300
|
||||
#define DEFAULT_GAP 500
|
||||
@@ -1,7 +1,6 @@
|
||||
#include "Status.h"
|
||||
|
||||
namespace SlimeVR {
|
||||
namespace Status {
|
||||
namespace SlimeVR::Status {
|
||||
const char* statusToString(Status status) {
|
||||
switch (status) {
|
||||
case LOADING:
|
||||
@@ -18,5 +17,4 @@ const char* statusToString(Status status) {
|
||||
return "UNKNOWN";
|
||||
}
|
||||
}
|
||||
} // namespace Status
|
||||
} // namespace SlimeVR
|
||||
} // namespace SlimeVR::Status
|
||||
|
||||
@@ -1,8 +1,7 @@
|
||||
#ifndef STATUS_STATUS_H
|
||||
#define STATUS_STATUS_H
|
||||
|
||||
namespace SlimeVR {
|
||||
namespace Status {
|
||||
namespace SlimeVR::Status {
|
||||
enum Status {
|
||||
LOADING = 1 << 0,
|
||||
LOW_BATTERY = 1 << 1,
|
||||
@@ -12,7 +11,6 @@ enum Status {
|
||||
};
|
||||
|
||||
const char* statusToString(Status status);
|
||||
} // namespace Status
|
||||
} // namespace SlimeVR
|
||||
} // namespace SlimeVR::Status
|
||||
|
||||
#endif
|
||||
|
||||
@@ -1,7 +1,6 @@
|
||||
#include "StatusManager.h"
|
||||
|
||||
namespace SlimeVR {
|
||||
namespace Status {
|
||||
namespace SlimeVR::Status {
|
||||
void StatusManager::setStatus(Status status, bool value) {
|
||||
if (value) {
|
||||
if (m_Status & status) {
|
||||
@@ -23,5 +22,4 @@ void StatusManager::setStatus(Status status, bool value) {
|
||||
}
|
||||
|
||||
bool StatusManager::hasStatus(Status status) { return (m_Status & status) == status; }
|
||||
} // namespace Status
|
||||
} // namespace SlimeVR
|
||||
} // namespace SlimeVR::Status
|
||||
|
||||
@@ -4,8 +4,7 @@
|
||||
#include "Status.h"
|
||||
#include "logging/Logger.h"
|
||||
|
||||
namespace SlimeVR {
|
||||
namespace Status {
|
||||
namespace SlimeVR::Status {
|
||||
class StatusManager {
|
||||
public:
|
||||
void setStatus(Status status, bool value);
|
||||
@@ -17,7 +16,6 @@ private:
|
||||
|
||||
Logging::Logger m_Logger = Logging::Logger("StatusManager");
|
||||
};
|
||||
} // namespace Status
|
||||
} // namespace SlimeVR
|
||||
} // namespace SlimeVR::Status
|
||||
|
||||
#endif
|
||||
|
||||
Reference in New Issue
Block a user