mirror of
https://github.com/SlimeVR/SlimeVR-Tracker-ESP.git
synced 2026-04-06 02:01:57 +02:00
Merge remote-tracking branch 'origin/main' into add-id-command
This commit is contained in:
File diff suppressed because it is too large
Load Diff
@@ -1,767 +0,0 @@
|
||||
/*
|
||||
===============================================
|
||||
BMI160 accelerometer/gyroscope library for Intel(R) Curie(TM) devices.
|
||||
Copyright (c) 2015 Intel Corporation. All rights reserved.
|
||||
|
||||
Based on MPU6050 Arduino library provided by Jeff Rowberg as part of his
|
||||
excellent I2Cdev device library: https://github.com/jrowberg/i2cdevlib
|
||||
|
||||
===============================================
|
||||
I2Cdev device library code is placed under the MIT license
|
||||
Copyright (c) 2012 Jeff Rowberg
|
||||
|
||||
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 _BMI160_H_
|
||||
#define _BMI160_H_
|
||||
|
||||
#include "Arduino.h"
|
||||
#include "I2Cdev.h"
|
||||
|
||||
#define BMI160_SPI_READ_BIT 7
|
||||
|
||||
#define BMI160_RA_CHIP_ID 0x00
|
||||
|
||||
#define BMI160_MAG_PMU_STATUS_BIT 0
|
||||
#define BMI160_MAG_PMU_STATUS_LEN 2
|
||||
|
||||
#define BMI160_STATUS_DRDY_MAG 5
|
||||
#define BMI160_STATUS_MAG_MAN_OP 2
|
||||
#define BMI160_MAG_RATE_SEL_BIT 0
|
||||
#define BMI160_MAG_RATE_SEL_LEN 4
|
||||
#define BMI160_FIFO_MAG_EN_BIT 5
|
||||
|
||||
#define BMI160_RA_MAG_CONF 0x44
|
||||
#define BMI160_RA_MAG_IF_0_DEVADDR 0x4B
|
||||
#define BMI160_RA_MAG_IF_1_MODE 0x4C
|
||||
#define BMI160_RA_MAG_IF_2_READ_RA 0x4D
|
||||
#define BMI160_RA_MAG_IF_3_WRITE_RA 0x4E
|
||||
#define BMI160_RA_MAG_IF_4_WRITE_VALUE 0x4F
|
||||
#define BMI160_RA_IF_CONF 0x6B
|
||||
|
||||
#define BMI160_IF_CONF_MODE_PRI_AUTO_SEC_OFF 0 << 4
|
||||
#define BMI160_IF_CONF_MODE_PRI_I2C_SEC_OIS 1 << 4
|
||||
#define BMI160_IF_CONF_MODE_PRI_AUTO_SEC_MAG 2 << 4
|
||||
|
||||
#define BMI160_MAG_SETUP_MODE 0x80
|
||||
#define BMI160_MAG_DATA_MODE_2 0x01
|
||||
#define BMI160_MAG_DATA_MODE_6 0x02
|
||||
#define BMI160_MAG_DATA_MODE_8 0x03
|
||||
|
||||
typedef enum {
|
||||
BMI160_MAG_RATE_25_32thHZ = 1, /**< 25/32 Hz */
|
||||
BMI160_MAG_RATE_25_16thHZ, /**< 25/16 Hz */
|
||||
BMI160_MAG_RATE_25_8thHZ, /**< 25/8 Hz */
|
||||
BMI160_MAG_RATE_25_4thHZ, /**< 25/4 Hz */
|
||||
BMI160_MAG_RATE_25_2thHZ, /**< 25/2 Hz */
|
||||
BMI160_MAG_RATE_25HZ, /**< 25 Hz */
|
||||
BMI160_MAG_RATE_50HZ, /**< 50 Hz */
|
||||
BMI160_MAG_RATE_100HZ, /**< 100 Hz */
|
||||
BMI160_MAG_RATE_200HZ, /**< 200 Hz */
|
||||
BMI160_MAG_RATE_400HZ, /**< 400 Hz */
|
||||
BMI160_MAG_RATE_800HZ, /**< 800 Hz */
|
||||
} BMI160MagRate;
|
||||
|
||||
#define BMI160_CMD_MAG_MODE_NORMAL 0x19
|
||||
|
||||
#define BMI160_EN_PULL_UP_REG_1 0x37
|
||||
#define BMI160_EN_PULL_UP_REG_2 0x9A
|
||||
#define BMI160_EN_PULL_UP_REG_3 0xC0
|
||||
#define BMI160_EN_PULL_UP_REG_4 0x90
|
||||
#define BMI160_EN_PULL_UP_REG_5 0x80
|
||||
|
||||
#define BMI160_7F 0x7F
|
||||
|
||||
#define BMI160_ACC_PMU_STATUS_BIT 4
|
||||
#define BMI160_ACC_PMU_STATUS_LEN 2
|
||||
#define BMI160_GYR_PMU_STATUS_BIT 2
|
||||
#define BMI160_GYR_PMU_STATUS_LEN 2
|
||||
|
||||
#define BMI160_RA_PMU_STATUS 0x03
|
||||
|
||||
#define BMI160_RA_MAG_X_L 0x04
|
||||
#define BMI160_RA_MAG_X_H 0x05
|
||||
#define BMI160_RA_MAG_Y_L 0x06
|
||||
#define BMI160_RA_MAG_Y_H 0x07
|
||||
#define BMI160_RA_MAG_Z_L 0x08
|
||||
#define BMI160_RA_MAG_Z_H 0x09
|
||||
#define BMI160_RA_GYRO_X_L 0x0C
|
||||
#define BMI160_RA_GYRO_X_H 0x0D
|
||||
#define BMI160_RA_GYRO_Y_L 0x0E
|
||||
#define BMI160_RA_GYRO_Y_H 0x0F
|
||||
#define BMI160_RA_GYRO_Z_L 0x10
|
||||
#define BMI160_RA_GYRO_Z_H 0x11
|
||||
#define BMI160_RA_ACCEL_X_L 0x12
|
||||
#define BMI160_RA_ACCEL_X_H 0x13
|
||||
#define BMI160_RA_ACCEL_Y_L 0x14
|
||||
#define BMI160_RA_ACCEL_Y_H 0x15
|
||||
#define BMI160_RA_ACCEL_Z_L 0x16
|
||||
#define BMI160_RA_ACCEL_Z_H 0x17
|
||||
|
||||
#define BMI160_RA_SENSORTIME 0x18
|
||||
|
||||
#define BMI160_STATUS_FOC_RDY 3
|
||||
#define BMI160_STATUS_NVM_RDY 4
|
||||
#define BMI160_STATUS_DRDY_MAG 5
|
||||
#define BMI160_STATUS_DRDY_GYR 6
|
||||
#define BMI160_STATUS_DRDY_ACC 7
|
||||
|
||||
#define BMI160_RA_STATUS 0x1B
|
||||
|
||||
#define BMI160_STEP_INT_BIT 0
|
||||
#define BMI160_ANYMOTION_INT_BIT 2
|
||||
#define BMI160_D_TAP_INT_BIT 4
|
||||
#define BMI160_S_TAP_INT_BIT 5
|
||||
#define BMI160_NOMOTION_INT_BIT 7
|
||||
#define BMI160_FFULL_INT_BIT 5
|
||||
#define BMI160_DRDY_INT_BIT 4
|
||||
#define BMI160_LOW_G_INT_BIT 3
|
||||
#define BMI160_HIGH_G_INT_BIT 2
|
||||
|
||||
#define BMI160_TAP_SIGN_BIT 7
|
||||
#define BMI160_TAP_1ST_Z_BIT 6
|
||||
#define BMI160_TAP_1ST_Y_BIT 5
|
||||
#define BMI160_TAP_1ST_X_BIT 4
|
||||
|
||||
#define BMI160_ANYMOTION_SIGN_BIT 3
|
||||
#define BMI160_ANYMOTION_1ST_Z_BIT 2
|
||||
#define BMI160_ANYMOTION_1ST_Y_BIT 1
|
||||
#define BMI160_ANYMOTION_1ST_X_BIT 0
|
||||
|
||||
#define BMI160_HIGH_G_SIGN_BIT 3
|
||||
#define BMI160_HIGH_G_1ST_Z_BIT 2
|
||||
#define BMI160_HIGH_G_1ST_Y_BIT 1
|
||||
#define BMI160_HIGH_G_1ST_X_BIT 0
|
||||
|
||||
#define BMI160_RA_INT_STATUS_0 0x1C
|
||||
#define BMI160_RA_INT_STATUS_1 0x1D
|
||||
#define BMI160_RA_INT_STATUS_2 0x1E
|
||||
#define BMI160_RA_INT_STATUS_3 0x1F
|
||||
|
||||
#define BMI160_RA_TEMP_L 0x20
|
||||
#define BMI160_RA_TEMP_H 0x21
|
||||
|
||||
#define BMI160_RA_FIFO_LENGTH_0 0x22
|
||||
#define BMI160_RA_FIFO_LENGTH_1 0x23
|
||||
|
||||
#define BMI160_FIFO_DATA_INVALID 0x80
|
||||
#define BMI160_RA_FIFO_DATA 0x24
|
||||
|
||||
#define BMI160_ACCEL_RATE_SEL_BIT 0
|
||||
#define BMI160_ACCEL_RATE_SEL_LEN 4
|
||||
|
||||
#define BMI160_RA_ACCEL_CONF 0x40
|
||||
#define BMI160_RA_ACCEL_RANGE 0x41
|
||||
|
||||
#define BMI160_RA_GYRO_CONF 0x42
|
||||
#define BMI160_RA_GYRO_RANGE 0x43
|
||||
|
||||
#define BMI160_FIFO_HEADER_EN_BIT 4
|
||||
#define BMI160_FIFO_MAG_EN_BIT 5
|
||||
#define BMI160_FIFO_ACC_EN_BIT 6
|
||||
#define BMI160_FIFO_GYR_EN_BIT 7
|
||||
|
||||
#define BMI160_RA_FIFO_CONFIG_0 0x46
|
||||
#define BMI160_RA_FIFO_CONFIG_1 0x47
|
||||
|
||||
#define BMI160_ANYMOTION_EN_BIT 0
|
||||
#define BMI160_ANYMOTION_EN_LEN 3
|
||||
#define BMI160_D_TAP_EN_BIT 4
|
||||
#define BMI160_S_TAP_EN_BIT 5
|
||||
#define BMI160_NOMOTION_EN_BIT 0
|
||||
#define BMI160_NOMOTION_EN_LEN 3
|
||||
#define BMI160_LOW_G_EN_BIT 3
|
||||
#define BMI160_LOW_G_EN_LEN 1
|
||||
#define BMI160_HIGH_G_EN_BIT 0
|
||||
#define BMI160_HIGH_G_EN_LEN 3
|
||||
|
||||
#define BMI160_STEP_EN_BIT 3
|
||||
#define BMI160_DRDY_EN_BIT 4
|
||||
#define BMI160_FFULL_EN_BIT 5
|
||||
|
||||
#define BMI160_RA_INT_EN_0 0x50
|
||||
#define BMI160_RA_INT_EN_1 0x51
|
||||
#define BMI160_RA_INT_EN_2 0x52
|
||||
|
||||
#define BMI160_INT1_EDGE_CTRL 0
|
||||
#define BMI160_INT1_LVL 1
|
||||
#define BMI160_INT1_OD 2
|
||||
#define BMI160_INT1_OUTPUT_EN 3
|
||||
|
||||
#define BMI160_RA_INT_OUT_CTRL 0x53
|
||||
|
||||
#define BMI160_LATCH_MODE_BIT 0
|
||||
#define BMI160_LATCH_MODE_LEN 4
|
||||
|
||||
#define BMI160_RA_INT_LATCH 0x54
|
||||
#define BMI160_RA_INT_MAP_0 0x55
|
||||
#define BMI160_RA_INT_MAP_1 0x56
|
||||
#define BMI160_RA_INT_MAP_2 0x57
|
||||
|
||||
#define BMI160_ANYMOTION_DUR_BIT 0
|
||||
#define BMI160_ANYMOTION_DUR_LEN 2
|
||||
#define BMI160_NOMOTION_DUR_BIT 2
|
||||
#define BMI160_NOMOTION_DUR_LEN 6
|
||||
|
||||
#define BMI160_NOMOTION_SEL_BIT 0
|
||||
#define BMI160_NOMOTION_SEL_LEN 1
|
||||
|
||||
#define BMI160_RA_INT_LOWHIGH_0 0x5A
|
||||
#define BMI160_RA_INT_LOWHIGH_1 0x5B
|
||||
#define BMI160_RA_INT_LOWHIGH_2 0x5C
|
||||
#define BMI160_RA_INT_LOWHIGH_3 0x5D
|
||||
#define BMI160_RA_INT_LOWHIGH_4 0x5E
|
||||
|
||||
#define BMI160_RA_INT_MOTION_0 0x5F
|
||||
#define BMI160_RA_INT_MOTION_1 0x60
|
||||
#define BMI160_RA_INT_MOTION_2 0x61
|
||||
#define BMI160_RA_INT_MOTION_3 0x62
|
||||
|
||||
#define BMI160_TAP_DUR_BIT 0
|
||||
#define BMI160_TAP_DUR_LEN 3
|
||||
#define BMI160_TAP_SHOCK_BIT 6
|
||||
#define BMI160_TAP_QUIET_BIT 7
|
||||
#define BMI160_TAP_THRESH_BIT 0
|
||||
#define BMI160_TAP_THRESH_LEN 5
|
||||
|
||||
#define BMI160_RA_INT_TAP_0 0x63
|
||||
#define BMI160_RA_INT_TAP_1 0x64
|
||||
|
||||
#define BMI160_FOC_ACC_Z_BIT 0
|
||||
#define BMI160_FOC_ACC_Z_LEN 2
|
||||
#define BMI160_FOC_ACC_Y_BIT 2
|
||||
#define BMI160_FOC_ACC_Y_LEN 2
|
||||
#define BMI160_FOC_ACC_X_BIT 4
|
||||
#define BMI160_FOC_ACC_X_LEN 2
|
||||
#define BMI160_FOC_GYR_EN 6
|
||||
|
||||
#define BMI160_RA_FOC_CONF 0x69
|
||||
|
||||
#define BMI160_GYR_OFFSET_X_MSB_BIT 0
|
||||
#define BMI160_GYR_OFFSET_X_MSB_LEN 2
|
||||
#define BMI160_GYR_OFFSET_Y_MSB_BIT 2
|
||||
#define BMI160_GYR_OFFSET_Y_MSB_LEN 2
|
||||
#define BMI160_GYR_OFFSET_Z_MSB_BIT 4
|
||||
#define BMI160_GYR_OFFSET_Z_MSB_LEN 2
|
||||
#define BMI160_ACC_OFFSET_EN 6
|
||||
#define BMI160_GYR_OFFSET_EN 7
|
||||
|
||||
#define BMI160_RA_OFFSET_0 0x71
|
||||
#define BMI160_RA_OFFSET_1 0x72
|
||||
#define BMI160_RA_OFFSET_2 0x73
|
||||
#define BMI160_RA_OFFSET_3 0x74
|
||||
#define BMI160_RA_OFFSET_4 0x75
|
||||
#define BMI160_RA_OFFSET_5 0x76
|
||||
#define BMI160_RA_OFFSET_6 0x77
|
||||
|
||||
#define BMI160_RA_STEP_CNT_L 0x78
|
||||
#define BMI160_RA_STEP_CNT_H 0x79
|
||||
|
||||
#define BMI160_STEP_BUF_MIN_BIT 0
|
||||
#define BMI160_STEP_BUF_MIN_LEN 3
|
||||
#define BMI160_STEP_CNT_EN_BIT 3
|
||||
|
||||
#define BMI160_STEP_TIME_MIN_BIT 0
|
||||
#define BMI160_STEP_TIME_MIN_LEN 3
|
||||
#define BMI160_STEP_THRESH_MIN_BIT 3
|
||||
#define BMI160_STEP_THRESH_MIN_LEN 2
|
||||
#define BMI160_STEP_ALPHA_BIT 5
|
||||
#define BMI160_STEP_ALPHA_LEN 3
|
||||
|
||||
#define BMI160_RA_STEP_CONF_0 0x7A
|
||||
#define BMI160_RA_STEP_CONF_1 0x7B
|
||||
|
||||
#define BMI160_RA_STEP_CONF_0_NOR 0x15
|
||||
#define BMI160_RA_STEP_CONF_0_SEN 0x2D
|
||||
#define BMI160_RA_STEP_CONF_0_ROB 0x1D
|
||||
#define BMI160_RA_STEP_CONF_1_NOR 0x03
|
||||
#define BMI160_RA_STEP_CONF_1_SEN 0x00
|
||||
#define BMI160_RA_STEP_CONF_1_ROB 0x07
|
||||
|
||||
|
||||
#define BMI160_GYRO_RANGE_SEL_BIT 0
|
||||
#define BMI160_GYRO_RANGE_SEL_LEN 3
|
||||
|
||||
#define BMI160_GYRO_RATE_SEL_BIT 0
|
||||
#define BMI160_GYRO_RATE_SEL_LEN 4
|
||||
|
||||
#define BMI160_GYRO_DLPF_SEL_BIT 4
|
||||
#define BMI160_GYRO_DLPF_SEL_LEN 2
|
||||
|
||||
#define BMI160_ACCEL_DLPF_SEL_BIT 4
|
||||
#define BMI160_ACCEL_DLPF_SEL_LEN 3
|
||||
|
||||
#define BMI160_ACCEL_RANGE_SEL_BIT 0
|
||||
#define BMI160_ACCEL_RANGE_SEL_LEN 4
|
||||
|
||||
#define BMI160_CMD_START_FOC 0x03
|
||||
#define BMI160_CMD_ACC_MODE_NORMAL 0x11
|
||||
#define BMI160_CMD_GYR_MODE_NORMAL 0x15
|
||||
#define BMI160_CMD_FIFO_FLUSH 0xB0
|
||||
#define BMI160_CMD_INT_RESET 0xB1
|
||||
#define BMI160_CMD_STEP_CNT_CLR 0xB2
|
||||
#define BMI160_CMD_SOFT_RESET 0xB6
|
||||
|
||||
#define BMI160_RA_CMD 0x7E
|
||||
|
||||
// mode parm ext
|
||||
#define BMI160_FIFO_HEADER_CTL_SKIP_FRAME 0x40 // 0b01 0 000 00
|
||||
#define BMI160_FIFO_HEADER_CTL_SENSOR_TIME 0x44 // 0b01 0 001 00
|
||||
#define BMI160_FIFO_HEADER_CTL_INPUT_CONFIG 0x48 // 0b01 0 010 00
|
||||
#define BMI160_FIFO_HEADER_DATA_FRAME_BASE 0x80 // 0b10 0 000 00
|
||||
#define BMI160_FIFO_HEADER_DATA_FRAME_FLAG_M 1 << 4 // 0b00 0 100 00
|
||||
#define BMI160_FIFO_HEADER_DATA_FRAME_FLAG_G 1 << 3 // 0b00 0 010 00
|
||||
#define BMI160_FIFO_HEADER_DATA_FRAME_FLAG_A 1 << 2 // 0b00 0 001 00
|
||||
#define BMI160_FIFO_HEADER_DATA_FRAME_MASK_HAS_DATA \
|
||||
(BMI160_FIFO_HEADER_DATA_FRAME_FLAG_M |\
|
||||
BMI160_FIFO_HEADER_DATA_FRAME_FLAG_G |\
|
||||
BMI160_FIFO_HEADER_DATA_FRAME_FLAG_A)
|
||||
|
||||
#define BMI160_FIFO_SKIP_FRAME_LEN 1
|
||||
#define BMI160_FIFO_INPUT_CONFIG_LEN 1
|
||||
#define BMI160_FIFO_SENSOR_TIME_LEN 3
|
||||
#define BMI160_FIFO_M_LEN 8
|
||||
#define BMI160_FIFO_G_LEN 6
|
||||
#define BMI160_FIFO_A_LEN 6
|
||||
|
||||
#define BMI160_RA_ERR 0x02
|
||||
#define BMI160_ERR_MASK_MAG_DRDY_ERR 0b10000000
|
||||
#define BMI160_ERR_MASK_DROP_CMD_ERR 0b01000000
|
||||
// datasheet is unclear - reserved or i2c_fail_err?
|
||||
// #define BMI160_ERR_MASK_I2C_FAIL 0b00100000
|
||||
#define BMI160_ERR_MASK_ERROR_CODE 0b00011110
|
||||
#define BMI160_ERR_MASK_CHIP_NOT_OPERABLE 0b00000001
|
||||
|
||||
/**
|
||||
* Interrupt Latch Mode options
|
||||
* @see setInterruptLatch()
|
||||
*/
|
||||
typedef enum {
|
||||
BMI160_LATCH_MODE_NONE = 0, /**< Non-latched */
|
||||
BMI160_LATCH_MODE_312_5_US, /**< Temporary, 312.50 microseconds */
|
||||
BMI160_LATCH_MODE_625_US, /**< Temporary, 625.00 microseconds */
|
||||
BMI160_LATCH_MODE_1_25_MS, /**< Temporary, 1.25 milliseconds */
|
||||
BMI160_LATCH_MODE_2_5_MS, /**< Temporary, 2.50 milliseconds */
|
||||
BMI160_LATCH_MODE_5_MS, /**< Temporary, 5.00 milliseconds */
|
||||
BMI160_LATCH_MODE_10_MS, /**< Temporary, 10.00 milliseconds */
|
||||
BMI160_LATCH_MODE_20_MS, /**< Temporary, 20.00 milliseconds */
|
||||
BMI160_LATCH_MODE_40_MS, /**< Temporary, 40.00 milliseconds */
|
||||
BMI160_LATCH_MODE_80_MS, /**< Temporary, 80.00 milliseconds */
|
||||
BMI160_LATCH_MODE_160_MS, /**< Temporary, 160.00 milliseconds */
|
||||
BMI160_LATCH_MODE_320_MS, /**< Temporary, 320.00 milliseconds */
|
||||
BMI160_LATCH_MODE_640_MS, /**< Temporary, 640.00 milliseconds */
|
||||
BMI160_LATCH_MODE_1_28_S, /**< Temporary, 1.28 seconds */
|
||||
BMI160_LATCH_MODE_2_56_S, /**< Temporary, 2.56 seconds */
|
||||
BMI160_LATCH_MODE_LATCH, /**< Latched, @see resetInterrupt() */
|
||||
} BMI160InterruptLatchMode;
|
||||
|
||||
/**
|
||||
* Digital Low-Pass Filter Mode options
|
||||
* @see setGyroDLPFMode()
|
||||
* @see setAccelDLPFMode()
|
||||
*/
|
||||
typedef enum {
|
||||
BMI160_DLPF_MODE_NORM = 0x2,
|
||||
BMI160_DLPF_MODE_OSR2 = 0x1,
|
||||
BMI160_DLPF_MODE_OSR4 = 0x0,
|
||||
} BMI160DLPFMode;
|
||||
|
||||
/**
|
||||
* Accelerometer Sensitivity Range options
|
||||
* @see setFullScaleAccelRange()
|
||||
*/
|
||||
typedef enum {
|
||||
BMI160_ACCEL_RANGE_2G = 0x03, /**< +/- 2g range */
|
||||
BMI160_ACCEL_RANGE_4G = 0x05, /**< +/- 4g range */
|
||||
BMI160_ACCEL_RANGE_8G = 0x08, /**< +/- 8g range */
|
||||
BMI160_ACCEL_RANGE_16G = 0x0C, /**< +/- 16g range */
|
||||
} BMI160AccelRange;
|
||||
|
||||
/**
|
||||
* Gyroscope Sensitivity Range options
|
||||
* @see setFullScaleGyroRange()
|
||||
*/
|
||||
typedef enum {
|
||||
BMI160_GYRO_RANGE_2000 = 0, /**< +/- 2000 degrees/second */
|
||||
BMI160_GYRO_RANGE_1000, /**< +/- 1000 degrees/second */
|
||||
BMI160_GYRO_RANGE_500, /**< +/- 500 degrees/second */
|
||||
BMI160_GYRO_RANGE_250, /**< +/- 250 degrees/second */
|
||||
BMI160_GYRO_RANGE_125, /**< +/- 125 degrees/second */
|
||||
} BMI160GyroRange;
|
||||
|
||||
/**
|
||||
* Accelerometer Output Data Rate options
|
||||
* @see setAccelRate()
|
||||
*/
|
||||
typedef enum {
|
||||
BMI160_ACCEL_RATE_25_2HZ = 5, /**< 25/2 Hz */
|
||||
BMI160_ACCEL_RATE_25HZ, /**< 25 Hz */
|
||||
BMI160_ACCEL_RATE_50HZ, /**< 50 Hz */
|
||||
BMI160_ACCEL_RATE_100HZ, /**< 100 Hz */
|
||||
BMI160_ACCEL_RATE_200HZ, /**< 200 Hz */
|
||||
BMI160_ACCEL_RATE_400HZ, /**< 400 Hz */
|
||||
BMI160_ACCEL_RATE_800HZ, /**< 800 Hz */
|
||||
BMI160_ACCEL_RATE_1600HZ, /**< 1600 Hz */
|
||||
} BMI160AccelRate;
|
||||
|
||||
/**
|
||||
* Gyroscope Output Data Rate options
|
||||
* @see setGyroRate()
|
||||
*/
|
||||
typedef enum {
|
||||
BMI160_GYRO_RATE_25HZ = 6, /**< 25 Hz */
|
||||
BMI160_GYRO_RATE_50HZ, /**< 50 Hz */
|
||||
BMI160_GYRO_RATE_100HZ, /**< 100 Hz */
|
||||
BMI160_GYRO_RATE_200HZ, /**< 200 Hz */
|
||||
BMI160_GYRO_RATE_400HZ, /**< 400 Hz */
|
||||
BMI160_GYRO_RATE_800HZ, /**< 800 Hz */
|
||||
BMI160_GYRO_RATE_1600HZ, /**< 1600 Hz */
|
||||
BMI160_GYRO_RATE_3200HZ, /**< 3200 Hz */
|
||||
} BMI160GyroRate;
|
||||
|
||||
/**
|
||||
* Step Detection Mode options
|
||||
* @see setStepDetectionMode()
|
||||
*/
|
||||
typedef enum {
|
||||
BMI160_STEP_MODE_NORMAL = 0,
|
||||
BMI160_STEP_MODE_SENSITIVE,
|
||||
BMI160_STEP_MODE_ROBUST,
|
||||
BMI160_STEP_MODE_UNKNOWN,
|
||||
} BMI160StepMode;
|
||||
|
||||
/**
|
||||
* Tap Detection Shock Duration options
|
||||
* @see setTapShockDuration()
|
||||
*/
|
||||
typedef enum {
|
||||
BMI160_TAP_SHOCK_DURATION_50MS = 0,
|
||||
BMI160_TAP_SHOCK_DURATION_75MS,
|
||||
} BMI160TapShockDuration;
|
||||
|
||||
/**
|
||||
* Tap Detection Quiet Duration options
|
||||
* @see setTapQuietDuration()
|
||||
*/
|
||||
typedef enum {
|
||||
BMI160_TAP_QUIET_DURATION_30MS = 0,
|
||||
BMI160_TAP_QUIET_DURATION_20MS,
|
||||
} BMI160TapQuietDuration;
|
||||
|
||||
/**
|
||||
* Double-Tap Detection Duration options
|
||||
* @see setDoubleTapDetectionDuration()
|
||||
*/
|
||||
typedef enum {
|
||||
BMI160_DOUBLE_TAP_DURATION_50MS = 0,
|
||||
BMI160_DOUBLE_TAP_DURATION_100MS,
|
||||
BMI160_DOUBLE_TAP_DURATION_150MS,
|
||||
BMI160_DOUBLE_TAP_DURATION_200MS,
|
||||
BMI160_DOUBLE_TAP_DURATION_250MS,
|
||||
BMI160_DOUBLE_TAP_DURATION_375MS,
|
||||
BMI160_DOUBLE_TAP_DURATION_500MS,
|
||||
BMI160_DOUBLE_TAP_DURATION_700MS,
|
||||
} BMI160DoubleTapDuration;
|
||||
|
||||
/**
|
||||
* Zero-Motion Detection Duration options
|
||||
* @see setZeroMotionDetectionDuration()
|
||||
*/
|
||||
typedef enum {
|
||||
BMI160_ZERO_MOTION_DURATION_1_28S = 0x00, /**< 1.28 seconds */
|
||||
BMI160_ZERO_MOTION_DURATION_2_56S, /**< 2.56 seconds */
|
||||
BMI160_ZERO_MOTION_DURATION_3_84S, /**< 3.84 seconds */
|
||||
BMI160_ZERO_MOTION_DURATION_5_12S, /**< 5.12 seconds */
|
||||
BMI160_ZERO_MOTION_DURATION_6_40S, /**< 6.40 seconds */
|
||||
BMI160_ZERO_MOTION_DURATION_7_68S, /**< 7.68 seconds */
|
||||
BMI160_ZERO_MOTION_DURATION_8_96S, /**< 8.96 seconds */
|
||||
BMI160_ZERO_MOTION_DURATION_10_24S, /**< 10.24 seconds */
|
||||
BMI160_ZERO_MOTION_DURATION_11_52S, /**< 11.52 seconds */
|
||||
BMI160_ZERO_MOTION_DURATION_12_80S, /**< 12.80 seconds */
|
||||
BMI160_ZERO_MOTION_DURATION_14_08S, /**< 14.08 seconds */
|
||||
BMI160_ZERO_MOTION_DURATION_15_36S, /**< 15.36 seconds */
|
||||
BMI160_ZERO_MOTION_DURATION_16_64S, /**< 16.64 seconds */
|
||||
BMI160_ZERO_MOTION_DURATION_17_92S, /**< 17.92 seconds */
|
||||
BMI160_ZERO_MOTION_DURATION_19_20S, /**< 19.20 seconds */
|
||||
BMI160_ZERO_MOTION_DURATION_20_48S, /**< 20.48 seconds */
|
||||
BMI160_ZERO_MOTION_DURATION_25_60S = 0x10, /**< 25.60 seconds */
|
||||
BMI160_ZERO_MOTION_DURATION_30_72S, /**< 30.72 seconds */
|
||||
BMI160_ZERO_MOTION_DURATION_35_84S, /**< 35.84 seconds */
|
||||
BMI160_ZERO_MOTION_DURATION_40_96S, /**< 40.96 seconds */
|
||||
BMI160_ZERO_MOTION_DURATION_46_08S, /**< 46.08 seconds */
|
||||
BMI160_ZERO_MOTION_DURATION_51_20S, /**< 51.20 seconds */
|
||||
BMI160_ZERO_MOTION_DURATION_56_32S, /**< 56.32 seconds */
|
||||
BMI160_ZERO_MOTION_DURATION_61_44S, /**< 61.44 seconds */
|
||||
BMI160_ZERO_MOTION_DURATION_66_56S, /**< 66.56 seconds */
|
||||
BMI160_ZERO_MOTION_DURATION_71_68S, /**< 71.68 seconds */
|
||||
BMI160_ZERO_MOTION_DURATION_76_80S, /**< 76.80 seconds */
|
||||
BMI160_ZERO_MOTION_DURATION_81_92S, /**< 81.92 seconds */
|
||||
BMI160_ZERO_MOTION_DURATION_87_04S, /**< 87.04 seconds */
|
||||
BMI160_ZERO_MOTION_DURATION_92_16S, /**< 92.16 seconds */
|
||||
BMI160_ZERO_MOTION_DURATION_97_28S, /**< 97.28 seconds */
|
||||
BMI160_ZERO_MOTION_DURATION_102_40S, /**< 102.40 seconds */
|
||||
BMI160_ZERO_MOTION_DURATION_112_64S = 0x20, /**< 112.64 seconds */
|
||||
BMI160_ZERO_MOTION_DURATION_122_88S, /**< 122.88 seconds */
|
||||
BMI160_ZERO_MOTION_DURATION_133_12S, /**< 133.12 seconds */
|
||||
BMI160_ZERO_MOTION_DURATION_143_36S, /**< 143.36 seconds */
|
||||
BMI160_ZERO_MOTION_DURATION_153_60S, /**< 153.60 seconds */
|
||||
BMI160_ZERO_MOTION_DURATION_163_84S, /**< 163.84 seconds */
|
||||
BMI160_ZERO_MOTION_DURATION_174_08S, /**< 174.08 seconds */
|
||||
BMI160_ZERO_MOTION_DURATION_184_32S, /**< 184.32 seconds */
|
||||
BMI160_ZERO_MOTION_DURATION_194_56S, /**< 194.56 seconds */
|
||||
BMI160_ZERO_MOTION_DURATION_204_80S, /**< 204.80 seconds */
|
||||
BMI160_ZERO_MOTION_DURATION_215_04S, /**< 215.04 seconds */
|
||||
BMI160_ZERO_MOTION_DURATION_225_28S, /**< 225.28 seconds */
|
||||
BMI160_ZERO_MOTION_DURATION_235_52S, /**< 235.52 seconds */
|
||||
BMI160_ZERO_MOTION_DURATION_245_76S, /**< 245.76 seconds */
|
||||
BMI160_ZERO_MOTION_DURATION_256_00S, /**< 256.00 seconds */
|
||||
BMI160_ZERO_MOTION_DURATION_266_24S, /**< 266.24 seconds */
|
||||
BMI160_ZERO_MOTION_DURATION_276_48S, /**< 276.48 seconds */
|
||||
BMI160_ZERO_MOTION_DURATION_286_72S, /**< 286.72 seconds */
|
||||
BMI160_ZERO_MOTION_DURATION_296_96S, /**< 296.96 seconds */
|
||||
BMI160_ZERO_MOTION_DURATION_307_20S, /**< 307.20 seconds */
|
||||
BMI160_ZERO_MOTION_DURATION_317_44S, /**< 317.44 seconds */
|
||||
BMI160_ZERO_MOTION_DURATION_327_68S, /**< 327.68 seconds */
|
||||
BMI160_ZERO_MOTION_DURATION_337_92S, /**< 337.92 seconds */
|
||||
BMI160_ZERO_MOTION_DURATION_348_16S, /**< 348.16 seconds */
|
||||
BMI160_ZERO_MOTION_DURATION_358_40S, /**< 358.40 seconds */
|
||||
BMI160_ZERO_MOTION_DURATION_368_64S, /**< 368.64 seconds */
|
||||
BMI160_ZERO_MOTION_DURATION_378_88S, /**< 378.88 seconds */
|
||||
BMI160_ZERO_MOTION_DURATION_389_12S, /**< 389.12 seconds */
|
||||
BMI160_ZERO_MOTION_DURATION_399_36S, /**< 399.36 seconds */
|
||||
BMI160_ZERO_MOTION_DURATION_409_60S, /**< 409.60 seconds */
|
||||
BMI160_ZERO_MOTION_DURATION_419_84S, /**< 419.84 seconds */
|
||||
BMI160_ZERO_MOTION_DURATION_430_08S, /**< 430.08 seconds */
|
||||
} BMI160ZeroMotionDuration;
|
||||
|
||||
class BMI160 {
|
||||
public:
|
||||
BMI160();
|
||||
void initialize(
|
||||
uint8_t addr,
|
||||
BMI160GyroRate gyroRate = BMI160_GYRO_RATE_800HZ,
|
||||
BMI160GyroRange gyroRange = BMI160_GYRO_RANGE_500,
|
||||
BMI160DLPFMode gyroFilterMode = BMI160_DLPF_MODE_NORM,
|
||||
BMI160AccelRate accelRate = BMI160_ACCEL_RATE_800HZ,
|
||||
BMI160AccelRange accelRange = BMI160_ACCEL_RANGE_4G,
|
||||
BMI160DLPFMode accelFilterMode = BMI160_DLPF_MODE_OSR4
|
||||
);
|
||||
bool testConnection();
|
||||
|
||||
uint8_t getGyroRate();
|
||||
void setGyroRate(uint8_t rate);
|
||||
|
||||
uint8_t getAccelRate();
|
||||
void setAccelRate(uint8_t rate);
|
||||
|
||||
uint8_t getGyroDLPFMode();
|
||||
void setGyroDLPFMode(uint8_t bandwidth);
|
||||
|
||||
uint8_t getAccelDLPFMode();
|
||||
void setAccelDLPFMode(uint8_t bandwidth);
|
||||
|
||||
uint8_t getFullScaleGyroRange();
|
||||
void setFullScaleGyroRange(uint8_t range);
|
||||
uint8_t getFullScaleAccelRange();
|
||||
void setFullScaleAccelRange(uint8_t range);
|
||||
|
||||
void autoCalibrateGyroOffset();
|
||||
bool getGyroOffsetEnabled();
|
||||
void setGyroOffsetEnabled(bool enabled);
|
||||
|
||||
int16_t getXGyroOffset();
|
||||
void setXGyroOffset(int16_t offset);
|
||||
int16_t getYGyroOffset();
|
||||
void setYGyroOffset(int16_t offset);
|
||||
int16_t getZGyroOffset();
|
||||
void setZGyroOffset(int16_t offset);
|
||||
|
||||
void autoCalibrateXAccelOffset(int target);
|
||||
void autoCalibrateYAccelOffset(int target);
|
||||
void autoCalibrateZAccelOffset(int target);
|
||||
bool getAccelOffsetEnabled();
|
||||
void setAccelOffsetEnabled(bool enabled);
|
||||
|
||||
int8_t getXAccelOffset();
|
||||
void setXAccelOffset(int8_t offset);
|
||||
int8_t getYAccelOffset();
|
||||
void setYAccelOffset(int8_t offset);
|
||||
int8_t getZAccelOffset();
|
||||
void setZAccelOffset(int8_t offset);
|
||||
|
||||
uint8_t getFreefallDetectionThreshold();
|
||||
void setFreefallDetectionThreshold(uint8_t threshold);
|
||||
|
||||
uint8_t getFreefallDetectionDuration();
|
||||
void setFreefallDetectionDuration(uint8_t duration);
|
||||
|
||||
uint8_t getShockDetectionThreshold();
|
||||
void setShockDetectionThreshold(uint8_t threshold);
|
||||
|
||||
uint8_t getShockDetectionDuration();
|
||||
void setShockDetectionDuration(uint8_t duration);
|
||||
|
||||
uint8_t getMotionDetectionThreshold();
|
||||
void setMotionDetectionThreshold(uint8_t threshold);
|
||||
|
||||
uint8_t getMotionDetectionDuration();
|
||||
void setMotionDetectionDuration(uint8_t duration);
|
||||
|
||||
uint8_t getZeroMotionDetectionThreshold();
|
||||
void setZeroMotionDetectionThreshold(uint8_t threshold);
|
||||
|
||||
uint8_t getZeroMotionDetectionDuration();
|
||||
void setZeroMotionDetectionDuration(uint8_t duration);
|
||||
|
||||
uint8_t getTapDetectionThreshold();
|
||||
void setTapDetectionThreshold(uint8_t threshold);
|
||||
|
||||
bool getTapShockDuration();
|
||||
void setTapShockDuration(bool duration);
|
||||
|
||||
bool getTapQuietDuration();
|
||||
void setTapQuietDuration(bool duration);
|
||||
|
||||
uint8_t getDoubleTapDetectionDuration();
|
||||
void setDoubleTapDetectionDuration(uint8_t duration);
|
||||
|
||||
uint8_t getStepDetectionMode();
|
||||
void setStepDetectionMode(BMI160StepMode mode);
|
||||
bool getStepCountEnabled();
|
||||
void setStepCountEnabled(bool enabled);
|
||||
uint16_t getStepCount();
|
||||
void resetStepCount();
|
||||
|
||||
bool getIntFreefallEnabled();
|
||||
void setIntFreefallEnabled(bool enabled);
|
||||
bool getIntShockEnabled();
|
||||
void setIntShockEnabled(bool enabled);
|
||||
bool getIntStepEnabled();
|
||||
void setIntStepEnabled(bool enabled);
|
||||
bool getIntMotionEnabled();
|
||||
void setIntMotionEnabled(bool enabled);
|
||||
bool getIntZeroMotionEnabled();
|
||||
void setIntZeroMotionEnabled(bool enabled);
|
||||
bool getIntTapEnabled();
|
||||
void setIntTapEnabled(bool enabled);
|
||||
bool getIntDoubleTapEnabled();
|
||||
void setIntDoubleTapEnabled(bool enabled);
|
||||
|
||||
bool getGyroFIFOEnabled();
|
||||
void setGyroFIFOEnabled(bool enabled);
|
||||
bool getAccelFIFOEnabled();
|
||||
void setAccelFIFOEnabled(bool enabled);
|
||||
bool getMagFIFOEnabled();
|
||||
void setMagFIFOEnabled(bool enabled);
|
||||
|
||||
bool getIntFIFOBufferFullEnabled();
|
||||
void setIntFIFOBufferFullEnabled(bool enabled);
|
||||
bool getIntDataReadyEnabled();
|
||||
void setIntDataReadyEnabled(bool enabled);
|
||||
|
||||
uint8_t getIntStatus0();
|
||||
uint8_t getIntStatus1();
|
||||
uint8_t getIntStatus2();
|
||||
uint8_t getIntStatus3();
|
||||
bool getIntFreefallStatus();
|
||||
bool getIntShockStatus();
|
||||
bool getIntStepStatus();
|
||||
bool getIntMotionStatus();
|
||||
bool getIntZeroMotionStatus();
|
||||
bool getIntTapStatus();
|
||||
bool getIntDoubleTapStatus();
|
||||
bool getIntFIFOBufferFullStatus();
|
||||
bool getIntDataReadyStatus();
|
||||
|
||||
void getMotion6(int16_t* ax, int16_t* ay, int16_t* az, int16_t* gx, int16_t* gy, int16_t* gz);
|
||||
void getAcceleration(int16_t* x, int16_t* y, int16_t* z);
|
||||
int16_t getAccelerationX();
|
||||
int16_t getAccelerationY();
|
||||
int16_t getAccelerationZ();
|
||||
|
||||
void getMagnetometer(int16_t* mx, int16_t* my, int16_t* mz);
|
||||
void getMagnetometerXYZBuffer(uint8_t* data);
|
||||
|
||||
bool getTemperature(int16_t* out);
|
||||
|
||||
void getRotation(int16_t* x, int16_t* y, int16_t* z);
|
||||
int16_t getRotationX();
|
||||
int16_t getRotationY();
|
||||
int16_t getRotationZ();
|
||||
|
||||
bool getXNegShockDetected();
|
||||
bool getXPosShockDetected();
|
||||
bool getYNegShockDetected();
|
||||
bool getYPosShockDetected();
|
||||
bool getZNegShockDetected();
|
||||
bool getZPosShockDetected();
|
||||
|
||||
bool getXNegMotionDetected();
|
||||
bool getXPosMotionDetected();
|
||||
bool getYNegMotionDetected();
|
||||
bool getYPosMotionDetected();
|
||||
bool getZNegMotionDetected();
|
||||
bool getZPosMotionDetected();
|
||||
|
||||
bool getXNegTapDetected();
|
||||
bool getXPosTapDetected();
|
||||
bool getYNegTapDetected();
|
||||
bool getYPosTapDetected();
|
||||
bool getZNegTapDetected();
|
||||
bool getZPosTapDetected();
|
||||
|
||||
bool getFIFOHeaderModeEnabled();
|
||||
void setFIFOHeaderModeEnabled(bool enabled);
|
||||
void resetFIFO();
|
||||
|
||||
bool getFIFOCount(uint16_t* outCount);
|
||||
bool getFIFOBytes(uint8_t *data, uint16_t length);
|
||||
|
||||
uint8_t getDeviceID();
|
||||
|
||||
uint8_t getRegister(uint8_t reg);
|
||||
void setRegister(uint8_t reg, uint8_t data);
|
||||
|
||||
bool getIntEnabled();
|
||||
void setIntEnabled(bool enabled);
|
||||
bool getInterruptMode();
|
||||
void setInterruptMode(bool mode);
|
||||
bool getInterruptDrive();
|
||||
void setInterruptDrive(bool drive);
|
||||
uint8_t getInterruptLatch();
|
||||
void setInterruptLatch(uint8_t latch);
|
||||
void resetInterrupt();
|
||||
|
||||
bool getGyroDrdy();
|
||||
void waitForGyroDrdy();
|
||||
void waitForAccelDrdy();
|
||||
void waitForMagDrdy();
|
||||
bool getSensorTime(uint32_t *v_sensor_time_u32);
|
||||
void setMagDeviceAddress(uint8_t addr);
|
||||
void setMagRegister(uint8_t addr, uint8_t value);
|
||||
|
||||
bool getErrReg(uint8_t* out);
|
||||
private:
|
||||
uint8_t buffer[14];
|
||||
uint8_t devAddr;
|
||||
};
|
||||
|
||||
#endif /* _BMI160_H_ */
|
||||
@@ -28,9 +28,9 @@
|
||||
|
||||
namespace SlimeVR {
|
||||
void LEDManager::setup() {
|
||||
#if ENABLE_LEDS
|
||||
pinMode(m_Pin, OUTPUT);
|
||||
#endif
|
||||
if (m_Enabled) {
|
||||
pinMode(m_Pin, OUTPUT);
|
||||
}
|
||||
|
||||
// Do the initial pull of the state
|
||||
update();
|
||||
@@ -41,9 +41,9 @@ void LEDManager::on() {
|
||||
return;
|
||||
}
|
||||
|
||||
#if ENABLE_LEDS
|
||||
digitalWrite(m_Pin, LED__ON);
|
||||
#endif
|
||||
if (m_Enabled) {
|
||||
digitalWrite(m_Pin, m_On);
|
||||
}
|
||||
}
|
||||
|
||||
void LEDManager::off() {
|
||||
@@ -51,9 +51,9 @@ void LEDManager::off() {
|
||||
return;
|
||||
}
|
||||
|
||||
#if ENABLE_LEDS
|
||||
digitalWrite(m_Pin, LED__OFF);
|
||||
#endif
|
||||
if (m_Enabled) {
|
||||
digitalWrite(m_Pin, m_Off);
|
||||
}
|
||||
}
|
||||
|
||||
void LEDManager::forceOn() {
|
||||
|
||||
@@ -51,9 +51,6 @@ enum LEDStage { OFF, ON, GAP, INTERVAL };
|
||||
|
||||
class LEDManager {
|
||||
public:
|
||||
LEDManager(uint8_t pin)
|
||||
: m_Pin(pin) {}
|
||||
|
||||
void setup();
|
||||
|
||||
/*!
|
||||
@@ -92,7 +89,10 @@ private:
|
||||
unsigned long m_LastUpdate = millis();
|
||||
bool forcedOn = false;
|
||||
|
||||
uint8_t m_Pin;
|
||||
uint8_t m_Pin = LED_PIN;
|
||||
bool m_Enabled = m_Pin >= 0 && m_Pin < LED_OFF;
|
||||
bool m_On = LED_INVERTED ? LOW : HIGH;
|
||||
bool m_Off = !m_On;
|
||||
|
||||
Logging::Logger m_Logger = Logging::Logger("LEDManager");
|
||||
};
|
||||
|
||||
@@ -52,9 +52,6 @@
|
||||
#endif
|
||||
|
||||
#if BATTERY_MONITOR == BAT_EXTERNAL
|
||||
#ifndef PIN_BATTERY_LEVEL
|
||||
#error Internal ADC enabled without pin! Please select a pin.
|
||||
#endif
|
||||
// Wemos D1 Mini has an internal Voltage Divider with R1=100K and R2=220K > this
|
||||
// means, 3.3V analogRead input voltage results in 1023.0 Wemos D1 Mini with Wemos
|
||||
// Battery Shield v1.2.0 or higher: Battery Shield with J2 closed, has an additional
|
||||
|
||||
176
src/board_default.h
Normal file
176
src/board_default.h
Normal file
@@ -0,0 +1,176 @@
|
||||
/*
|
||||
* LED configuration:
|
||||
* Configuration Priority 1 = Highest:
|
||||
* 1. LED_PIN
|
||||
* 2. LED_BUILTIN
|
||||
*
|
||||
* LED_PIN
|
||||
* - Number or Symbol (D1,..) of the Output
|
||||
* - To turn off the LED, set LED_PIN to LED_OFF
|
||||
* LED_INVERTED
|
||||
* - false for output 3.3V on high
|
||||
* - true for pull down to GND on high
|
||||
*/
|
||||
|
||||
/*
|
||||
* D1 Mini boards with ESP8266 have internal resistors. For these boards you only have
|
||||
* to adjust BATTERY_SHIELD_RESISTANCE. For other boards you can now adjust the other
|
||||
* resistor values. The diagram looks like this:
|
||||
* (Battery)--- [BATTERY_SHIELD_RESISTANCE] ---(INPUT_BOARD)--- [BATTERY_SHIELD_R2]
|
||||
* ---(ESP32_INPUT)--- [BATTERY_SHIELD_R1] --- (GND)
|
||||
* BATTERY_SHIELD_R(180)
|
||||
* 130k BatteryShield, 180k SlimeVR or fill in
|
||||
* external resistor value in kOhm BATTERY_R1(100)
|
||||
* Board voltage divider resistor Ain to GND in kOhm BATTERY_R2(220)
|
||||
* Board voltage divider resistor Ain to INPUT_BOARD in kOhm
|
||||
*/
|
||||
|
||||
#include "defines_helpers.h"
|
||||
|
||||
// Board-specific configurations
|
||||
#if BOARD == BOARD_SLIMEVR
|
||||
|
||||
SDA(14)
|
||||
SCL(12)
|
||||
INT(16)
|
||||
INT2(13)
|
||||
BATTERY(17)
|
||||
LED(2)
|
||||
INVERTED_LED(true)
|
||||
BATTERY_SHIELD_R(0)
|
||||
BATTERY_R1(10)
|
||||
BATTERY_R2(40.2)
|
||||
|
||||
#elif BOARD == BOARD_SLIMEVR_V1_2
|
||||
|
||||
SDA(4)
|
||||
SCL(5)
|
||||
INT(2)
|
||||
INT2(16)
|
||||
BATTERY(17)
|
||||
LED(2)
|
||||
INVERTED_LED(true)
|
||||
BATTERY_SHIELD_R(0)
|
||||
BATTERY_R1(10)
|
||||
BATTERY_R2(40.2)
|
||||
|
||||
#elif BOARD == BOARD_SLIMEVR_LEGACY || BOARD == BOARD_SLIMEVR_DEV
|
||||
|
||||
SDA(4)
|
||||
SCL(5)
|
||||
INT(10)
|
||||
INT2(13)
|
||||
BATTERY(17)
|
||||
LED(2)
|
||||
INVERTED_LED(true)
|
||||
BATTERY_SHIELD_R(0)
|
||||
BATTERY_R1(10)
|
||||
BATTERY_R2(40.2)
|
||||
|
||||
#elif BOARD == BOARD_NODEMCU || BOARD == BOARD_WEMOSD1MINI
|
||||
|
||||
SDA(D2)
|
||||
SCL(D1)
|
||||
INT(D5)
|
||||
INT2(D6)
|
||||
BATTERY(A0)
|
||||
BATTERY_SHIELD_R(180)
|
||||
BATTERY_R1(100)
|
||||
BATTERY_R2(220)
|
||||
|
||||
#elif BOARD == BOARD_ESP01
|
||||
|
||||
SDA(2)
|
||||
SCL(0)
|
||||
INT(255)
|
||||
INT2(255)
|
||||
BATTERY(255)
|
||||
LED(LED_OFF)
|
||||
INVERTED_LED(false)
|
||||
|
||||
#elif BOARD == BOARD_TTGO_TBASE
|
||||
|
||||
SDA(5)
|
||||
SCL(4)
|
||||
INT(14)
|
||||
INT2(13)
|
||||
BATTERY(A0)
|
||||
|
||||
#elif BOARD == BOARD_CUSTOM
|
||||
|
||||
// Define pins by the examples above
|
||||
|
||||
#elif BOARD == BOARD_WROOM32
|
||||
|
||||
SDA(21)
|
||||
SCL(22)
|
||||
INT(23)
|
||||
INT2(25)
|
||||
BATTERY(36)
|
||||
|
||||
#elif BOARD == BOARD_LOLIN_C3_MINI
|
||||
|
||||
SDA(5)
|
||||
SCL(4)
|
||||
INT(6)
|
||||
INT2(8)
|
||||
BATTERY(3)
|
||||
LED(7)
|
||||
|
||||
#elif BOARD == BOARD_BEETLE32C3
|
||||
|
||||
SDA(8)
|
||||
SCL(9)
|
||||
INT(6)
|
||||
INT2(7)
|
||||
BATTERY(3)
|
||||
LED(10)
|
||||
INVERTED_LED(false)
|
||||
|
||||
#elif BOARD == BOARD_ESP32C3DEVKITM1 || BOARD == BOARD_ESP32C6DEVKITC1
|
||||
|
||||
SDA(5)
|
||||
SCL(4)
|
||||
INT(6)
|
||||
INT2(7)
|
||||
BATTERY(3)
|
||||
LED(LED_OFF)
|
||||
|
||||
#elif BOARD == BOARD_WEMOSWROOM02
|
||||
|
||||
SDA(2)
|
||||
SCL(14)
|
||||
INT(0)
|
||||
INT2(4)
|
||||
BATTERY(A0)
|
||||
LED(16)
|
||||
INVERTED_LED(true)
|
||||
|
||||
#elif BOARD == BOARD_XIAO_ESP32C3
|
||||
|
||||
SDA(6)
|
||||
SCL(7) // D5
|
||||
INT(5) // D3
|
||||
INT2(10) // D10
|
||||
LED(4) // D2
|
||||
INVERTED_LED(false)
|
||||
BATTERY(2) // D0 / A0
|
||||
BATTERY_SHIELD_R(0)
|
||||
BATTERY_R1(100)
|
||||
BATTERY_R2(100)
|
||||
|
||||
#elif BOARD == BOARD_GLOVE_IMU_SLIMEVR_DEV
|
||||
|
||||
SDA(1)
|
||||
SCL(0)
|
||||
#define PCA_ADDR 0x70
|
||||
INT(16)
|
||||
INT2(13)
|
||||
BATTERY(3)
|
||||
LED(2)
|
||||
INVERTED_LED(true)
|
||||
BATTERY_SHIELD_R(0)
|
||||
BATTERY_R1(10)
|
||||
BATTERY_R2(40.2)
|
||||
|
||||
#endif
|
||||
@@ -58,7 +58,7 @@ enum class SensorTypeID : uint8_t {
|
||||
#define IMU_BNO055 BNO055Sensor
|
||||
#define IMU_MPU6050 MPU6050Sensor
|
||||
#define IMU_BNO086 BNO086Sensor
|
||||
#define IMU_BMI160 BMI160Sensor
|
||||
#define IMU_BMI160 SoftFusionBMI160
|
||||
#define IMU_ICM20948 ICM20948Sensor
|
||||
#define IMU_ICM42688 SoftFusionICM42688
|
||||
#define IMU_BMI270 SoftFusionBMI270
|
||||
|
||||
198
src/defines.h
198
src/defines.h
@@ -235,191 +235,17 @@ PIN_IMU_SDA, PRIMARY_IMU_OPTIONAL, BMI160_QMC_REMAP) \
|
||||
// BAT_MCP3021 for external ADC connected over I2C
|
||||
#define BATTERY_MONITOR BAT_EXTERNAL
|
||||
|
||||
// BAT_EXTERNAL definition override
|
||||
// D1 Mini boards with ESP8266 have internal resistors. For these boards you only have
|
||||
// to adjust BATTERY_SHIELD_RESISTANCE. For other boards you can now adjust the other
|
||||
// resistor values. The diagram looks like this:
|
||||
// (Battery)--- [BATTERY_SHIELD_RESISTANCE] ---(INPUT_BOARD)--- [BATTERY_SHIELD_R2]
|
||||
// ---(ESP32_INPUT)--- [BATTERY_SHIELD_R1] --- (GND)
|
||||
// #define BATTERY_SHIELD_RESISTANCE 180 //130k BatteryShield, 180k SlimeVR or fill in
|
||||
// external resistor value in kOhm #define BATTERY_SHIELD_R1 100 // Board voltage
|
||||
// divider resistor Ain to GND in kOhm #define BATTERY_SHIELD_R2 220 // Board voltage
|
||||
// divider resistor Ain to INPUT_BOARD in kOhm
|
||||
// --- OVERRIDES FOR DEFAULT PINS
|
||||
|
||||
// LED configuration:
|
||||
// Configuration Priority 1 = Highest:
|
||||
// 1. LED_PIN
|
||||
// 2. LED_BUILTIN
|
||||
//
|
||||
// LED_PIN
|
||||
// - Number or Symbol (D1,..) of the Output
|
||||
// - To turn off the LED, set LED_PIN to LED_OFF
|
||||
// LED_INVERTED
|
||||
// - false for output 3.3V on high
|
||||
// - true for pull down to GND on high
|
||||
// #define PIN_IMU_SDA 14
|
||||
// #define PIN_IMU_SCL 12
|
||||
// #define PIN_IMU_INT 16
|
||||
// #define PIN_IMU_INT_2 13
|
||||
// #define PIN_BATTERY_LEVEL 17
|
||||
// #define LED_PIN 2
|
||||
// #define LED_INVERTED true
|
||||
// #define BATTERY_SHILED_RESISTANCE 0
|
||||
// #define BATTERY_SHIELD_R1 10
|
||||
// #define BATTERY_SHIELD_R2 40.2
|
||||
|
||||
// Board-specific configurations
|
||||
#if BOARD == BOARD_SLIMEVR
|
||||
#define PIN_IMU_SDA 14
|
||||
#define PIN_IMU_SCL 12
|
||||
#define PIN_IMU_INT 16
|
||||
#define PIN_IMU_INT_2 13
|
||||
#define PIN_BATTERY_LEVEL 17
|
||||
#define LED_PIN 2
|
||||
#define LED_INVERTED true
|
||||
#ifndef BATTERY_SHIELD_RESISTANCE
|
||||
#define BATTERY_SHIELD_RESISTANCE 0
|
||||
#endif
|
||||
#ifndef BATTERY_SHIELD_R1
|
||||
#define BATTERY_SHIELD_R1 10
|
||||
#endif
|
||||
#ifndef BATTERY_SHIELD_R2
|
||||
#define BATTERY_SHIELD_R2 40.2
|
||||
#endif
|
||||
#elif BOARD == BOARD_SLIMEVR_V1_2
|
||||
#define PIN_IMU_SDA 4
|
||||
#define PIN_IMU_SCL 5
|
||||
#define PIN_IMU_INT 2
|
||||
#define PIN_IMU_INT_2 16
|
||||
#define PIN_BATTERY_LEVEL 17
|
||||
#define LED_PIN 2
|
||||
#define LED_INVERTED true
|
||||
#ifndef BATTERY_SHIELD_RESISTANCE
|
||||
#define BATTERY_SHIELD_RESISTANCE 0
|
||||
#endif
|
||||
#ifndef BATTERY_SHIELD_R1
|
||||
#define BATTERY_SHIELD_R1 10
|
||||
#endif
|
||||
#ifndef BATTERY_SHIELD_R2
|
||||
#define BATTERY_SHIELD_R2 40.2
|
||||
#endif
|
||||
#elif BOARD == BOARD_SLIMEVR_LEGACY || BOARD == BOARD_SLIMEVR_DEV
|
||||
#define PIN_IMU_SDA 4
|
||||
#define PIN_IMU_SCL 5
|
||||
#define PIN_IMU_INT 10
|
||||
#define PIN_IMU_INT_2 13
|
||||
#define PIN_BATTERY_LEVEL 17
|
||||
#define LED_PIN 2
|
||||
#define LED_INVERTED true
|
||||
#ifndef BATTERY_SHIELD_RESISTANCE
|
||||
#define BATTERY_SHIELD_RESISTANCE 0
|
||||
#endif
|
||||
#ifndef BATTERY_SHIELD_R1
|
||||
#define BATTERY_SHIELD_R1 10
|
||||
#endif
|
||||
#ifndef BATTERY_SHIELD_R2
|
||||
#define BATTERY_SHIELD_R2 40.2
|
||||
#endif
|
||||
#elif BOARD == BOARD_NODEMCU || BOARD == BOARD_WEMOSD1MINI
|
||||
#define PIN_IMU_SDA D2
|
||||
#define PIN_IMU_SCL D1
|
||||
#define PIN_IMU_INT D5
|
||||
#define PIN_IMU_INT_2 D6
|
||||
#define PIN_BATTERY_LEVEL A0
|
||||
// #define LED_PIN 2
|
||||
// #define LED_INVERTED true
|
||||
#ifndef BATTERY_SHIELD_RESISTANCE
|
||||
#define BATTERY_SHIELD_RESISTANCE 180
|
||||
#endif
|
||||
#ifndef BATTERY_SHIELD_R1
|
||||
#define BATTERY_SHIELD_R1 100
|
||||
#endif
|
||||
#ifndef BATTERY_SHIELD_R2
|
||||
#define BATTERY_SHIELD_R2 220
|
||||
#endif
|
||||
#elif BOARD == BOARD_ESP01
|
||||
#define PIN_IMU_SDA 2
|
||||
#define PIN_IMU_SCL 0
|
||||
#define PIN_IMU_INT 255
|
||||
#define PIN_IMU_INT_2 255
|
||||
#define PIN_BATTERY_LEVEL 255
|
||||
#define LED_PIN LED_OFF
|
||||
#define LED_INVERTED false
|
||||
#elif BOARD == BOARD_TTGO_TBASE
|
||||
#define PIN_IMU_SDA 5
|
||||
#define PIN_IMU_SCL 4
|
||||
#define PIN_IMU_INT 14
|
||||
#define PIN_IMU_INT_2 13
|
||||
#define PIN_BATTERY_LEVEL A0
|
||||
// #define LED_PIN 2
|
||||
// #define LED_INVERTED false
|
||||
#elif BOARD == BOARD_CUSTOM
|
||||
// Define pins by the examples above
|
||||
#elif BOARD == BOARD_WROOM32
|
||||
#define PIN_IMU_SDA 21
|
||||
#define PIN_IMU_SCL 22
|
||||
#define PIN_IMU_INT 23
|
||||
#define PIN_IMU_INT_2 25
|
||||
#define PIN_BATTERY_LEVEL 36
|
||||
// #define LED_PIN 2
|
||||
// #define LED_INVERTED false
|
||||
#elif BOARD == BOARD_LOLIN_C3_MINI
|
||||
#define PIN_IMU_SDA 5
|
||||
#define PIN_IMU_SCL 4
|
||||
#define PIN_IMU_INT 6
|
||||
#define PIN_IMU_INT_2 8
|
||||
#define PIN_BATTERY_LEVEL 3
|
||||
#define LED_PIN 7
|
||||
// #define LED_INVERTED false
|
||||
#elif BOARD == BOARD_BEETLE32C3
|
||||
#define PIN_IMU_SDA 8
|
||||
#define PIN_IMU_SCL 9
|
||||
#define PIN_IMU_INT 6
|
||||
#define PIN_IMU_INT_2 7
|
||||
#define PIN_BATTERY_LEVEL 3
|
||||
#define LED_PIN 10
|
||||
#define LED_INVERTED false
|
||||
#elif BOARD == BOARD_ESP32C3DEVKITM1 || BOARD == BOARD_ESP32C6DEVKITC1
|
||||
#define PIN_IMU_SDA 5
|
||||
#define PIN_IMU_SCL 4
|
||||
#define PIN_IMU_INT 6
|
||||
#define PIN_IMU_INT_2 7
|
||||
#define PIN_BATTERY_LEVEL 3
|
||||
#define LED_PIN \
|
||||
LED_OFF // RGB LED Protocol would need to be implementetet did not brother for the
|
||||
// test, because the board ideal for tracker ifself
|
||||
// #define LED_INVERTED false
|
||||
#elif BOARD == BOARD_WEMOSWROOM02
|
||||
#define PIN_IMU_SDA 2
|
||||
#define PIN_IMU_SCL 14
|
||||
#define PIN_IMU_INT 0
|
||||
#define PIN_IMU_INT_2 4
|
||||
#define PIN_BATTERY_LEVEL A0
|
||||
#define LED_PIN 16
|
||||
#define LED_INVERTED true
|
||||
#elif BOARD == BOARD_XIAO_ESP32C3
|
||||
#define PIN_IMU_SDA 6 // D4
|
||||
#define PIN_IMU_SCL 7 // D5
|
||||
#define PIN_IMU_INT 5 // D3
|
||||
#define PIN_IMU_INT_2 10 // D10
|
||||
#define LED_PIN 4 // D2
|
||||
#define LED_INVERTED false
|
||||
#define PIN_BATTERY_LEVEL 2 // D0 / A0
|
||||
#ifndef BATTERY_SHIELD_RESISTANCE
|
||||
#define BATTERY_SHIELD_RESISTANCE 0
|
||||
#endif
|
||||
#ifndef BATTERY_SHIELD_R1
|
||||
#define BATTERY_SHIELD_R1 100
|
||||
#endif
|
||||
#ifndef BATTERY_SHIELD_R2
|
||||
#define BATTERY_SHIELD_R2 100
|
||||
#endif
|
||||
#elif BOARD == BOARD_GLOVE_IMU_SLIMEVR_DEV
|
||||
#define PIN_IMU_SDA 1
|
||||
#define PIN_IMU_SCL 0
|
||||
#define PCA_ADDR 0x70
|
||||
#define PIN_IMU_INT 16
|
||||
#define PIN_IMU_INT_2 13
|
||||
#define PIN_BATTERY_LEVEL 3
|
||||
#define LED_PIN 2
|
||||
#define LED_INVERTED true
|
||||
#ifndef BATTERY_SHIELD_RESISTANCE
|
||||
#define BATTERY_SHIELD_RESISTANCE 0
|
||||
#endif
|
||||
#ifndef BATTERY_SHIELD_R1
|
||||
#define BATTERY_SHIELD_R1 10
|
||||
#endif
|
||||
#ifndef BATTERY_SHIELD_R2
|
||||
#define BATTERY_SHIELD_R2 40.2
|
||||
#endif
|
||||
#endif
|
||||
// ------------------------------
|
||||
|
||||
@@ -1,73 +0,0 @@
|
||||
/*
|
||||
SlimeVR Code is placed under the MIT license
|
||||
Copyright (c) 2022 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 BMI160_DEFINES_H
|
||||
#define BMI160_DEFINES_H
|
||||
|
||||
// BMI160 magnetometer type, applies to both main and aux trackers, mixed types are not
|
||||
// supported currently. If only 1 out of 2 trackers has a mag, tracker without a mag
|
||||
// should still function normally. NOT USED if USE_6_AXIS == true Pick one:
|
||||
#define BMI160_MAG_TYPE BMI160_MAG_TYPE_HMC
|
||||
// #define BMI160_MAG_TYPE BMI160_MAG_TYPE_QMC
|
||||
|
||||
// Use VQF instead of mahony sensor fusion.
|
||||
// Features: rest bias estimation, magnetic distortion rejection.
|
||||
#define BMI160_USE_VQF true
|
||||
|
||||
// Use BasicVQF instead of VQF (if BMI160_USE_VQF == true).
|
||||
// Disables the features above.
|
||||
#define BMI160_USE_BASIC_VQF false
|
||||
|
||||
// Use temperature calibration.
|
||||
#define BMI160_USE_TEMPCAL true
|
||||
|
||||
// How long to run gyro calibration for.
|
||||
// Disables this calibration step if value is 0.
|
||||
// Default: 5
|
||||
#define BMI160_CALIBRATION_GYRO_SECONDS 5
|
||||
|
||||
// Calibration method options:
|
||||
// - Skip: disable this calibration step;
|
||||
// - Rotation: rotate the device in hand;
|
||||
// - 6 point: put the device in 6 unique orientations.
|
||||
// Default: ACCEL_CALIBRATION_METHOD_6POINT
|
||||
// #define BMI160_ACCEL_CALIBRATION_METHOD ACCEL_CALIBRATION_METHOD_SKIP
|
||||
// #define BMI160_ACCEL_CALIBRATION_METHOD ACCEL_CALIBRATION_METHOD_ROTATION
|
||||
#define BMI160_ACCEL_CALIBRATION_METHOD ACCEL_CALIBRATION_METHOD_6POINT
|
||||
|
||||
// How long to run magnetometer calibration for, if enabled and you have added a
|
||||
// magnetometer. Magnetometer not be used until you calibrate it. Disables this
|
||||
// calibration step if value is 0. NOT USED if USE_6_AXIS == true Default: 20
|
||||
#define BMI160_CALIBRATION_MAG_SECONDS 20
|
||||
|
||||
// Send temperature to the server as AXXYY,
|
||||
// where XX is calibration progress from 0 to 60, and YY is temperature,
|
||||
// A is 1: not in calibration mode or 2: calibration in progress.
|
||||
#define BMI160_TEMPCAL_DEBUG false
|
||||
|
||||
// Print debug info every second.
|
||||
#define BMI160_DEBUG false
|
||||
|
||||
// Use sensitivity calibration.
|
||||
#define BMI160_USE_SENSCAL true
|
||||
|
||||
#endif
|
||||
33
src/defines_helpers.cpp
Normal file
33
src/defines_helpers.cpp
Normal file
@@ -0,0 +1,33 @@
|
||||
/*
|
||||
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 "defines_helpers.h"
|
||||
|
||||
#include "consts.h"
|
||||
|
||||
#ifndef LED_BUILTIN
|
||||
#define LED_BUILTIN LED_OFF
|
||||
#endif
|
||||
|
||||
extern const uint8_t __attribute__((weak)) LED_PIN = LED_BUILTIN;
|
||||
extern const bool __attribute__((weak)) LED_INVERTED = true;
|
||||
92
src/defines_helpers.h
Normal file
92
src/defines_helpers.h
Normal file
@@ -0,0 +1,92 @@
|
||||
/*
|
||||
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 <cstdint>
|
||||
|
||||
#include "pins_arduino.h"
|
||||
|
||||
#ifndef PIN_IMU_SDA
|
||||
#define SDA(pin) constexpr uint8_t PIN_IMU_SDA = pin;
|
||||
#else
|
||||
#define SDA(pin)
|
||||
#endif
|
||||
|
||||
#ifndef PIN_IMU_SCL
|
||||
#define SCL(pin) constexpr uint8_t PIN_IMU_SCL = pin;
|
||||
#else
|
||||
#define SCL(pin)
|
||||
#endif
|
||||
|
||||
#ifndef PIN_IMU_INT
|
||||
#define INT(pin) constexpr uint8_t PIN_IMU_INT = pin;
|
||||
#else
|
||||
#define INT(pin)
|
||||
#endif
|
||||
|
||||
#ifndef PIN_IMU_INT_2
|
||||
#define INT2(pin) constexpr uint8_t PIN_IMU_INT_2 = pin;
|
||||
#else
|
||||
#define INT2(pin)
|
||||
#endif
|
||||
|
||||
#ifndef PIN_BATTERY_LEVEL
|
||||
#define BATTERY(pin) constexpr uint8_t PIN_BATTERY_LEVEL = pin;
|
||||
#else
|
||||
#define BATTERY(pin)
|
||||
#endif
|
||||
|
||||
#ifndef LED_PIN
|
||||
#define LED(pin) const uint8_t LED_PIN = pin;
|
||||
#else
|
||||
#define LED(pin)
|
||||
#endif
|
||||
|
||||
extern const bool __attribute__((weak)) LED_INVERTED;
|
||||
|
||||
#ifndef BATTERY_SHIELD_RESISTANCE
|
||||
#define BATTERY_SHIELD_R(value) constexpr float BATTERY_SHIELD_RESISTANCE = value;
|
||||
#else
|
||||
#define BATTERY_SHIELD_R(value)
|
||||
#endif
|
||||
|
||||
#ifndef BATTERY_SHIELD_R1
|
||||
#define BATTERY_R1(value) constexpr float BATTERY_SHIELD_R1 = value;
|
||||
#else
|
||||
#define BATTERY_R1(value)
|
||||
#endif
|
||||
|
||||
#ifndef BATTERY_SHIELD_R2
|
||||
#define BATTERY_R2(value) constexpr float BATTERY_SHIELD_R2 = value;
|
||||
#else
|
||||
#define BATTERY_R2(value)
|
||||
#endif
|
||||
|
||||
#ifndef LED_INVERTED
|
||||
#define INVERTED_LED(value) const bool LED_INVERTED = value;
|
||||
#else
|
||||
#define INVERTED_LED(value)
|
||||
#endif
|
||||
|
||||
extern const uint8_t __attribute__((weak)) LED_PIN;
|
||||
@@ -1,92 +0,0 @@
|
||||
/*
|
||||
SlimeVR Code is placed under the MIT license
|
||||
Copyright (c) 2022 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 DEFINES_SENSITIVITY_H
|
||||
#define DEFINES_SENSITIVITY_H
|
||||
|
||||
// ==========================
|
||||
// Sensitivity calibration
|
||||
// Only for: BMI160
|
||||
// ==========================
|
||||
|
||||
// This type of calibration attempts to reduce "extra degrees measures",
|
||||
// useful if you do 360 spins
|
||||
|
||||
// Trackers are identified by sensor id and MAC address of the device,
|
||||
// which is displayed in serial when you upload firmware
|
||||
|
||||
// Number of spins determines calibration accuracy
|
||||
|
||||
// 1. Put the axis you want to calibrate vertically
|
||||
// 2. Put the tracker into an orientation that you can repeat later
|
||||
// 3. Do a full reset, rotation must now be 0 0 0
|
||||
// 4. Spin the tracker clockwise <.spins> times around the axis
|
||||
// 5. Put the tracker back into the reset position
|
||||
// 6. Write down the resulting Y (yaw) value into the table below
|
||||
// Reflash, do the same rotation and check if the resulting angle is now 0
|
||||
|
||||
#define SENSORID_PRIMARY 0
|
||||
#define SENSORID_AUX 1
|
||||
struct SensitivityOffsetXYZ {
|
||||
const char* mac;
|
||||
unsigned char sensorId;
|
||||
double spins;
|
||||
double x;
|
||||
double y;
|
||||
double z;
|
||||
};
|
||||
const SensitivityOffsetXYZ sensitivityOffsets[] = {
|
||||
// example values
|
||||
{.mac = "A4:E5:7C:B6:00:01",
|
||||
.sensorId = SENSORID_PRIMARY,
|
||||
.spins = 10,
|
||||
.x = 2.63,
|
||||
.y = 37.82,
|
||||
.z = 31.11},
|
||||
{.mac = "A4:E5:7C:B6:00:02",
|
||||
.sensorId = SENSORID_PRIMARY,
|
||||
.spins = 10,
|
||||
.x = -2.38,
|
||||
.y = -26.8,
|
||||
.z = -42.78},
|
||||
{.mac = "A4:E5:7C:B6:00:03",
|
||||
.sensorId = SENSORID_PRIMARY,
|
||||
.spins = 10,
|
||||
.x = 11,
|
||||
.y = 2.2,
|
||||
.z = -1},
|
||||
{.mac = "A4:E5:7C:B6:00:04",
|
||||
.sensorId = SENSORID_PRIMARY,
|
||||
.spins = 10,
|
||||
.x = -7,
|
||||
.y = -53.7,
|
||||
.z = -57},
|
||||
{.mac = "A4:E5:7C:B6:00:05",
|
||||
.sensorId = SENSORID_PRIMARY,
|
||||
.spins = 10,
|
||||
.x = -10.63,
|
||||
.y = -8.25,
|
||||
.z = -18.6},
|
||||
};
|
||||
|
||||
#endif
|
||||
@@ -28,8 +28,10 @@
|
||||
#include "consts.h"
|
||||
#include "debug.h"
|
||||
#include "defines.h"
|
||||
#include "defines_bmi160.h"
|
||||
#include "defines_sensitivity.h"
|
||||
|
||||
// clang-format off
|
||||
#include "board_default.h"
|
||||
// clang-format on
|
||||
|
||||
#ifndef SECOND_IMU
|
||||
#define SECOND_IMU IMU
|
||||
@@ -43,39 +45,6 @@
|
||||
#define BATTERY_MONITOR BAT_INTERNAL
|
||||
#endif
|
||||
|
||||
// If LED_PIN is not defined in "defines.h" take the default pin from "pins_arduino.h"
|
||||
// framework. If there is no pin defined for the board, use LED_PIN 255 and disable LED
|
||||
#if defined(LED_PIN)
|
||||
// LED_PIN is defined
|
||||
#if (LED_PIN < 0) || (LED_PIN >= LED_OFF)
|
||||
#define ENABLE_LEDS false
|
||||
#else
|
||||
#define ENABLE_LEDS true
|
||||
#endif
|
||||
#else
|
||||
// LED_PIN is not defined
|
||||
#if defined(LED_BUILTIN) && (LED_BUILTIN < LED_OFF) && (LED_BUILTIN >= 0)
|
||||
#define LED_PIN LED_BUILTIN
|
||||
#define ENABLE_LEDS true
|
||||
#else
|
||||
#define LED_PIN LED_OFF
|
||||
#define ENABLE_LEDS false
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#if !defined(LED_INVERTED)
|
||||
// default is inverted for SlimeVR / ESP-12E
|
||||
#define LED_INVERTED true
|
||||
#endif
|
||||
|
||||
#if LED_INVERTED
|
||||
#define LED__ON LOW
|
||||
#define LED__OFF HIGH
|
||||
#else
|
||||
#define LED__ON HIGH
|
||||
#define LED__OFF LOW
|
||||
#endif
|
||||
|
||||
#ifndef SENSOR_INFO_LIST
|
||||
#define SENSOR_INFO_LIST
|
||||
#endif
|
||||
|
||||
@@ -37,7 +37,7 @@
|
||||
Timer<> globalTimer;
|
||||
SlimeVR::Logging::Logger logger("SlimeVR");
|
||||
SlimeVR::Sensors::SensorManager sensorManager;
|
||||
SlimeVR::LEDManager ledManager(LED_PIN);
|
||||
SlimeVR::LEDManager ledManager;
|
||||
SlimeVR::Status::StatusManager statusManager;
|
||||
SlimeVR::Configuration::Configuration configuration;
|
||||
SlimeVR::Network::Manager networkManager;
|
||||
|
||||
@@ -30,7 +30,6 @@
|
||||
#include "EmptySensor.h"
|
||||
#include "ErroneousSensor.h"
|
||||
#include "SensorManager.h"
|
||||
#include "bmi160sensor.h"
|
||||
#include "bno055sensor.h"
|
||||
#include "bno080sensor.h"
|
||||
#include "globals.h"
|
||||
@@ -47,6 +46,7 @@
|
||||
#include "sensorinterface/SPIImpl.h"
|
||||
#include "sensorinterface/SensorInterfaceManager.h"
|
||||
#include "sensorinterface/i2cimpl.h"
|
||||
#include "softfusion/drivers/bmi160.h"
|
||||
#include "softfusion/drivers/bmi270.h"
|
||||
#include "softfusion/drivers/icm42688.h"
|
||||
#include "softfusion/drivers/icm45605.h"
|
||||
@@ -92,6 +92,7 @@ using SoftFusionICM45686
|
||||
= SoftFusionSensor<SoftFusion::Drivers::ICM45686, SFCALIBRATOR>;
|
||||
using SoftFusionICM45605
|
||||
= SoftFusionSensor<SoftFusion::Drivers::ICM45605, SFCALIBRATOR>;
|
||||
using SoftFusionBMI160 = SoftFusionSensor<SoftFusion::Drivers::BMI160, SFCALIBRATOR>;
|
||||
class SensorAuto {};
|
||||
|
||||
struct SensorBuilder {
|
||||
|
||||
File diff suppressed because it is too large
Load Diff
@@ -1,272 +0,0 @@
|
||||
/*
|
||||
SlimeVR Code is placed under the MIT license
|
||||
Copyright (c) 2022 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 SENSORS_BMI160SENSOR_H
|
||||
#define SENSORS_BMI160SENSOR_H
|
||||
|
||||
#include <BMI160.h>
|
||||
|
||||
#include "../motionprocessing/GyroTemperatureCalibrator.h"
|
||||
#include "../motionprocessing/RestDetection.h"
|
||||
#include "../motionprocessing/types.h"
|
||||
#include "RestCalibrationDetector.h"
|
||||
#include "SensorFusionRestDetect.h"
|
||||
#include "magneto1.4.h"
|
||||
#include "sensor.h"
|
||||
#include "sensors/axisremap.h"
|
||||
|
||||
#if BMI160_USE_VQF
|
||||
#if USE_6_AXIS
|
||||
#define BMI160_GYRO_RATE BMI160_GYRO_RATE_400HZ
|
||||
#else
|
||||
#define BMI160_GYRO_RATE BMI160_GYRO_RATE_200HZ
|
||||
#endif
|
||||
#else
|
||||
#if USE_6_AXIS
|
||||
#define BMI160_GYRO_RATE BMI160_GYRO_RATE_800HZ
|
||||
#else
|
||||
#define BMI160_GYRO_RATE BMI160_GYRO_RATE_400HZ
|
||||
#endif
|
||||
#endif
|
||||
#define BMI160_GYRO_RANGE BMI160_GYRO_RANGE_1000
|
||||
#define BMI160_GYRO_FILTER_MODE BMI160_DLPF_MODE_NORM
|
||||
|
||||
#define BMI160_ACCEL_RATE BMI160_ACCEL_RATE_100HZ
|
||||
#define BMI160_ACCEL_RANGE BMI160_ACCEL_RANGE_4G
|
||||
#define BMI160_ACCEL_FILTER_MODE BMI160_DLPF_MODE_NORM
|
||||
|
||||
// note: if changing ODR or filter modes - adjust rest detection params and buffer size
|
||||
|
||||
#define BMI160_TIMESTAMP_RESOLUTION_MICROS 39.0625f
|
||||
// #define BMI160_TIMESTAMP_RESOLUTION_MICROS 39.0f
|
||||
#define BMI160_MAP_ODR_MICROS(micros) \
|
||||
((uint16_t)((micros) / BMI160_TIMESTAMP_RESOLUTION_MICROS) \
|
||||
* BMI160_TIMESTAMP_RESOLUTION_MICROS)
|
||||
constexpr float BMI160_ODR_GYR_HZ = 25.0f * (1 << (BMI160_GYRO_RATE - 6));
|
||||
constexpr float BMI160_ODR_ACC_HZ = 12.5f * (1 << (BMI160_ACCEL_RATE - 5));
|
||||
constexpr float BMI160_ODR_GYR_MICROS
|
||||
= BMI160_MAP_ODR_MICROS(1.0f / BMI160_ODR_GYR_HZ * 1e6f);
|
||||
constexpr float BMI160_ODR_ACC_MICROS
|
||||
= BMI160_MAP_ODR_MICROS(1.0f / BMI160_ODR_ACC_HZ * 1e6f);
|
||||
#if !USE_6_AXIS
|
||||
// note: this value only sets polling and fusion update rate - HMC is internally sampled
|
||||
// at 75hz, QMC at 200hz
|
||||
#define BMI160_MAG_RATE BMI160_MAG_RATE_50HZ
|
||||
constexpr float BMI160_ODR_MAG_HZ = (25.0f / 32.0f) * (1 << (BMI160_MAG_RATE - 1));
|
||||
constexpr float BMI160_ODR_MAG_MICROS
|
||||
= BMI160_MAP_ODR_MICROS(1.0f / BMI160_ODR_MAG_HZ * 1e6f);
|
||||
#else
|
||||
constexpr float BMI160_ODR_MAG_HZ = 0;
|
||||
constexpr float BMI160_ODR_MAG_MICROS = 0;
|
||||
#endif
|
||||
|
||||
constexpr uint16_t BMI160_SETTINGS_MAX_ODR_HZ
|
||||
= max(max(BMI160_ODR_GYR_HZ, BMI160_ODR_ACC_HZ), BMI160_ODR_MAG_HZ);
|
||||
constexpr uint16_t BMI160_SETTINGS_MAX_ODR_MICROS
|
||||
= BMI160_MAP_ODR_MICROS(1.0f / BMI160_SETTINGS_MAX_ODR_HZ * 1e6f);
|
||||
|
||||
constexpr float BMI160_FIFO_AVG_DATA_FRAME_LENGTH
|
||||
= (BMI160_SETTINGS_MAX_ODR_HZ * 1 + BMI160_ODR_GYR_HZ * BMI160_FIFO_G_LEN
|
||||
+ BMI160_ODR_ACC_HZ * BMI160_FIFO_A_LEN + BMI160_ODR_MAG_HZ * BMI160_FIFO_M_LEN)
|
||||
/ BMI160_SETTINGS_MAX_ODR_HZ;
|
||||
constexpr float BMI160_FIFO_READ_BUFFER_SIZE_MICROS = 30000;
|
||||
constexpr float BMI160_FIFO_READ_BUFFER_SIZE_SAMPLES
|
||||
= BMI160_SETTINGS_MAX_ODR_HZ * BMI160_FIFO_READ_BUFFER_SIZE_MICROS / 1e6f;
|
||||
constexpr uint16_t BMI160_FIFO_MAX_LENGTH = 1024;
|
||||
constexpr uint16_t BMI160_FIFO_READ_BUFFER_SIZE_BYTES = min(
|
||||
(float)BMI160_FIFO_MAX_LENGTH - 64,
|
||||
BMI160_FIFO_READ_BUFFER_SIZE_SAMPLES* BMI160_FIFO_AVG_DATA_FRAME_LENGTH * 1.25f
|
||||
);
|
||||
|
||||
// Typical sensitivity at 25C
|
||||
// See p. 9 of https://www.mouser.com/datasheet/2/783/BST-BMI160-DS000-1509569.pdf
|
||||
// #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 262.4f // 125 deg 4
|
||||
constexpr double BMI160_GYRO_TYPICAL_SENSITIVITY_LSB
|
||||
= (16.4f * (1 << BMI160_GYRO_RANGE));
|
||||
|
||||
constexpr std::pair<uint8_t, float> BMI160_ACCEL_SENSITIVITY_LSB_MAP[]
|
||||
= {{BMI160_ACCEL_RANGE_2G, 16384.0f},
|
||||
{BMI160_ACCEL_RANGE_4G, 8192.0f},
|
||||
{BMI160_ACCEL_RANGE_8G, 4096.0f},
|
||||
{BMI160_ACCEL_RANGE_16G, 2048.0f}};
|
||||
constexpr double BMI160_ACCEL_TYPICAL_SENSITIVITY_LSB
|
||||
= BMI160_ACCEL_SENSITIVITY_LSB_MAP[BMI160_ACCEL_RANGE / 4].second;
|
||||
constexpr double BMI160_ASCALE
|
||||
= CONST_EARTH_GRAVITY / BMI160_ACCEL_TYPICAL_SENSITIVITY_LSB;
|
||||
|
||||
// Scale conversion steps: LSB/°/s -> °/s -> step/°/s -> step/rad/s
|
||||
constexpr double BMI160_GSCALE
|
||||
= ((32768. / BMI160_GYRO_TYPICAL_SENSITIVITY_LSB) / 32768.) * (PI / 180.0);
|
||||
|
||||
constexpr float targetSampleRateMs = 10.0f;
|
||||
constexpr uint32_t targetSampleRateMicros = (uint32_t)targetSampleRateMs * 1e3;
|
||||
|
||||
constexpr uint32_t BMI160_TEMP_CALIBRATION_REQUIRED_SAMPLES_PER_STEP
|
||||
= TEMP_CALIBRATION_SECONDS_PER_STEP / (BMI160_ODR_GYR_MICROS / 1e6);
|
||||
static_assert(
|
||||
0x7FFF * BMI160_TEMP_CALIBRATION_REQUIRED_SAMPLES_PER_STEP < 0x7FFFFFFF,
|
||||
"Temperature calibration sum overflow"
|
||||
);
|
||||
|
||||
class BMI160Sensor : public Sensor {
|
||||
public:
|
||||
static constexpr uint8_t Address = 0x68;
|
||||
static constexpr auto TypeID = SensorTypeID::BMI160;
|
||||
|
||||
BMI160Sensor(
|
||||
uint8_t id,
|
||||
SlimeVR::Sensors::RegisterInterface& registerInterface,
|
||||
float rotation,
|
||||
SlimeVR::SensorInterface* sensorInterface,
|
||||
PinInterface*,
|
||||
int axisRemapParam
|
||||
)
|
||||
: Sensor(
|
||||
"BMI160Sensor",
|
||||
SensorTypeID::BMI160,
|
||||
id,
|
||||
registerInterface,
|
||||
rotation,
|
||||
sensorInterface
|
||||
)
|
||||
, sfusion(
|
||||
BMI160_ODR_GYR_MICROS / 1e6f,
|
||||
BMI160_ODR_ACC_MICROS / 1e6f,
|
||||
BMI160_ODR_MAG_MICROS / 1e6f
|
||||
) {
|
||||
if (axisRemapParam < 256) {
|
||||
axisRemap = AXIS_REMAP_DEFAULT;
|
||||
} else {
|
||||
axisRemap = axisRemapParam;
|
||||
}
|
||||
};
|
||||
~BMI160Sensor(){};
|
||||
void initHMC(BMI160MagRate magRate);
|
||||
void initQMC(BMI160MagRate magRate);
|
||||
|
||||
void motionSetup() override final;
|
||||
void motionLoop() override final;
|
||||
void startCalibration(int calibrationType) override final;
|
||||
void maybeCalibrateGyro();
|
||||
void maybeCalibrateAccel();
|
||||
void maybeCalibrateMag();
|
||||
|
||||
void printTemperatureCalibrationState() override final;
|
||||
void printDebugTemperatureCalibrationState() override final;
|
||||
void resetTemperatureCalibrationState() override final {
|
||||
gyroTempCalibrator->reset();
|
||||
m_Logger.info(
|
||||
"Temperature calibration state has been reset for sensorId:%i",
|
||||
sensorId
|
||||
);
|
||||
};
|
||||
void saveTemperatureCalibration() override final;
|
||||
|
||||
void applyAccelCalibrationAndScale(sensor_real_t Axyz[3]);
|
||||
void applyMagCalibrationAndScale(sensor_real_t Mxyz[3]);
|
||||
|
||||
bool hasGyroCalibration();
|
||||
bool hasAccelCalibration();
|
||||
bool hasMagCalibration();
|
||||
|
||||
void onGyroRawSample(uint32_t dtMicros, int16_t x, int16_t y, int16_t z);
|
||||
void onAccelRawSample(uint32_t dtMicros, int16_t x, int16_t y, int16_t z);
|
||||
void onMagRawSample(uint32_t dtMicros, int16_t x, int16_t y, int16_t z);
|
||||
void readFIFO();
|
||||
|
||||
void
|
||||
getMagnetometerXYZFromBuffer(uint8_t* data, int16_t* x, int16_t* y, int16_t* z);
|
||||
|
||||
void remapGyroAccel(sensor_real_t* x, sensor_real_t* y, sensor_real_t* z);
|
||||
void remapMagnetometer(sensor_real_t* x, sensor_real_t* y, sensor_real_t* z);
|
||||
void getRemappedRotation(int16_t* x, int16_t* y, int16_t* z);
|
||||
void getRemappedAcceleration(int16_t* x, int16_t* y, int16_t* z);
|
||||
|
||||
bool getTemperature(float* out);
|
||||
|
||||
private:
|
||||
BMI160 imu{};
|
||||
int axisRemap;
|
||||
|
||||
SlimeVR::Sensors::SensorFusionRestDetect sfusion;
|
||||
|
||||
// clock sync and sample timestamping
|
||||
uint32_t sensorTime0 = 0;
|
||||
uint32_t sensorTime1 = 0;
|
||||
uint32_t localTime0 = 0;
|
||||
uint32_t localTime1 = 0;
|
||||
double sensorTimeRatio = 1;
|
||||
double sensorTimeRatioEma = 1;
|
||||
double sampleDtMicros = BMI160_ODR_GYR_MICROS;
|
||||
uint32_t syncLatencyMicros = 0;
|
||||
uint32_t samplesSinceClockSync = 0;
|
||||
uint32_t timestamp0 = 0;
|
||||
uint32_t timestamp1 = 0;
|
||||
|
||||
// scheduling
|
||||
uint32_t lastPollTime = micros();
|
||||
uint32_t lastClockPollTime = micros();
|
||||
#if BMI160_DEBUG
|
||||
uint32_t cpuUsageMicros = 0;
|
||||
uint32_t lastCpuUsagePrinted = 0;
|
||||
uint32_t gyrReads = 0;
|
||||
uint32_t accReads = 0;
|
||||
uint32_t magReads = 0;
|
||||
uint16_t numFIFODropped = 0;
|
||||
uint16_t numFIFOFailedReads = 0;
|
||||
#endif
|
||||
|
||||
uint32_t lastRotationPacketSent = 0;
|
||||
uint32_t lastTemperaturePacketSent = 0;
|
||||
|
||||
struct BMI160FIFO {
|
||||
uint8_t data[BMI160_FIFO_READ_BUFFER_SIZE_BYTES];
|
||||
uint16_t length;
|
||||
} fifo{};
|
||||
float temperature = 0;
|
||||
GyroTemperatureCalibrator* gyroTempCalibrator = nullptr;
|
||||
sensor_real_t Gxyz[3] = {0};
|
||||
sensor_real_t Axyz[3] = {0};
|
||||
sensor_real_t Mxyz[3] = {0};
|
||||
sensor_real_t lastAxyz[3] = {0};
|
||||
|
||||
double gscaleX = BMI160_GSCALE;
|
||||
double gscaleY = BMI160_GSCALE;
|
||||
double gscaleZ = BMI160_GSCALE;
|
||||
|
||||
double GOxyzStaticTempCompensated[3] = {0.0, 0.0, 0.0};
|
||||
|
||||
bool isGyroCalibrated = false;
|
||||
bool isAccelCalibrated = false;
|
||||
bool isMagCalibrated = false;
|
||||
|
||||
SlimeVR::Configuration::BMI160SensorConfig m_Config = {};
|
||||
|
||||
SlimeVR::Sensors::RestCalibrationDetector calibrationDetector;
|
||||
};
|
||||
|
||||
#endif
|
||||
235
src/sensors/softfusion/drivers/bmi160.h
Normal file
235
src/sensors/softfusion/drivers/bmi160.h
Normal file
@@ -0,0 +1,235 @@
|
||||
/*
|
||||
SlimeVR Code is placed under the MIT license
|
||||
Copyright (c) 2025 kounocom & 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 <algorithm>
|
||||
#include <array>
|
||||
#include <cstdint>
|
||||
#include <cstring>
|
||||
#include <limits>
|
||||
|
||||
#include "../../../sensorinterface/RegisterInterface.h"
|
||||
#include "vqf.h"
|
||||
|
||||
namespace SlimeVR::Sensors::SoftFusion::Drivers {
|
||||
|
||||
// Driver uses acceleration range at 4G
|
||||
// and gyroscope range at 1000DPS
|
||||
// Gyroscope ODR = 400Hz, accel ODR = 100Hz
|
||||
// Timestamps reading are not used
|
||||
|
||||
// Sensorhub to be implemented
|
||||
|
||||
struct BMI160 {
|
||||
static constexpr uint8_t Address = 0x68;
|
||||
static constexpr auto Name = "BMI160";
|
||||
static constexpr auto Type = SensorTypeID::BMI160;
|
||||
|
||||
static constexpr float GyrTs = 1.0 / 400.0;
|
||||
static constexpr float AccTs = 1.0 / 100.0;
|
||||
|
||||
static constexpr float MagTs = 1.0 / 100;
|
||||
|
||||
static constexpr float GyroSensitivity = 32.768f;
|
||||
static constexpr float AccelSensitivity = 8192.0f;
|
||||
|
||||
static constexpr float TemperatureZROChange
|
||||
= 2.0f; // wow maybe BMI270 isn't that bad actually
|
||||
|
||||
static constexpr VQFParams SensorVQFParams{
|
||||
// need to be refined, this IMU sucks
|
||||
.motionBiasEstEnabled = true,
|
||||
.biasSigmaInit = 0.5f,
|
||||
.biasClip = 2.0f,
|
||||
.restThGyr = 0.5f,
|
||||
.restThAcc = 0.196f,
|
||||
};
|
||||
|
||||
RegisterInterface& m_RegisterInterface;
|
||||
SlimeVR::Logging::Logger& m_Logger;
|
||||
|
||||
BMI160(RegisterInterface& registerInterface, SlimeVR::Logging::Logger& logger)
|
||||
: m_RegisterInterface(registerInterface)
|
||||
, m_Logger(logger) {}
|
||||
|
||||
struct Regs {
|
||||
struct WhoAmI {
|
||||
static constexpr uint8_t reg = 0x00;
|
||||
static constexpr uint8_t value = 0xD1;
|
||||
};
|
||||
static constexpr uint8_t TempData = 0x20;
|
||||
|
||||
struct Cmd {
|
||||
static constexpr uint8_t reg = 0x7E;
|
||||
static constexpr uint8_t valueSoftReset = 0xB6;
|
||||
static constexpr uint8_t valueFifoFlush = 0xB0;
|
||||
static constexpr uint8_t valueAccPowerNormal = 0x11;
|
||||
static constexpr uint8_t valueGyrPowerNormal = 0x15;
|
||||
};
|
||||
|
||||
struct AccelConf {
|
||||
static constexpr uint8_t reg = 0x40;
|
||||
static constexpr uint8_t value = 0b0101000; // 100Hz, filter mode normal
|
||||
};
|
||||
|
||||
struct AccelRange {
|
||||
static constexpr uint8_t reg = 0x41;
|
||||
static constexpr uint8_t value = 0b0101; // 4G range
|
||||
};
|
||||
|
||||
struct GyrConf {
|
||||
static constexpr uint8_t reg = 0x42;
|
||||
static constexpr uint8_t value = 0b0101010; // 400Hz, filter mode normal
|
||||
};
|
||||
|
||||
struct GyrRange {
|
||||
static constexpr uint8_t reg = 0x43;
|
||||
static constexpr uint8_t value = 0b001; // 1000 DPS range
|
||||
};
|
||||
|
||||
struct FifoConfig {
|
||||
static constexpr uint8_t reg = 0x47;
|
||||
static constexpr uint8_t value
|
||||
= 0b11010000; // Gyro and accel data in FIFO, enable FIFO header
|
||||
};
|
||||
|
||||
static constexpr uint8_t FifoLength = 0x22;
|
||||
static constexpr uint8_t FifoData = 0x24;
|
||||
static constexpr uint8_t ErrReg = 0x02;
|
||||
};
|
||||
|
||||
struct Fifo {
|
||||
static constexpr uint8_t ModeMask = 0b11000000;
|
||||
static constexpr uint8_t SkipFrame = 0b01000000;
|
||||
static constexpr uint8_t DataFrame = 0b10000000;
|
||||
|
||||
static constexpr uint8_t GyrDataBit = 0b00001000;
|
||||
static constexpr uint8_t AccelDataBit = 0b00000100;
|
||||
};
|
||||
|
||||
bool initialize() {
|
||||
m_RegisterInterface.writeReg(Regs::Cmd::reg, Regs::Cmd::valueSoftReset);
|
||||
delay(12);
|
||||
m_RegisterInterface.writeReg(Regs::AccelConf::reg, Regs::AccelConf::value);
|
||||
delay(1);
|
||||
m_RegisterInterface.writeReg(Regs::AccelRange::reg, Regs::AccelRange::value);
|
||||
delay(1);
|
||||
m_RegisterInterface.writeReg(Regs::GyrConf::reg, Regs::GyrConf::value);
|
||||
delay(1);
|
||||
m_RegisterInterface.writeReg(Regs::GyrRange::reg, Regs::GyrRange::value);
|
||||
delay(1);
|
||||
m_RegisterInterface.writeReg(Regs::Cmd::reg, Regs::Cmd::valueAccPowerNormal);
|
||||
delay(10);
|
||||
m_RegisterInterface.writeReg(Regs::Cmd::reg, Regs::Cmd::valueGyrPowerNormal);
|
||||
delay(100);
|
||||
m_RegisterInterface.writeReg(Regs::FifoConfig::reg, Regs::FifoConfig::value);
|
||||
delay(4);
|
||||
m_RegisterInterface.writeReg(Regs::Cmd::reg, Regs::Cmd::valueFifoFlush);
|
||||
delay(2); // delay values ripped straight from old BMI160 driver, could maybe
|
||||
// be lower?
|
||||
|
||||
if (m_RegisterInterface.readReg(Regs::ErrReg) != 0) {
|
||||
m_Logger.error(
|
||||
"BMI160 error: 0x%x",
|
||||
m_RegisterInterface.readReg(Regs::ErrReg)
|
||||
);
|
||||
return false;
|
||||
} else {
|
||||
return true;
|
||||
}
|
||||
}
|
||||
|
||||
float getDirectTemp() const {
|
||||
// 0x0 is 23C
|
||||
// Resolution is 1/2^9 K / LSB
|
||||
constexpr float step = 1 / 512.0f;
|
||||
const uint16_t value = m_RegisterInterface.readReg16(Regs::TempData);
|
||||
return value * step + 23.0f;
|
||||
}
|
||||
|
||||
using FifoBuffer = std::array<uint8_t, RegisterInterface::MaxTransactionLength>;
|
||||
FifoBuffer read_buffer;
|
||||
|
||||
template <typename T> // sorry tailsy I ripped all of this from BMI270 driver
|
||||
// because I don't even want to try and understand the FIFO
|
||||
// format
|
||||
inline T getFromFifo(uint32_t& position, FifoBuffer& fifo) {
|
||||
T to_ret;
|
||||
std::memcpy(&to_ret, &fifo[position], sizeof(T));
|
||||
position += sizeof(T);
|
||||
return to_ret;
|
||||
}
|
||||
|
||||
template <typename AccelCall, typename GyroCall, typename TempCall>
|
||||
void bulkRead(
|
||||
AccelCall&& processAccelSample,
|
||||
GyroCall&& processGyroSample,
|
||||
TempCall&& processTempSample
|
||||
) {
|
||||
const auto fifo_bytes = m_RegisterInterface.readReg16(Regs::FifoLength) & 0x7FF;
|
||||
|
||||
const auto bytes_to_read = std::min(
|
||||
static_cast<size_t>(read_buffer.size()),
|
||||
static_cast<size_t>(fifo_bytes)
|
||||
);
|
||||
m_RegisterInterface
|
||||
.readBytes(Regs::FifoData, bytes_to_read, read_buffer.data());
|
||||
|
||||
for (uint32_t i = 0u; i < bytes_to_read;) {
|
||||
const uint8_t header = getFromFifo<uint8_t>(i, read_buffer);
|
||||
if ((header & Fifo::ModeMask) == Fifo::SkipFrame) {
|
||||
if (i + 1 > bytes_to_read) {
|
||||
// incomplete frame, nothing left to process
|
||||
break;
|
||||
}
|
||||
getFromFifo<uint8_t>(i, read_buffer); // skip 1 byte
|
||||
} else if ((header & Fifo::ModeMask) == Fifo::DataFrame) {
|
||||
uint8_t gyro_data_length = header & Fifo::GyrDataBit ? 6 : 0;
|
||||
uint8_t accel_data_length = header & Fifo::AccelDataBit ? 6 : 0;
|
||||
uint8_t required_length = gyro_data_length + accel_data_length;
|
||||
if (i + required_length > bytes_to_read) {
|
||||
// incomplete frame, will be re-read next time
|
||||
break;
|
||||
}
|
||||
if (header & Fifo::GyrDataBit) {
|
||||
int16_t gyro[3];
|
||||
gyro[0] = getFromFifo<uint16_t>(i, read_buffer);
|
||||
gyro[1] = getFromFifo<uint16_t>(i, read_buffer);
|
||||
gyro[2] = getFromFifo<uint16_t>(i, read_buffer);
|
||||
processGyroSample(gyro, GyrTs);
|
||||
}
|
||||
|
||||
if (header & Fifo::AccelDataBit) {
|
||||
int16_t accel[3];
|
||||
accel[0] = getFromFifo<uint16_t>(i, read_buffer);
|
||||
accel[1] = getFromFifo<uint16_t>(i, read_buffer);
|
||||
accel[2] = getFromFifo<uint16_t>(i, read_buffer);
|
||||
processAccelSample(accel, AccTs);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
};
|
||||
|
||||
} // namespace SlimeVR::Sensors::SoftFusion::Drivers
|
||||
Reference in New Issue
Block a user