Updated sensor driver read signatures
This commit is contained in:
parent
60053e9a51
commit
1d3bfc86d4
|
@ -37,7 +37,7 @@
|
||||||
typedef struct gyroDev_s {
|
typedef struct gyroDev_s {
|
||||||
sensorGyroInitFuncPtr init; // initialize function
|
sensorGyroInitFuncPtr init; // initialize function
|
||||||
sensorGyroReadFuncPtr read; // read 3 axis data function
|
sensorGyroReadFuncPtr read; // read 3 axis data function
|
||||||
sensorReadFuncPtr temperature; // read temperature if available
|
sensorGyroReadDataFuncPtr temperature; // read temperature if available
|
||||||
sensorGyroInterruptStatusFuncPtr intStatus;
|
sensorGyroInterruptStatusFuncPtr intStatus;
|
||||||
extiCallbackRec_t exti;
|
extiCallbackRec_t exti;
|
||||||
float scale; // scalefactor
|
float scale; // scalefactor
|
||||||
|
@ -49,8 +49,9 @@ typedef struct gyroDev_s {
|
||||||
|
|
||||||
typedef struct accDev_s {
|
typedef struct accDev_s {
|
||||||
sensorAccInitFuncPtr init; // initialize function
|
sensorAccInitFuncPtr init; // initialize function
|
||||||
sensorReadFuncPtr read; // read 3 axis data function
|
sensorAccReadFuncPtr read; // read 3 axis data function
|
||||||
uint16_t acc_1G;
|
uint16_t acc_1G;
|
||||||
|
int16_t ADCRaw[XYZ_AXIS_COUNT];
|
||||||
char revisionCode; // a revision code for the sensor, if known
|
char revisionCode; // a revision code for the sensor, if known
|
||||||
sensor_align_e accAlign;
|
sensor_align_e accAlign;
|
||||||
} accDev_t;
|
} accDev_t;
|
||||||
|
|
|
@ -76,7 +76,7 @@ static void adxl345Init(accDev_t *acc)
|
||||||
|
|
||||||
uint8_t acc_samples = 0;
|
uint8_t acc_samples = 0;
|
||||||
|
|
||||||
static bool adxl345Read(int16_t *accelData)
|
static bool adxl345Read(accDev_t *acc)
|
||||||
{
|
{
|
||||||
uint8_t buf[8];
|
uint8_t buf[8];
|
||||||
|
|
||||||
|
@ -99,9 +99,9 @@ static bool adxl345Read(int16_t *accelData)
|
||||||
z += (int16_t)(buf[4] + (buf[5] << 8));
|
z += (int16_t)(buf[4] + (buf[5] << 8));
|
||||||
samples_remaining = buf[7] & 0x7F;
|
samples_remaining = buf[7] & 0x7F;
|
||||||
} while ((i < 32) && (samples_remaining > 0));
|
} while ((i < 32) && (samples_remaining > 0));
|
||||||
accelData[0] = x / i;
|
acc->ADCRaw[0] = x / i;
|
||||||
accelData[1] = y / i;
|
acc->ADCRaw[1] = y / i;
|
||||||
accelData[2] = z / i;
|
acc->ADCRaw[2] = z / i;
|
||||||
acc_samples = i;
|
acc_samples = i;
|
||||||
} else {
|
} else {
|
||||||
|
|
||||||
|
@ -109,9 +109,9 @@ static bool adxl345Read(int16_t *accelData)
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
accelData[0] = buf[0] + (buf[1] << 8);
|
acc->ADCRaw[0] = buf[0] + (buf[1] << 8);
|
||||||
accelData[1] = buf[2] + (buf[3] << 8);
|
acc->ADCRaw[1] = buf[2] + (buf[3] << 8);
|
||||||
accelData[2] = buf[4] + (buf[5] << 8);
|
acc->ADCRaw[2] = buf[4] + (buf[5] << 8);
|
||||||
}
|
}
|
||||||
|
|
||||||
return true;
|
return true;
|
||||||
|
|
|
@ -40,7 +40,7 @@ static void bma280Init(accDev_t *acc)
|
||||||
acc->acc_1G = 512 * 8;
|
acc->acc_1G = 512 * 8;
|
||||||
}
|
}
|
||||||
|
|
||||||
static bool bma280Read(int16_t *accelData)
|
static bool bma280Read(accDev_t *acc)
|
||||||
{
|
{
|
||||||
uint8_t buf[6];
|
uint8_t buf[6];
|
||||||
|
|
||||||
|
@ -49,9 +49,9 @@ static bool bma280Read(int16_t *accelData)
|
||||||
}
|
}
|
||||||
|
|
||||||
// Data format is lsb<5:0><crap><new_data_bit> | msb<13:6>
|
// Data format is lsb<5:0><crap><new_data_bit> | msb<13:6>
|
||||||
accelData[0] = (int16_t)((buf[0] >> 2) + (buf[1] << 8));
|
acc->ADCRaw[0] = (int16_t)((buf[0] >> 2) + (buf[1] << 8));
|
||||||
accelData[1] = (int16_t)((buf[2] >> 2) + (buf[3] << 8));
|
acc->ADCRaw[1] = (int16_t)((buf[2] >> 2) + (buf[3] << 8));
|
||||||
accelData[2] = (int16_t)((buf[4] >> 2) + (buf[5] << 8));
|
acc->ADCRaw[2] = (int16_t)((buf[4] >> 2) + (buf[5] << 8));
|
||||||
|
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
|
@ -51,9 +51,10 @@ static bool fakeGyroRead(gyroDev_t *gyro)
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
static bool fakeGyroReadTemperature(int16_t *tempData)
|
static bool fakeGyroReadTemperature(gyroDev_t *gyro, int16_t *temperatureData)
|
||||||
{
|
{
|
||||||
UNUSED(tempData);
|
UNUSED(gyro);
|
||||||
|
UNUSED(temperatureData);
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -91,11 +92,11 @@ void fakeAccSet(int16_t x, int16_t y, int16_t z)
|
||||||
fakeAccData[Z] = z;
|
fakeAccData[Z] = z;
|
||||||
}
|
}
|
||||||
|
|
||||||
static bool fakeAccRead(int16_t *accData)
|
static bool fakeAccRead(accDev_t *acc)
|
||||||
{
|
{
|
||||||
accData[X] = fakeAccData[X];
|
acc->ADCRaw[X] = fakeAccData[X];
|
||||||
accData[Y] = fakeAccData[Y];
|
acc->ADCRaw[Y] = fakeAccData[Y];
|
||||||
accData[Z] = fakeAccData[Z];
|
acc->ADCRaw[Z] = fakeAccData[Z];
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -133,7 +133,7 @@ void lsm303dlhcAccInit(accDev_t *acc)
|
||||||
}
|
}
|
||||||
|
|
||||||
// Read 3 gyro values into user-provided buffer. No overrun checking is done.
|
// Read 3 gyro values into user-provided buffer. No overrun checking is done.
|
||||||
static bool lsm303dlhcAccRead(int16_t *gyroADC)
|
static bool lsm303dlhcAccRead(accDev_t *acc)
|
||||||
{
|
{
|
||||||
uint8_t buf[6];
|
uint8_t buf[6];
|
||||||
|
|
||||||
|
@ -144,9 +144,9 @@ static bool lsm303dlhcAccRead(int16_t *gyroADC)
|
||||||
}
|
}
|
||||||
|
|
||||||
// the values range from -8192 to +8191
|
// the values range from -8192 to +8191
|
||||||
gyroADC[X] = (int16_t)((buf[1] << 8) | buf[0]) / 2;
|
acc->ADCRaw[X] = (int16_t)((buf[1] << 8) | buf[0]) / 2;
|
||||||
gyroADC[Y] = (int16_t)((buf[3] << 8) | buf[2]) / 2;
|
acc->ADCRaw[Y] = (int16_t)((buf[3] << 8) | buf[2]) / 2;
|
||||||
gyroADC[Z] = (int16_t)((buf[5] << 8) | buf[4]) / 2;
|
acc->ADCRaw[Z] = (int16_t)((buf[5] << 8) | buf[4]) / 2;
|
||||||
|
|
||||||
#if 0
|
#if 0
|
||||||
debug[0] = (int16_t)((buf[1] << 8) | buf[0]);
|
debug[0] = (int16_t)((buf[1] << 8) | buf[0]);
|
||||||
|
|
|
@ -111,7 +111,7 @@ static void mma8452Init(accDev_t *acc)
|
||||||
acc->acc_1G = 256;
|
acc->acc_1G = 256;
|
||||||
}
|
}
|
||||||
|
|
||||||
static bool mma8452Read(int16_t *accelData)
|
static bool mma8452Read(accDev_t *acc)
|
||||||
{
|
{
|
||||||
uint8_t buf[6];
|
uint8_t buf[6];
|
||||||
|
|
||||||
|
@ -119,9 +119,9 @@ static bool mma8452Read(int16_t *accelData)
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
accelData[0] = ((int16_t)((buf[0] << 8) | buf[1]) >> 2) / 4;
|
acc->ADCRaw[0] = ((int16_t)((buf[0] << 8) | buf[1]) >> 2) / 4;
|
||||||
accelData[1] = ((int16_t)((buf[2] << 8) | buf[3]) >> 2) / 4;
|
acc->ADCRaw[1] = ((int16_t)((buf[2] << 8) | buf[3]) >> 2) / 4;
|
||||||
accelData[2] = ((int16_t)((buf[4] << 8) | buf[5]) >> 2) / 4;
|
acc->ADCRaw[2] = ((int16_t)((buf[4] << 8) | buf[5]) >> 2) / 4;
|
||||||
|
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
|
@ -290,7 +290,7 @@ static bool mpuWriteRegisterI2C(uint8_t reg, uint8_t data)
|
||||||
return ack;
|
return ack;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool mpuAccRead(int16_t *accData)
|
bool mpuAccRead(accDev_t *acc)
|
||||||
{
|
{
|
||||||
uint8_t data[6];
|
uint8_t data[6];
|
||||||
|
|
||||||
|
@ -299,9 +299,9 @@ bool mpuAccRead(int16_t *accData)
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
accData[0] = (int16_t)((data[0] << 8) | data[1]);
|
acc->ADCRaw[X] = (int16_t)((data[0] << 8) | data[1]);
|
||||||
accData[1] = (int16_t)((data[2] << 8) | data[3]);
|
acc->ADCRaw[Y] = (int16_t)((data[2] << 8) | data[3]);
|
||||||
accData[2] = (int16_t)((data[4] << 8) | data[5]);
|
acc->ADCRaw[Z] = (int16_t)((data[4] << 8) | data[5]);
|
||||||
|
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
|
@ -186,7 +186,8 @@ extern mpuDetectionResult_t mpuDetectionResult;
|
||||||
void mpuConfigureDataReadyInterruptHandling(void);
|
void mpuConfigureDataReadyInterruptHandling(void);
|
||||||
struct gyroDev_s;
|
struct gyroDev_s;
|
||||||
void mpuGyroInit(struct gyroDev_s *gyro);
|
void mpuGyroInit(struct gyroDev_s *gyro);
|
||||||
bool mpuAccRead(int16_t *accData);
|
struct accDev_s;
|
||||||
|
bool mpuAccRead(struct accDev_s *acc);
|
||||||
bool mpuGyroRead(struct gyroDev_s *gyro);
|
bool mpuGyroRead(struct gyroDev_s *gyro);
|
||||||
mpuDetectionResult_t *mpuDetect(const extiConfig_t *configToUse);
|
mpuDetectionResult_t *mpuDetect(const extiConfig_t *configToUse);
|
||||||
bool mpuCheckDataReady(struct gyroDev_s *gyro);
|
bool mpuCheckDataReady(struct gyroDev_s *gyro);
|
||||||
|
|
|
@ -21,6 +21,7 @@
|
||||||
#include "platform.h"
|
#include "platform.h"
|
||||||
|
|
||||||
#include "common/maths.h"
|
#include "common/maths.h"
|
||||||
|
#include "common/utils.h"
|
||||||
|
|
||||||
#include "system.h"
|
#include "system.h"
|
||||||
#include "exti.h"
|
#include "exti.h"
|
||||||
|
@ -62,8 +63,9 @@ static void mpu3050Init(gyroDev_t *gyro)
|
||||||
mpuConfiguration.write(MPU3050_PWR_MGM, MPU3050_CLK_SEL_PLL_GX);
|
mpuConfiguration.write(MPU3050_PWR_MGM, MPU3050_CLK_SEL_PLL_GX);
|
||||||
}
|
}
|
||||||
|
|
||||||
static bool mpu3050ReadTemperature(int16_t *tempData)
|
static bool mpu3050ReadTemperature(gyroDev_t *gyro, int16_t *tempData)
|
||||||
{
|
{
|
||||||
|
UNUSED(gyro);
|
||||||
uint8_t buf[2];
|
uint8_t buf[2];
|
||||||
if (!mpuConfiguration.read(MPU3050_TEMP_OUT, 2, buf)) {
|
if (!mpuConfiguration.read(MPU3050_TEMP_OUT, 2, buf)) {
|
||||||
return false;
|
return false;
|
||||||
|
|
|
@ -188,7 +188,7 @@ static bool ak8963SensorWrite(uint8_t addr_, uint8_t reg_, uint8_t data)
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
static void ak8963Init()
|
static bool ak8963Init()
|
||||||
{
|
{
|
||||||
uint8_t calibration[3];
|
uint8_t calibration[3];
|
||||||
uint8_t status;
|
uint8_t status;
|
||||||
|
@ -219,6 +219,7 @@ static void ak8963Init()
|
||||||
#else
|
#else
|
||||||
ak8963SensorWrite(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_CNTL, CNTL_MODE_ONCE);
|
ak8963SensorWrite(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_CNTL, CNTL_MODE_ONCE);
|
||||||
#endif
|
#endif
|
||||||
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
static bool ak8963Read(int16_t *magData)
|
static bool ak8963Read(int16_t *magData)
|
||||||
|
|
|
@ -61,7 +61,7 @@
|
||||||
#define AK8975A_ASAY 0x11 // Fuse ROM y-axis sensitivity adjustment value
|
#define AK8975A_ASAY 0x11 // Fuse ROM y-axis sensitivity adjustment value
|
||||||
#define AK8975A_ASAZ 0x12 // Fuse ROM z-axis sensitivity adjustment value
|
#define AK8975A_ASAZ 0x12 // Fuse ROM z-axis sensitivity adjustment value
|
||||||
|
|
||||||
static void ak8975Init()
|
static bool ak8975Init()
|
||||||
{
|
{
|
||||||
uint8_t buffer[3];
|
uint8_t buffer[3];
|
||||||
uint8_t status;
|
uint8_t status;
|
||||||
|
@ -84,6 +84,7 @@ static void ak8975Init()
|
||||||
|
|
||||||
// Trigger first measurement
|
// Trigger first measurement
|
||||||
i2cWrite(MAG_I2C_INSTANCE, AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_CNTL, 0x01);
|
i2cWrite(MAG_I2C_INSTANCE, AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_CNTL, 0x01);
|
||||||
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
#define BIT_STATUS1_REG_DATA_READY (1 << 0)
|
#define BIT_STATUS1_REG_DATA_READY (1 << 0)
|
||||||
|
|
|
@ -32,12 +32,13 @@
|
||||||
|
|
||||||
static int16_t fakeMagData[XYZ_AXIS_COUNT];
|
static int16_t fakeMagData[XYZ_AXIS_COUNT];
|
||||||
|
|
||||||
static void fakeMagInit(void)
|
static bool fakeMagInit(void)
|
||||||
{
|
{
|
||||||
// initially point north
|
// initially point north
|
||||||
fakeMagData[X] = 4096;
|
fakeMagData[X] = 4096;
|
||||||
fakeMagData[Y] = 0;
|
fakeMagData[Y] = 0;
|
||||||
fakeMagData[Z] = 0;
|
fakeMagData[Z] = 0;
|
||||||
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
void fakeMagSet(int16_t x, int16_t y, int16_t z)
|
void fakeMagSet(int16_t x, int16_t y, int16_t z)
|
||||||
|
|
|
@ -184,7 +184,7 @@ static bool hmc5883lRead(int16_t *magData)
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
static void hmc5883lInit(void)
|
static bool hmc5883lInit(void)
|
||||||
{
|
{
|
||||||
int16_t magADC[3];
|
int16_t magADC[3];
|
||||||
int i;
|
int i;
|
||||||
|
@ -254,6 +254,7 @@ static void hmc5883lInit(void)
|
||||||
}
|
}
|
||||||
|
|
||||||
hmc5883lConfigureDataReadyInterruptHandling();
|
hmc5883lConfigureDataReadyInterruptHandling();
|
||||||
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool hmc5883lDetect(magDev_t* mag, const hmc5883Config_t *hmc5883ConfigToUse)
|
bool hmc5883lDetect(magDev_t* mag, const hmc5883Config_t *hmc5883ConfigToUse)
|
||||||
|
|
|
@ -29,12 +29,14 @@ typedef enum {
|
||||||
CW270_DEG_FLIP = 8
|
CW270_DEG_FLIP = 8
|
||||||
} sensor_align_e;
|
} sensor_align_e;
|
||||||
|
|
||||||
struct accDev_s;
|
typedef bool (*sensorInitFuncPtr)(void); // sensor init prototype
|
||||||
typedef void (*sensorInitFuncPtr)(void); // sensor init prototype
|
|
||||||
typedef bool (*sensorReadFuncPtr)(int16_t *data); // sensor read and align prototype
|
typedef bool (*sensorReadFuncPtr)(int16_t *data); // sensor read and align prototype
|
||||||
typedef void (*sensorAccInitFuncPtr)(struct accDev_s *acc); // sensor init prototype
|
typedef bool (*sensorInterruptFuncPtr)(void);
|
||||||
|
struct accDev_s;
|
||||||
|
typedef void (*sensorAccInitFuncPtr)(struct accDev_s *acc);
|
||||||
|
typedef bool (*sensorAccReadFuncPtr)(struct accDev_s *acc);
|
||||||
struct gyroDev_s;
|
struct gyroDev_s;
|
||||||
typedef void (*sensorGyroInitFuncPtr)(struct gyroDev_s *gyro);
|
typedef void (*sensorGyroInitFuncPtr)(struct gyroDev_s *gyro);
|
||||||
typedef bool (*sensorGyroReadFuncPtr)(struct gyroDev_s *gyro);
|
typedef bool (*sensorGyroReadFuncPtr)(struct gyroDev_s *gyro);
|
||||||
|
typedef bool (*sensorGyroReadDataFuncPtr)(struct gyroDev_s *gyro, int16_t *data);
|
||||||
typedef bool (*sensorGyroInterruptStatusFuncPtr)(struct gyroDev_s *gyro);
|
typedef bool (*sensorGyroInterruptStatusFuncPtr)(struct gyroDev_s *gyro);
|
||||||
typedef bool (*sensorInterruptFuncPtr)(void);
|
|
||||||
|
|
|
@ -693,7 +693,7 @@ void subTaskMainSubprocesses(void)
|
||||||
|
|
||||||
// Read out gyro temperature. can use it for something somewhere. maybe get MCU temperature instead? lots of fun possibilities.
|
// Read out gyro temperature. can use it for something somewhere. maybe get MCU temperature instead? lots of fun possibilities.
|
||||||
if (gyro.dev.temperature) {
|
if (gyro.dev.temperature) {
|
||||||
gyro.dev.temperature(&telemTemperature1);
|
gyro.dev.temperature(&gyro.dev, &telemTemperature1);
|
||||||
}
|
}
|
||||||
|
|
||||||
#ifdef MAG
|
#ifdef MAG
|
||||||
|
|
|
@ -379,15 +379,13 @@ static void applyAccelerationTrims(const flightDynamicsTrims_t *accelerationTrim
|
||||||
|
|
||||||
void updateAccelerationReadings(rollAndPitchTrims_t *rollAndPitchTrims)
|
void updateAccelerationReadings(rollAndPitchTrims_t *rollAndPitchTrims)
|
||||||
{
|
{
|
||||||
int16_t accADCRaw[XYZ_AXIS_COUNT];
|
if (!acc.dev.read(&acc.dev)) {
|
||||||
|
|
||||||
if (!acc.dev.read(accADCRaw)) {
|
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) {
|
for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) {
|
||||||
DEBUG_SET(DEBUG_ACCELEROMETER, axis, accADCRaw[axis]);
|
DEBUG_SET(DEBUG_ACCELEROMETER, axis, acc.dev.ADCRaw[axis]);
|
||||||
acc.accSmooth[axis] = accADCRaw[axis];
|
acc.accSmooth[axis] = acc.dev.ADCRaw[axis];
|
||||||
}
|
}
|
||||||
|
|
||||||
if (accLpfCutHz) {
|
if (accLpfCutHz) {
|
||||||
|
|
Loading…
Reference in New Issue