mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-16 12:55:19 +03:00
Add support for LSM6DSO gyro/acc
Also supports the LSM6DSOX variant which has the additional machine learning core (not used by Betaflight).
This commit is contained in:
parent
97ad043f9e
commit
99a9543968
13 changed files with 403 additions and 5 deletions
|
@ -224,6 +224,7 @@ SPEED_OPTIMISED_SRC := $(SPEED_OPTIMISED_SRC) \
|
||||||
drivers/accgyro/accgyro_mpu3050.c \
|
drivers/accgyro/accgyro_mpu3050.c \
|
||||||
drivers/accgyro/accgyro_spi_bmi160.c \
|
drivers/accgyro/accgyro_spi_bmi160.c \
|
||||||
drivers/accgyro/accgyro_spi_bmi270.c \
|
drivers/accgyro/accgyro_spi_bmi270.c \
|
||||||
|
drivers/accgyro/accgyro_spi_lsm6dso.c \
|
||||||
drivers/accgyro_legacy/accgyro_adxl345.c \
|
drivers/accgyro_legacy/accgyro_adxl345.c \
|
||||||
drivers/accgyro_legacy/accgyro_bma280.c \
|
drivers/accgyro_legacy/accgyro_bma280.c \
|
||||||
drivers/accgyro_legacy/accgyro_l3g4200d.c \
|
drivers/accgyro_legacy/accgyro_l3g4200d.c \
|
||||||
|
@ -357,7 +358,8 @@ SIZE_OPTIMISED_SRC := $(SIZE_OPTIMISED_SRC) \
|
||||||
drivers/accgyro/accgyro_spi_mpu6000.c \
|
drivers/accgyro/accgyro_spi_mpu6000.c \
|
||||||
drivers/accgyro/accgyro_spi_mpu6500.c \
|
drivers/accgyro/accgyro_spi_mpu6500.c \
|
||||||
drivers/accgyro/accgyro_spi_mpu9250.c \
|
drivers/accgyro/accgyro_spi_mpu9250.c \
|
||||||
drivers/accgyro/accgyro_spi_icm20689.c
|
drivers/accgyro/accgyro_spi_icm20689.c \
|
||||||
|
drivers/accgyro/accgyro_spi_lsm6dso_init.c
|
||||||
|
|
||||||
|
|
||||||
# F4 and F7 optimizations
|
# F4 and F7 optimizations
|
||||||
|
|
|
@ -129,14 +129,14 @@
|
||||||
const char * const lookupTableAccHardware[] = {
|
const char * const lookupTableAccHardware[] = {
|
||||||
"AUTO", "NONE", "ADXL345", "MPU6050", "MMA8452", "BMA280", "LSM303DLHC",
|
"AUTO", "NONE", "ADXL345", "MPU6050", "MMA8452", "BMA280", "LSM303DLHC",
|
||||||
"MPU6000", "MPU6500", "MPU9250", "ICM20601", "ICM20602", "ICM20608G", "ICM20649", "ICM20689", "ICM42605",
|
"MPU6000", "MPU6500", "MPU9250", "ICM20601", "ICM20602", "ICM20608G", "ICM20649", "ICM20689", "ICM42605",
|
||||||
"BMI160", "BMI270", "FAKE"
|
"BMI160", "BMI270", "LSM6DSO", "FAKE"
|
||||||
};
|
};
|
||||||
|
|
||||||
// sync with gyroHardware_e
|
// sync with gyroHardware_e
|
||||||
const char * const lookupTableGyroHardware[] = {
|
const char * const lookupTableGyroHardware[] = {
|
||||||
"AUTO", "NONE", "MPU6050", "L3G4200D", "MPU3050", "L3GD20",
|
"AUTO", "NONE", "MPU6050", "L3G4200D", "MPU3050", "L3GD20",
|
||||||
"MPU6000", "MPU6500", "MPU9250", "ICM20601", "ICM20602", "ICM20608G", "ICM20649", "ICM20689", "ICM42605",
|
"MPU6000", "MPU6500", "MPU9250", "ICM20601", "ICM20602", "ICM20608G", "ICM20649", "ICM20689", "ICM42605",
|
||||||
"BMI160", "BMI270", "FAKE"
|
"BMI160", "BMI270", "LSM6SDO", "FAKE"
|
||||||
};
|
};
|
||||||
|
|
||||||
#if defined(USE_SENSOR_NAMES) || defined(USE_BARO)
|
#if defined(USE_SENSOR_NAMES) || defined(USE_BARO)
|
||||||
|
|
|
@ -58,6 +58,7 @@ typedef enum {
|
||||||
GYRO_ICM42605,
|
GYRO_ICM42605,
|
||||||
GYRO_BMI160,
|
GYRO_BMI160,
|
||||||
GYRO_BMI270,
|
GYRO_BMI270,
|
||||||
|
GYRO_LSM6DSO,
|
||||||
GYRO_FAKE
|
GYRO_FAKE
|
||||||
} gyroHardware_e;
|
} gyroHardware_e;
|
||||||
|
|
||||||
|
@ -73,6 +74,7 @@ typedef enum {
|
||||||
GYRO_RATE_1100_Hz,
|
GYRO_RATE_1100_Hz,
|
||||||
GYRO_RATE_3200_Hz,
|
GYRO_RATE_3200_Hz,
|
||||||
GYRO_RATE_6400_Hz,
|
GYRO_RATE_6400_Hz,
|
||||||
|
GYRO_RATE_6664_Hz,
|
||||||
GYRO_RATE_8_kHz,
|
GYRO_RATE_8_kHz,
|
||||||
GYRO_RATE_9_kHz,
|
GYRO_RATE_9_kHz,
|
||||||
GYRO_RATE_32_kHz,
|
GYRO_RATE_32_kHz,
|
||||||
|
|
|
@ -51,6 +51,7 @@
|
||||||
#include "drivers/accgyro/accgyro_spi_icm20649.h"
|
#include "drivers/accgyro/accgyro_spi_icm20649.h"
|
||||||
#include "drivers/accgyro/accgyro_spi_icm20689.h"
|
#include "drivers/accgyro/accgyro_spi_icm20689.h"
|
||||||
#include "drivers/accgyro/accgyro_spi_icm42605.h"
|
#include "drivers/accgyro/accgyro_spi_icm42605.h"
|
||||||
|
#include "drivers/accgyro/accgyro_spi_lsm6dso.h"
|
||||||
#include "drivers/accgyro/accgyro_spi_mpu6000.h"
|
#include "drivers/accgyro/accgyro_spi_mpu6000.h"
|
||||||
#include "drivers/accgyro/accgyro_spi_mpu6500.h"
|
#include "drivers/accgyro/accgyro_spi_mpu6500.h"
|
||||||
#include "drivers/accgyro/accgyro_spi_mpu9250.h"
|
#include "drivers/accgyro/accgyro_spi_mpu9250.h"
|
||||||
|
@ -223,6 +224,9 @@ static gyroSpiDetectFn_t gyroSpiDetectFnTable[] = {
|
||||||
#endif
|
#endif
|
||||||
#ifdef USE_GYRO_L3GD20
|
#ifdef USE_GYRO_L3GD20
|
||||||
l3gd20Detect,
|
l3gd20Detect,
|
||||||
|
#endif
|
||||||
|
#ifdef USE_ACCGYRO_LSM6DSO
|
||||||
|
lsm6dsoDetect,
|
||||||
#endif
|
#endif
|
||||||
NULL // Avoid an empty array
|
NULL // Avoid an empty array
|
||||||
};
|
};
|
||||||
|
|
|
@ -202,6 +202,7 @@ typedef enum {
|
||||||
ICM_42605_SPI,
|
ICM_42605_SPI,
|
||||||
BMI_160_SPI,
|
BMI_160_SPI,
|
||||||
BMI_270_SPI,
|
BMI_270_SPI,
|
||||||
|
LSM6DSO_SPI,
|
||||||
L3GD20_SPI,
|
L3GD20_SPI,
|
||||||
} mpuSensor_e;
|
} mpuSensor_e;
|
||||||
|
|
||||||
|
|
90
src/main/drivers/accgyro/accgyro_spi_lsm6dso.c
Normal file
90
src/main/drivers/accgyro/accgyro_spi_lsm6dso.c
Normal file
|
@ -0,0 +1,90 @@
|
||||||
|
/*
|
||||||
|
* This file is part of Cleanflight and Betaflight.
|
||||||
|
*
|
||||||
|
* Cleanflight and Betaflight are free software. You can redistribute
|
||||||
|
* this software and/or modify this software under the terms of the
|
||||||
|
* GNU General Public License as published by the Free Software
|
||||||
|
* Foundation, either version 3 of the License, or (at your option)
|
||||||
|
* any later version.
|
||||||
|
*
|
||||||
|
* Cleanflight and Betaflight are distributed in the hope that they
|
||||||
|
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
|
||||||
|
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
||||||
|
* See the GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with this software.
|
||||||
|
*
|
||||||
|
* If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include <stdbool.h>
|
||||||
|
#include <stdint.h>
|
||||||
|
|
||||||
|
#include "platform.h"
|
||||||
|
|
||||||
|
#ifdef USE_ACCGYRO_LSM6DSO
|
||||||
|
|
||||||
|
#include "drivers/accgyro/accgyro.h"
|
||||||
|
#include "drivers/accgyro/accgyro_spi_lsm6dso.h"
|
||||||
|
#include "drivers/bus_spi.h"
|
||||||
|
#include "drivers/exti.h"
|
||||||
|
#include "drivers/io.h"
|
||||||
|
#include "drivers/io_impl.h"
|
||||||
|
|
||||||
|
#if defined(USE_GYRO_EXTI) && defined(USE_MPU_DATA_READY_SIGNAL)
|
||||||
|
void lsm6dsoExtiHandler(extiCallbackRec_t *cb)
|
||||||
|
{
|
||||||
|
gyroDev_t *gyro = container_of(cb, gyroDev_t, exti);
|
||||||
|
gyro->dataReady = true;
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
bool lsm6dsoAccRead(accDev_t *acc)
|
||||||
|
{
|
||||||
|
enum {
|
||||||
|
IDX_ACCEL_XOUT_L,
|
||||||
|
IDX_ACCEL_XOUT_H,
|
||||||
|
IDX_ACCEL_YOUT_L,
|
||||||
|
IDX_ACCEL_YOUT_H,
|
||||||
|
IDX_ACCEL_ZOUT_L,
|
||||||
|
IDX_ACCEL_ZOUT_H,
|
||||||
|
BUFFER_SIZE,
|
||||||
|
};
|
||||||
|
|
||||||
|
uint8_t lsm6dso_rx_buf[BUFFER_SIZE];
|
||||||
|
|
||||||
|
const busDevice_t *busdev = &acc->bus;
|
||||||
|
busReadRegisterBuffer(busdev, LSM6DSO_REG_OUTX_L_A, lsm6dso_rx_buf, BUFFER_SIZE);
|
||||||
|
|
||||||
|
acc->ADCRaw[X] = (int16_t)((lsm6dso_rx_buf[IDX_ACCEL_XOUT_H] << 8) | lsm6dso_rx_buf[IDX_ACCEL_XOUT_L]);
|
||||||
|
acc->ADCRaw[Y] = (int16_t)((lsm6dso_rx_buf[IDX_ACCEL_YOUT_H] << 8) | lsm6dso_rx_buf[IDX_ACCEL_YOUT_L]);
|
||||||
|
acc->ADCRaw[Z] = (int16_t)((lsm6dso_rx_buf[IDX_ACCEL_ZOUT_H] << 8) | lsm6dso_rx_buf[IDX_ACCEL_ZOUT_L]);
|
||||||
|
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool lsm6dsoGyroRead(gyroDev_t *gyro)
|
||||||
|
{
|
||||||
|
enum {
|
||||||
|
IDX_GYRO_XOUT_L,
|
||||||
|
IDX_GYRO_XOUT_H,
|
||||||
|
IDX_GYRO_YOUT_L,
|
||||||
|
IDX_GYRO_YOUT_H,
|
||||||
|
IDX_GYRO_ZOUT_L,
|
||||||
|
IDX_GYRO_ZOUT_H,
|
||||||
|
BUFFER_SIZE,
|
||||||
|
};
|
||||||
|
|
||||||
|
uint8_t lsm6dso_rx_buf[BUFFER_SIZE];
|
||||||
|
|
||||||
|
const busDevice_t *busdev = &gyro->bus;
|
||||||
|
busReadRegisterBuffer(busdev, LSM6DSO_REG_OUTX_L_G, lsm6dso_rx_buf, BUFFER_SIZE);
|
||||||
|
|
||||||
|
gyro->gyroADCRaw[X] = (int16_t)((lsm6dso_rx_buf[IDX_GYRO_XOUT_H] << 8) | lsm6dso_rx_buf[IDX_GYRO_XOUT_L]);
|
||||||
|
gyro->gyroADCRaw[Y] = (int16_t)((lsm6dso_rx_buf[IDX_GYRO_YOUT_H] << 8) | lsm6dso_rx_buf[IDX_GYRO_YOUT_L]);
|
||||||
|
gyro->gyroADCRaw[Z] = (int16_t)((lsm6dso_rx_buf[IDX_GYRO_ZOUT_H] << 8) | lsm6dso_rx_buf[IDX_GYRO_ZOUT_L]);
|
||||||
|
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
#endif
|
66
src/main/drivers/accgyro/accgyro_spi_lsm6dso.h
Normal file
66
src/main/drivers/accgyro/accgyro_spi_lsm6dso.h
Normal file
|
@ -0,0 +1,66 @@
|
||||||
|
/*
|
||||||
|
* This file is part of Cleanflight and Betaflight.
|
||||||
|
*
|
||||||
|
* Cleanflight and Betaflight are free software. You can redistribute
|
||||||
|
* this software and/or modify this software under the terms of the
|
||||||
|
* GNU General Public License as published by the Free Software
|
||||||
|
* Foundation, either version 3 of the License, or (at your option)
|
||||||
|
* any later version.
|
||||||
|
*
|
||||||
|
* Cleanflight and Betaflight are distributed in the hope that they
|
||||||
|
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
|
||||||
|
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
||||||
|
* See the GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with this software.
|
||||||
|
*
|
||||||
|
* If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
#include "drivers/bus.h"
|
||||||
|
#include "drivers/exti.h"
|
||||||
|
|
||||||
|
// LSM6DSO registers (not the complete list)
|
||||||
|
typedef enum {
|
||||||
|
LSM6DSO_REG_INT1_CTRL = 0x0D, // int pin 1 control
|
||||||
|
LSM6DSO_REG_INT2_CTRL = 0x0E, // int pin 2 control
|
||||||
|
LSM6DSO_REG_WHO_AM_I = 0x0F, // chip ID
|
||||||
|
LSM6DSO_REG_CTRL1_XL = 0x10, // accelerometer control
|
||||||
|
LSM6DSO_REG_CTRL2_G = 0x11, // gyro control
|
||||||
|
LSM6DSO_REG_CTRL3_C = 0x12, // control register 3
|
||||||
|
LSM6DSO_REG_CTRL4_C = 0x13, // control register 4
|
||||||
|
LSM6DSO_REG_CTRL5_C = 0x14, // control register 5
|
||||||
|
LSM6DSO_REG_CTRL6_C = 0x15, // control register 6
|
||||||
|
LSM6DSO_REG_CTRL7_G = 0x16, // control register 7
|
||||||
|
LSM6DSO_REG_CTRL8_XL = 0x17, // control register 8
|
||||||
|
LSM6DSO_REG_CTRL9_XL = 0x18, // control register 9
|
||||||
|
LSM6DSO_REG_CTRL10_C = 0x19, // control register 10
|
||||||
|
LSM6DSO_REG_STATUS = 0x1E, // status register
|
||||||
|
LSM6DSO_REG_OUT_TEMP_L = 0x20, // temperature LSB
|
||||||
|
LSM6DSO_REG_OUT_TEMP_H = 0x21, // temperature MSB
|
||||||
|
LSM6DSO_REG_OUTX_L_G = 0x22, // gyro X axis LSB
|
||||||
|
LSM6DSO_REG_OUTX_H_G = 0x23, // gyro X axis MSB
|
||||||
|
LSM6DSO_REG_OUTY_L_G = 0x24, // gyro Y axis LSB
|
||||||
|
LSM6DSO_REG_OUTY_H_G = 0x25, // gyro Y axis MSB
|
||||||
|
LSM6DSO_REG_OUTZ_L_G = 0x26, // gyro Z axis LSB
|
||||||
|
LSM6DSO_REG_OUTZ_H_G = 0x27, // gyro Z axis MSB
|
||||||
|
LSM6DSO_REG_OUTX_L_A = 0x28, // acc X axis LSB
|
||||||
|
LSM6DSO_REG_OUTX_H_A = 0x29, // acc X axis MSB
|
||||||
|
LSM6DSO_REG_OUTY_L_A = 0x2A, // acc Y axis LSB
|
||||||
|
LSM6DSO_REG_OUTY_H_A = 0x2B, // acc Y axis MSB
|
||||||
|
LSM6DSO_REG_OUTZ_L_A = 0x2C, // acc Z axis LSB
|
||||||
|
LSM6DSO_REG_OUTZ_H_A = 0x2D, // acc Z axis MSB
|
||||||
|
} lsm6dsoRegister_e;
|
||||||
|
|
||||||
|
// Contained in accgyro_spi_lsm6dso_init.c which is size-optimized
|
||||||
|
uint8_t lsm6dsoDetect(const busDevice_t *bus);
|
||||||
|
bool lsm6dsoSpiAccDetect(accDev_t *acc);
|
||||||
|
bool lsm6dsoSpiGyroDetect(gyroDev_t *gyro);
|
||||||
|
|
||||||
|
// Contained in accgyro_spi_lsm6dso.c which is speed-optimized
|
||||||
|
void lsm6dsoExtiHandler(extiCallbackRec_t *cb);
|
||||||
|
bool lsm6dsoAccRead(accDev_t *acc);
|
||||||
|
bool lsm6dsoGyroRead(gyroDev_t *gyro);
|
203
src/main/drivers/accgyro/accgyro_spi_lsm6dso_init.c
Normal file
203
src/main/drivers/accgyro/accgyro_spi_lsm6dso_init.c
Normal file
|
@ -0,0 +1,203 @@
|
||||||
|
/*
|
||||||
|
* This file is part of Cleanflight and Betaflight.
|
||||||
|
*
|
||||||
|
* Cleanflight and Betaflight are free software. You can redistribute
|
||||||
|
* this software and/or modify this software under the terms of the
|
||||||
|
* GNU General Public License as published by the Free Software
|
||||||
|
* Foundation, either version 3 of the License, or (at your option)
|
||||||
|
* any later version.
|
||||||
|
*
|
||||||
|
* Cleanflight and Betaflight are distributed in the hope that they
|
||||||
|
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
|
||||||
|
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
||||||
|
* See the GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with this software.
|
||||||
|
*
|
||||||
|
* If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include <stdbool.h>
|
||||||
|
#include <stdint.h>
|
||||||
|
|
||||||
|
#include "platform.h"
|
||||||
|
|
||||||
|
#ifdef USE_ACCGYRO_LSM6DSO
|
||||||
|
|
||||||
|
#include "drivers/accgyro/accgyro.h"
|
||||||
|
#include "drivers/accgyro/accgyro_spi_lsm6dso.h"
|
||||||
|
#include "drivers/bus_spi.h"
|
||||||
|
#include "drivers/exti.h"
|
||||||
|
#include "drivers/io.h"
|
||||||
|
#include "drivers/io_impl.h"
|
||||||
|
#include "drivers/nvic.h"
|
||||||
|
#include "drivers/sensor.h"
|
||||||
|
#include "drivers/time.h"
|
||||||
|
|
||||||
|
#define LSM6DSO_CHIP_ID 0x6C
|
||||||
|
|
||||||
|
// LSM6DSO register configuration values
|
||||||
|
typedef enum {
|
||||||
|
LSM6DSO_VAL_INT1_CTRL = 0x02, // enable gyro data ready interrupt pin 1
|
||||||
|
LSM6DSO_VAL_INT2_CTRL = 0x02, // enable gyro data ready interrupt pin 2
|
||||||
|
LSM6DSO_VAL_CTRL1_XL_ODR833 = 0x07, // accelerometer 833hz output data rate (gyro/8)
|
||||||
|
LSM6DSO_VAL_CTRL1_XL_ODR1667 = 0x08, // accelerometer 1666hz output data rate (gyro/4)
|
||||||
|
LSM6DSO_VAL_CTRL1_XL_ODR3332 = 0x09, // accelerometer 3332hz output data rate (gyro/2)
|
||||||
|
LSM6DSO_VAL_CTRL1_XL_ODR3333 = 0x0A, // accelerometer 6664hz output data rate (gyro/1)
|
||||||
|
LSM6DSO_VAL_CTRL1_XL_8G = 0x03, // accelerometer 8G scale
|
||||||
|
LSM6DSO_VAL_CTRL1_XL_16G = 0x01, // accelerometer 16G scale
|
||||||
|
LSM6DSO_VAL_CTRL1_XL_LPF1 = 0x00, // accelerometer output from LPF1
|
||||||
|
LSM6DSO_VAL_CTRL1_XL_LPF2 = 0x01, // accelerometer output from LPF2
|
||||||
|
LSM6DSO_VAL_CTRL2_G_ODR6664 = 0x0A, // gyro 6664hz output data rate
|
||||||
|
LSM6DSO_VAL_CTRL2_G_2000DPS = 0x03, // gyro 2000dps scale
|
||||||
|
LSM6DSO_VAL_CTRL3_C_BDU = BIT(6), // (bit 6) output registers are not updated until MSB and LSB have been read (prevents MSB from being updated while burst reading LSB/MSB)
|
||||||
|
LSM6DSO_VAL_CTRL3_C_H_LACTIVE = 0, // (bit 5) interrupt pins active high
|
||||||
|
LSM6DSO_VAL_CTRL3_C_PP_OD = 0, // (bit 4) interrupt pins push/pull
|
||||||
|
LSM6DSO_VAL_CTRL3_C_SIM = 0, // (bit 3) SPI 4-wire interface mode
|
||||||
|
LSM6DSO_VAL_CTRL3_C_IF_INC = BIT(2), // (bit 2) auto-increment address for burst reads
|
||||||
|
LSM6DSO_VAL_CTRL4_C_I2C_DISABLE = BIT(2), // (bit 2) disable I2C interface
|
||||||
|
LSM6DSO_VAL_CTRL4_C_LPF1_SEL_G = BIT(1), // (bit 1) enable gyro LPF1
|
||||||
|
LSM6DSO_VAL_CTRL6_C_XL_HM_MODE = 0, // (bit 4) enable accelerometer high performance mode
|
||||||
|
LSM6DSO_VAL_CTRL6_C_FTYPE_335HZ = 0x00, // (bits 2:0) gyro LPF1 cutoff 335.5hz
|
||||||
|
LSM6DSO_VAL_CTRL6_C_FTYPE_232HZ = 0x01, // (bits 2:0) gyro LPF1 cutoff 232.0hz
|
||||||
|
LSM6DSO_VAL_CTRL6_C_FTYPE_171HZ = 0x02, // (bits 2:0) gyro LPF1 cutoff 171.1hz
|
||||||
|
LSM6DSO_VAL_CTRL6_C_FTYPE_609HZ = 0x03, // (bits 2:0) gyro LPF1 cutoff 609.0hz
|
||||||
|
LSM6DSO_VAL_CTRL9_XL_I3C_DISABLE = BIT(1),// (bit 1) disable I3C interface
|
||||||
|
} lsm6dsoConfigValues_e;
|
||||||
|
|
||||||
|
// LSM6DSO register configuration bit masks
|
||||||
|
typedef enum {
|
||||||
|
LSM6DSO_MASK_CTRL3_C = 0x7C, // 0b01111100
|
||||||
|
LSM6DSO_MASK_CTRL3_C_RESET = BIT(0), // 0b00000001
|
||||||
|
LSM6DSO_MASK_CTRL4_C = 0x06, // 0b00000110
|
||||||
|
LSM6DSO_MASK_CTRL6_C = 0x17, // 0b00010111
|
||||||
|
LSM6DSO_MASK_CTRL9_XL = 0x02, // 0b00000010
|
||||||
|
} lsm6dsoConfigMasks_e;
|
||||||
|
|
||||||
|
uint8_t lsm6dsoDetect(const busDevice_t *bus)
|
||||||
|
{
|
||||||
|
uint8_t chipID = 0;
|
||||||
|
spiSetDivisor(bus->busdev_u.spi.instance, SPI_CLOCK_STANDARD);
|
||||||
|
|
||||||
|
if (busReadRegisterBuffer(bus, LSM6DSO_REG_WHO_AM_I, &chipID, 1)) {
|
||||||
|
if (chipID == LSM6DSO_CHIP_ID) {
|
||||||
|
return LSM6DSO_SPI;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
return MPU_NONE;
|
||||||
|
}
|
||||||
|
|
||||||
|
static void lsm6dsoWriteRegister(const busDevice_t *bus, lsm6dsoRegister_e registerID, uint8_t value, unsigned delayMs)
|
||||||
|
{
|
||||||
|
busWriteRegister(bus, registerID, value);
|
||||||
|
if (delayMs) {
|
||||||
|
delay(delayMs);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
static void lsm6dsoWriteRegisterBits(const busDevice_t *bus, lsm6dsoRegister_e registerID, lsm6dsoConfigMasks_e mask, uint8_t value, unsigned delayMs)
|
||||||
|
{
|
||||||
|
uint8_t newValue;
|
||||||
|
if (busReadRegisterBuffer(bus, registerID, &newValue, 1)) {
|
||||||
|
delayMicroseconds(2);
|
||||||
|
newValue = (newValue & ~mask) | value;
|
||||||
|
lsm6dsoWriteRegister(bus, registerID, newValue, delayMs);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
static void lsm6dsoConfig(const gyroDev_t *gyro)
|
||||||
|
{
|
||||||
|
const busDevice_t *bus = &gyro->bus;
|
||||||
|
|
||||||
|
// Reset the device (wait 100ms before continuing config)
|
||||||
|
lsm6dsoWriteRegisterBits(bus, LSM6DSO_REG_CTRL3_C, LSM6DSO_MASK_CTRL3_C_RESET, BIT(0), 100);
|
||||||
|
|
||||||
|
// Configure interrupt pin 1 for gyro data ready only
|
||||||
|
lsm6dsoWriteRegister(bus, LSM6DSO_REG_INT1_CTRL, LSM6DSO_VAL_INT1_CTRL, 1);
|
||||||
|
|
||||||
|
// Disable interrupt pin 2
|
||||||
|
lsm6dsoWriteRegister(bus, LSM6DSO_REG_INT2_CTRL, LSM6DSO_VAL_INT2_CTRL, 1);
|
||||||
|
|
||||||
|
// Configure the accelerometer
|
||||||
|
// 833hz ODR, 16G scale, use LPF1 output
|
||||||
|
lsm6dsoWriteRegister(bus, LSM6DSO_REG_CTRL1_XL, (LSM6DSO_VAL_CTRL1_XL_ODR833 << 4) | (LSM6DSO_VAL_CTRL1_XL_16G << 2) | (LSM6DSO_VAL_CTRL1_XL_LPF1 << 1), 1);
|
||||||
|
|
||||||
|
// Configure the gyro
|
||||||
|
// 6664hz ODR, 2000dps scale
|
||||||
|
lsm6dsoWriteRegister(bus, LSM6DSO_REG_CTRL2_G, (LSM6DSO_VAL_CTRL2_G_ODR6664 << 4) | (LSM6DSO_VAL_CTRL2_G_2000DPS << 2), 1);
|
||||||
|
|
||||||
|
// Configure control register 3
|
||||||
|
// latch LSB/MSB during reads; set interrupt pins active high; set interrupt pins push/pull; set 4-wire SPI; enable auto-increment burst reads
|
||||||
|
lsm6dsoWriteRegisterBits(bus, LSM6DSO_REG_CTRL3_C, LSM6DSO_MASK_CTRL3_C, (LSM6DSO_VAL_CTRL3_C_BDU | LSM6DSO_VAL_CTRL3_C_H_LACTIVE | LSM6DSO_VAL_CTRL3_C_PP_OD | LSM6DSO_VAL_CTRL3_C_SIM | LSM6DSO_VAL_CTRL3_C_IF_INC), 1);
|
||||||
|
|
||||||
|
// Configure control register 4
|
||||||
|
// enable accelerometer high performane mode; set gyro LPF1 cutoff to 335.5hz
|
||||||
|
lsm6dsoWriteRegisterBits(bus, LSM6DSO_REG_CTRL4_C, LSM6DSO_MASK_CTRL4_C, (LSM6DSO_VAL_CTRL4_C_I2C_DISABLE | LSM6DSO_VAL_CTRL4_C_LPF1_SEL_G), 1);
|
||||||
|
|
||||||
|
// Configure control register 6
|
||||||
|
// disable I2C interface; enable gyro LPF1
|
||||||
|
lsm6dsoWriteRegisterBits(bus, LSM6DSO_REG_CTRL6_C, LSM6DSO_MASK_CTRL6_C, (LSM6DSO_VAL_CTRL6_C_XL_HM_MODE | LSM6DSO_VAL_CTRL6_C_FTYPE_335HZ), 1);
|
||||||
|
|
||||||
|
// Configure control register 9
|
||||||
|
// disable I3C interface
|
||||||
|
lsm6dsoWriteRegisterBits(bus, LSM6DSO_REG_CTRL9_XL, LSM6DSO_MASK_CTRL9_XL, LSM6DSO_VAL_CTRL9_XL_I3C_DISABLE, 1);
|
||||||
|
}
|
||||||
|
|
||||||
|
#if defined(USE_GYRO_EXTI) && defined(USE_MPU_DATA_READY_SIGNAL)
|
||||||
|
static void lsm6dsoIntExtiInit(gyroDev_t *gyro)
|
||||||
|
{
|
||||||
|
if (gyro->mpuIntExtiTag == IO_TAG_NONE) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
IO_t mpuIntIO = IOGetByTag(gyro->mpuIntExtiTag);
|
||||||
|
|
||||||
|
IOInit(mpuIntIO, OWNER_GYRO_EXTI, 0);
|
||||||
|
EXTIHandlerInit(&gyro->exti, lsm6dsoExtiHandler);
|
||||||
|
EXTIConfig(mpuIntIO, &gyro->exti, NVIC_PRIO_MPU_INT_EXTI, IOCFG_IN_FLOATING, BETAFLIGHT_EXTI_TRIGGER_RISING);
|
||||||
|
EXTIEnable(mpuIntIO, true);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
static void lsm6dsoSpiGyroInit(gyroDev_t *gyro)
|
||||||
|
{
|
||||||
|
lsm6dsoConfig(gyro);
|
||||||
|
|
||||||
|
#if defined(USE_GYRO_EXTI) && defined(USE_MPU_DATA_READY_SIGNAL)
|
||||||
|
lsm6dsoIntExtiInit(gyro);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
static void lsm6dsoSpiAccInit(accDev_t *acc)
|
||||||
|
{
|
||||||
|
// sensor is configured during gyro init
|
||||||
|
acc->acc_1G = 512 * 4; // 16G sensor scale
|
||||||
|
}
|
||||||
|
|
||||||
|
bool lsm6dsoSpiAccDetect(accDev_t *acc)
|
||||||
|
{
|
||||||
|
if (acc->mpuDetectionResult.sensor != LSM6DSO_SPI) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
acc->initFn = lsm6dsoSpiAccInit;
|
||||||
|
acc->readFn = lsm6dsoAccRead;
|
||||||
|
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool lsm6dsoSpiGyroDetect(gyroDev_t *gyro)
|
||||||
|
{
|
||||||
|
if (gyro->mpuDetectionResult.sensor != LSM6DSO_SPI) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
gyro->initFn = lsm6dsoSpiGyroInit;
|
||||||
|
gyro->readFn = lsm6dsoGyroRead;
|
||||||
|
gyro->scale = GYRO_SCALE_2000DPS;
|
||||||
|
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
#endif // USE_ACCGYRO_LSM6DSO
|
|
@ -77,6 +77,13 @@ uint16_t gyroSetSampleRate(gyroDev_t *gyro)
|
||||||
gyroSampleRateHz = 9000;
|
gyroSampleRateHz = 9000;
|
||||||
accSampleRateHz = 1125;
|
accSampleRateHz = 1125;
|
||||||
break;
|
break;
|
||||||
|
#ifdef USE_ACCGYRO_LSM6DSO
|
||||||
|
case LSM6DSO_SPI:
|
||||||
|
gyro->gyroRateKHz = GYRO_RATE_6664_Hz;
|
||||||
|
gyroSampleRateHz = 6664; // Yes, this is correct per the datasheet. Will effectively round to 150us and 6.67KHz.
|
||||||
|
accSampleRateHz = 833;
|
||||||
|
break;
|
||||||
|
#endif
|
||||||
default:
|
default:
|
||||||
gyro->gyroRateKHz = GYRO_RATE_8_kHz;
|
gyro->gyroRateKHz = GYRO_RATE_8_kHz;
|
||||||
gyroSampleRateHz = 8000;
|
gyroSampleRateHz = 8000;
|
||||||
|
|
|
@ -47,6 +47,7 @@
|
||||||
#include "drivers/accgyro/accgyro_spi_icm20649.h"
|
#include "drivers/accgyro/accgyro_spi_icm20649.h"
|
||||||
#include "drivers/accgyro/accgyro_spi_icm20689.h"
|
#include "drivers/accgyro/accgyro_spi_icm20689.h"
|
||||||
#include "drivers/accgyro/accgyro_spi_icm42605.h"
|
#include "drivers/accgyro/accgyro_spi_icm42605.h"
|
||||||
|
#include "drivers/accgyro/accgyro_spi_lsm6dso.h"
|
||||||
#include "drivers/accgyro/accgyro_spi_mpu6000.h"
|
#include "drivers/accgyro/accgyro_spi_mpu6000.h"
|
||||||
#include "drivers/accgyro/accgyro_spi_mpu6500.h"
|
#include "drivers/accgyro/accgyro_spi_mpu6500.h"
|
||||||
#include "drivers/accgyro/accgyro_spi_mpu9250.h"
|
#include "drivers/accgyro/accgyro_spi_mpu9250.h"
|
||||||
|
@ -303,6 +304,15 @@ retry:
|
||||||
FALLTHROUGH;
|
FALLTHROUGH;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#ifdef USE_ACCGYRO_LSM6DSO
|
||||||
|
case ACC_LSM6DSO:
|
||||||
|
if (lsm6dsoSpiAccDetect(dev)) {
|
||||||
|
accHardware = ACC_LSM6DSO;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
FALLTHROUGH;
|
||||||
|
#endif
|
||||||
|
|
||||||
#ifdef USE_FAKE_ACC
|
#ifdef USE_FAKE_ACC
|
||||||
case ACC_FAKE:
|
case ACC_FAKE:
|
||||||
if (fakeAccDetect(dev)) {
|
if (fakeAccDetect(dev)) {
|
||||||
|
|
|
@ -45,6 +45,7 @@ typedef enum {
|
||||||
ACC_ICM42605,
|
ACC_ICM42605,
|
||||||
ACC_BMI160,
|
ACC_BMI160,
|
||||||
ACC_BMI270,
|
ACC_BMI270,
|
||||||
|
ACC_LSM6DSO,
|
||||||
ACC_FAKE
|
ACC_FAKE
|
||||||
} accelerationSensor_e;
|
} accelerationSensor_e;
|
||||||
|
|
||||||
|
|
|
@ -46,6 +46,7 @@
|
||||||
#include "drivers/accgyro/accgyro_spi_icm20689.h"
|
#include "drivers/accgyro/accgyro_spi_icm20689.h"
|
||||||
#include "drivers/accgyro/accgyro_spi_icm20689.h"
|
#include "drivers/accgyro/accgyro_spi_icm20689.h"
|
||||||
#include "drivers/accgyro/accgyro_spi_icm42605.h"
|
#include "drivers/accgyro/accgyro_spi_icm42605.h"
|
||||||
|
#include "drivers/accgyro/accgyro_spi_lsm6dso.h"
|
||||||
#include "drivers/accgyro/accgyro_spi_mpu6000.h"
|
#include "drivers/accgyro/accgyro_spi_mpu6000.h"
|
||||||
#include "drivers/accgyro/accgyro_spi_mpu6500.h"
|
#include "drivers/accgyro/accgyro_spi_mpu6500.h"
|
||||||
#include "drivers/accgyro/accgyro_spi_mpu9250.h"
|
#include "drivers/accgyro/accgyro_spi_mpu9250.h"
|
||||||
|
@ -312,6 +313,7 @@ void gyroInitSensor(gyroSensor_t *gyroSensor, const gyroDeviceConfig_t *config)
|
||||||
case GYRO_MPU6000:
|
case GYRO_MPU6000:
|
||||||
case GYRO_MPU6500:
|
case GYRO_MPU6500:
|
||||||
case GYRO_MPU9250:
|
case GYRO_MPU9250:
|
||||||
|
case GYRO_LSM6DSO:
|
||||||
gyroSensor->gyroDev.gyroHasOverflowProtection = true;
|
gyroSensor->gyroDev.gyroHasOverflowProtection = true;
|
||||||
break;
|
break;
|
||||||
|
|
||||||
|
@ -469,6 +471,15 @@ STATIC_UNIT_TESTED gyroHardware_e gyroDetect(gyroDev_t *dev)
|
||||||
FALLTHROUGH;
|
FALLTHROUGH;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#ifdef USE_ACCGYRO_LSM6DSO
|
||||||
|
case GYRO_LSM6DSO:
|
||||||
|
if (lsm6dsoSpiGyroDetect(dev)) {
|
||||||
|
gyroHardware = GYRO_LSM6DSO;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
FALLTHROUGH;
|
||||||
|
#endif
|
||||||
|
|
||||||
#ifdef USE_FAKE_GYRO
|
#ifdef USE_FAKE_GYRO
|
||||||
case GYRO_FAKE:
|
case GYRO_FAKE:
|
||||||
if (fakeGyroDetect(dev)) {
|
if (fakeGyroDetect(dev)) {
|
||||||
|
@ -494,7 +505,7 @@ static bool gyroDetectSensor(gyroSensor_t *gyroSensor, const gyroDeviceConfig_t
|
||||||
{
|
{
|
||||||
#if defined(USE_GYRO_MPU6050) || defined(USE_GYRO_MPU3050) || defined(USE_GYRO_MPU6500) || defined(USE_GYRO_SPI_MPU6500) || defined(USE_GYRO_SPI_MPU6000) \
|
#if defined(USE_GYRO_MPU6050) || defined(USE_GYRO_MPU3050) || defined(USE_GYRO_MPU6500) || defined(USE_GYRO_SPI_MPU6500) || defined(USE_GYRO_SPI_MPU6000) \
|
||||||
|| defined(USE_ACC_MPU6050) || defined(USE_GYRO_SPI_MPU9250) || defined(USE_GYRO_SPI_ICM20601) || defined(USE_GYRO_SPI_ICM20649) \
|
|| defined(USE_ACC_MPU6050) || defined(USE_GYRO_SPI_MPU9250) || defined(USE_GYRO_SPI_ICM20601) || defined(USE_GYRO_SPI_ICM20649) \
|
||||||
|| defined(USE_GYRO_SPI_ICM20689) || defined(USE_GYRO_L3GD20) || defined(USE_ACCGYRO_BMI160) || defined(USE_ACCGYRO_BMI270)
|
|| defined(USE_GYRO_SPI_ICM20689) || defined(USE_GYRO_L3GD20) || defined(USE_ACCGYRO_BMI160) || defined(USE_ACCGYRO_BMI270) || defined(USE_ACCGYRO_LSM6DSO)
|
||||||
|
|
||||||
bool gyroFound = mpuDetect(&gyroSensor->gyroDev, config);
|
bool gyroFound = mpuDetect(&gyroSensor->gyroDev, config);
|
||||||
|
|
||||||
|
@ -519,7 +530,7 @@ static void gyroPreInitSensor(const gyroDeviceConfig_t *config)
|
||||||
{
|
{
|
||||||
#if defined(USE_GYRO_MPU6050) || defined(USE_GYRO_MPU3050) || defined(USE_GYRO_MPU6500) || defined(USE_GYRO_SPI_MPU6500) || defined(USE_GYRO_SPI_MPU6000) \
|
#if defined(USE_GYRO_MPU6050) || defined(USE_GYRO_MPU3050) || defined(USE_GYRO_MPU6500) || defined(USE_GYRO_SPI_MPU6500) || defined(USE_GYRO_SPI_MPU6000) \
|
||||||
|| defined(USE_ACC_MPU6050) || defined(USE_GYRO_SPI_MPU9250) || defined(USE_GYRO_SPI_ICM20601) || defined(USE_GYRO_SPI_ICM20649) \
|
|| defined(USE_ACC_MPU6050) || defined(USE_GYRO_SPI_MPU9250) || defined(USE_GYRO_SPI_ICM20601) || defined(USE_GYRO_SPI_ICM20649) \
|
||||||
|| defined(USE_GYRO_SPI_ICM20689) || defined(USE_ACCGYRO_BMI160) || defined(USE_ACCGYRO_BMI270)
|
|| defined(USE_GYRO_SPI_ICM20689) || defined(USE_ACCGYRO_BMI160) || defined(USE_ACCGYRO_BMI270) || defined(USE_ACCGRYO_LSM6DSO)
|
||||||
mpuPreInit(config);
|
mpuPreInit(config);
|
||||||
#else
|
#else
|
||||||
UNUSED(config);
|
UNUSED(config);
|
||||||
|
|
|
@ -169,6 +169,7 @@
|
||||||
#define USE_GYRO_SPI_MPU6500
|
#define USE_GYRO_SPI_MPU6500
|
||||||
#define USE_ACC_SPI_ICM20689
|
#define USE_ACC_SPI_ICM20689
|
||||||
#define USE_GYRO_SPI_ICM20689
|
#define USE_GYRO_SPI_ICM20689
|
||||||
|
#define USE_ACCGYRO_LSM6DSO
|
||||||
|
|
||||||
#define USE_MAG
|
#define USE_MAG
|
||||||
#define USE_MAG_DATA_READY_SIGNAL
|
#define USE_MAG_DATA_READY_SIGNAL
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue