Reordered accgyro functions to avoid forward declarations
This commit is contained in:
parent
ccfb19edfe
commit
f4e9ea40df
|
@ -56,27 +56,8 @@
|
|||
#define ADXL345_RANGE_16G 0x03
|
||||
#define ADXL345_FIFO_STREAM 0x80
|
||||
|
||||
static void adxl345Init(accDev_t *acc);
|
||||
static bool adxl345Read(int16_t *accelData);
|
||||
|
||||
static bool useFifo = false;
|
||||
|
||||
bool adxl345Detect(drv_adxl345_config_t *init, accDev_t *acc)
|
||||
{
|
||||
uint8_t sig = 0;
|
||||
bool ack = i2cRead(MPU_I2C_INSTANCE, ADXL345_ADDRESS, 0x00, 1, &sig);
|
||||
|
||||
if (!ack || sig != 0xE5)
|
||||
return false;
|
||||
|
||||
// use ADXL345's fifo to filter data or not
|
||||
useFifo = init->useFifo;
|
||||
|
||||
acc->init = adxl345Init;
|
||||
acc->read = adxl345Read;
|
||||
return true;
|
||||
}
|
||||
|
||||
static void adxl345Init(accDev_t *acc)
|
||||
{
|
||||
if (useFifo) {
|
||||
|
@ -135,3 +116,19 @@ static bool adxl345Read(int16_t *accelData)
|
|||
|
||||
return true;
|
||||
}
|
||||
|
||||
bool adxl345Detect(drv_adxl345_config_t *init, accDev_t *acc)
|
||||
{
|
||||
uint8_t sig = 0;
|
||||
bool ack = i2cRead(MPU_I2C_INSTANCE, ADXL345_ADDRESS, 0x00, 1, &sig);
|
||||
|
||||
if (!ack || sig != 0xE5)
|
||||
return false;
|
||||
|
||||
// use ADXL345's fifo to filter data or not
|
||||
useFifo = init->useFifo;
|
||||
|
||||
acc->init = adxl345Init;
|
||||
acc->read = adxl345Read;
|
||||
return true;
|
||||
}
|
||||
|
|
|
@ -32,22 +32,6 @@
|
|||
#define BMA280_PMU_BW 0x10
|
||||
#define BMA280_PMU_RANGE 0x0F
|
||||
|
||||
static void bma280Init(accDev_t *acc);
|
||||
static bool bma280Read(int16_t *accelData);
|
||||
|
||||
bool bma280Detect(accDev_t *acc)
|
||||
{
|
||||
uint8_t sig = 0;
|
||||
bool ack = i2cRead(MPU_I2C_INSTANCE, BMA280_ADDRESS, 0x00, 1, &sig);
|
||||
|
||||
if (!ack || sig != 0xFB)
|
||||
return false;
|
||||
|
||||
acc->init = bma280Init;
|
||||
acc->read = bma280Read;
|
||||
return true;
|
||||
}
|
||||
|
||||
static void bma280Init(accDev_t *acc)
|
||||
{
|
||||
i2cWrite(MPU_I2C_INSTANCE, BMA280_ADDRESS, BMA280_PMU_RANGE, 0x08); // +-8g range
|
||||
|
@ -71,3 +55,16 @@ static bool bma280Read(int16_t *accelData)
|
|||
|
||||
return true;
|
||||
}
|
||||
|
||||
bool bma280Detect(accDev_t *acc)
|
||||
{
|
||||
uint8_t sig = 0;
|
||||
bool ack = i2cRead(MPU_I2C_INSTANCE, BMA280_ADDRESS, 0x00, 1, &sig);
|
||||
|
||||
if (!ack || sig != 0xFB)
|
||||
return false;
|
||||
|
||||
acc->init = bma280Init;
|
||||
acc->read = bma280Read;
|
||||
return true;
|
||||
}
|
||||
|
|
|
@ -54,28 +54,6 @@
|
|||
#define L3G4200D_DLPF_78HZ 0x80
|
||||
#define L3G4200D_DLPF_93HZ 0xC0
|
||||
|
||||
static void l3g4200dInit(gyroDev_t *gyro);
|
||||
static bool l3g4200dRead(gyroDev_t *gyro);
|
||||
|
||||
bool l3g4200dDetect(gyroDev_t *gyro)
|
||||
{
|
||||
uint8_t deviceid;
|
||||
|
||||
delay(25);
|
||||
|
||||
i2cRead(MPU_I2C_INSTANCE, L3G4200D_ADDRESS, L3G4200D_WHO_AM_I, 1, &deviceid);
|
||||
if (deviceid != L3G4200D_ID)
|
||||
return false;
|
||||
|
||||
gyro->init = l3g4200dInit;
|
||||
gyro->read = l3g4200dRead;
|
||||
|
||||
// 14.2857dps/lsb scalefactor
|
||||
gyro->scale = 1.0f / 14.2857f;
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
static void l3g4200dInit(gyroDev_t *gyro)
|
||||
{
|
||||
bool ack;
|
||||
|
@ -123,3 +101,22 @@ static bool l3g4200dRead(gyroDev_t *gyro)
|
|||
|
||||
return true;
|
||||
}
|
||||
|
||||
bool l3g4200dDetect(gyroDev_t *gyro)
|
||||
{
|
||||
uint8_t deviceid;
|
||||
|
||||
delay(25);
|
||||
|
||||
i2cRead(MPU_I2C_INSTANCE, L3G4200D_ADDRESS, L3G4200D_WHO_AM_I, 1, &deviceid);
|
||||
if (deviceid != L3G4200D_ID)
|
||||
return false;
|
||||
|
||||
gyro->init = l3g4200dInit;
|
||||
gyro->read = l3g4200dRead;
|
||||
|
||||
// 14.2857dps/lsb scalefactor
|
||||
gyro->scale = 1.0f / 14.2857f;
|
||||
|
||||
return true;
|
||||
}
|
||||
|
|
|
@ -81,23 +81,6 @@
|
|||
|
||||
static uint8_t device_id;
|
||||
|
||||
static void mma8452Init(accDev_t *acc);
|
||||
static bool mma8452Read(int16_t *accelData);
|
||||
|
||||
bool mma8452Detect(accDev_t *acc)
|
||||
{
|
||||
uint8_t sig = 0;
|
||||
bool ack = i2cRead(MPU_I2C_INSTANCE, MMA8452_ADDRESS, MMA8452_WHO_AM_I, 1, &sig);
|
||||
|
||||
if (!ack || (sig != MMA8452_DEVICE_SIGNATURE && sig != MMA8451_DEVICE_SIGNATURE))
|
||||
return false;
|
||||
|
||||
acc->init = mma8452Init;
|
||||
acc->read = mma8452Read;
|
||||
device_id = sig;
|
||||
return true;
|
||||
}
|
||||
|
||||
static inline void mma8451ConfigureInterrupt(void)
|
||||
{
|
||||
#ifdef NAZE
|
||||
|
@ -142,3 +125,17 @@ static bool mma8452Read(int16_t *accelData)
|
|||
|
||||
return true;
|
||||
}
|
||||
|
||||
bool mma8452Detect(accDev_t *acc)
|
||||
{
|
||||
uint8_t sig = 0;
|
||||
bool ack = i2cRead(MPU_I2C_INSTANCE, MMA8452_ADDRESS, MMA8452_WHO_AM_I, 1, &sig);
|
||||
|
||||
if (!ack || (sig != MMA8452_DEVICE_SIGNATURE && sig != MMA8451_DEVICE_SIGNATURE))
|
||||
return false;
|
||||
|
||||
acc->init = mma8452Init;
|
||||
acc->read = mma8452Read;
|
||||
device_id = sig;
|
||||
return true;
|
||||
}
|
||||
|
|
|
@ -46,25 +46,6 @@
|
|||
#define MPU3050_USER_RESET 0x01
|
||||
#define MPU3050_CLK_SEL_PLL_GX 0x01
|
||||
|
||||
static void mpu3050Init(gyroDev_t *gyro);
|
||||
static bool mpu3050ReadTemp(int16_t *tempData);
|
||||
|
||||
bool mpu3050Detect(gyroDev_t *gyro)
|
||||
{
|
||||
if (mpuDetectionResult.sensor != MPU_3050) {
|
||||
return false;
|
||||
}
|
||||
gyro->init = mpu3050Init;
|
||||
gyro->read = mpuGyroRead;
|
||||
gyro->temperature = mpu3050ReadTemp;
|
||||
gyro->intStatus = checkMPUDataReady;
|
||||
|
||||
// 16.4 dps/lsb scalefactor
|
||||
gyro->scale = 1.0f / 16.4f;
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
static void mpu3050Init(gyroDev_t *gyro)
|
||||
{
|
||||
bool ack;
|
||||
|
@ -81,7 +62,7 @@ static void mpu3050Init(gyroDev_t *gyro)
|
|||
mpuConfiguration.write(MPU3050_PWR_MGM, MPU3050_CLK_SEL_PLL_GX);
|
||||
}
|
||||
|
||||
static bool mpu3050ReadTemp(int16_t *tempData)
|
||||
static bool mpu3050ReadTemperature(int16_t *tempData)
|
||||
{
|
||||
uint8_t buf[2];
|
||||
if (!mpuConfiguration.read(MPU3050_TEMP_OUT, 2, buf)) {
|
||||
|
@ -92,3 +73,19 @@ static bool mpu3050ReadTemp(int16_t *tempData)
|
|||
|
||||
return true;
|
||||
}
|
||||
|
||||
bool mpu3050Detect(gyroDev_t *gyro)
|
||||
{
|
||||
if (mpuDetectionResult.sensor != MPU_3050) {
|
||||
return false;
|
||||
}
|
||||
gyro->init = mpu3050Init;
|
||||
gyro->read = mpuGyroRead;
|
||||
gyro->temperature = mpu3050ReadTemperature;
|
||||
gyro->intStatus = checkMPUDataReady;
|
||||
|
||||
// 16.4 dps/lsb scalefactor
|
||||
gyro->scale = 1.0f / 16.4f;
|
||||
|
||||
return true;
|
||||
}
|
||||
|
|
|
@ -50,8 +50,17 @@
|
|||
|
||||
#define MPU6050_SMPLRT_DIV 0 // 8000Hz
|
||||
|
||||
static void mpu6050AccInit(accDev_t *acc);
|
||||
static void mpu6050GyroInit(gyroDev_t *gyro);
|
||||
static void mpu6050AccInit(accDev_t *acc)
|
||||
{
|
||||
switch (mpuDetectionResult.resolution) {
|
||||
case MPU_HALF_RESOLUTION:
|
||||
acc->acc_1G = 256 * 4;
|
||||
break;
|
||||
case MPU_FULL_RESOLUTION:
|
||||
acc->acc_1G = 512 * 4;
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
bool mpu6050AccDetect(accDev_t *acc)
|
||||
{
|
||||
|
@ -66,33 +75,6 @@ bool mpu6050AccDetect(accDev_t *acc)
|
|||
return true;
|
||||
}
|
||||
|
||||
bool mpu6050GyroDetect(gyroDev_t *gyro)
|
||||
{
|
||||
if (mpuDetectionResult.sensor != MPU_60x0) {
|
||||
return false;
|
||||
}
|
||||
gyro->init = mpu6050GyroInit;
|
||||
gyro->read = mpuGyroRead;
|
||||
gyro->intStatus = checkMPUDataReady;
|
||||
|
||||
// 16.4 dps/lsb scalefactor
|
||||
gyro->scale = 1.0f / 16.4f;
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
static void mpu6050AccInit(accDev_t *acc)
|
||||
{
|
||||
switch (mpuDetectionResult.resolution) {
|
||||
case MPU_HALF_RESOLUTION:
|
||||
acc->acc_1G = 256 * 4;
|
||||
break;
|
||||
case MPU_FULL_RESOLUTION:
|
||||
acc->acc_1G = 512 * 4;
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
static void mpu6050GyroInit(gyroDev_t *gyro)
|
||||
{
|
||||
mpuGyroInit(gyro);
|
||||
|
@ -116,3 +98,18 @@ static void mpu6050GyroInit(gyroDev_t *gyro)
|
|||
mpuConfiguration.write(MPU_RA_INT_ENABLE, MPU_RF_DATA_RDY_EN);
|
||||
#endif
|
||||
}
|
||||
|
||||
bool mpu6050GyroDetect(gyroDev_t *gyro)
|
||||
{
|
||||
if (mpuDetectionResult.sensor != MPU_60x0) {
|
||||
return false;
|
||||
}
|
||||
gyro->init = mpu6050GyroInit;
|
||||
gyro->read = mpuGyroRead;
|
||||
gyro->intStatus = checkMPUDataReady;
|
||||
|
||||
// 16.4 dps/lsb scalefactor
|
||||
gyro->scale = 1.0f / 16.4f;
|
||||
|
||||
return true;
|
||||
}
|
||||
|
|
|
@ -34,6 +34,11 @@
|
|||
#include "accgyro_mpu.h"
|
||||
#include "accgyro_mpu6500.h"
|
||||
|
||||
void mpu6500AccInit(accDev_t *acc)
|
||||
{
|
||||
acc->acc_1G = 512 * 4;
|
||||
}
|
||||
|
||||
bool mpu6500AccDetect(accDev_t *acc)
|
||||
{
|
||||
if (mpuDetectionResult.sensor != MPU_65xx_I2C) {
|
||||
|
@ -46,27 +51,6 @@ bool mpu6500AccDetect(accDev_t *acc)
|
|||
return true;
|
||||
}
|
||||
|
||||
bool mpu6500GyroDetect(gyroDev_t *gyro)
|
||||
{
|
||||
if (mpuDetectionResult.sensor != MPU_65xx_I2C) {
|
||||
return false;
|
||||
}
|
||||
|
||||
gyro->init = mpu6500GyroInit;
|
||||
gyro->read = mpuGyroRead;
|
||||
gyro->intStatus = checkMPUDataReady;
|
||||
|
||||
// 16.4 dps/lsb scalefactor
|
||||
gyro->scale = 1.0f / 16.4f;
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
void mpu6500AccInit(accDev_t *acc)
|
||||
{
|
||||
acc->acc_1G = 512 * 4;
|
||||
}
|
||||
|
||||
void mpu6500GyroInit(gyroDev_t *gyro)
|
||||
{
|
||||
mpuGyroInit(gyro);
|
||||
|
@ -101,3 +85,19 @@ void mpu6500GyroInit(gyroDev_t *gyro)
|
|||
#endif
|
||||
delay(15);
|
||||
}
|
||||
|
||||
bool mpu6500GyroDetect(gyroDev_t *gyro)
|
||||
{
|
||||
if (mpuDetectionResult.sensor != MPU_65xx_I2C) {
|
||||
return false;
|
||||
}
|
||||
|
||||
gyro->init = mpu6500GyroInit;
|
||||
gyro->read = mpuGyroRead;
|
||||
gyro->intStatus = checkMPUDataReady;
|
||||
|
||||
// 16.4 dps/lsb scalefactor
|
||||
gyro->scale = 1.0f / 16.4f;
|
||||
|
||||
return true;
|
||||
}
|
||||
|
|
|
@ -107,6 +107,11 @@ bool icm20689SpiDetect(void)
|
|||
|
||||
}
|
||||
|
||||
void icm20689AccInit(accDev_t *acc)
|
||||
{
|
||||
acc->acc_1G = 512 * 4;
|
||||
}
|
||||
|
||||
bool icm20689SpiAccDetect(accDev_t *acc)
|
||||
{
|
||||
if (mpuDetectionResult.sensor != ICM_20689_SPI) {
|
||||
|
@ -119,27 +124,6 @@ bool icm20689SpiAccDetect(accDev_t *acc)
|
|||
return true;
|
||||
}
|
||||
|
||||
bool icm20689SpiGyroDetect(gyroDev_t *gyro)
|
||||
{
|
||||
if (mpuDetectionResult.sensor != ICM_20689_SPI) {
|
||||
return false;
|
||||
}
|
||||
|
||||
gyro->init = icm20689GyroInit;
|
||||
gyro->read = mpuGyroRead;
|
||||
gyro->intStatus = checkMPUDataReady;
|
||||
|
||||
// 16.4 dps/lsb scalefactor
|
||||
gyro->scale = 1.0f / 16.4f;
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
void icm20689AccInit(accDev_t *acc)
|
||||
{
|
||||
acc->acc_1G = 512 * 4;
|
||||
}
|
||||
|
||||
void icm20689GyroInit(gyroDev_t *gyro)
|
||||
{
|
||||
mpuGyroInit(gyro);
|
||||
|
@ -174,5 +158,20 @@ void icm20689GyroInit(gyroDev_t *gyro)
|
|||
#endif
|
||||
|
||||
spiSetDivisor(ICM20689_SPI_INSTANCE, SPI_CLOCK_STANDARD);
|
||||
|
||||
}
|
||||
|
||||
bool icm20689SpiGyroDetect(gyroDev_t *gyro)
|
||||
{
|
||||
if (mpuDetectionResult.sensor != ICM_20689_SPI) {
|
||||
return false;
|
||||
}
|
||||
|
||||
gyro->init = icm20689GyroInit;
|
||||
gyro->read = mpuGyroRead;
|
||||
gyro->intStatus = checkMPUDataReady;
|
||||
|
||||
// 16.4 dps/lsb scalefactor
|
||||
gyro->scale = 1.0f / 16.4f;
|
||||
|
||||
return true;
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue