mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-17 21:35:44 +03:00
Acc fn/variable renames to align with iNav
This commit is contained in:
parent
ff0628193f
commit
d90b42970c
10 changed files with 39 additions and 40 deletions
|
@ -231,11 +231,10 @@ retry:
|
|||
case ACC_ICM20608G:
|
||||
#if defined(USE_ACC_MPU6500) || defined(USE_ACC_SPI_MPU6500)
|
||||
#ifdef USE_ACC_SPI_MPU6500
|
||||
if (mpu6500AccDetect(dev) || mpu6500SpiAccDetect(dev))
|
||||
if (mpu6500AccDetect(dev) || mpu6500SpiAccDetect(dev)) {
|
||||
#else
|
||||
if (mpu6500AccDetect(dev))
|
||||
if (mpu6500AccDetect(dev)) {
|
||||
#endif
|
||||
{
|
||||
#ifdef ACC_MPU6500_ALIGN
|
||||
dev->accAlign = ACC_MPU6500_ALIGN;
|
||||
#endif
|
||||
|
@ -371,7 +370,7 @@ void accSetCalibrationCycles(uint16_t calibrationCyclesRequired)
|
|||
calibratingA = calibrationCyclesRequired;
|
||||
}
|
||||
|
||||
bool isAccelerationCalibrationComplete(void)
|
||||
bool accIsCalibrationComplete(void)
|
||||
{
|
||||
return calibratingA == 0;
|
||||
}
|
||||
|
@ -393,14 +392,15 @@ static void performAcclerationCalibration(rollAndPitchTrims_t *rollAndPitchTrims
|
|||
for (int axis = 0; axis < 3; axis++) {
|
||||
|
||||
// Reset a[axis] at start of calibration
|
||||
if (isOnFirstAccelerationCalibrationCycle())
|
||||
if (isOnFirstAccelerationCalibrationCycle()) {
|
||||
a[axis] = 0;
|
||||
}
|
||||
|
||||
// Sum up CALIBRATING_ACC_CYCLES readings
|
||||
a[axis] += acc.accSmooth[axis];
|
||||
a[axis] += acc.accADC[axis];
|
||||
|
||||
// Reset global variables to prevent other code from using un-calibrated data
|
||||
acc.accSmooth[axis] = 0;
|
||||
acc.accADC[axis] = 0;
|
||||
accelerationTrims->raw[axis] = 0;
|
||||
}
|
||||
|
||||
|
@ -420,7 +420,6 @@ static void performAcclerationCalibration(rollAndPitchTrims_t *rollAndPitchTrims
|
|||
|
||||
static void performInflightAccelerationCalibration(rollAndPitchTrims_t *rollAndPitchTrims)
|
||||
{
|
||||
uint8_t axis;
|
||||
static int32_t b[3];
|
||||
static int16_t accZero_saved[3] = { 0, 0, 0 };
|
||||
static rollAndPitchTrims_t angleTrim_saved = { { 0, 0 } };
|
||||
|
@ -434,14 +433,14 @@ static void performInflightAccelerationCalibration(rollAndPitchTrims_t *rollAndP
|
|||
angleTrim_saved.values.pitch = rollAndPitchTrims->values.pitch;
|
||||
}
|
||||
if (InflightcalibratingA > 0) {
|
||||
for (axis = 0; axis < 3; axis++) {
|
||||
for (int axis = 0; axis < 3; axis++) {
|
||||
// Reset a[axis] at start of calibration
|
||||
if (InflightcalibratingA == 50)
|
||||
b[axis] = 0;
|
||||
// Sum up 50 readings
|
||||
b[axis] += acc.accSmooth[axis];
|
||||
b[axis] += acc.accADC[axis];
|
||||
// Clear global variables for next reading
|
||||
acc.accSmooth[axis] = 0;
|
||||
acc.accADC[axis] = 0;
|
||||
accelerationTrims->raw[axis] = 0;
|
||||
}
|
||||
// all values are measured
|
||||
|
@ -473,9 +472,9 @@ static void performInflightAccelerationCalibration(rollAndPitchTrims_t *rollAndP
|
|||
|
||||
static void applyAccelerationTrims(const flightDynamicsTrims_t *accelerationTrims)
|
||||
{
|
||||
acc.accSmooth[X] -= accelerationTrims->raw[X];
|
||||
acc.accSmooth[Y] -= accelerationTrims->raw[Y];
|
||||
acc.accSmooth[Z] -= accelerationTrims->raw[Z];
|
||||
acc.accADC[X] -= accelerationTrims->raw[X];
|
||||
acc.accADC[Y] -= accelerationTrims->raw[Y];
|
||||
acc.accADC[Z] -= accelerationTrims->raw[Z];
|
||||
}
|
||||
|
||||
void accUpdate(timeUs_t currentTimeUs, rollAndPitchTrims_t *rollAndPitchTrims)
|
||||
|
@ -489,18 +488,18 @@ void accUpdate(timeUs_t currentTimeUs, rollAndPitchTrims_t *rollAndPitchTrims)
|
|||
|
||||
for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) {
|
||||
DEBUG_SET(DEBUG_ACCELEROMETER, axis, acc.dev.ADCRaw[axis]);
|
||||
acc.accSmooth[axis] = acc.dev.ADCRaw[axis];
|
||||
acc.accADC[axis] = acc.dev.ADCRaw[axis];
|
||||
}
|
||||
|
||||
if (accLpfCutHz) {
|
||||
for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) {
|
||||
acc.accSmooth[axis] = lrintf(biquadFilterApply(&accFilter[axis], (float)acc.accSmooth[axis]));
|
||||
acc.accADC[axis] = lrintf(biquadFilterApply(&accFilter[axis], (float)acc.accADC[axis]));
|
||||
}
|
||||
}
|
||||
|
||||
alignSensors(acc.accSmooth, acc.dev.accAlign);
|
||||
alignSensors(acc.accADC, acc.dev.accAlign);
|
||||
|
||||
if (!isAccelerationCalibrationComplete()) {
|
||||
if (!accIsCalibrationComplete()) {
|
||||
performAcclerationCalibration(rollAndPitchTrims);
|
||||
}
|
||||
|
||||
|
@ -512,7 +511,7 @@ void accUpdate(timeUs_t currentTimeUs, rollAndPitchTrims_t *rollAndPitchTrims)
|
|||
|
||||
++accumulatedMeasurementCount;
|
||||
for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) {
|
||||
accumulatedMeasurements[axis] += acc.accSmooth[axis];
|
||||
accumulatedMeasurements[axis] += acc.accADC[axis];
|
||||
}
|
||||
}
|
||||
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue