Merge pull request #3045 from martinbudden/bf_accgyro_fnptr_rename
Add Fn suffix to accgyro function pointers
This commit is contained in:
commit
a518531c3f
|
@ -47,11 +47,11 @@ typedef enum {
|
|||
} gyroRateKHz_e;
|
||||
|
||||
typedef struct gyroDev_s {
|
||||
sensorGyroInitFuncPtr init; // initialize function
|
||||
sensorGyroReadFuncPtr read; // read 3 axis data function
|
||||
sensorGyroReadDataFuncPtr temperature; // read temperature if available
|
||||
sensorGyroInterruptStatusFuncPtr intStatus;
|
||||
sensorGyroUpdateFuncPtr update;
|
||||
sensorGyroInitFuncPtr initFn; // initialize function
|
||||
sensorGyroReadFuncPtr readFn; // read 3 axis data function
|
||||
sensorGyroReadDataFuncPtr temperatureFn; // read temperature if available
|
||||
sensorGyroInterruptStatusFuncPtr intStatusFn;
|
||||
sensorGyroUpdateFuncPtr updateFn;
|
||||
extiCallbackRec_t exti;
|
||||
busDevice_t bus;
|
||||
float scale; // scalefactor
|
||||
|
@ -72,8 +72,8 @@ typedef struct gyroDev_s {
|
|||
} gyroDev_t;
|
||||
|
||||
typedef struct accDev_s {
|
||||
sensorAccInitFuncPtr init; // initialize function
|
||||
sensorAccReadFuncPtr read; // read 3 axis data function
|
||||
sensorAccInitFuncPtr initFn; // initialize function
|
||||
sensorAccReadFuncPtr readFn; // read 3 axis data function
|
||||
busDevice_t bus;
|
||||
uint16_t acc_1G;
|
||||
int16_t ADCRaw[XYZ_AXIS_COUNT];
|
||||
|
|
|
@ -128,7 +128,7 @@ bool adxl345Detect(drv_adxl345_config_t *init, accDev_t *acc)
|
|||
// use ADXL345's fifo to filter data or not
|
||||
useFifo = init->useFifo;
|
||||
|
||||
acc->init = adxl345Init;
|
||||
acc->read = adxl345Read;
|
||||
acc->initFn = adxl345Init;
|
||||
acc->readFn = adxl345Read;
|
||||
return true;
|
||||
}
|
||||
|
|
|
@ -64,7 +64,7 @@ bool bma280Detect(accDev_t *acc)
|
|||
if (!ack || sig != 0xFB)
|
||||
return false;
|
||||
|
||||
acc->init = bma280Init;
|
||||
acc->read = bma280Read;
|
||||
acc->initFn = bma280Init;
|
||||
acc->readFn = bma280Read;
|
||||
return true;
|
||||
}
|
||||
|
|
|
@ -91,10 +91,10 @@ static bool fakeGyroInitStatus(gyroDev_t *gyro)
|
|||
|
||||
bool fakeGyroDetect(gyroDev_t *gyro)
|
||||
{
|
||||
gyro->init = fakeGyroInit;
|
||||
gyro->intStatus = fakeGyroInitStatus;
|
||||
gyro->read = fakeGyroRead;
|
||||
gyro->temperature = fakeGyroReadTemperature;
|
||||
gyro->initFn = fakeGyroInit;
|
||||
gyro->intStatusFn = fakeGyroInitStatus;
|
||||
gyro->readFn = fakeGyroRead;
|
||||
gyro->temperatureFn = fakeGyroReadTemperature;
|
||||
#if defined(SIMULATOR_BUILD)
|
||||
gyro->scale = 1.0f / 16.4f;
|
||||
#else
|
||||
|
@ -152,8 +152,8 @@ static bool fakeAccRead(accDev_t *acc)
|
|||
|
||||
bool fakeAccDetect(accDev_t *acc)
|
||||
{
|
||||
acc->init = fakeAccInit;
|
||||
acc->read = fakeAccRead;
|
||||
acc->initFn = fakeAccInit;
|
||||
acc->readFn = fakeAccRead;
|
||||
acc->revisionCode = 0;
|
||||
return true;
|
||||
}
|
||||
|
|
|
@ -112,8 +112,8 @@ bool l3g4200dDetect(gyroDev_t *gyro)
|
|||
if (deviceid != L3G4200D_ID)
|
||||
return false;
|
||||
|
||||
gyro->init = l3g4200dInit;
|
||||
gyro->read = l3g4200dRead;
|
||||
gyro->initFn = l3g4200dInit;
|
||||
gyro->readFn = l3g4200dRead;
|
||||
|
||||
// 14.2857dps/lsb scalefactor
|
||||
gyro->scale = 1.0f / 14.2857f;
|
||||
|
|
|
@ -152,8 +152,8 @@ static bool l3gd20GyroRead(gyroDev_t *gyro)
|
|||
|
||||
bool l3gd20Detect(gyroDev_t *gyro)
|
||||
{
|
||||
gyro->init = l3gd20GyroInit;
|
||||
gyro->read = l3gd20GyroRead;
|
||||
gyro->initFn = l3gd20GyroInit;
|
||||
gyro->readFn = l3gd20GyroRead;
|
||||
|
||||
gyro->scale = L3GD20_GYRO_SCALE_FACTOR;
|
||||
|
||||
|
|
|
@ -166,8 +166,8 @@ bool lsm303dlhcAccDetect(accDev_t *acc)
|
|||
if (!ack)
|
||||
return false;
|
||||
|
||||
acc->init = lsm303dlhcAccInit;
|
||||
acc->read = lsm303dlhcAccRead;
|
||||
acc->initFn = lsm303dlhcAccInit;
|
||||
acc->readFn = lsm303dlhcAccRead;
|
||||
return true;
|
||||
}
|
||||
#endif
|
||||
|
|
|
@ -132,8 +132,8 @@ bool mma8452Detect(accDev_t *acc)
|
|||
if (!ack || (sig != MMA8452_DEVICE_SIGNATURE && sig != MMA8451_DEVICE_SIGNATURE))
|
||||
return false;
|
||||
|
||||
acc->init = mma8452Init;
|
||||
acc->read = mma8452Read;
|
||||
acc->initFn = mma8452Init;
|
||||
acc->readFn = mma8452Read;
|
||||
device_id = sig;
|
||||
return true;
|
||||
}
|
||||
|
|
|
@ -118,8 +118,8 @@ static void mpuIntExtiHandler(extiCallbackRec_t *cb)
|
|||
#endif
|
||||
gyroDev_t *gyro = container_of(cb, gyroDev_t, exti);
|
||||
gyro->dataReady = true;
|
||||
if (gyro->update) {
|
||||
gyro->update(gyro);
|
||||
if (gyro->updateFn) {
|
||||
gyro->updateFn(gyro);
|
||||
}
|
||||
#ifdef DEBUG_MPU_DATA_READY_INTERRUPT
|
||||
const uint32_t now2Us = micros();
|
||||
|
@ -196,7 +196,7 @@ bool mpuAccRead(accDev_t *acc)
|
|||
void mpuGyroSetIsrUpdate(gyroDev_t *gyro, sensorGyroUpdateFuncPtr updateFn)
|
||||
{
|
||||
ATOMIC_BLOCK(NVIC_PRIO_MPU_INT_EXTI) {
|
||||
gyro->update = updateFn;
|
||||
gyro->updateFn = updateFn;
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -80,10 +80,10 @@ bool mpu3050Detect(gyroDev_t *gyro)
|
|||
if (gyro->mpuDetectionResult.sensor != MPU_3050) {
|
||||
return false;
|
||||
}
|
||||
gyro->init = mpu3050Init;
|
||||
gyro->read = mpuGyroRead;
|
||||
gyro->temperature = mpu3050ReadTemperature;
|
||||
gyro->intStatus = mpuCheckDataReady;
|
||||
gyro->initFn = mpu3050Init;
|
||||
gyro->readFn = mpuGyroRead;
|
||||
gyro->temperatureFn = mpu3050ReadTemperature;
|
||||
gyro->intStatusFn = mpuCheckDataReady;
|
||||
|
||||
// 16.4 dps/lsb scalefactor
|
||||
gyro->scale = 1.0f / 16.4f;
|
||||
|
|
|
@ -68,8 +68,8 @@ bool mpu6050AccDetect(accDev_t *acc)
|
|||
return false;
|
||||
}
|
||||
|
||||
acc->init = mpu6050AccInit;
|
||||
acc->read = mpuAccRead;
|
||||
acc->initFn = mpu6050AccInit;
|
||||
acc->readFn = mpuAccRead;
|
||||
acc->revisionCode = (acc->mpuDetectionResult.resolution == MPU_HALF_RESOLUTION ? 'o' : 'n'); // es/non-es variance between MPU6050 sensors, half of the naze boards are mpu6000ES.
|
||||
|
||||
return true;
|
||||
|
@ -104,9 +104,9 @@ bool mpu6050GyroDetect(gyroDev_t *gyro)
|
|||
if (gyro->mpuDetectionResult.sensor != MPU_60x0) {
|
||||
return false;
|
||||
}
|
||||
gyro->init = mpu6050GyroInit;
|
||||
gyro->read = mpuGyroRead;
|
||||
gyro->intStatus = mpuCheckDataReady;
|
||||
gyro->initFn = mpu6050GyroInit;
|
||||
gyro->readFn = mpuGyroRead;
|
||||
gyro->intStatusFn = mpuCheckDataReady;
|
||||
|
||||
// 16.4 dps/lsb scalefactor
|
||||
gyro->scale = 1.0f / 16.4f;
|
||||
|
|
|
@ -45,8 +45,8 @@ bool mpu6500AccDetect(accDev_t *acc)
|
|||
return false;
|
||||
}
|
||||
|
||||
acc->init = mpu6500AccInit;
|
||||
acc->read = mpuAccRead;
|
||||
acc->initFn = mpu6500AccInit;
|
||||
acc->readFn = mpuAccRead;
|
||||
|
||||
return true;
|
||||
}
|
||||
|
@ -93,9 +93,9 @@ bool mpu6500GyroDetect(gyroDev_t *gyro)
|
|||
return false;
|
||||
}
|
||||
|
||||
gyro->init = mpu6500GyroInit;
|
||||
gyro->read = mpuGyroRead;
|
||||
gyro->intStatus = mpuCheckDataReady;
|
||||
gyro->initFn = mpu6500GyroInit;
|
||||
gyro->readFn = mpuGyroRead;
|
||||
gyro->intStatusFn = mpuCheckDataReady;
|
||||
|
||||
// 16.4 dps/lsb scalefactor
|
||||
gyro->scale = 1.0f / 16.4f;
|
||||
|
|
|
@ -437,8 +437,8 @@ bool bmi160SpiAccDetect(accDev_t *acc)
|
|||
return false;
|
||||
}
|
||||
|
||||
acc->init = bmi160SpiAccInit;
|
||||
acc->read = bmi160AccRead;
|
||||
acc->initFn = bmi160SpiAccInit;
|
||||
acc->readFn = bmi160AccRead;
|
||||
|
||||
return true;
|
||||
}
|
||||
|
@ -450,9 +450,9 @@ bool bmi160SpiGyroDetect(gyroDev_t *gyro)
|
|||
return false;
|
||||
}
|
||||
|
||||
gyro->init = bmi160SpiGyroInit;
|
||||
gyro->read = bmi160GyroRead;
|
||||
gyro->intStatus = checkBMI160DataReady;
|
||||
gyro->initFn = bmi160SpiGyroInit;
|
||||
gyro->readFn = bmi160GyroRead;
|
||||
gyro->intStatusFn = checkBMI160DataReady;
|
||||
gyro->scale = 1.0f / 16.4f;
|
||||
|
||||
return true;
|
||||
|
|
|
@ -115,8 +115,8 @@ bool icm20689SpiAccDetect(accDev_t *acc)
|
|||
return false;
|
||||
}
|
||||
|
||||
acc->init = icm20689AccInit;
|
||||
acc->read = mpuAccRead;
|
||||
acc->initFn = icm20689AccInit;
|
||||
acc->readFn = mpuAccRead;
|
||||
|
||||
return true;
|
||||
}
|
||||
|
@ -164,9 +164,9 @@ bool icm20689SpiGyroDetect(gyroDev_t *gyro)
|
|||
return false;
|
||||
}
|
||||
|
||||
gyro->init = icm20689GyroInit;
|
||||
gyro->read = mpuGyroRead;
|
||||
gyro->intStatus = mpuCheckDataReady;
|
||||
gyro->initFn = icm20689GyroInit;
|
||||
gyro->readFn = mpuGyroRead;
|
||||
gyro->intStatusFn = mpuCheckDataReady;
|
||||
|
||||
// 16.4 dps/lsb scalefactor
|
||||
gyro->scale = 1.0f / 16.4f;
|
||||
|
|
|
@ -255,8 +255,8 @@ bool mpu6000SpiAccDetect(accDev_t *acc)
|
|||
return false;
|
||||
}
|
||||
|
||||
acc->init = mpu6000SpiAccInit;
|
||||
acc->read = mpuAccRead;
|
||||
acc->initFn = mpu6000SpiAccInit;
|
||||
acc->readFn = mpuAccRead;
|
||||
|
||||
return true;
|
||||
}
|
||||
|
@ -267,9 +267,9 @@ bool mpu6000SpiGyroDetect(gyroDev_t *gyro)
|
|||
return false;
|
||||
}
|
||||
|
||||
gyro->init = mpu6000SpiGyroInit;
|
||||
gyro->read = mpuGyroRead;
|
||||
gyro->intStatus = mpuCheckDataReady;
|
||||
gyro->initFn = mpu6000SpiGyroInit;
|
||||
gyro->readFn = mpuGyroRead;
|
||||
gyro->intStatusFn = mpuCheckDataReady;
|
||||
// 16.4 dps/lsb scalefactor
|
||||
gyro->scale = 1.0f / 16.4f;
|
||||
|
||||
|
|
|
@ -147,8 +147,8 @@ bool mpu6500SpiAccDetect(accDev_t *acc)
|
|||
return false;
|
||||
}
|
||||
|
||||
acc->init = mpu6500SpiAccInit;
|
||||
acc->read = mpuAccRead;
|
||||
acc->initFn = mpu6500SpiAccInit;
|
||||
acc->readFn = mpuAccRead;
|
||||
|
||||
return true;
|
||||
}
|
||||
|
@ -166,9 +166,9 @@ bool mpu6500SpiGyroDetect(gyroDev_t *gyro)
|
|||
return false;
|
||||
}
|
||||
|
||||
gyro->init = mpu6500SpiGyroInit;
|
||||
gyro->read = mpuGyroRead;
|
||||
gyro->intStatus = mpuCheckDataReady;
|
||||
gyro->initFn = mpu6500SpiGyroInit;
|
||||
gyro->readFn = mpuGyroRead;
|
||||
gyro->intStatusFn = mpuCheckDataReady;
|
||||
|
||||
// 16.4 dps/lsb scalefactor
|
||||
gyro->scale = 1.0f / 16.4f;
|
||||
|
|
|
@ -214,8 +214,8 @@ bool mpu9250SpiAccDetect(accDev_t *acc)
|
|||
return false;
|
||||
}
|
||||
|
||||
acc->init = mpu9250SpiAccInit;
|
||||
acc->read = mpuAccRead;
|
||||
acc->initFn = mpu9250SpiAccInit;
|
||||
acc->readFn = mpuAccRead;
|
||||
|
||||
return true;
|
||||
}
|
||||
|
@ -226,9 +226,9 @@ bool mpu9250SpiGyroDetect(gyroDev_t *gyro)
|
|||
return false;
|
||||
}
|
||||
|
||||
gyro->init = mpu9250SpiGyroInit;
|
||||
gyro->read = mpuGyroRead;
|
||||
gyro->intStatus = mpuCheckDataReady;
|
||||
gyro->initFn = mpu9250SpiGyroInit;
|
||||
gyro->readFn = mpuGyroRead;
|
||||
gyro->intStatusFn = mpuCheckDataReady;
|
||||
|
||||
// 16.4 dps/lsb scalefactor
|
||||
gyro->scale = 1.0f / 16.4f;
|
||||
|
|
|
@ -17,9 +17,9 @@
|
|||
|
||||
bool gyroSyncCheckUpdate(gyroDev_t *gyro)
|
||||
{
|
||||
if (!gyro->intStatus)
|
||||
if (!gyro->intStatusFn)
|
||||
return false;
|
||||
return gyro->intStatus(gyro);
|
||||
return gyro->intStatusFn(gyro);
|
||||
}
|
||||
|
||||
uint32_t gyroSetSampleRate(gyroDev_t *gyro, uint8_t lpf, uint8_t gyroSyncDenominator, bool gyro_use_32khz)
|
||||
|
|
|
@ -311,7 +311,7 @@ bool accInit(uint32_t gyroSamplingInverval)
|
|||
return false;
|
||||
}
|
||||
acc.dev.acc_1G = 256; // set default
|
||||
acc.dev.init(&acc.dev); // driver initialisation
|
||||
acc.dev.initFn(&acc.dev); // driver initialisation
|
||||
// set the acc sampling interval according to the gyro sampling interval
|
||||
switch (gyroSamplingInverval) { // Switch statement kept in place to change acc sampling interval in the future
|
||||
case 500:
|
||||
|
@ -453,7 +453,7 @@ static void applyAccelerationTrims(const flightDynamicsTrims_t *accelerationTrim
|
|||
|
||||
void accUpdate(rollAndPitchTrims_t *rollAndPitchTrims)
|
||||
{
|
||||
if (!acc.dev.read(&acc.dev)) {
|
||||
if (!acc.dev.readFn(&acc.dev)) {
|
||||
return;
|
||||
}
|
||||
acc.isAccelUpdatedAtLeastOnce = true;
|
||||
|
|
|
@ -329,7 +329,7 @@ bool gyroInit(void)
|
|||
// Must set gyro targetLooptime before gyroDev.init and initialisation of filters
|
||||
gyro.targetLooptime = gyroSetSampleRate(&gyroDev0, gyroConfig()->gyro_lpf, gyroConfig()->gyro_sync_denom, gyroConfig()->gyro_use_32khz);
|
||||
gyroDev0.lpf = gyroConfig()->gyro_lpf;
|
||||
gyroDev0.init(&gyroDev0);
|
||||
gyroDev0.initFn(&gyroDev0);
|
||||
if (gyroConfig()->gyro_align != ALIGN_DEFAULT) {
|
||||
gyroDev0.gyroAlign = gyroConfig()->gyro_align;
|
||||
}
|
||||
|
@ -481,7 +481,7 @@ STATIC_UNIT_TESTED void performGyroCalibration(gyroDev_t *gyroDev, gyroCalibrati
|
|||
#if defined(GYRO_USES_SPI) && defined(USE_MPU_DATA_READY_SIGNAL)
|
||||
static bool gyroUpdateISR(gyroDev_t* gyroDev)
|
||||
{
|
||||
if (!gyroDev->dataReady || !gyroDev->read(gyroDev)) {
|
||||
if (!gyroDev->dataReady || !gyroDev->readFn(gyroDev)) {
|
||||
return false;
|
||||
}
|
||||
#ifdef DEBUG_MPU_DATA_READY_INTERRUPT
|
||||
|
@ -513,11 +513,11 @@ static bool gyroUpdateISR(gyroDev_t* gyroDev)
|
|||
void gyroUpdate(void)
|
||||
{
|
||||
// range: +/- 8192; +/- 2000 deg/sec
|
||||
if (gyroDev0.update) {
|
||||
if (gyroDev0.updateFn) {
|
||||
// if the gyro update function is set then return, since the gyro is read in gyroUpdateISR
|
||||
return;
|
||||
}
|
||||
if (!gyroDev0.read(&gyroDev0)) {
|
||||
if (!gyroDev0.readFn(&gyroDev0)) {
|
||||
return;
|
||||
}
|
||||
gyroDev0.dataReady = false;
|
||||
|
@ -571,8 +571,8 @@ void gyroUpdate(void)
|
|||
|
||||
void gyroReadTemperature(void)
|
||||
{
|
||||
if (gyroDev0.temperature) {
|
||||
gyroDev0.temperature(&gyroDev0, &gyroTemperature0);
|
||||
if (gyroDev0.temperatureFn) {
|
||||
gyroDev0.temperatureFn(&gyroDev0, &gyroTemperature0);
|
||||
}
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue