Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Fixes helio attitude estimation #886

Merged
merged 4 commits into from
May 11, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
8 changes: 6 additions & 2 deletions src/main/interface/msp.c
Original file line number Diff line number Diff line change
Expand Up @@ -745,20 +745,24 @@ bool mspProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst) {
case MSP_RAW_IMU: {
// Hack scale due to choice of units for sensor data in multiwii
uint8_t scale = 1;
#ifndef USE_GYRO_IMUF9001
//#ifndef USE_GYRO_IMUF9001
if (acc.dev.acc_1G > 512 * 4) {
scale = 8;
} else if (acc.dev.acc_1G > 512 * 2) {
scale = 4;
} else if (acc.dev.acc_1G >= 512) {
scale = 2;
}
#endif //USE_GYRO_IMUF9001
//#endif //USE_GYRO_IMUF9001
for (int i = 0; i < 3; i++) {
sbufWriteU16(dst, lrintf(acc.accADC[i] / scale));
}
for (int i = 0; i < 3; i++) {
#ifdef USE_GYRO_IMUF9001
sbufWriteU16(dst, gyroRateDps(i) * scale);
#else
sbufWriteU16(dst, gyroRateDps(i));
#endif
}
for (int i = 0; i < 3; i++) {
sbufWriteU16(dst, lrintf(mag.magADC[i]));
Expand Down
17 changes: 6 additions & 11 deletions src/main/sensors/gyro.c
Original file line number Diff line number Diff line change
Expand Up @@ -1141,11 +1141,6 @@ static FAST_CODE_NOINLINE void gyroUpdateSensor(gyroSensor_t* gyroSensor, timeUs
for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) {
// NOTE: this branch optimized for when there is no gyro debugging, ensure it is kept in step with non-optimized branch
DEBUG_SET(DEBUG_GYRO_SCALED, axis, lrintf(gyroSensor->gyroDev.gyroADCf[axis]));
if (!gyroSensor->overflowDetected) {
// integrate using trapezium rule to avoid bias
accumulatedMeasurements[axis] += 0.5f * (gyroPrevious[axis] + gyro.gyroADCf[axis]) * gyro.targetLooptime;
gyroPrevious[axis] = gyroSensor->gyroDev.gyroADCf[axis];
}
}
if (!isGyroSensorCalibrationComplete(gyroSensor)) {
performGyroCalibration(gyroSensor, gyroConfig()->gyroMovementCalibrationThreshold);
Expand Down Expand Up @@ -1298,7 +1293,7 @@ FAST_CODE_NOINLINE void gyroUpdate(timeUs_t currentTimeUs) {
if (!overflowDetected) {
for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) {
// integrate using trapezium rule to avoid bias
accumulatedMeasurements[axis] += 0.5f * (gyroPrevious[axis] + gyro.gyroADCf[axis]) * gyro.targetLooptime;
accumulatedMeasurements[axis] += (gyroPrevious[axis] + gyro.gyroADCf[axis]);
gyroPrevious[axis] = gyro.gyroADCf[axis];
}
accumulatedMeasurementCount++;
Expand All @@ -1307,11 +1302,11 @@ FAST_CODE_NOINLINE void gyroUpdate(timeUs_t currentTimeUs) {

bool gyroGetAverage(quaternion *vAverage) {
if (accumulatedMeasurementCount) {
const timeUs_t accumulatedMeasurementTimeUs = accumulatedMeasurementCount * gyro.targetLooptime;
const timeUs_t accumulatedMeasurementTimeUs = accumulatedMeasurementCount;
vAverage->w = 0;
vAverage->x = DEGREES_TO_RADIANS(accumulatedMeasurements[X] / accumulatedMeasurementTimeUs);
vAverage->y = DEGREES_TO_RADIANS(accumulatedMeasurements[Y] / accumulatedMeasurementTimeUs);
vAverage->z = DEGREES_TO_RADIANS(accumulatedMeasurements[Z] / accumulatedMeasurementTimeUs);
vAverage->x = 0.5f * DEGREES_TO_RADIANS(accumulatedMeasurements[X] / accumulatedMeasurementTimeUs);
vAverage->y = 0.5f * DEGREES_TO_RADIANS(accumulatedMeasurements[Y] / accumulatedMeasurementTimeUs);
vAverage->z = 0.5f * DEGREES_TO_RADIANS(accumulatedMeasurements[Z] / accumulatedMeasurementTimeUs);
for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) {
accumulatedMeasurements[axis] = 0.0f;
}
Expand Down Expand Up @@ -1413,4 +1408,4 @@ void initYawSpinRecovery(int maxYawRate)
yawSpinRecoveryEnabled = enabledFlag;
yawSpinRecoveryThreshold = threshold;
}
#endif
#endif