Drop IMU2 functionality
[inav.git] / src / main / navigation / navigation_pos_estimator.c
blobd991ec6ee97679895b911a70a6319b20fbad0a02
1 /*
2 * This file is part of Cleanflight.
4 * Cleanflight is free software: you can redistribute it and/or modify
5 * it under the terms of the GNU General Public License as published by
6 * the Free Software Foundation, either version 3 of the License, or
7 * (at your option) any later version.
9 * Cleanflight is distributed in the hope that it will be useful,
10 * but WITHOUT ANY WARRANTY; without even the implied warranty of
11 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12 * GNU General Public License for more details.
14 * You should have received a copy of the GNU General Public License
15 * along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
18 #include <stdbool.h>
19 #include <stdint.h>
20 #include <math.h>
21 #include <string.h>
23 #include "platform.h"
25 #include "build/build_config.h"
26 #include "build/debug.h"
28 #include "common/axis.h"
29 #include "common/log.h"
30 #include "common/maths.h"
32 #include "config/parameter_group.h"
33 #include "config/parameter_group_ids.h"
35 #include "drivers/time.h"
37 #include "fc/config.h"
38 #include "fc/settings.h"
40 #include "flight/imu.h"
42 #include "io/gps.h"
44 #include "navigation/navigation.h"
45 #include "navigation/navigation_private.h"
46 #include "navigation/navigation_pos_estimator_private.h"
48 #include "sensors/acceleration.h"
49 #include "sensors/barometer.h"
50 #include "sensors/compass.h"
51 #include "sensors/gyro.h"
52 #include "sensors/pitotmeter.h"
53 #include "sensors/opflow.h"
55 navigationPosEstimator_t posEstimator;
57 PG_REGISTER_WITH_RESET_TEMPLATE(positionEstimationConfig_t, positionEstimationConfig, PG_POSITION_ESTIMATION_CONFIG, 5);
59 PG_RESET_TEMPLATE(positionEstimationConfig_t, positionEstimationConfig,
60 // Inertial position estimator parameters
61 .automatic_mag_declination = SETTING_INAV_AUTO_MAG_DECL_DEFAULT,
62 .reset_altitude_type = SETTING_INAV_RESET_ALTITUDE_DEFAULT,
63 .reset_home_type = SETTING_INAV_RESET_HOME_DEFAULT,
64 .gravity_calibration_tolerance = SETTING_INAV_GRAVITY_CAL_TOLERANCE_DEFAULT, // 5 cm/s/s calibration error accepted (0.5% of gravity)
65 .use_gps_velned = SETTING_INAV_USE_GPS_VELNED_DEFAULT, // "Disabled" is mandatory with gps_dyn_model = Pedestrian
66 .use_gps_no_baro = SETTING_INAV_USE_GPS_NO_BARO_DEFAULT, // Use GPS altitude if no baro is available on all aircrafts
67 .allow_dead_reckoning = SETTING_INAV_ALLOW_DEAD_RECKONING_DEFAULT,
69 .max_surface_altitude = SETTING_INAV_MAX_SURFACE_ALTITUDE_DEFAULT,
71 .w_xyz_acc_p = SETTING_INAV_W_XYZ_ACC_P_DEFAULT,
73 .w_z_baro_p = SETTING_INAV_W_Z_BARO_P_DEFAULT,
75 .w_z_surface_p = SETTING_INAV_W_Z_SURFACE_P_DEFAULT,
76 .w_z_surface_v = SETTING_INAV_W_Z_SURFACE_V_DEFAULT,
78 .w_z_gps_p = SETTING_INAV_W_Z_GPS_P_DEFAULT,
79 .w_z_gps_v = SETTING_INAV_W_Z_GPS_V_DEFAULT,
81 .w_xy_gps_p = SETTING_INAV_W_XY_GPS_P_DEFAULT,
82 .w_xy_gps_v = SETTING_INAV_W_XY_GPS_V_DEFAULT,
84 .w_xy_flow_p = SETTING_INAV_W_XY_FLOW_P_DEFAULT,
85 .w_xy_flow_v = SETTING_INAV_W_XY_FLOW_V_DEFAULT,
87 .w_z_res_v = SETTING_INAV_W_Z_RES_V_DEFAULT,
88 .w_xy_res_v = SETTING_INAV_W_XY_RES_V_DEFAULT,
90 .w_acc_bias = SETTING_INAV_W_ACC_BIAS_DEFAULT,
92 .max_eph_epv = SETTING_INAV_MAX_EPH_EPV_DEFAULT,
93 .baro_epv = SETTING_INAV_BARO_EPV_DEFAULT
96 #define resetTimer(tim, currentTimeUs) { (tim)->deltaTime = 0; (tim)->lastTriggeredTime = currentTimeUs; }
97 #define getTimerDeltaMicros(tim) ((tim)->deltaTime)
98 static bool updateTimer(navigationTimer_t * tim, timeUs_t interval, timeUs_t currentTimeUs)
100 if ((currentTimeUs - tim->lastTriggeredTime) >= interval) {
101 tim->deltaTime = currentTimeUs - tim->lastTriggeredTime;
102 tim->lastTriggeredTime = currentTimeUs;
103 return true;
105 else {
106 return false;
110 static bool shouldResetReferenceAltitude(void)
112 switch ((nav_reset_type_e)positionEstimationConfig()->reset_altitude_type) {
113 case NAV_RESET_NEVER:
114 return false;
115 case NAV_RESET_ON_FIRST_ARM:
116 return !ARMING_FLAG(ARMED) && !ARMING_FLAG(WAS_EVER_ARMED);
117 case NAV_RESET_ON_EACH_ARM:
118 return !ARMING_FLAG(ARMED);
121 return false;
124 #if defined(USE_GPS)
125 /* Why is this here: Because GPS will be sending at quiet a nailed rate (if not overloaded by junk tasks at the brink of its specs)
126 * but we might read out with timejitter because Irq might be off by a few us so we do a +-10% margin around the time between GPS
127 * datasets representing the most common Hz-rates today. You might want to extend the list or find a smarter way.
128 * Don't overload your GPS in its config with trash, choose a Hz rate that it can deliver at a sustained rate.
129 * (c) CrashPilot1000
131 static timeUs_t getGPSDeltaTimeFilter(timeUs_t dTus)
133 if (dTus >= 225000 && dTus <= 275000) return HZ2US(4); // 4Hz Data 250ms
134 if (dTus >= 180000 && dTus <= 220000) return HZ2US(5); // 5Hz Data 200ms
135 if (dTus >= 90000 && dTus <= 110000) return HZ2US(10); // 10Hz Data 100ms
136 if (dTus >= 45000 && dTus <= 55000) return HZ2US(20); // 20Hz Data 50ms
137 if (dTus >= 30000 && dTus <= 36000) return HZ2US(30); // 30Hz Data 33ms
138 if (dTus >= 23000 && dTus <= 27000) return HZ2US(40); // 40Hz Data 25ms
139 if (dTus >= 18000 && dTus <= 22000) return HZ2US(50); // 50Hz Data 20ms
140 return dTus; // Filter failed. Set GPS Hz by measurement
143 #if defined(NAV_GPS_GLITCH_DETECTION)
144 static bool detectGPSGlitch(timeUs_t currentTimeUs)
146 static timeUs_t previousTime = 0;
147 static fpVector3_t lastKnownGoodPosition;
148 static fpVector3_t lastKnownGoodVelocity;
150 bool isGlitching = false;
152 if (previousTime == 0) {
153 isGlitching = false;
155 else {
156 fpVector3_t predictedGpsPosition;
157 float gpsDistance;
158 float dT = US2S(currentTimeUs - previousTime);
160 /* We predict new position based on previous GPS velocity and position */
161 predictedGpsPosition.x = lastKnownGoodPosition.x + lastKnownGoodVelocity.x * dT;
162 predictedGpsPosition.y = lastKnownGoodPosition.y + lastKnownGoodVelocity.y * dT;
164 /* New pos is within predefined radius of predicted pos, radius is expanded exponentially */
165 gpsDistance = calc_length_pythagorean_2D(predictedGpsPosition.x - lastKnownGoodPosition.x, predictedGpsPosition.y - lastKnownGoodPosition.y);
166 if (gpsDistance <= (INAV_GPS_GLITCH_RADIUS + 0.5f * INAV_GPS_GLITCH_ACCEL * dT * dT)) {
167 isGlitching = false;
169 else {
170 isGlitching = true;
174 if (!isGlitching) {
175 previousTime = currentTimeUs;
176 lastKnownGoodPosition = posEstimator.gps.pos;
177 lastKnownGoodVelocity = posEstimator.gps.vel;
180 return isGlitching;
182 #endif
185 * Update GPS topic
186 * Function is called on each GPS update
188 void onNewGPSData(void)
190 static timeUs_t lastGPSNewDataTime;
191 static int32_t previousLat;
192 static int32_t previousLon;
193 static int32_t previousAlt;
194 static bool isFirstGPSUpdate = true;
196 gpsLocation_t newLLH;
197 const timeUs_t currentTimeUs = micros();
199 newLLH.lat = gpsSol.llh.lat;
200 newLLH.lon = gpsSol.llh.lon;
201 newLLH.alt = gpsSol.llh.alt;
203 if (sensors(SENSOR_GPS)) {
204 if (!STATE(GPS_FIX)) {
205 isFirstGPSUpdate = true;
206 return;
209 if ((currentTimeUs - lastGPSNewDataTime) > MS2US(INAV_GPS_TIMEOUT_MS)) {
210 isFirstGPSUpdate = true;
213 /* Automatic magnetic declination calculation - do this once */
214 if(STATE(GPS_FIX_HOME)){
215 static bool magDeclinationSet = false;
216 if (positionEstimationConfig()->automatic_mag_declination && !magDeclinationSet) {
217 const float declination = geoCalculateMagDeclination(&newLLH);
218 imuSetMagneticDeclination(declination);
219 magDeclinationSet = true;
222 /* Process position update if GPS origin is already set, or precision is good enough */
223 // FIXME: Add HDOP check for acquisition of GPS origin
224 /* Set GPS origin or reset the origin altitude - keep initial pre-arming altitude at zero */
225 if (!posControl.gpsOrigin.valid) {
226 geoSetOrigin(&posControl.gpsOrigin, &newLLH, GEO_ORIGIN_SET);
228 else if (shouldResetReferenceAltitude()) {
229 /* If we were never armed - keep altitude at zero */
230 geoSetOrigin(&posControl.gpsOrigin, &newLLH, GEO_ORIGIN_RESET_ALTITUDE);
233 if (posControl.gpsOrigin.valid) {
234 /* Convert LLH position to local coordinates */
235 geoConvertGeodeticToLocal(&posEstimator.gps.pos, &posControl.gpsOrigin, &newLLH, GEO_ALT_ABSOLUTE);
237 /* If not the first update - calculate velocities */
238 if (!isFirstGPSUpdate) {
239 float dT = US2S(getGPSDeltaTimeFilter(currentTimeUs - lastGPSNewDataTime));
241 /* Use VELNED provided by GPS if available, calculate from coordinates otherwise */
242 float gpsScaleLonDown = constrainf(cos_approx((ABS(gpsSol.llh.lat) / 10000000.0f) * 0.0174532925f), 0.01f, 1.0f);
243 if (positionEstimationConfig()->use_gps_velned && gpsSol.flags.validVelNE) {
244 posEstimator.gps.vel.x = gpsSol.velNED[X];
245 posEstimator.gps.vel.y = gpsSol.velNED[Y];
247 else {
248 posEstimator.gps.vel.x = (posEstimator.gps.vel.x + (DISTANCE_BETWEEN_TWO_LONGITUDE_POINTS_AT_EQUATOR * (gpsSol.llh.lat - previousLat) / dT)) / 2.0f;
249 posEstimator.gps.vel.y = (posEstimator.gps.vel.y + (gpsScaleLonDown * DISTANCE_BETWEEN_TWO_LONGITUDE_POINTS_AT_EQUATOR * (gpsSol.llh.lon - previousLon) / dT)) / 2.0f;
252 if (positionEstimationConfig()->use_gps_velned && gpsSol.flags.validVelD) {
253 posEstimator.gps.vel.z = -gpsSol.velNED[Z]; // NEU
255 else {
256 posEstimator.gps.vel.z = (posEstimator.gps.vel.z + (gpsSol.llh.alt - previousAlt) / dT) / 2.0f;
259 #if defined(NAV_GPS_GLITCH_DETECTION)
260 /* GPS glitch protection. We have local coordinates and local velocity for current GPS update. Check if they are sane */
261 if (detectGPSGlitch(currentTimeUs)) {
262 posEstimator.gps.glitchRecovery = false;
263 posEstimator.gps.glitchDetected = true;
265 else {
266 /* Store previous glitch flag in glitchRecovery to indicate a valid reading after a glitch */
267 posEstimator.gps.glitchRecovery = posEstimator.gps.glitchDetected;
268 posEstimator.gps.glitchDetected = false;
270 #endif
272 /* FIXME: use HDOP/VDOP */
273 if (gpsSol.flags.validEPE) {
274 posEstimator.gps.eph = gpsSol.eph;
275 posEstimator.gps.epv = gpsSol.epv;
277 else {
278 posEstimator.gps.eph = INAV_GPS_DEFAULT_EPH;
279 posEstimator.gps.epv = INAV_GPS_DEFAULT_EPV;
282 /* Indicate a last valid reading of Pos/Vel */
283 posEstimator.gps.lastUpdateTime = currentTimeUs;
286 previousLat = gpsSol.llh.lat;
287 previousLon = gpsSol.llh.lon;
288 previousAlt = gpsSol.llh.alt;
289 isFirstGPSUpdate = false;
291 lastGPSNewDataTime = currentTimeUs;
294 else {
295 posEstimator.gps.lastUpdateTime = 0;
298 #endif
300 #if defined(USE_BARO)
302 * Read BARO and update alt/vel topic
303 * Function is called from TASK_BARO
305 void updatePositionEstimator_BaroTopic(timeUs_t currentTimeUs)
307 static float initialBaroAltitudeOffset = 0.0f;
308 float newBaroAlt = baroCalculateAltitude();
310 /* If we are required - keep altitude at zero */
311 if (shouldResetReferenceAltitude()) {
312 initialBaroAltitudeOffset = newBaroAlt;
315 if (sensors(SENSOR_BARO) && baroIsCalibrationComplete()) {
316 const timeUs_t baroDtUs = currentTimeUs - posEstimator.baro.lastUpdateTime;
318 posEstimator.baro.alt = newBaroAlt - initialBaroAltitudeOffset;
319 posEstimator.baro.epv = positionEstimationConfig()->baro_epv;
320 posEstimator.baro.lastUpdateTime = currentTimeUs;
322 if (baroDtUs <= MS2US(INAV_BARO_TIMEOUT_MS)) {
323 pt1FilterApply3(&posEstimator.baro.avgFilter, posEstimator.baro.alt, US2S(baroDtUs));
326 else {
327 posEstimator.baro.alt = 0;
328 posEstimator.baro.lastUpdateTime = 0;
331 #endif
333 #if defined(USE_PITOT)
335 * Read Pitot and update airspeed topic
336 * Function is called at main loop rate, updates happen at reduced rate
338 void updatePositionEstimator_PitotTopic(timeUs_t currentTimeUs)
340 posEstimator.pitot.airspeed = getAirspeedEstimate();
341 posEstimator.pitot.lastUpdateTime = currentTimeUs;
343 #endif
346 * Update IMU topic
347 * Function is called at main loop rate
349 static void restartGravityCalibration(void)
351 if (!gyroConfig()->init_gyro_cal_enabled) {
352 return;
355 zeroCalibrationStartS(&posEstimator.imu.gravityCalibration, CALIBRATING_GRAVITY_TIME_MS, positionEstimationConfig()->gravity_calibration_tolerance, false);
358 static bool gravityCalibrationComplete(void)
360 if (!gyroConfig()->init_gyro_cal_enabled) {
361 return true;
364 return zeroCalibrationIsCompleteS(&posEstimator.imu.gravityCalibration);
367 static void updateIMUEstimationWeight(const float dt)
369 bool isAccClipped = accIsClipped();
371 // If accelerometer measurement is clipped - drop the acc weight to zero
372 // and gradually restore weight back to 1.0 over time
373 if (isAccClipped) {
374 posEstimator.imu.accWeightFactor = 0.0f;
376 else {
377 const float relAlpha = dt / (dt + INAV_ACC_CLIPPING_RC_CONSTANT);
378 posEstimator.imu.accWeightFactor = posEstimator.imu.accWeightFactor * (1.0f - relAlpha) + 1.0f * relAlpha;
381 // DEBUG_VIBE[0-3] are used in IMU
382 DEBUG_SET(DEBUG_VIBE, 4, posEstimator.imu.accWeightFactor * 1000);
385 float navGetAccelerometerWeight(void)
387 const float accWeightScaled = posEstimator.imu.accWeightFactor * positionEstimationConfig()->w_xyz_acc_p;
388 DEBUG_SET(DEBUG_VIBE, 5, accWeightScaled * 1000);
390 return accWeightScaled;
393 static void updateIMUTopic(timeUs_t currentTimeUs)
395 const float dt = US2S(currentTimeUs - posEstimator.imu.lastUpdateTime);
396 posEstimator.imu.lastUpdateTime = currentTimeUs;
398 if (!isImuReady()) {
399 posEstimator.imu.accelNEU.x = 0.0f;
400 posEstimator.imu.accelNEU.y = 0.0f;
401 posEstimator.imu.accelNEU.z = 0.0f;
403 restartGravityCalibration();
405 else {
406 /* Update acceleration weight based on vibration levels and clipping */
407 updateIMUEstimationWeight(dt);
409 fpVector3_t accelBF;
411 /* Read acceleration data in body frame */
412 accelBF.x = imuMeasuredAccelBF.x;
413 accelBF.y = imuMeasuredAccelBF.y;
414 accelBF.z = imuMeasuredAccelBF.z;
416 /* Correct accelerometer bias */
417 accelBF.x -= posEstimator.imu.accelBias.x;
418 accelBF.y -= posEstimator.imu.accelBias.y;
419 accelBF.z -= posEstimator.imu.accelBias.z;
421 /* Rotate vector to Earth frame - from Forward-Right-Down to North-East-Up*/
422 imuTransformVectorBodyToEarth(&accelBF);
424 /* Read acceleration data in NEU frame from IMU */
425 posEstimator.imu.accelNEU.x = accelBF.x;
426 posEstimator.imu.accelNEU.y = accelBF.y;
427 posEstimator.imu.accelNEU.z = accelBF.z;
429 /* When unarmed, assume that accelerometer should measure 1G. Use that to correct accelerometer gain */
430 if (gyroConfig()->init_gyro_cal_enabled) {
431 if (!ARMING_FLAG(ARMED) && !gravityCalibrationComplete()) {
432 zeroCalibrationAddValueS(&posEstimator.imu.gravityCalibration, posEstimator.imu.accelNEU.z);
434 if (gravityCalibrationComplete()) {
435 zeroCalibrationGetZeroS(&posEstimator.imu.gravityCalibration, &posEstimator.imu.calibratedGravityCMSS);
436 setGravityCalibrationAndWriteEEPROM(posEstimator.imu.calibratedGravityCMSS);
437 LOG_DEBUG(POS_ESTIMATOR, "Gravity calibration complete (%d)", (int)lrintf(posEstimator.imu.calibratedGravityCMSS));
440 } else {
441 posEstimator.imu.gravityCalibration.params.state = ZERO_CALIBRATION_DONE;
442 posEstimator.imu.calibratedGravityCMSS = gyroConfig()->gravity_cmss_cal;
445 /* If calibration is incomplete - report zero acceleration */
446 if (gravityCalibrationComplete()) {
447 #ifdef USE_SIMULATOR
448 if (ARMING_FLAG(SIMULATOR_MODE)) {
449 posEstimator.imu.calibratedGravityCMSS = GRAVITY_CMSS;
451 #endif
452 posEstimator.imu.accelNEU.z -= posEstimator.imu.calibratedGravityCMSS;
454 else {
455 posEstimator.imu.accelNEU.x = 0.0f;
456 posEstimator.imu.accelNEU.y = 0.0f;
457 posEstimator.imu.accelNEU.z = 0.0f;
460 /* Update blackbox values */
461 navAccNEU[X] = posEstimator.imu.accelNEU.x;
462 navAccNEU[Y] = posEstimator.imu.accelNEU.y;
463 navAccNEU[Z] = posEstimator.imu.accelNEU.z;
467 float updateEPE(const float oldEPE, const float dt, const float newEPE, const float w)
469 return oldEPE + (newEPE - oldEPE) * w * dt;
472 static bool navIsAccelerationUsable(void)
474 return true;
477 static bool navIsHeadingUsable(void)
479 if (sensors(SENSOR_GPS)) {
480 // If we have GPS - we need true IMU north (valid heading)
481 return isImuHeadingValid();
483 else {
484 // If we don't have GPS - we may use whatever we have, other sensors are operating in body frame
485 return isImuHeadingValid() || positionEstimationConfig()->allow_dead_reckoning;
489 static uint32_t calculateCurrentValidityFlags(timeUs_t currentTimeUs)
491 /* Figure out if we have valid position data from our data sources */
492 uint32_t newFlags = 0;
494 if (sensors(SENSOR_GPS) && posControl.gpsOrigin.valid &&
495 ((currentTimeUs - posEstimator.gps.lastUpdateTime) <= MS2US(INAV_GPS_TIMEOUT_MS)) &&
496 (posEstimator.gps.eph < positionEstimationConfig()->max_eph_epv)) {
497 if (posEstimator.gps.epv < positionEstimationConfig()->max_eph_epv) {
498 newFlags |= EST_GPS_XY_VALID | EST_GPS_Z_VALID;
500 else {
501 newFlags |= EST_GPS_XY_VALID;
505 if (sensors(SENSOR_BARO) && ((currentTimeUs - posEstimator.baro.lastUpdateTime) <= MS2US(INAV_BARO_TIMEOUT_MS))) {
506 newFlags |= EST_BARO_VALID;
509 if (sensors(SENSOR_RANGEFINDER) && ((currentTimeUs - posEstimator.surface.lastUpdateTime) <= MS2US(INAV_SURFACE_TIMEOUT_MS))) {
510 newFlags |= EST_SURFACE_VALID;
513 if (sensors(SENSOR_OPFLOW) && posEstimator.flow.isValid && ((currentTimeUs - posEstimator.flow.lastUpdateTime) <= MS2US(INAV_FLOW_TIMEOUT_MS))) {
514 newFlags |= EST_FLOW_VALID;
517 if (posEstimator.est.eph < positionEstimationConfig()->max_eph_epv) {
518 newFlags |= EST_XY_VALID;
521 if (posEstimator.est.epv < positionEstimationConfig()->max_eph_epv) {
522 newFlags |= EST_Z_VALID;
525 return newFlags;
528 static void estimationPredict(estimationContext_t * ctx)
530 const float accWeight = navGetAccelerometerWeight();
532 /* Prediction step: Z-axis */
533 if ((ctx->newFlags & EST_Z_VALID)) {
534 posEstimator.est.pos.z += posEstimator.est.vel.z * ctx->dt;
535 posEstimator.est.pos.z += posEstimator.imu.accelNEU.z * sq(ctx->dt) / 2.0f * accWeight;
536 posEstimator.est.vel.z += posEstimator.imu.accelNEU.z * ctx->dt * sq(accWeight);
539 /* Prediction step: XY-axis */
540 if ((ctx->newFlags & EST_XY_VALID)) {
541 // Predict based on known velocity
542 posEstimator.est.pos.x += posEstimator.est.vel.x * ctx->dt;
543 posEstimator.est.pos.y += posEstimator.est.vel.y * ctx->dt;
545 // If heading is valid, accelNEU is valid as well. Account for acceleration
546 if (navIsHeadingUsable() && navIsAccelerationUsable()) {
547 posEstimator.est.pos.x += posEstimator.imu.accelNEU.x * sq(ctx->dt) / 2.0f * accWeight;
548 posEstimator.est.pos.y += posEstimator.imu.accelNEU.y * sq(ctx->dt) / 2.0f * accWeight;
549 posEstimator.est.vel.x += posEstimator.imu.accelNEU.x * ctx->dt * sq(accWeight);
550 posEstimator.est.vel.y += posEstimator.imu.accelNEU.y * ctx->dt * sq(accWeight);
555 static bool estimationCalculateCorrection_Z(estimationContext_t * ctx)
557 if (ctx->newFlags & EST_BARO_VALID) {
558 timeUs_t currentTimeUs = micros();
560 if (!ARMING_FLAG(ARMED)) {
561 posEstimator.state.baroGroundAlt = posEstimator.est.pos.z;
562 posEstimator.state.isBaroGroundValid = true;
563 posEstimator.state.baroGroundTimeout = currentTimeUs + 250000; // 0.25 sec
565 else {
566 if (posEstimator.est.vel.z > 15) {
567 if (currentTimeUs > posEstimator.state.baroGroundTimeout) {
568 posEstimator.state.isBaroGroundValid = false;
571 else {
572 posEstimator.state.baroGroundTimeout = currentTimeUs + 250000; // 0.25 sec
576 // We might be experiencing air cushion effect - use sonar or baro groung altitude to detect it
577 bool isAirCushionEffectDetected = ARMING_FLAG(ARMED) &&
578 (((ctx->newFlags & EST_SURFACE_VALID) && posEstimator.surface.alt < 20.0f && posEstimator.state.isBaroGroundValid) ||
579 ((ctx->newFlags & EST_BARO_VALID) && posEstimator.state.isBaroGroundValid && posEstimator.baro.alt < posEstimator.state.baroGroundAlt));
581 // Altitude
582 const float baroAltResidual = (isAirCushionEffectDetected ? posEstimator.state.baroGroundAlt : posEstimator.baro.alt) - posEstimator.est.pos.z;
583 ctx->estPosCorr.z += baroAltResidual * positionEstimationConfig()->w_z_baro_p * ctx->dt;
584 ctx->estVelCorr.z += baroAltResidual * sq(positionEstimationConfig()->w_z_baro_p) * ctx->dt;
586 // If GPS is available - also use GPS climb rate
587 if (ctx->newFlags & EST_GPS_Z_VALID) {
588 // Trust GPS velocity only if residual/error is less than 2.5 m/s, scale weight according to gaussian distribution
589 const float gpsRocResidual = posEstimator.gps.vel.z - posEstimator.est.vel.z;
590 const float gpsRocScaler = bellCurve(gpsRocResidual, 250.0f);
591 ctx->estVelCorr.z += gpsRocResidual * positionEstimationConfig()->w_z_gps_v * gpsRocScaler * ctx->dt;
594 ctx->newEPV = updateEPE(posEstimator.est.epv, ctx->dt, posEstimator.baro.epv, positionEstimationConfig()->w_z_baro_p);
596 // Accelerometer bias
597 if (!isAirCushionEffectDetected) {
598 ctx->accBiasCorr.z -= baroAltResidual * sq(positionEstimationConfig()->w_z_baro_p);
601 return true;
603 else if ((STATE(FIXED_WING_LEGACY) || positionEstimationConfig()->use_gps_no_baro) && (ctx->newFlags & EST_GPS_Z_VALID)) {
604 // If baro is not available - use GPS Z for correction on a plane
605 // Reset current estimate to GPS altitude if estimate not valid
606 if (!(ctx->newFlags & EST_Z_VALID)) {
607 ctx->estPosCorr.z += posEstimator.gps.pos.z - posEstimator.est.pos.z;
608 ctx->estVelCorr.z += posEstimator.gps.vel.z - posEstimator.est.vel.z;
609 ctx->newEPV = posEstimator.gps.epv;
611 else {
612 // Altitude
613 const float gpsAltResudual = posEstimator.gps.pos.z - posEstimator.est.pos.z;
615 ctx->estPosCorr.z += gpsAltResudual * positionEstimationConfig()->w_z_gps_p * ctx->dt;
616 ctx->estVelCorr.z += gpsAltResudual * sq(positionEstimationConfig()->w_z_gps_p) * ctx->dt;
617 ctx->estVelCorr.z += (posEstimator.gps.vel.z - posEstimator.est.vel.z) * positionEstimationConfig()->w_z_gps_v * ctx->dt;
618 ctx->newEPV = updateEPE(posEstimator.est.epv, ctx->dt, MAX(posEstimator.gps.epv, gpsAltResudual), positionEstimationConfig()->w_z_gps_p);
620 // Accelerometer bias
621 ctx->accBiasCorr.z -= gpsAltResudual * sq(positionEstimationConfig()->w_z_gps_p);
624 return true;
627 DEBUG_SET(DEBUG_ALTITUDE, 0, posEstimator.est.pos.z); // Position estimate
628 DEBUG_SET(DEBUG_ALTITUDE, 2, posEstimator.baro.alt); // Baro altitude
629 DEBUG_SET(DEBUG_ALTITUDE, 4, posEstimator.gps.pos.z); // GPS altitude
630 DEBUG_SET(DEBUG_ALTITUDE, 6, accGetVibrationLevel()); // Vibration level
631 DEBUG_SET(DEBUG_ALTITUDE, 1, posEstimator.est.vel.z); // Vertical speed estimate
632 DEBUG_SET(DEBUG_ALTITUDE, 3, posEstimator.imu.accelNEU.z); // Vertical acceleration on earth frame
633 DEBUG_SET(DEBUG_ALTITUDE, 5, posEstimator.gps.vel.z); // GPS vertical speed
634 DEBUG_SET(DEBUG_ALTITUDE, 7, accGetClipCount()); // Clip count
636 return false;
639 static bool estimationCalculateCorrection_XY_GPS(estimationContext_t * ctx)
641 if (ctx->newFlags & EST_GPS_XY_VALID) {
642 /* If GPS is valid and our estimate is NOT valid - reset it to GPS coordinates and velocity */
643 if (!(ctx->newFlags & EST_XY_VALID)) {
644 ctx->estPosCorr.x += posEstimator.gps.pos.x - posEstimator.est.pos.x;
645 ctx->estPosCorr.y += posEstimator.gps.pos.y - posEstimator.est.pos.y;
646 ctx->estVelCorr.x += posEstimator.gps.vel.x - posEstimator.est.vel.x;
647 ctx->estVelCorr.y += posEstimator.gps.vel.y - posEstimator.est.vel.y;
648 ctx->newEPH = posEstimator.gps.eph;
650 else {
651 const float gpsPosXResidual = posEstimator.gps.pos.x - posEstimator.est.pos.x;
652 const float gpsPosYResidual = posEstimator.gps.pos.y - posEstimator.est.pos.y;
653 const float gpsVelXResidual = posEstimator.gps.vel.x - posEstimator.est.vel.x;
654 const float gpsVelYResidual = posEstimator.gps.vel.y - posEstimator.est.vel.y;
655 const float gpsPosResidualMag = calc_length_pythagorean_2D(gpsPosXResidual, gpsPosYResidual);
657 //const float gpsWeightScaler = scaleRangef(bellCurve(gpsPosResidualMag, INAV_GPS_ACCEPTANCE_EPE), 0.0f, 1.0f, 0.1f, 1.0f);
658 const float gpsWeightScaler = 1.0f;
660 const float w_xy_gps_p = positionEstimationConfig()->w_xy_gps_p * gpsWeightScaler;
661 const float w_xy_gps_v = positionEstimationConfig()->w_xy_gps_v * sq(gpsWeightScaler);
663 // Coordinates
664 ctx->estPosCorr.x += gpsPosXResidual * w_xy_gps_p * ctx->dt;
665 ctx->estPosCorr.y += gpsPosYResidual * w_xy_gps_p * ctx->dt;
667 // Velocity from coordinates
668 ctx->estVelCorr.x += gpsPosXResidual * sq(w_xy_gps_p) * ctx->dt;
669 ctx->estVelCorr.y += gpsPosYResidual * sq(w_xy_gps_p) * ctx->dt;
671 // Velocity from direct measurement
672 ctx->estVelCorr.x += gpsVelXResidual * w_xy_gps_v * ctx->dt;
673 ctx->estVelCorr.y += gpsVelYResidual * w_xy_gps_v * ctx->dt;
675 // Accelerometer bias
676 ctx->accBiasCorr.x -= gpsPosXResidual * sq(w_xy_gps_p);
677 ctx->accBiasCorr.y -= gpsPosYResidual * sq(w_xy_gps_p);
679 /* Adjust EPH */
680 ctx->newEPH = updateEPE(posEstimator.est.eph, ctx->dt, MAX(posEstimator.gps.eph, gpsPosResidualMag), w_xy_gps_p);
683 return true;
686 return false;
690 * Calculate next estimate using IMU and apply corrections from reference sensors (GPS, BARO etc)
691 * Function is called at main loop rate
693 static void updateEstimatedTopic(timeUs_t currentTimeUs)
695 estimationContext_t ctx;
697 /* Calculate dT */
698 ctx.dt = US2S(currentTimeUs - posEstimator.est.lastUpdateTime);
699 posEstimator.est.lastUpdateTime = currentTimeUs;
701 /* If IMU is not ready we can't estimate anything */
702 if (!isImuReady()) {
703 posEstimator.est.eph = positionEstimationConfig()->max_eph_epv + 0.001f;
704 posEstimator.est.epv = positionEstimationConfig()->max_eph_epv + 0.001f;
705 posEstimator.flags = 0;
706 return;
709 /* Calculate new EPH and EPV for the case we didn't update postion */
710 ctx.newEPH = posEstimator.est.eph * ((posEstimator.est.eph <= positionEstimationConfig()->max_eph_epv) ? 1.0f + ctx.dt : 1.0f);
711 ctx.newEPV = posEstimator.est.epv * ((posEstimator.est.epv <= positionEstimationConfig()->max_eph_epv) ? 1.0f + ctx.dt : 1.0f);
712 ctx.newFlags = calculateCurrentValidityFlags(currentTimeUs);
713 vectorZero(&ctx.estPosCorr);
714 vectorZero(&ctx.estVelCorr);
715 vectorZero(&ctx.accBiasCorr);
717 /* AGL estimation - separate process, decouples from Z coordinate */
718 estimationCalculateAGL(&ctx);
720 /* Prediction stage: X,Y,Z */
721 estimationPredict(&ctx);
723 /* Correction stage: Z */
724 const bool estZCorrectOk =
725 estimationCalculateCorrection_Z(&ctx);
727 /* Correction stage: XY: GPS, FLOW */
728 // FIXME: Handle transition from FLOW to GPS and back - seamlessly fly indoor/outdoor
729 const bool estXYCorrectOk =
730 estimationCalculateCorrection_XY_GPS(&ctx) ||
731 estimationCalculateCorrection_XY_FLOW(&ctx);
733 // If we can't apply correction or accuracy is off the charts - decay velocity to zero
734 if (!estXYCorrectOk || ctx.newEPH > positionEstimationConfig()->max_eph_epv) {
735 ctx.estVelCorr.x = (0.0f - posEstimator.est.vel.x) * positionEstimationConfig()->w_xy_res_v * ctx.dt;
736 ctx.estVelCorr.y = (0.0f - posEstimator.est.vel.y) * positionEstimationConfig()->w_xy_res_v * ctx.dt;
739 if (!estZCorrectOk || ctx.newEPV > positionEstimationConfig()->max_eph_epv) {
740 ctx.estVelCorr.z = (0.0f - posEstimator.est.vel.z) * positionEstimationConfig()->w_z_res_v * ctx.dt;
743 // Apply corrections
744 vectorAdd(&posEstimator.est.pos, &posEstimator.est.pos, &ctx.estPosCorr);
745 vectorAdd(&posEstimator.est.vel, &posEstimator.est.vel, &ctx.estVelCorr);
747 /* Correct accelerometer bias */
748 if (positionEstimationConfig()->w_acc_bias > 0.0f) {
749 const float accelBiasCorrMagnitudeSq = sq(ctx.accBiasCorr.x) + sq(ctx.accBiasCorr.y) + sq(ctx.accBiasCorr.z);
750 if (accelBiasCorrMagnitudeSq < sq(INAV_ACC_BIAS_ACCEPTANCE_VALUE)) {
751 /* transform error vector from NEU frame to body frame */
752 imuTransformVectorEarthToBody(&ctx.accBiasCorr);
754 /* Correct accel bias */
755 posEstimator.imu.accelBias.x += ctx.accBiasCorr.x * positionEstimationConfig()->w_acc_bias * ctx.dt;
756 posEstimator.imu.accelBias.y += ctx.accBiasCorr.y * positionEstimationConfig()->w_acc_bias * ctx.dt;
757 posEstimator.imu.accelBias.z += ctx.accBiasCorr.z * positionEstimationConfig()->w_acc_bias * ctx.dt;
761 /* Update uncertainty */
762 posEstimator.est.eph = ctx.newEPH;
763 posEstimator.est.epv = ctx.newEPV;
765 // Keep flags for further usage
766 posEstimator.flags = ctx.newFlags;
770 * Examine estimation error and update navigation system if estimate is good enough
771 * Function is called at main loop rate, but updates happen less frequently - at a fixed rate
773 static void publishEstimatedTopic(timeUs_t currentTimeUs)
775 static navigationTimer_t posPublishTimer;
777 /* IMU operates in decidegrees while INAV operates in deg*100 */
778 updateActualHeading(navIsHeadingUsable(), DECIDEGREES_TO_CENTIDEGREES(attitude.values.yaw));
780 /* Position and velocity are published with INAV_POSITION_PUBLISH_RATE_HZ */
781 if (updateTimer(&posPublishTimer, HZ2US(INAV_POSITION_PUBLISH_RATE_HZ), currentTimeUs)) {
782 /* Publish position update */
783 if (posEstimator.est.eph < positionEstimationConfig()->max_eph_epv) {
784 // FIXME!!!!!
785 updateActualHorizontalPositionAndVelocity(true, true, posEstimator.est.pos.x, posEstimator.est.pos.y, posEstimator.est.vel.x, posEstimator.est.vel.y);
787 else {
788 updateActualHorizontalPositionAndVelocity(false, false, posEstimator.est.pos.x, posEstimator.est.pos.y, 0, 0);
791 /* Publish altitude update and set altitude validity */
792 if (posEstimator.est.epv < positionEstimationConfig()->max_eph_epv) {
793 navigationEstimateStatus_e aglStatus = (posEstimator.est.aglQual == SURFACE_QUAL_LOW) ? EST_USABLE : EST_TRUSTED;
794 updateActualAltitudeAndClimbRate(true, posEstimator.est.pos.z, posEstimator.est.vel.z, posEstimator.est.aglAlt, posEstimator.est.aglVel, aglStatus);
796 else {
797 updateActualAltitudeAndClimbRate(false, posEstimator.est.pos.z, 0, posEstimator.est.aglAlt, 0, EST_NONE);
800 //Update Blackbox states
801 navEPH = posEstimator.est.eph;
802 navEPV = posEstimator.est.epv;
806 #if defined(NAV_GPS_GLITCH_DETECTION)
807 bool isGPSGlitchDetected(void)
809 return posEstimator.gps.glitchDetected;
811 #endif
813 float getEstimatedAglPosition(void) {
814 return posEstimator.est.aglAlt;
817 bool isEstimatedAglTrusted(void) {
818 return (posEstimator.est.aglQual == SURFACE_QUAL_HIGH) ? true : false;
822 * Initialize position estimator
823 * Should be called once before any update occurs
825 void initializePositionEstimator(void)
827 int axis;
829 posEstimator.est.eph = positionEstimationConfig()->max_eph_epv + 0.001f;
830 posEstimator.est.epv = positionEstimationConfig()->max_eph_epv + 0.001f;
832 posEstimator.imu.lastUpdateTime = 0;
833 posEstimator.gps.lastUpdateTime = 0;
834 posEstimator.baro.lastUpdateTime = 0;
835 posEstimator.surface.lastUpdateTime = 0;
837 posEstimator.est.aglAlt = 0;
838 posEstimator.est.aglVel = 0;
840 posEstimator.est.flowCoordinates[X] = 0;
841 posEstimator.est.flowCoordinates[Y] = 0;
843 posEstimator.imu.accWeightFactor = 0;
845 restartGravityCalibration();
847 for (axis = 0; axis < 3; axis++) {
848 posEstimator.imu.accelBias.v[axis] = 0;
849 posEstimator.est.pos.v[axis] = 0;
850 posEstimator.est.vel.v[axis] = 0;
853 pt1FilterInit(&posEstimator.baro.avgFilter, INAV_BARO_AVERAGE_HZ, 0.0f);
854 pt1FilterInit(&posEstimator.surface.avgFilter, INAV_SURFACE_AVERAGE_HZ, 0.0f);
858 * Update estimator
859 * Update rate: loop rate (>100Hz)
861 void updatePositionEstimator(void)
863 static bool isInitialized = false;
865 if (!isInitialized) {
866 initializePositionEstimator();
867 isInitialized = true;
870 const timeUs_t currentTimeUs = micros();
872 /* Read updates from IMU, preprocess */
873 updateIMUTopic(currentTimeUs);
875 /* Update estimate */
876 updateEstimatedTopic(currentTimeUs);
878 /* Publish estimate */
879 publishEstimatedTopic(currentTimeUs);
882 bool navIsCalibrationComplete(void)
884 return gravityCalibrationComplete();