mirror of
https://github.com/iNavFlight/inav.git
synced 2025-07-24 00:35:34 +03:00
[CALIBRATION] Separate library for zero calibration with variance calculation (time based, with retry); Migrate GYRO and ACC to new calibration; Implement movement threshold for acc calibration to discard shaky measurements
This commit is contained in:
parent
96bd8149bc
commit
f8017b9d35
11 changed files with 338 additions and 99 deletions
|
@ -11,6 +11,7 @@ COMMON_SRC = \
|
||||||
common/encoding.c \
|
common/encoding.c \
|
||||||
common/filter.c \
|
common/filter.c \
|
||||||
common/maths.c \
|
common/maths.c \
|
||||||
|
common/calibration.c \
|
||||||
common/memory.c \
|
common/memory.c \
|
||||||
common/olc.c \
|
common/olc.c \
|
||||||
common/printf.c \
|
common/printf.c \
|
||||||
|
|
189
src/main/common/calibration.c
Normal file
189
src/main/common/calibration.c
Normal file
|
@ -0,0 +1,189 @@
|
||||||
|
/*
|
||||||
|
* This file is part of INAV Project.
|
||||||
|
*
|
||||||
|
* This Source Code Form is subject to the terms of the Mozilla Public
|
||||||
|
* License, v. 2.0. If a copy of the MPL was not distributed with this file,
|
||||||
|
* You can obtain one at http://mozilla.org/MPL/2.0/.
|
||||||
|
*
|
||||||
|
* Alternatively, the contents of this file may be used under the terms
|
||||||
|
* of the GNU General Public License Version 3, as described below:
|
||||||
|
*
|
||||||
|
* This file is free software: you may copy, redistribute and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by the
|
||||||
|
* Free Software Foundation, either version 3 of the License, or (at your
|
||||||
|
* option) any later version.
|
||||||
|
*
|
||||||
|
* This file is distributed in the hope that it will be useful, but
|
||||||
|
* WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General
|
||||||
|
* Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with this program. If not, see http://www.gnu.org/licenses/.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include <stdint.h>
|
||||||
|
#include <string.h>
|
||||||
|
#include <math.h>
|
||||||
|
|
||||||
|
#include "build/debug.h"
|
||||||
|
#include "drivers/time.h"
|
||||||
|
#include "common/calibration.h"
|
||||||
|
|
||||||
|
void zeroCalibrationStartS(zeroCalibrationScalar_t * s, timeMs_t window, float threshold, bool allowFailure)
|
||||||
|
{
|
||||||
|
// Reset parameters and state
|
||||||
|
s->params.state = ZERO_CALIBRATION_IN_PROGRESS;
|
||||||
|
s->params.startTimeMs = millis();
|
||||||
|
s->params.windowSizeMs = window;
|
||||||
|
s->params.stdDevThreshold = threshold;
|
||||||
|
s->params.allowFailure = allowFailure;
|
||||||
|
|
||||||
|
s->params.sampleCount = 0;
|
||||||
|
s->val.accumulatedValue = 0;
|
||||||
|
devClear(&s->val.stdDev);
|
||||||
|
}
|
||||||
|
|
||||||
|
bool zeroCalibrationIsCompleteS(zeroCalibrationScalar_t * s)
|
||||||
|
{
|
||||||
|
return !(s->params.state == ZERO_CALIBRATION_IN_PROGRESS);
|
||||||
|
}
|
||||||
|
|
||||||
|
bool zeroCalibrationIsSuccessfulS(zeroCalibrationScalar_t * s)
|
||||||
|
{
|
||||||
|
return (s->params.state == ZERO_CALIBRATION_DONE);
|
||||||
|
}
|
||||||
|
|
||||||
|
void zeroCalibrationAddValueS(zeroCalibrationScalar_t * s, const float v)
|
||||||
|
{
|
||||||
|
if (s->params.state != ZERO_CALIBRATION_IN_PROGRESS) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Add value
|
||||||
|
s->val.accumulatedValue += v;
|
||||||
|
s->params.sampleCount++;
|
||||||
|
devPush(&s->val.stdDev, v);
|
||||||
|
|
||||||
|
// Check if calibration is complete
|
||||||
|
if ((millis() - s->params.startTimeMs) > s->params.windowSizeMs) {
|
||||||
|
const float stddev = devStandardDeviation(&s->val.stdDev);
|
||||||
|
if (stddev > s->params.stdDevThreshold) {
|
||||||
|
if (!s->params.allowFailure) {
|
||||||
|
// If deviation is too big - restart calibration
|
||||||
|
s->params.startTimeMs = millis();
|
||||||
|
s->params.sampleCount = 0;
|
||||||
|
s->val.accumulatedValue = 0;
|
||||||
|
devClear(&s->val.stdDev);
|
||||||
|
}
|
||||||
|
else {
|
||||||
|
// We are allowed to fail
|
||||||
|
s->params.state = ZERO_CALIBRATION_FAIL;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
else {
|
||||||
|
// All seems ok - calculate average value
|
||||||
|
s->val.accumulatedValue = s->val.accumulatedValue / s->params.sampleCount;
|
||||||
|
s->params.state = ZERO_CALIBRATION_DONE;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void zeroCalibrationGetZeroS(zeroCalibrationScalar_t * s, float * v)
|
||||||
|
{
|
||||||
|
if (s->params.state != ZERO_CALIBRATION_DONE) {
|
||||||
|
*v = 0.0f;
|
||||||
|
}
|
||||||
|
else {
|
||||||
|
*v = s->val.accumulatedValue;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void zeroCalibrationStartV(zeroCalibrationVector_t * s, timeMs_t window, float threshold, bool allowFailure)
|
||||||
|
{
|
||||||
|
// Reset parameters and state
|
||||||
|
s->params.state = ZERO_CALIBRATION_IN_PROGRESS;
|
||||||
|
s->params.startTimeMs = millis();
|
||||||
|
s->params.windowSizeMs = window;
|
||||||
|
s->params.stdDevThreshold = threshold;
|
||||||
|
s->params.allowFailure = allowFailure;
|
||||||
|
|
||||||
|
s->params.sampleCount = 0;
|
||||||
|
for (int i = 0; i < 3; i++) {
|
||||||
|
s->val[i].accumulatedValue = 0;
|
||||||
|
devClear(&s->val[i].stdDev);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
bool zeroCalibrationIsCompleteV(zeroCalibrationVector_t * s)
|
||||||
|
{
|
||||||
|
return !(s->params.state == ZERO_CALIBRATION_IN_PROGRESS);
|
||||||
|
}
|
||||||
|
|
||||||
|
bool zeroCalibrationIsSuccessfulV(zeroCalibrationVector_t * s)
|
||||||
|
{
|
||||||
|
return (s->params.state == ZERO_CALIBRATION_DONE);
|
||||||
|
}
|
||||||
|
|
||||||
|
void zeroCalibrationAddValueV(zeroCalibrationVector_t * s, const fpVector3_t * v)
|
||||||
|
{
|
||||||
|
if (s->params.state != ZERO_CALIBRATION_IN_PROGRESS) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Add value
|
||||||
|
for (int i = 0; i < 3; i++) {
|
||||||
|
s->val[i].accumulatedValue += v->v[i];
|
||||||
|
devPush(&s->val[i].stdDev, v->v[i]);
|
||||||
|
}
|
||||||
|
|
||||||
|
s->params.sampleCount++;
|
||||||
|
|
||||||
|
// Check if calibration is complete
|
||||||
|
if ((millis() - s->params.startTimeMs) > s->params.windowSizeMs) {
|
||||||
|
bool needRecalibration = false;
|
||||||
|
|
||||||
|
for (int i = 0; i < 3 && !needRecalibration; i++) {
|
||||||
|
const float stddev = devStandardDeviation(&s->val[i].stdDev);
|
||||||
|
//debug[i] = stddev;
|
||||||
|
if (stddev > s->params.stdDevThreshold) {
|
||||||
|
needRecalibration = true;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
if (needRecalibration) {
|
||||||
|
if (!s->params.allowFailure) {
|
||||||
|
// If deviation is too big - restart calibration
|
||||||
|
s->params.startTimeMs = millis();
|
||||||
|
s->params.sampleCount = 0;
|
||||||
|
for (int i = 0; i < 3; i++) {
|
||||||
|
s->val[i].accumulatedValue = 0;
|
||||||
|
devClear(&s->val[i].stdDev);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
else {
|
||||||
|
// We are allowed to fail
|
||||||
|
s->params.state = ZERO_CALIBRATION_FAIL;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
else {
|
||||||
|
// All seems ok - calculate average value
|
||||||
|
s->val[0].accumulatedValue = s->val[0].accumulatedValue / s->params.sampleCount;
|
||||||
|
s->val[1].accumulatedValue = s->val[1].accumulatedValue / s->params.sampleCount;
|
||||||
|
s->val[2].accumulatedValue = s->val[2].accumulatedValue / s->params.sampleCount;
|
||||||
|
s->params.state = ZERO_CALIBRATION_DONE;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void zeroCalibrationGetZeroV(zeroCalibrationVector_t * s, fpVector3_t * v)
|
||||||
|
{
|
||||||
|
if (s->params.state != ZERO_CALIBRATION_DONE) {
|
||||||
|
vectorZero(v);
|
||||||
|
}
|
||||||
|
else {
|
||||||
|
v->v[0] = s->val[0].accumulatedValue;
|
||||||
|
v->v[1] = s->val[1].accumulatedValue;
|
||||||
|
v->v[2] = s->val[2].accumulatedValue;
|
||||||
|
}
|
||||||
|
}
|
76
src/main/common/calibration.h
Normal file
76
src/main/common/calibration.h
Normal file
|
@ -0,0 +1,76 @@
|
||||||
|
/*
|
||||||
|
* This file is part of INAV Project.
|
||||||
|
*
|
||||||
|
* This Source Code Form is subject to the terms of the Mozilla Public
|
||||||
|
* License, v. 2.0. If a copy of the MPL was not distributed with this file,
|
||||||
|
* You can obtain one at http://mozilla.org/MPL/2.0/.
|
||||||
|
*
|
||||||
|
* Alternatively, the contents of this file may be used under the terms
|
||||||
|
* of the GNU General Public License Version 3, as described below:
|
||||||
|
*
|
||||||
|
* This file is free software: you may copy, redistribute and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by the
|
||||||
|
* Free Software Foundation, either version 3 of the License, or (at your
|
||||||
|
* option) any later version.
|
||||||
|
*
|
||||||
|
* This file is distributed in the hope that it will be useful, but
|
||||||
|
* WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General
|
||||||
|
* Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with this program. If not, see http://www.gnu.org/licenses/.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
#include <stdint.h>
|
||||||
|
#include <string.h>
|
||||||
|
#include <math.h>
|
||||||
|
|
||||||
|
#include "common/maths.h"
|
||||||
|
#include "common/time.h"
|
||||||
|
#include "common/vector.h"
|
||||||
|
|
||||||
|
typedef enum {
|
||||||
|
ZERO_CALIBRATION_NONE,
|
||||||
|
ZERO_CALIBRATION_IN_PROGRESS,
|
||||||
|
ZERO_CALIBRATION_DONE,
|
||||||
|
ZERO_CALIBRATION_FAIL,
|
||||||
|
} zeroCalibrationState_e;
|
||||||
|
|
||||||
|
typedef struct {
|
||||||
|
zeroCalibrationState_e state;
|
||||||
|
timeMs_t startTimeMs;
|
||||||
|
timeMs_t windowSizeMs;
|
||||||
|
bool allowFailure;
|
||||||
|
unsigned sampleCount;
|
||||||
|
float stdDevThreshold;
|
||||||
|
} zeroCalibrationParams_t;
|
||||||
|
|
||||||
|
typedef struct {
|
||||||
|
float accumulatedValue;
|
||||||
|
stdev_t stdDev;
|
||||||
|
} zeroCalibrationValue_t;
|
||||||
|
|
||||||
|
typedef struct {
|
||||||
|
zeroCalibrationParams_t params;
|
||||||
|
zeroCalibrationValue_t val;
|
||||||
|
} zeroCalibrationScalar_t;
|
||||||
|
|
||||||
|
typedef struct {
|
||||||
|
zeroCalibrationParams_t params;
|
||||||
|
zeroCalibrationValue_t val[3];
|
||||||
|
} zeroCalibrationVector_t;
|
||||||
|
|
||||||
|
void zeroCalibrationStartS(zeroCalibrationScalar_t * s, timeMs_t window, float threshold, bool allowFailure);
|
||||||
|
bool zeroCalibrationIsCompleteS(zeroCalibrationScalar_t * s);
|
||||||
|
bool zeroCalibrationIsSuccessfulS(zeroCalibrationScalar_t * s);
|
||||||
|
void zeroCalibrationAddValueS(zeroCalibrationScalar_t * s, const float v);
|
||||||
|
void zeroCalibrationGetZeroS(zeroCalibrationScalar_t * s, float * v);
|
||||||
|
|
||||||
|
void zeroCalibrationStartV(zeroCalibrationVector_t * s, timeMs_t window, float threshold, bool allowFailure);
|
||||||
|
bool zeroCalibrationIsCompleteV(zeroCalibrationVector_t * s);
|
||||||
|
bool zeroCalibrationIsSuccessfulV(zeroCalibrationVector_t * s);
|
||||||
|
void zeroCalibrationAddValueV(zeroCalibrationVector_t * s, const fpVector3_t * v);
|
||||||
|
void zeroCalibrationGetZeroV(zeroCalibrationVector_t * s, fpVector3_t * v);
|
|
@ -629,7 +629,8 @@ void init(void)
|
||||||
blackboxInit();
|
blackboxInit();
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
gyroSetCalibrationCycles(CALIBRATING_GYRO_CYCLES);
|
gyroStartCalibration();
|
||||||
|
|
||||||
#ifdef USE_BARO
|
#ifdef USE_BARO
|
||||||
baroStartCalibration();
|
baroStartCalibration();
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -2068,7 +2068,7 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
|
||||||
|
|
||||||
case MSP_ACC_CALIBRATION:
|
case MSP_ACC_CALIBRATION:
|
||||||
if (!ARMING_FLAG(ARMED))
|
if (!ARMING_FLAG(ARMED))
|
||||||
accSetCalibrationCycles(CALIBRATING_ACC_CYCLES);
|
accStartCalibration();
|
||||||
else
|
else
|
||||||
return MSP_RESULT_ERROR;
|
return MSP_RESULT_ERROR;
|
||||||
break;
|
break;
|
||||||
|
|
|
@ -235,7 +235,7 @@ void processRcStickPositions(throttleStatus_e throttleStatus)
|
||||||
|
|
||||||
// GYRO calibration
|
// GYRO calibration
|
||||||
if (rcSticks == THR_LO + YAW_LO + PIT_LO + ROL_CE) {
|
if (rcSticks == THR_LO + YAW_LO + PIT_LO + ROL_CE) {
|
||||||
gyroSetCalibrationCycles(CALIBRATING_GYRO_CYCLES);
|
gyroStartCalibration();
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -317,7 +317,7 @@ void processRcStickPositions(throttleStatus_e throttleStatus)
|
||||||
|
|
||||||
// Calibrating Acc
|
// Calibrating Acc
|
||||||
if (rcSticks == THR_HI + YAW_LO + PIT_LO + ROL_CE) {
|
if (rcSticks == THR_HI + YAW_LO + PIT_LO + ROL_CE) {
|
||||||
accSetCalibrationCycles(CALIBRATING_ACC_CYCLES);
|
accStartCalibration();
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -27,6 +27,7 @@
|
||||||
#include "common/filter.h"
|
#include "common/filter.h"
|
||||||
#include "common/maths.h"
|
#include "common/maths.h"
|
||||||
#include "common/utils.h"
|
#include "common/utils.h"
|
||||||
|
#include "common/calibration.h"
|
||||||
|
|
||||||
#include "config/config_reset.h"
|
#include "config/config_reset.h"
|
||||||
#include "config/parameter_group.h"
|
#include "config/parameter_group.h"
|
||||||
|
@ -70,7 +71,7 @@
|
||||||
|
|
||||||
FASTRAM acc_t acc; // acc access functions
|
FASTRAM 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_FASTRAM zeroCalibrationVector_t zeroCalibration;
|
||||||
|
|
||||||
STATIC_FASTRAM int32_t accADC[XYZ_AXIS_COUNT];
|
STATIC_FASTRAM int32_t accADC[XYZ_AXIS_COUNT];
|
||||||
|
|
||||||
|
@ -341,26 +342,6 @@ bool accInit(uint32_t targetLooptime)
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
void accSetCalibrationCycles(uint16_t calibrationCyclesRequired)
|
|
||||||
{
|
|
||||||
calibratingA = calibrationCyclesRequired;
|
|
||||||
}
|
|
||||||
|
|
||||||
bool accIsCalibrationComplete(void)
|
|
||||||
{
|
|
||||||
return calibratingA == 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
static bool isOnFinalAccelerationCalibrationCycle(void)
|
|
||||||
{
|
|
||||||
return calibratingA == 1;
|
|
||||||
}
|
|
||||||
|
|
||||||
static bool isOnFirstAccelerationCalibrationCycle(void)
|
|
||||||
{
|
|
||||||
return calibratingA == CALIBRATING_ACC_CYCLES;
|
|
||||||
}
|
|
||||||
|
|
||||||
static bool calibratedPosition[6];
|
static bool calibratedPosition[6];
|
||||||
static int32_t accSamples[6][3];
|
static int32_t accSamples[6][3];
|
||||||
static int calibratedAxisCount = 0;
|
static int calibratedAxisCount = 0;
|
||||||
|
@ -406,17 +387,21 @@ static int getPrimaryAxisIndex(int32_t accADCData[3])
|
||||||
return -1;
|
return -1;
|
||||||
}
|
}
|
||||||
|
|
||||||
static void performAcclerationCalibration(void)
|
bool accIsCalibrationComplete(void)
|
||||||
|
{
|
||||||
|
return zeroCalibrationIsCompleteV(&zeroCalibration);
|
||||||
|
}
|
||||||
|
|
||||||
|
void accStartCalibration(void)
|
||||||
{
|
{
|
||||||
int positionIndex = getPrimaryAxisIndex(accADC);
|
int positionIndex = getPrimaryAxisIndex(accADC);
|
||||||
|
|
||||||
// Check if sample is usable
|
|
||||||
if (positionIndex < 0) {
|
if (positionIndex < 0) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Top-up and first calibration cycle, reset everything
|
// Top+up and first calibration cycle, reset everything
|
||||||
if (positionIndex == 0 && isOnFirstAccelerationCalibrationCycle()) {
|
if (positionIndex == 0) {
|
||||||
for (int axis = 0; axis < 6; axis++) {
|
for (int axis = 0; axis < 6; axis++) {
|
||||||
calibratedPosition[axis] = false;
|
calibratedPosition[axis] = false;
|
||||||
accSamples[axis][X] = 0;
|
accSamples[axis][X] = 0;
|
||||||
|
@ -428,19 +413,40 @@ static void performAcclerationCalibration(void)
|
||||||
DISABLE_STATE(ACCELEROMETER_CALIBRATED);
|
DISABLE_STATE(ACCELEROMETER_CALIBRATED);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
zeroCalibrationStartV(&zeroCalibration, CALIBRATING_ACC_TIME_MS, acc.dev.acc_1G * 0.01f, true);
|
||||||
|
}
|
||||||
|
|
||||||
|
static void performAcclerationCalibration(void)
|
||||||
|
{
|
||||||
|
fpVector3_t v;
|
||||||
|
int positionIndex = getPrimaryAxisIndex(accADC);
|
||||||
|
|
||||||
|
// Check if sample is usable
|
||||||
|
if (positionIndex < 0) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
if (!calibratedPosition[positionIndex]) {
|
if (!calibratedPosition[positionIndex]) {
|
||||||
accSamples[positionIndex][X] += accADC[X];
|
v.v[0] = accADC[0];
|
||||||
accSamples[positionIndex][Y] += accADC[Y];
|
v.v[1] = accADC[1];
|
||||||
accSamples[positionIndex][Z] += accADC[Z];
|
v.v[2] = accADC[2];
|
||||||
|
|
||||||
if (isOnFinalAccelerationCalibrationCycle()) {
|
zeroCalibrationAddValueV(&zeroCalibration, &v);
|
||||||
calibratedPosition[positionIndex] = true;
|
|
||||||
|
|
||||||
accSamples[positionIndex][X] = accSamples[positionIndex][X] / CALIBRATING_ACC_CYCLES;
|
if (zeroCalibrationIsCompleteV(&zeroCalibration)) {
|
||||||
accSamples[positionIndex][Y] = accSamples[positionIndex][Y] / CALIBRATING_ACC_CYCLES;
|
if (zeroCalibrationIsSuccessfulV(&zeroCalibration)) {
|
||||||
accSamples[positionIndex][Z] = accSamples[positionIndex][Z] / CALIBRATING_ACC_CYCLES;
|
zeroCalibrationGetZeroV(&zeroCalibration, &v);
|
||||||
|
|
||||||
calibratedAxisCount++;
|
accSamples[positionIndex][X] = v.v[X];
|
||||||
|
accSamples[positionIndex][Y] = v.v[Y];
|
||||||
|
accSamples[positionIndex][Z] = v.v[Z];
|
||||||
|
|
||||||
|
calibratedPosition[positionIndex] = true;
|
||||||
|
calibratedAxisCount++;
|
||||||
|
}
|
||||||
|
else {
|
||||||
|
calibratedPosition[positionIndex] = false;
|
||||||
|
}
|
||||||
|
|
||||||
beeperConfirmationBeeps(2);
|
beeperConfirmationBeeps(2);
|
||||||
}
|
}
|
||||||
|
@ -459,9 +465,9 @@ static void performAcclerationCalibration(void)
|
||||||
|
|
||||||
sensorCalibrationSolveForOffset(&calState, accTmp);
|
sensorCalibrationSolveForOffset(&calState, accTmp);
|
||||||
|
|
||||||
for (int axis = 0; axis < 3; axis++) {
|
accelerometerConfigMutable()->accZero.raw[X] = lrintf(accTmp[X]);
|
||||||
accelerometerConfigMutable()->accZero.raw[axis] = lrintf(accTmp[axis]);
|
accelerometerConfigMutable()->accZero.raw[Y] = lrintf(accTmp[Y]);
|
||||||
}
|
accelerometerConfigMutable()->accZero.raw[Z] = lrintf(accTmp[Z]);
|
||||||
|
|
||||||
/* Not we can offset our accumulated averages samples and calculate scale factors and calculate gains */
|
/* Not we can offset our accumulated averages samples and calculate scale factors and calculate gains */
|
||||||
sensorCalibrationResetState(&calState);
|
sensorCalibrationResetState(&calState);
|
||||||
|
@ -484,8 +490,6 @@ static void performAcclerationCalibration(void)
|
||||||
|
|
||||||
saveConfigAndNotify();
|
saveConfigAndNotify();
|
||||||
}
|
}
|
||||||
|
|
||||||
calibratingA--;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
static void applyAccelerationZero(const flightDynamicsTrims_t * accZero, const flightDynamicsTrims_t * accGain)
|
static void applyAccelerationZero(const flightDynamicsTrims_t * accZero, const flightDynamicsTrims_t * accGain)
|
||||||
|
|
|
@ -73,7 +73,7 @@ PG_DECLARE(accelerometerConfig_t, accelerometerConfig);
|
||||||
|
|
||||||
bool accInit(uint32_t accTargetLooptime);
|
bool accInit(uint32_t accTargetLooptime);
|
||||||
bool accIsCalibrationComplete(void);
|
bool accIsCalibrationComplete(void);
|
||||||
void accSetCalibrationCycles(uint16_t calibrationCyclesRequired);
|
void accStartCalibration(void);
|
||||||
void accGetMeasuredAcceleration(fpVector3_t *measuredAcc);
|
void accGetMeasuredAcceleration(fpVector3_t *measuredAcc);
|
||||||
void accGetVibrationLevels(fpVector3_t *accVibeLevels);
|
void accGetVibrationLevels(fpVector3_t *accVibeLevels);
|
||||||
float accGetVibrationLevel(void);
|
float accGetVibrationLevel(void);
|
||||||
|
|
|
@ -27,6 +27,7 @@
|
||||||
|
|
||||||
#include "common/axis.h"
|
#include "common/axis.h"
|
||||||
#include "common/maths.h"
|
#include "common/maths.h"
|
||||||
|
#include "common/calibration.h"
|
||||||
#include "common/filter.h"
|
#include "common/filter.h"
|
||||||
#include "common/utils.h"
|
#include "common/utils.h"
|
||||||
|
|
||||||
|
@ -74,13 +75,7 @@ FASTRAM gyro_t gyro; // gyro sensor object
|
||||||
STATIC_UNIT_TESTED gyroDev_t gyroDev0; // Not in FASTRAM since it may hold DMA buffers
|
STATIC_UNIT_TESTED gyroDev_t gyroDev0; // Not in FASTRAM since it may hold DMA buffers
|
||||||
STATIC_FASTRAM int16_t gyroTemperature0;
|
STATIC_FASTRAM int16_t gyroTemperature0;
|
||||||
|
|
||||||
typedef struct gyroCalibration_s {
|
STATIC_FASTRAM_UNIT_TESTED zeroCalibrationVector_t gyroCalibration;
|
||||||
int32_t g[XYZ_AXIS_COUNT];
|
|
||||||
stdev_t var[XYZ_AXIS_COUNT];
|
|
||||||
uint16_t calibratingG;
|
|
||||||
} gyroCalibration_t;
|
|
||||||
|
|
||||||
STATIC_FASTRAM_UNIT_TESTED gyroCalibration_t gyroCalibration;
|
|
||||||
STATIC_FASTRAM int32_t gyroADC[XYZ_AXIS_COUNT];
|
STATIC_FASTRAM int32_t gyroADC[XYZ_AXIS_COUNT];
|
||||||
|
|
||||||
STATIC_FASTRAM filterApplyFnPtr softLpfFilterApplyFn;
|
STATIC_FASTRAM filterApplyFnPtr softLpfFilterApplyFn;
|
||||||
|
@ -344,64 +339,37 @@ void gyroInitFilters(void)
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
void gyroSetCalibrationCycles(uint16_t calibrationCyclesRequired)
|
void gyroStartCalibration(void)
|
||||||
{
|
{
|
||||||
gyroCalibration.calibratingG = calibrationCyclesRequired;
|
zeroCalibrationStartV(&gyroCalibration, CALIBRATING_GYRO_TIME_MS, gyroConfig()->gyroMovementCalibrationThreshold, false);
|
||||||
}
|
|
||||||
|
|
||||||
STATIC_UNIT_TESTED bool isCalibrationComplete(gyroCalibration_t *gyroCalibration)
|
|
||||||
{
|
|
||||||
return gyroCalibration->calibratingG == 0;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
bool gyroIsCalibrationComplete(void)
|
bool gyroIsCalibrationComplete(void)
|
||||||
{
|
{
|
||||||
return gyroCalibration.calibratingG == 0;
|
return zeroCalibrationIsCompleteV(&gyroCalibration) && zeroCalibrationIsSuccessfulV(&gyroCalibration);
|
||||||
}
|
}
|
||||||
|
|
||||||
static bool isOnFinalGyroCalibrationCycle(gyroCalibration_t *gyroCalibration)
|
STATIC_UNIT_TESTED void performGyroCalibration(gyroDev_t *dev, zeroCalibrationVector_t *gyroCalibration)
|
||||||
{
|
{
|
||||||
return gyroCalibration->calibratingG == 1;
|
fpVector3_t v;
|
||||||
}
|
|
||||||
|
|
||||||
static bool isOnFirstGyroCalibrationCycle(gyroCalibration_t *gyroCalibration)
|
// Consume gyro reading
|
||||||
{
|
v.v[0] = dev->gyroADCRaw[0];
|
||||||
return gyroCalibration->calibratingG == CALIBRATING_GYRO_CYCLES;
|
v.v[1] = dev->gyroADCRaw[1];
|
||||||
}
|
v.v[2] = dev->gyroADCRaw[2];
|
||||||
|
|
||||||
STATIC_UNIT_TESTED void performGyroCalibration(gyroDev_t *dev, gyroCalibration_t *gyroCalibration, uint8_t gyroMovementCalibrationThreshold)
|
zeroCalibrationAddValueV(gyroCalibration, &v);
|
||||||
{
|
|
||||||
for (int axis = 0; axis < 3; axis++) {
|
|
||||||
// Reset g[axis] at start of calibration
|
|
||||||
if (isOnFirstGyroCalibrationCycle(gyroCalibration)) {
|
|
||||||
gyroCalibration->g[axis] = 0;
|
|
||||||
devClear(&gyroCalibration->var[axis]);
|
|
||||||
}
|
|
||||||
|
|
||||||
// Sum up CALIBRATING_GYRO_CYCLES readings
|
// Check if calibration is complete after this cycle
|
||||||
gyroCalibration->g[axis] += dev->gyroADCRaw[axis];
|
if (zeroCalibrationIsCompleteV(gyroCalibration)) {
|
||||||
devPush(&gyroCalibration->var[axis], dev->gyroADCRaw[axis]);
|
zeroCalibrationGetZeroV(gyroCalibration, &v);
|
||||||
|
dev->gyroZero[0] = v.v[0];
|
||||||
|
dev->gyroZero[1] = v.v[1];
|
||||||
|
dev->gyroZero[2] = v.v[2];
|
||||||
|
|
||||||
// gyroZero is set to zero until calibration complete
|
|
||||||
dev->gyroZero[axis] = 0;
|
|
||||||
|
|
||||||
if (isOnFinalGyroCalibrationCycle(gyroCalibration)) {
|
|
||||||
const float stddev = devStandardDeviation(&gyroCalibration->var[axis]);
|
|
||||||
// check deviation and start over if the model was moved
|
|
||||||
if (gyroMovementCalibrationThreshold && stddev > gyroMovementCalibrationThreshold) {
|
|
||||||
gyroSetCalibrationCycles(CALIBRATING_GYRO_CYCLES);
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
// calibration complete, so set the gyro zero values
|
|
||||||
dev->gyroZero[axis] = (gyroCalibration->g[axis] + (CALIBRATING_GYRO_CYCLES / 2)) / CALIBRATING_GYRO_CYCLES;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
if (isOnFinalGyroCalibrationCycle(gyroCalibration)) {
|
|
||||||
DEBUG_TRACE_SYNC("Gyro calibration complete (%d, %d, %d)", dev->gyroZero[0], dev->gyroZero[1], dev->gyroZero[2]);
|
DEBUG_TRACE_SYNC("Gyro calibration complete (%d, %d, %d)", dev->gyroZero[0], dev->gyroZero[1], dev->gyroZero[2]);
|
||||||
schedulerResetTaskStatistics(TASK_SELF); // so calibration cycles do not pollute tasks statistics
|
schedulerResetTaskStatistics(TASK_SELF); // so calibration cycles do not pollute tasks statistics
|
||||||
}
|
}
|
||||||
gyroCalibration->calibratingG--;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
@ -418,7 +386,7 @@ void gyroUpdate()
|
||||||
{
|
{
|
||||||
// range: +/- 8192; +/- 2000 deg/sec
|
// range: +/- 8192; +/- 2000 deg/sec
|
||||||
if (gyroDev0.readFn(&gyroDev0)) {
|
if (gyroDev0.readFn(&gyroDev0)) {
|
||||||
if (isCalibrationComplete(&gyroCalibration)) {
|
if (zeroCalibrationIsCompleteV(&gyroCalibration)) {
|
||||||
// Copy gyro value into int32_t (to prevent overflow) and then apply calibration and alignment
|
// Copy gyro value into int32_t (to prevent overflow) and then apply calibration and alignment
|
||||||
gyroADC[X] = (int32_t)gyroDev0.gyroADCRaw[X] - (int32_t)gyroDev0.gyroZero[X];
|
gyroADC[X] = (int32_t)gyroDev0.gyroADCRaw[X] - (int32_t)gyroDev0.gyroZero[X];
|
||||||
gyroADC[Y] = (int32_t)gyroDev0.gyroADCRaw[Y] - (int32_t)gyroDev0.gyroZero[Y];
|
gyroADC[Y] = (int32_t)gyroDev0.gyroADCRaw[Y] - (int32_t)gyroDev0.gyroZero[Y];
|
||||||
|
@ -426,7 +394,7 @@ void gyroUpdate()
|
||||||
applySensorAlignment(gyroADC, gyroADC, gyroDev0.gyroAlign);
|
applySensorAlignment(gyroADC, gyroADC, gyroDev0.gyroAlign);
|
||||||
applyBoardAlignment(gyroADC);
|
applyBoardAlignment(gyroADC);
|
||||||
} else {
|
} else {
|
||||||
performGyroCalibration(&gyroDev0, &gyroCalibration, gyroConfig()->gyroMovementCalibrationThreshold);
|
performGyroCalibration(&gyroDev0, &gyroCalibration);
|
||||||
// Reset gyro values to zero to prevent other code from using uncalibrated data
|
// Reset gyro values to zero to prevent other code from using uncalibrated data
|
||||||
gyro.gyroADCf[X] = 0.0f;
|
gyro.gyroADCf[X] = 0.0f;
|
||||||
gyro.gyroADCf[Y] = 0.0f;
|
gyro.gyroADCf[Y] = 0.0f;
|
||||||
|
|
|
@ -68,7 +68,7 @@ bool gyroInit(void);
|
||||||
void gyroInitFilters(void);
|
void gyroInitFilters(void);
|
||||||
void gyroGetMeasuredRotationRate(fpVector3_t *imuMeasuredRotationBF);
|
void gyroGetMeasuredRotationRate(fpVector3_t *imuMeasuredRotationBF);
|
||||||
void gyroUpdate();
|
void gyroUpdate();
|
||||||
void gyroSetCalibrationCycles(uint16_t calibrationCyclesRequired);
|
void gyroStartCalibration(void);
|
||||||
bool gyroIsCalibrationComplete(void);
|
bool gyroIsCalibrationComplete(void);
|
||||||
bool gyroReadTemperature(void);
|
bool gyroReadTemperature(void);
|
||||||
int16_t gyroGetTemperature(void);
|
int16_t gyroGetTemperature(void);
|
||||||
|
|
|
@ -39,8 +39,8 @@ typedef union flightDynamicsTrims_u {
|
||||||
flightDynamicsTrims_def_t values;
|
flightDynamicsTrims_def_t values;
|
||||||
} flightDynamicsTrims_t;
|
} flightDynamicsTrims_t;
|
||||||
|
|
||||||
#define CALIBRATING_GYRO_CYCLES 1000
|
#define CALIBRATING_GYRO_TIME_MS 2000
|
||||||
#define CALIBRATING_ACC_CYCLES 400
|
#define CALIBRATING_ACC_TIME_MS 500
|
||||||
|
|
||||||
// These bits have to be aligned with sensorIndex_e
|
// These bits have to be aligned with sensorIndex_e
|
||||||
typedef enum {
|
typedef enum {
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue