1
0
Fork 0
mirror of https://github.com/iNavFlight/inav.git synced 2025-07-25 17:25:18 +03:00

Changed accRead to use accDev_t parameter

This commit is contained in:
Martin Budden 2016-12-12 16:04:58 +00:00
parent 9b4a11612b
commit 115b1e76f9
9 changed files with 35 additions and 33 deletions

View file

@ -36,7 +36,7 @@
typedef struct gyroDev_s {
sensorGyroInitFuncPtr init; // initialize function
sensorGyroReadFuncPtr read; // read 3 axis data function
sensorGyroReadFuncPtr read; // read 3 axis data function
sensorReadFuncPtr temperature; // read temperature if available
sensorGyroInterruptStatusFuncPtr intStatus;
float scale; // scalefactor
@ -48,9 +48,10 @@ typedef struct gyroDev_s {
} gyroDev_t;
typedef struct accDev_s {
sensorAccInitFuncPtr init; // initialize function
sensorReadFuncPtr read; // read 3 axis data function
sensorAccInitFuncPtr init; // initialize function
sensorAccReadFuncPtr read; // read 3 axis data function
uint16_t acc_1G;
int16_t ADCRaw[XYZ_AXIS_COUNT];
char revisionCode; // a revision code for the sensor, if known
sensor_align_e accAlign;
} accDev_t;

View file

@ -76,7 +76,7 @@ static void adxl345Init(accDev_t *acc)
uint8_t acc_samples = 0;
static bool adxl345Read(int16_t *accelData)
static bool adxl345Read(accDev_t *acc)
{
uint8_t buf[8];
@ -99,9 +99,9 @@ static bool adxl345Read(int16_t *accelData)
z += (int16_t)(buf[4] + (buf[5] << 8));
samples_remaining = buf[7] & 0x7F;
} while ((i < 32) && (samples_remaining > 0));
accelData[0] = x / i;
accelData[1] = y / i;
accelData[2] = z / i;
acc->ADCRaw[0] = x / i;
acc->ADCRaw[1] = y / i;
acc->ADCRaw[2] = z / i;
acc_samples = i;
} else {
@ -109,9 +109,9 @@ static bool adxl345Read(int16_t *accelData)
return false;
}
accelData[0] = buf[0] + (buf[1] << 8);
accelData[1] = buf[2] + (buf[3] << 8);
accelData[2] = buf[4] + (buf[5] << 8);
acc->ADCRaw[0] = buf[0] + (buf[1] << 8);
acc->ADCRaw[1] = buf[2] + (buf[3] << 8);
acc->ADCRaw[2] = buf[4] + (buf[5] << 8);
}
return true;

View file

@ -40,7 +40,7 @@ static void bma280Init(accDev_t *acc)
acc->acc_1G = 512 * 8;
}
static bool bma280Read(int16_t *accelData)
static bool bma280Read(accDev_t *acc)
{
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>
accelData[0] = (int16_t)((buf[0] >> 2) + (buf[1] << 8));
accelData[1] = (int16_t)((buf[2] >> 2) + (buf[3] << 8));
accelData[2] = (int16_t)((buf[4] >> 2) + (buf[5] << 8));
acc->ADCRaw[0] = (int16_t)((buf[0] >> 2) + (buf[1] << 8));
acc->ADCRaw[1] = (int16_t)((buf[2] >> 2) + (buf[3] << 8));
acc->ADCRaw[2] = (int16_t)((buf[4] >> 2) + (buf[5] << 8));
return true;
}

View file

@ -91,11 +91,11 @@ void fakeAccSet(int16_t x, int16_t y, int16_t z)
fakeAccData[Z] = z;
}
static bool fakeAccRead(int16_t *accData)
static bool fakeAccRead(accDev_t *acc)
{
accData[X] = fakeAccData[X];
accData[Y] = fakeAccData[Y];
accData[Z] = fakeAccData[Z];
acc->ADCRaw[X] = fakeAccData[X];
acc->ADCRaw[Y] = fakeAccData[Y];
acc->ADCRaw[Z] = fakeAccData[Z];
return true;
}

View file

@ -111,7 +111,7 @@ static void mma8452Init(accDev_t *acc)
acc->acc_1G = 256;
}
static bool mma8452Read(int16_t *accelData)
static bool mma8452Read(accDev_t *acc)
{
uint8_t buf[6];
@ -119,9 +119,9 @@ static bool mma8452Read(int16_t *accelData)
return false;
}
accelData[0] = ((int16_t)((buf[0] << 8) | buf[1]) >> 2) / 4;
accelData[1] = ((int16_t)((buf[2] << 8) | buf[3]) >> 2) / 4;
accelData[2] = ((int16_t)((buf[4] << 8) | buf[5]) >> 2) / 4;
acc->ADCRaw[0] = ((int16_t)((buf[0] << 8) | buf[1]) >> 2) / 4;
acc->ADCRaw[1] = ((int16_t)((buf[2] << 8) | buf[3]) >> 2) / 4;
acc->ADCRaw[2] = ((int16_t)((buf[4] << 8) | buf[5]) >> 2) / 4;
return true;
}

View file

@ -292,7 +292,7 @@ static bool mpuWriteRegisterI2C(uint8_t reg, uint8_t data)
return ack;
}
bool mpuAccRead(int16_t *accData)
bool mpuAccRead(accDev_t *acc)
{
uint8_t data[6];
@ -301,9 +301,9 @@ bool mpuAccRead(int16_t *accData)
return false;
}
accData[0] = (int16_t)((data[0] << 8) | data[1]);
accData[1] = (int16_t)((data[2] << 8) | data[3]);
accData[2] = (int16_t)((data[4] << 8) | data[5]);
acc->ADCRaw[X] = (int16_t)((data[0] << 8) | data[1]);
acc->ADCRaw[Y] = (int16_t)((data[2] << 8) | data[3]);
acc->ADCRaw[Z] = (int16_t)((data[4] << 8) | data[5]);
return true;
}

View file

@ -185,7 +185,8 @@ extern mpuDetectionResult_t mpuDetectionResult;
struct gyroDev_s;
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);
mpuDetectionResult_t *mpuDetect(void);
bool mpuCheckDataReady(struct gyroDev_s *gyro);

View file

@ -29,12 +29,13 @@ typedef enum {
CW270_DEG_FLIP = 8
} sensor_align_e;
struct accDev_s;
typedef bool (*sensorInitFuncPtr)(void); // sensor init 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;
typedef void (*sensorGyroInitFuncPtr)(struct gyroDev_s *gyro);
typedef bool (*sensorGyroReadFuncPtr)(struct gyroDev_s *gyro);
typedef bool (*sensorGyroInterruptStatusFuncPtr)(struct gyroDev_s *gyro);
typedef bool (*sensorInterruptFuncPtr)(void);

View file

@ -62,7 +62,6 @@
acc_t acc; // acc access functions
static uint16_t calibratingA = 0; // the calibration is done is the main loop. Calibrating decreases at each cycle down to 0, then we enter in a normal mode.
static int16_t accADCRaw[XYZ_AXIS_COUNT];
static flightDynamicsTrims_t * accZero;
static flightDynamicsTrims_t * accGain;
@ -359,12 +358,12 @@ static void applyAccelerationZero(const flightDynamicsTrims_t * accZero, const f
void updateAccelerationReadings(void)
{
if (!acc.dev.read(accADCRaw)) {
if (!acc.dev.read(&acc.dev)) {
return;
}
for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) {
acc.accADC[axis] = accADCRaw[axis];
acc.accADC[axis] = acc.dev.ADCRaw[axis];
}
if (accLpfCutHz) {