Skip to content

Commit

Permalink
CR134
Browse files Browse the repository at this point in the history
  • Loading branch information
breadoven committed Oct 4, 2024
1 parent 8383996 commit 9141dc5
Show file tree
Hide file tree
Showing 11 changed files with 156 additions and 116 deletions.
1 change: 1 addition & 0 deletions src/main/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -460,6 +460,7 @@ main_sources(COMMON_SRC
sensors/esc_sensor.h
sensors/irlock.c
sensors/irlock.h
sensors/sensors.c
sensors/temperature.c
sensors/temperature.h

Expand Down
28 changes: 14 additions & 14 deletions src/main/fc/settings.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -459,6 +459,13 @@ groups:
default_value: "BIQUAD"
field: acc_soft_lpf_type
table: filter_type
# CR134
- name: acc_temp_correction
description: "Accelerometer temperature correction factor to compensate for acceleromter altitude drift with changes in acceleromter temperature [cm/Degs C]. Internally limited to between -50 and 50. Typical setting for MPU6000 acceleromter is around 2.5. Setting to 51 initiates auto calibration which ends after 5 minutes or on first Arm."
field: acc_temp_correction
min: -50
max: 51
default_value: 0
- name: acczero_x
description: "Calculated value after '6 position avanced calibration'. See Wiki page."
default_value: 0
Expand Down Expand Up @@ -634,6 +641,13 @@ groups:
field: baro_calibration_tolerance
min: 0
max: 1000
# // CR134
- name: baro_temp_correction
description: "Baro temperature correction factor to compensate for Baro altitude drift with changes in Baro temperature [cm/Degs C]. Internally limited to between -50 and 50. Typical setting for BMP280 Baro is around 20. Setting to 51 initiates auto calibration which ends after 5 minutes or on first Arm."
field: baro_temp_correction
min: -50
max: 51
default_value: 0

- name: PG_PITOTMETER_CONFIG
type: pitotmeterConfig_t
Expand Down Expand Up @@ -2498,20 +2512,6 @@ groups:
field: default_alt_sensor
table: default_altitude_source
# CR131
# CR134
- name: baro_temp_correction
description: "Baro temperature correction factor to compensate for Baro altitude drift with changes in Baro temperature [cm/Degs C]. Internally limited to between -50 and 50. Typical setting for BMP280 Baro is around 20. Setting to 51 initiates auto calibration which ends after 5 minutes or on first Arm."
field: baro_temp_correction
min: -50
max: 51
default_value: 0
- name: acc_temp_correction
description: "Accelerometer temperature correction factor to compensate for acceleromter altitude drift with changes in acceleromter temperature [cm/Degs C]. Internally limited to between -50 and 50. Typical setting for MPU6000 acceleromter is around 2.5. Setting to 51 initiates auto calibration which ends after 5 minutes or on first Arm."
field: acc_temp_correction
min: -50
max: 51
default_value: 0
# CR134
- name: PG_NAV_CONFIG
type: navConfig_t
headers: ["navigation/navigation.h"]
Expand Down
2 changes: 0 additions & 2 deletions src/main/navigation/navigation.h
Original file line number Diff line number Diff line change
Expand Up @@ -262,8 +262,6 @@ typedef struct positionEstimationConfig_s {
float baro_epv; // Baro position error

uint8_t default_alt_sensor; // default altitude sensor source // CR131
float baro_temp_correction; // Barometer temperature compensation factor CR1334
float acc_temp_correction; // Accelerometer temperature compensation factor
#ifdef USE_GPS_FIX_ESTIMATION
uint8_t allow_gps_fix_estimation;
#endif
Expand Down
82 changes: 6 additions & 76 deletions src/main/navigation/navigation_pos_estimator.c
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,6 @@
#include "flight/imu.h"

#include "io/gps.h"
#include "io/beeper.h" // CR134

#include "navigation/navigation.h"
#include "navigation/navigation_private.h"
Expand All @@ -53,6 +52,7 @@
#include "sensors/gyro.h"
#include "sensors/pitotmeter.h"
#include "sensors/opflow.h"
#include "sensors/sensors.h" // CR134
#include "sensors/temperature.h"

navigationPosEstimator_t posEstimator;
Expand Down Expand Up @@ -93,8 +93,6 @@ PG_RESET_TEMPLATE(positionEstimationConfig_t, positionEstimationConfig,
.max_eph_epv = SETTING_INAV_MAX_EPH_EPV_DEFAULT,
.baro_epv = SETTING_INAV_BARO_EPV_DEFAULT,
.default_alt_sensor = SETTING_INAV_DEFAULT_ALT_SENSOR_DEFAULT, // CR131
.baro_temp_correction = SETTING_BARO_TEMP_CORRECTION_DEFAULT, // CR134
.acc_temp_correction = SETTING_ACC_TEMP_CORRECTION_DEFAULT,
#ifdef USE_GPS_FIX_ESTIMATION
.allow_gps_fix_estimation = SETTING_INAV_ALLOW_GPS_FIX_ESTIMATION_DEFAULT
#endif
Expand Down Expand Up @@ -286,12 +284,12 @@ void updatePositionEstimator_BaroTopic(timeUs_t currentTimeUs)
{
float newBaroAlt = baroCalculateAltitude();

/* If we are required - keep altitude at zero */
if (shouldResetReferenceAltitude()) {
initialBaroAltitudeOffset = newBaroAlt;
}

if (sensors(SENSOR_BARO) && baroIsCalibrationComplete()) {
/* If we are required - keep altitude at zero */
if (shouldResetReferenceAltitude()) {
initialBaroAltitudeOffset = newBaroAlt;
}

const timeUs_t baroDtUs = currentTimeUs - posEstimator.baro.lastUpdateTime;

posEstimator.baro.alt = newBaroAlt - initialBaroAltitudeOffset;
Expand Down Expand Up @@ -957,71 +955,3 @@ bool navIsCalibrationComplete(void)
// return gravityCalibrationComplete();
return gravityCalibrationIsValid(); // CR131
}
// CR134
sensor_compensation_t sensor_comp_data[SENSOR_INDEX_COUNT];
float applySensorTempCompensation(int16_t sensorTemp, float sensorMeasurement, sensorIndex_e sensorType)
{
float setting = 0.0f;
if (sensorType == SENSOR_INDEX_ACC) {
setting = positionEstimationConfig()->acc_temp_correction;
} else if (sensorType == SENSOR_INDEX_BARO) {
setting = positionEstimationConfig()->baro_temp_correction;
}

// DEBUG_SET(DEBUG_ALWAYS, 1, sensorTemp);
if (!setting) {
return 0.0f;
}

// DEBUG_SET(DEBUG_ALWAYS, 0, sensor_comp_data[sensorType].correctionFactor * 100);
// DEBUG_SET(DEBUG_ALWAYS, 5, sensorMeasurement);
static timeMs_t startTimeMs = 0;
if (sensor_comp_data[sensorType].calibrationState == SENSOR_TEMP_CAL_COMPLETE) {
startTimeMs = 0;
float tempCal = sensor_comp_data[sensorType].correctionFactor * CENTIDEGREES_TO_DEGREES(sensor_comp_data[sensorType].referenceTemp - sensorTemp);
// DEBUG_SET(DEBUG_ALWAYS, 2, tempCal);
return tempCal;
// return correctionFactor * CENTIDEGREES_TO_DEGREES(referenceTemp - baro.baroTemperature);
}



if (!ARMING_FLAG(WAS_EVER_ARMED)) {
static float referenceMeasurement = 0.0f;
static int16_t lastTemp = 0.0f;

if (sensor_comp_data[sensorType].calibrationState == SENSOR_TEMP_CAL_INITIALISE) {
sensor_comp_data[sensorType].referenceTemp = lastTemp = sensorTemp;
referenceMeasurement = sensorMeasurement;
sensor_comp_data[sensorType].calibrationState = SENSOR_TEMP_CAL_IN_PROGRESS;
startTimeMs = millis();
}

if (setting == 51.0f) {
float referenceDeltaTemp = ABS(sensorTemp - sensor_comp_data[sensorType].referenceTemp);
if (referenceDeltaTemp > 300 && referenceDeltaTemp > ABS(lastTemp - sensor_comp_data[sensorType].referenceTemp)) { // centidegrees
lastTemp = sensorTemp;
sensor_comp_data[sensorType].correctionFactor = 0.8f * sensor_comp_data[sensorType].correctionFactor + 0.2f * (sensorMeasurement - referenceMeasurement) / CENTIDEGREES_TO_DEGREES(lastTemp - sensor_comp_data[sensorType].referenceTemp);
sensor_comp_data[sensorType].correctionFactor = constrainf(sensor_comp_data[sensorType].correctionFactor, -50.0f, 50.0f);
}
} else {
sensor_comp_data[sensorType].correctionFactor = setting;
sensor_comp_data[sensorType].calibrationState = SENSOR_TEMP_CAL_COMPLETE;
}
}

if (sensor_comp_data[sensorType].calibrationState == SENSOR_TEMP_CAL_IN_PROGRESS && (ARMING_FLAG(WAS_EVER_ARMED) || millis() > startTimeMs + 300000)) {
if (sensorType == SENSOR_INDEX_ACC) {
positionEstimationConfigMutable()->acc_temp_correction = sensor_comp_data[sensorType].correctionFactor;
} else if (sensorType == SENSOR_INDEX_BARO) {
positionEstimationConfigMutable()->baro_temp_correction = sensor_comp_data[sensorType].correctionFactor;
}
sensor_comp_data[sensorType].calibrationState = SENSOR_TEMP_CAL_COMPLETE;
if (!ARMING_FLAG(WAS_EVER_ARMED)) {
beeper(sensor_comp_data[sensorType].correctionFactor ? BEEPER_ACTION_SUCCESS : BEEPER_ACTION_FAIL);
}
}

return 0.0f;
}
// CR134
16 changes: 1 addition & 15 deletions src/main/navigation/navigation_pos_estimator_private.h
Original file line number Diff line number Diff line change
Expand Up @@ -189,21 +189,7 @@ typedef struct {
fpVector3_t estVelCorr;
fpVector3_t accBiasCorr;
} estimationContext_t;
// CR134
typedef enum {
SENSOR_TEMP_CAL_INITIALISE,
SENSOR_TEMP_CAL_IN_PROGRESS,
SENSOR_TEMP_CAL_COMPLETE,
} sensorTempCalState_e;

typedef struct sensor_compensation_s {
float correctionFactor;
int16_t referenceTemp;
sensorTempCalState_e calibrationState;
} sensor_compensation_t;

float applySensorTempCompensation(int16_t sensorTemp, float sensorMeasurement, sensorIndex_e sensorType);
// // CR134

extern navigationPosEstimator_t posEstimator;

extern float updateEPE(const float oldEPE, const float dt, const float newEPE, const float w);
Expand Down
13 changes: 7 additions & 6 deletions src/main/sensors/acceleration.c
Original file line number Diff line number Diff line change
Expand Up @@ -94,7 +94,8 @@ void pgResetFn_accelerometerConfig(accelerometerConfig_t *instance)
.acc_lpf_hz = SETTING_ACC_LPF_HZ_DEFAULT,
.acc_notch_hz = SETTING_ACC_NOTCH_HZ_DEFAULT,
.acc_notch_cutoff = SETTING_ACC_NOTCH_CUTOFF_DEFAULT,
.acc_soft_lpf_type = SETTING_ACC_LPF_TYPE_DEFAULT
.acc_soft_lpf_type = SETTING_ACC_LPF_TYPE_DEFAULT,
.acc_temp_correction = SETTING_ACC_TEMP_CORRECTION_DEFAULT // CR134
);
RESET_CONFIG_2(flightDynamicsTrims_t, &instance->accZero,
.raw[X] = SETTING_ACCZERO_X_DEFAULT,
Expand Down Expand Up @@ -557,8 +558,8 @@ void accUpdate(void)

if (!ARMING_FLAG(SIMULATOR_MODE_SITL)) {
performAcclerationCalibration();
applyAccelerationZero();
}
applyAccelerationZero();
}

applySensorAlignment(accADC, accADC, acc.dev.accAlign);
applyBoardAlignment(accADC);
Expand Down Expand Up @@ -637,7 +638,7 @@ bool accIsClipped(void)

void accSetCalibrationValues(void)
{
if (!ARMING_FLAG(SIMULATOR_MODE_SITL) &&
if (!ARMING_FLAG(SIMULATOR_MODE_SITL) &&
((accelerometerConfig()->accZero.raw[X] == 0) && (accelerometerConfig()->accZero.raw[Y] == 0) && (accelerometerConfig()->accZero.raw[Z] == 0) &&
(accelerometerConfig()->accGain.raw[X] == 4096) && (accelerometerConfig()->accGain.raw[Y] == 4096) &&(accelerometerConfig()->accGain.raw[Z] == 4096))) {
DISABLE_STATE(ACCELEROMETER_CALIBRATED);
Expand All @@ -648,12 +649,12 @@ void accSetCalibrationValues(void)
}

void accInitFilters(void)
{
{
accSoftLpfFilterApplyFn = nullFilterApply;

if (acc.accTargetLooptime && accelerometerConfig()->acc_lpf_hz) {

switch (accelerometerConfig()->acc_soft_lpf_type)
switch (accelerometerConfig()->acc_soft_lpf_type)
{
case FILTER_PT1:
accSoftLpfFilterApplyFn = (filterApplyFnPtr)pt1FilterApply;
Expand Down
3 changes: 2 additions & 1 deletion src/main/sensors/acceleration.h
Original file line number Diff line number Diff line change
Expand Up @@ -74,7 +74,8 @@ typedef struct accelerometerConfig_s {
flightDynamicsTrims_t accGain; // Accelerometer gain to read exactly 1G
uint8_t acc_notch_hz; // Accelerometer notch filter frequency
uint8_t acc_notch_cutoff; // Accelerometer notch filter cutoff frequency
uint8_t acc_soft_lpf_type; // Accelerometer LPF type
uint8_t acc_soft_lpf_type; // Accelerometer LPF type
float acc_temp_correction; // Accelerometer temperature compensation factor CR134
} accelerometerConfig_t;

PG_DECLARE(accelerometerConfig_t, accelerometerConfig);
Expand Down
3 changes: 1 addition & 2 deletions src/main/sensors/barometer.c
Original file line number Diff line number Diff line change
Expand Up @@ -47,8 +47,6 @@
#include "fc/runtime_config.h"
#include "fc/settings.h"

#include "navigation/navigation_pos_estimator_private.h" // CR134

#include "sensors/barometer.h"
#include "sensors/sensors.h"

Expand All @@ -65,6 +63,7 @@ PG_REGISTER_WITH_RESET_TEMPLATE(barometerConfig_t, barometerConfig, PG_BAROMETER
PG_RESET_TEMPLATE(barometerConfig_t, barometerConfig,
.baro_hardware = SETTING_BARO_HARDWARE_DEFAULT,
.baro_calibration_tolerance = SETTING_BARO_CAL_TOLERANCE_DEFAULT,
.baro_temp_correction = SETTING_BARO_TEMP_CORRECTION_DEFAULT, // CR134
);

static zeroCalibrationScalar_t zeroCalibration;
Expand Down
1 change: 1 addition & 0 deletions src/main/sensors/barometer.h
Original file line number Diff line number Diff line change
Expand Up @@ -52,6 +52,7 @@ extern baro_t baro;
typedef struct barometerConfig_s {
uint8_t baro_hardware; // Barometer hardware to use
uint16_t baro_calibration_tolerance; // Baro calibration tolerance (cm at sea level)
float baro_temp_correction; // CR134
} barometerConfig_t;

PG_DECLARE(barometerConfig_t, barometerConfig);
Expand Down
107 changes: 107 additions & 0 deletions src/main/sensors/sensors.c
Original file line number Diff line number Diff line change
@@ -0,0 +1,107 @@
/*
* This file is part of INAV.
*
* INAV is free software: you can redistribute it 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.
*
* INAV 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 INAV. If not, see <http://www.gnu.org/licenses/>.
*/

#include "platform.h"

#include "build/debug.h"

#include "common/maths.h"

#include "config/parameter_group.h"
#include "config/parameter_group_ids.h"

#include "drivers/time.h"

#include "fc/runtime_config.h"

#include "io/beeper.h"

#include "navigation/navigation.h"
#include "navigation/navigation_pos_estimator_private.h"

#include "sensors/acceleration.h"
#include "sensors/barometer.h"
#include "sensors/sensors.h"

sensor_compensation_t sensor_comp_data[SENSOR_INDEX_COUNT];

float applySensorTempCompensation(int16_t sensorTemp, float sensorMeasurement, sensorIndex_e sensorType)
{
float setting = 0.0f;
if (sensorType == SENSOR_INDEX_ACC) {
// setting = positionEstimationConfig()->acc_temp_correction;
setting = accelerometerConfig()->acc_temp_correction;
} else if (sensorType == SENSOR_INDEX_BARO) {
setting = barometerConfig()->baro_temp_correction;
// setting = positionEstimationConfig()->baro_temp_correction;
}

if (!setting) {
return 0.0f;
}
DEBUG_SET(DEBUG_ALWAYS, 1, sensorTemp);
DEBUG_SET(DEBUG_ALWAYS, 0, sensor_comp_data[sensorType].correctionFactor * 100);
DEBUG_SET(DEBUG_ALWAYS, 5, sensorMeasurement);
static timeMs_t startTimeMs = 0;
if (sensor_comp_data[sensorType].calibrationState == SENSOR_TEMP_CAL_COMPLETE) {
startTimeMs = 0;
float tempCal = sensor_comp_data[sensorType].correctionFactor * CENTIDEGREES_TO_DEGREES(sensor_comp_data[sensorType].referenceTemp - sensorTemp);
DEBUG_SET(DEBUG_ALWAYS, 2, tempCal);
return tempCal;
// return correctionFactor * CENTIDEGREES_TO_DEGREES(referenceTemp - baro.baroTemperature);
}

if (!ARMING_FLAG(WAS_EVER_ARMED)) {
static float referenceMeasurement = 0.0f;
static int16_t lastTemp = 0.0f;

if (sensor_comp_data[sensorType].calibrationState == SENSOR_TEMP_CAL_INITIALISE) {
sensor_comp_data[sensorType].referenceTemp = lastTemp = sensorTemp;
referenceMeasurement = sensorMeasurement;
sensor_comp_data[sensorType].calibrationState = SENSOR_TEMP_CAL_IN_PROGRESS;
startTimeMs = millis();
}

if (setting == 51.0f) {
float referenceDeltaTemp = ABS(sensorTemp - sensor_comp_data[sensorType].referenceTemp);
if (referenceDeltaTemp > 300 && referenceDeltaTemp > ABS(lastTemp - sensor_comp_data[sensorType].referenceTemp)) { // centidegrees
lastTemp = sensorTemp;
sensor_comp_data[sensorType].correctionFactor = 0.8f * sensor_comp_data[sensorType].correctionFactor + 0.2f * (sensorMeasurement - referenceMeasurement) / CENTIDEGREES_TO_DEGREES(lastTemp - sensor_comp_data[sensorType].referenceTemp);
sensor_comp_data[sensorType].correctionFactor = constrainf(sensor_comp_data[sensorType].correctionFactor, -50.0f, 50.0f);
}
} else {
sensor_comp_data[sensorType].correctionFactor = setting;
sensor_comp_data[sensorType].calibrationState = SENSOR_TEMP_CAL_COMPLETE;
}
}

if (sensor_comp_data[sensorType].calibrationState == SENSOR_TEMP_CAL_IN_PROGRESS && (ARMING_FLAG(WAS_EVER_ARMED) || millis() > startTimeMs + 300000)) {
if (sensorType == SENSOR_INDEX_ACC) {
// positionEstimationConfigMutable()->acc_temp_correction = sensor_comp_data[sensorType].correctionFactor;
accelerometerConfigMutable()->acc_temp_correction = sensor_comp_data[sensorType].correctionFactor;
} else if (sensorType == SENSOR_INDEX_BARO) {
// positionEstimationConfigMutable()->baro_temp_correction = sensor_comp_data[sensorType].correctionFactor;
barometerConfigMutable()->baro_temp_correction = sensor_comp_data[sensorType].correctionFactor;
}
sensor_comp_data[sensorType].calibrationState = SENSOR_TEMP_CAL_COMPLETE;
if (!ARMING_FLAG(WAS_EVER_ARMED)) {
beeper(sensor_comp_data[sensorType].correctionFactor ? BEEPER_ACTION_SUCCESS : BEEPER_ACTION_FAIL);
}
}

return 0.0f;
}
Loading

0 comments on commit 9141dc5

Please sign in to comment.