updates
[inav.git] / src / main / navigation / navigation_pos_estimator.c
blobf66c641928b54279cc8170fa2f5df83e859f0043
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"
39 #include "fc/rc_modes.h"
41 #include "flight/imu.h"
43 #include "io/gps.h"
45 #include "navigation/navigation.h"
46 #include "navigation/navigation_private.h"
47 #include "navigation/navigation_pos_estimator_private.h"
49 #include "sensors/acceleration.h"
50 #include "sensors/barometer.h"
51 #include "sensors/compass.h"
52 #include "sensors/gyro.h"
53 #include "sensors/pitotmeter.h"
54 #include "sensors/opflow.h"
56 navigationPosEstimator_t posEstimator;
57 static float initialBaroAltitudeOffset = 0.0f;
59 PG_REGISTER_WITH_RESET_TEMPLATE(positionEstimationConfig_t, positionEstimationConfig, PG_POSITION_ESTIMATION_CONFIG, 5);
61 PG_RESET_TEMPLATE(positionEstimationConfig_t, positionEstimationConfig,
62 // Inertial position estimator parameters
63 .automatic_mag_declination = SETTING_INAV_AUTO_MAG_DECL_DEFAULT,
64 .reset_altitude_type = SETTING_INAV_RESET_ALTITUDE_DEFAULT,
65 .reset_home_type = SETTING_INAV_RESET_HOME_DEFAULT,
66 .gravity_calibration_tolerance = SETTING_INAV_GRAVITY_CAL_TOLERANCE_DEFAULT, // 5 cm/s/s calibration error accepted (0.5% of gravity)
67 .use_gps_velned = SETTING_INAV_USE_GPS_VELNED_DEFAULT, // "Disabled" is mandatory with gps_dyn_model = Pedestrian
68 .use_gps_no_baro = SETTING_INAV_USE_GPS_NO_BARO_DEFAULT, // Use GPS altitude if no baro is available on all aircrafts
69 .allow_dead_reckoning = SETTING_INAV_ALLOW_DEAD_RECKONING_DEFAULT,
71 .max_surface_altitude = SETTING_INAV_MAX_SURFACE_ALTITUDE_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 /* Reference altitudes reset constantly when disarmed.
113 * On arming ref altitudes saved as backup in case of emerg in flight rearm
114 * If emerg in flight rearm active ref altitudes reset to backup values to avoid unwanted altitude reset */
116 static float backupInitialBaroAltitudeOffset = 0.0f;
117 static int32_t backupGpsOriginAltitude = 0;
118 static bool emergRearmResetCheck = false;
120 if (ARMING_FLAG(ARMED) && emergRearmResetCheck) {
121 if (STATE(IN_FLIGHT_EMERG_REARM)) {
122 initialBaroAltitudeOffset = backupInitialBaroAltitudeOffset;
123 posControl.gpsOrigin.alt = backupGpsOriginAltitude;
124 } else {
125 backupInitialBaroAltitudeOffset = initialBaroAltitudeOffset;
126 backupGpsOriginAltitude = posControl.gpsOrigin.alt;
129 emergRearmResetCheck = !ARMING_FLAG(ARMED);
131 switch ((nav_reset_type_e)positionEstimationConfig()->reset_altitude_type) {
132 case NAV_RESET_NEVER:
133 return false;
134 case NAV_RESET_ON_FIRST_ARM:
135 return !ARMING_FLAG(ARMED) && !ARMING_FLAG(WAS_EVER_ARMED);
136 case NAV_RESET_ON_EACH_ARM:
137 return !ARMING_FLAG(ARMED);
140 return false;
143 #if defined(USE_GPS)
144 /* 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)
145 * 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
146 * datasets representing the most common Hz-rates today. You might want to extend the list or find a smarter way.
147 * Don't overload your GPS in its config with trash, choose a Hz rate that it can deliver at a sustained rate.
148 * (c) CrashPilot1000
150 static timeUs_t getGPSDeltaTimeFilter(timeUs_t dTus)
152 if (dTus >= 225000 && dTus <= 275000) return HZ2US(4); // 4Hz Data 250ms
153 if (dTus >= 180000 && dTus <= 220000) return HZ2US(5); // 5Hz Data 200ms
154 if (dTus >= 90000 && dTus <= 110000) return HZ2US(10); // 10Hz Data 100ms
155 if (dTus >= 45000 && dTus <= 55000) return HZ2US(20); // 20Hz Data 50ms
156 if (dTus >= 30000 && dTus <= 36000) return HZ2US(30); // 30Hz Data 33ms
157 if (dTus >= 23000 && dTus <= 27000) return HZ2US(40); // 40Hz Data 25ms
158 if (dTus >= 18000 && dTus <= 22000) return HZ2US(50); // 50Hz Data 20ms
159 return dTus; // Filter failed. Set GPS Hz by measurement
162 #if defined(NAV_GPS_GLITCH_DETECTION)
163 static bool detectGPSGlitch(timeUs_t currentTimeUs)
165 static timeUs_t previousTime = 0;
166 static fpVector3_t lastKnownGoodPosition;
167 static fpVector3_t lastKnownGoodVelocity;
169 bool isGlitching = false;
171 if (previousTime == 0) {
172 isGlitching = false;
174 else {
175 fpVector3_t predictedGpsPosition;
176 float gpsDistance;
177 float dT = US2S(currentTimeUs - previousTime);
179 /* We predict new position based on previous GPS velocity and position */
180 predictedGpsPosition.x = lastKnownGoodPosition.x + lastKnownGoodVelocity.x * dT;
181 predictedGpsPosition.y = lastKnownGoodPosition.y + lastKnownGoodVelocity.y * dT;
183 /* New pos is within predefined radius of predicted pos, radius is expanded exponentially */
184 gpsDistance = calc_length_pythagorean_2D(predictedGpsPosition.x - lastKnownGoodPosition.x, predictedGpsPosition.y - lastKnownGoodPosition.y);
185 if (gpsDistance <= (INAV_GPS_GLITCH_RADIUS + 0.5f * INAV_GPS_GLITCH_ACCEL * dT * dT)) {
186 isGlitching = false;
188 else {
189 isGlitching = true;
193 if (!isGlitching) {
194 previousTime = currentTimeUs;
195 lastKnownGoodPosition = posEstimator.gps.pos;
196 lastKnownGoodVelocity = posEstimator.gps.vel;
199 return isGlitching;
201 #endif
204 * Update GPS topic
205 * Function is called on each GPS update
207 void onNewGPSData(void)
209 static timeUs_t lastGPSNewDataTime;
210 static int32_t previousLat;
211 static int32_t previousLon;
212 static int32_t previousAlt;
213 static bool isFirstGPSUpdate = true;
215 gpsLocation_t newLLH;
216 const timeUs_t currentTimeUs = micros();
218 newLLH.lat = gpsSol.llh.lat;
219 newLLH.lon = gpsSol.llh.lon;
220 newLLH.alt = gpsSol.llh.alt;
222 if (sensors(SENSOR_GPS)) {
223 if (!STATE(GPS_FIX)) {
224 isFirstGPSUpdate = true;
225 return;
228 if ((currentTimeUs - lastGPSNewDataTime) > MS2US(INAV_GPS_TIMEOUT_MS)) {
229 isFirstGPSUpdate = true;
232 /* Automatic magnetic declination calculation - do this once */
233 if(STATE(GPS_FIX_HOME)){
234 static bool magDeclinationSet = false;
235 if (positionEstimationConfig()->automatic_mag_declination && !magDeclinationSet) {
236 const float declination = geoCalculateMagDeclination(&newLLH);
237 imuSetMagneticDeclination(declination);
238 magDeclinationSet = true;
241 /* Process position update if GPS origin is already set, or precision is good enough */
242 // FIXME: Add HDOP check for acquisition of GPS origin
243 /* Set GPS origin or reset the origin altitude - keep initial pre-arming altitude at zero */
244 if (!posControl.gpsOrigin.valid) {
245 geoSetOrigin(&posControl.gpsOrigin, &newLLH, GEO_ORIGIN_SET);
247 else if (shouldResetReferenceAltitude()) {
248 /* If we were never armed - keep altitude at zero */
249 geoSetOrigin(&posControl.gpsOrigin, &newLLH, GEO_ORIGIN_RESET_ALTITUDE);
252 if (posControl.gpsOrigin.valid) {
253 /* Convert LLH position to local coordinates */
254 geoConvertGeodeticToLocal(&posEstimator.gps.pos, &posControl.gpsOrigin, &newLLH, GEO_ALT_ABSOLUTE);
256 /* If not the first update - calculate velocities */
257 if (!isFirstGPSUpdate) {
258 float dT = US2S(getGPSDeltaTimeFilter(currentTimeUs - lastGPSNewDataTime));
260 /* Use VELNED provided by GPS if available, calculate from coordinates otherwise */
261 float gpsScaleLonDown = constrainf(cos_approx((ABS(gpsSol.llh.lat) / 10000000.0f) * 0.0174532925f), 0.01f, 1.0f);
262 if (!ARMING_FLAG(SIMULATOR_MODE_SITL) && positionEstimationConfig()->use_gps_velned && gpsSol.flags.validVelNE) {
263 posEstimator.gps.vel.x = gpsSol.velNED[X];
264 posEstimator.gps.vel.y = gpsSol.velNED[Y];
266 else {
267 posEstimator.gps.vel.x = (posEstimator.gps.vel.x + (DISTANCE_BETWEEN_TWO_LONGITUDE_POINTS_AT_EQUATOR * (gpsSol.llh.lat - previousLat) / dT)) / 2.0f;
268 posEstimator.gps.vel.y = (posEstimator.gps.vel.y + (gpsScaleLonDown * DISTANCE_BETWEEN_TWO_LONGITUDE_POINTS_AT_EQUATOR * (gpsSol.llh.lon - previousLon) / dT)) / 2.0f;
271 if (positionEstimationConfig()->use_gps_velned && gpsSol.flags.validVelD) {
272 posEstimator.gps.vel.z = -gpsSol.velNED[Z]; // NEU
274 else {
275 posEstimator.gps.vel.z = (posEstimator.gps.vel.z + (gpsSol.llh.alt - previousAlt) / dT) / 2.0f;
278 #if defined(NAV_GPS_GLITCH_DETECTION)
279 /* GPS glitch protection. We have local coordinates and local velocity for current GPS update. Check if they are sane */
280 if (detectGPSGlitch(currentTimeUs)) {
281 posEstimator.gps.glitchRecovery = false;
282 posEstimator.gps.glitchDetected = true;
284 else {
285 /* Store previous glitch flag in glitchRecovery to indicate a valid reading after a glitch */
286 posEstimator.gps.glitchRecovery = posEstimator.gps.glitchDetected;
287 posEstimator.gps.glitchDetected = false;
289 #endif
291 /* FIXME: use HDOP/VDOP */
292 if (gpsSol.flags.validEPE) {
293 posEstimator.gps.eph = gpsSol.eph;
294 posEstimator.gps.epv = gpsSol.epv;
296 else {
297 posEstimator.gps.eph = INAV_GPS_DEFAULT_EPH;
298 posEstimator.gps.epv = INAV_GPS_DEFAULT_EPV;
301 /* Indicate a last valid reading of Pos/Vel */
302 posEstimator.gps.lastUpdateTime = currentTimeUs;
305 previousLat = gpsSol.llh.lat;
306 previousLon = gpsSol.llh.lon;
307 previousAlt = gpsSol.llh.alt;
308 isFirstGPSUpdate = false;
310 lastGPSNewDataTime = currentTimeUs;
313 else {
314 posEstimator.gps.lastUpdateTime = 0;
317 #endif
319 #if defined(USE_BARO)
321 * Read BARO and update alt/vel topic
322 * Function is called from TASK_BARO
324 void updatePositionEstimator_BaroTopic(timeUs_t currentTimeUs)
326 float newBaroAlt = baroCalculateAltitude();
328 /* If we are required - keep altitude at zero */
329 if (shouldResetReferenceAltitude()) {
330 initialBaroAltitudeOffset = newBaroAlt;
333 if (sensors(SENSOR_BARO) && baroIsCalibrationComplete()) {
334 const timeUs_t baroDtUs = currentTimeUs - posEstimator.baro.lastUpdateTime;
336 posEstimator.baro.alt = newBaroAlt - initialBaroAltitudeOffset;
337 posEstimator.baro.epv = positionEstimationConfig()->baro_epv;
338 posEstimator.baro.lastUpdateTime = currentTimeUs;
340 if (baroDtUs <= MS2US(INAV_BARO_TIMEOUT_MS)) {
341 posEstimator.baro.alt = pt1FilterApply3(&posEstimator.baro.avgFilter, posEstimator.baro.alt, US2S(baroDtUs));
343 // baro altitude rate
344 static float baroAltPrevious = 0;
345 posEstimator.baro.baroAltRate = (posEstimator.baro.alt - baroAltPrevious) / US2S(baroDtUs);
346 baroAltPrevious = posEstimator.baro.alt;
347 updateBaroAltitudeRate(posEstimator.baro.baroAltRate, true);
350 else {
351 posEstimator.baro.alt = 0;
352 posEstimator.baro.lastUpdateTime = 0;
355 #endif
357 #if defined(USE_PITOT)
359 * Read Pitot and update airspeed topic
360 * Function is called at main loop rate, updates happen at reduced rate
362 void updatePositionEstimator_PitotTopic(timeUs_t currentTimeUs)
364 posEstimator.pitot.airspeed = getAirspeedEstimate();
365 posEstimator.pitot.lastUpdateTime = currentTimeUs;
367 #endif
370 * Update IMU topic
371 * Function is called at main loop rate
373 static void restartGravityCalibration(void)
375 if (!gyroConfig()->init_gyro_cal_enabled) {
376 return;
379 zeroCalibrationStartS(&posEstimator.imu.gravityCalibration, CALIBRATING_GRAVITY_TIME_MS, positionEstimationConfig()->gravity_calibration_tolerance, false);
382 static bool gravityCalibrationComplete(void)
384 if (!gyroConfig()->init_gyro_cal_enabled) {
385 return true;
388 return zeroCalibrationIsCompleteS(&posEstimator.imu.gravityCalibration);
390 #define ACC_VIB_FACTOR_S 1.0f
391 #define ACC_VIB_FACTOR_E 3.0f
392 static void updateIMUEstimationWeight(const float dt)
394 static float acc_clip_factor = 1.0f;
395 // If accelerometer measurement is clipped - drop the acc weight to 0.3
396 // and gradually restore weight back to 1.0 over time
397 if (accIsClipped()) {
398 acc_clip_factor = 0.5f;
400 else {
401 const float relAlpha = dt / (dt + INAV_ACC_CLIPPING_RC_CONSTANT);
402 acc_clip_factor = acc_clip_factor * (1.0f - relAlpha) + 1.0f * relAlpha;
404 // Update accelerometer weight based on vibration levels and clipping
405 float acc_vibration_factor = scaleRangef(constrainf(accGetVibrationLevel(),ACC_VIB_FACTOR_S,ACC_VIB_FACTOR_E),ACC_VIB_FACTOR_S,ACC_VIB_FACTOR_E,1.0f,0.3f); // g/s
406 posEstimator.imu.accWeightFactor = acc_vibration_factor * acc_clip_factor;
407 // DEBUG_VIBE[0-3] are used in IMU
408 DEBUG_SET(DEBUG_VIBE, 4, posEstimator.imu.accWeightFactor * 1000);
411 float navGetAccelerometerWeight(void)
413 const float accWeightScaled = posEstimator.imu.accWeightFactor;
414 DEBUG_SET(DEBUG_VIBE, 5, accWeightScaled * 1000);
416 return accWeightScaled;
419 static void updateIMUTopic(timeUs_t currentTimeUs)
421 const float dt = US2S(currentTimeUs - posEstimator.imu.lastUpdateTime);
422 posEstimator.imu.lastUpdateTime = currentTimeUs;
424 if (!isImuReady()) {
425 posEstimator.imu.accelNEU.x = 0.0f;
426 posEstimator.imu.accelNEU.y = 0.0f;
427 posEstimator.imu.accelNEU.z = 0.0f;
429 restartGravityCalibration();
431 else {
432 /* Update acceleration weight based on vibration levels and clipping */
433 updateIMUEstimationWeight(dt);
435 fpVector3_t accelBF;
437 /* Read acceleration data in body frame */
438 accelBF.x = imuMeasuredAccelBF.x;
439 accelBF.y = imuMeasuredAccelBF.y;
440 accelBF.z = imuMeasuredAccelBF.z;
442 /* Correct accelerometer bias */
443 accelBF.x -= posEstimator.imu.accelBias.x;
444 accelBF.y -= posEstimator.imu.accelBias.y;
445 accelBF.z -= posEstimator.imu.accelBias.z;
447 /* Rotate vector to Earth frame - from Forward-Right-Down to North-East-Up*/
448 imuTransformVectorBodyToEarth(&accelBF);
450 /* Read acceleration data in NEU frame from IMU */
451 posEstimator.imu.accelNEU.x = accelBF.x;
452 posEstimator.imu.accelNEU.y = accelBF.y;
453 posEstimator.imu.accelNEU.z = accelBF.z;
455 /* When unarmed, assume that accelerometer should measure 1G. Use that to correct accelerometer gain */
456 if (gyroConfig()->init_gyro_cal_enabled) {
457 if (!ARMING_FLAG(ARMED) && !gravityCalibrationComplete()) {
458 zeroCalibrationAddValueS(&posEstimator.imu.gravityCalibration, posEstimator.imu.accelNEU.z);
460 if (gravityCalibrationComplete()) {
461 zeroCalibrationGetZeroS(&posEstimator.imu.gravityCalibration, &posEstimator.imu.calibratedGravityCMSS);
462 setGravityCalibration(posEstimator.imu.calibratedGravityCMSS);
463 LOG_DEBUG(POS_ESTIMATOR, "Gravity calibration complete (%d)", (int)lrintf(posEstimator.imu.calibratedGravityCMSS));
466 } else {
467 posEstimator.imu.gravityCalibration.params.state = ZERO_CALIBRATION_DONE;
468 posEstimator.imu.calibratedGravityCMSS = gyroConfig()->gravity_cmss_cal;
471 /* If calibration is incomplete - report zero acceleration */
472 if (gravityCalibrationComplete()) {
473 #ifdef USE_SIMULATOR
474 if (ARMING_FLAG(SIMULATOR_MODE_HITL) || ARMING_FLAG(SIMULATOR_MODE_SITL)) {
475 posEstimator.imu.calibratedGravityCMSS = GRAVITY_CMSS;
477 #endif
478 posEstimator.imu.accelNEU.z -= posEstimator.imu.calibratedGravityCMSS;
480 else {
481 posEstimator.imu.accelNEU.x = 0.0f;
482 posEstimator.imu.accelNEU.y = 0.0f;
483 posEstimator.imu.accelNEU.z = 0.0f;
486 /* Update blackbox values */
487 navAccNEU[X] = posEstimator.imu.accelNEU.x;
488 navAccNEU[Y] = posEstimator.imu.accelNEU.y;
489 navAccNEU[Z] = posEstimator.imu.accelNEU.z;
493 float updateEPE(const float oldEPE, const float dt, const float newEPE, const float w)
495 return oldEPE + (newEPE - oldEPE) * w * dt;
498 static bool navIsAccelerationUsable(void)
500 return true;
503 static bool navIsHeadingUsable(void)
505 if (sensors(SENSOR_GPS)) {
506 // If we have GPS - we need true IMU north (valid heading)
507 return isImuHeadingValid();
509 else {
510 // If we don't have GPS - we may use whatever we have, other sensors are operating in body frame
511 return isImuHeadingValid() || positionEstimationConfig()->allow_dead_reckoning;
515 static uint32_t calculateCurrentValidityFlags(timeUs_t currentTimeUs)
517 /* Figure out if we have valid position data from our data sources */
518 uint32_t newFlags = 0;
520 if (sensors(SENSOR_GPS) && posControl.gpsOrigin.valid &&
521 ((currentTimeUs - posEstimator.gps.lastUpdateTime) <= MS2US(INAV_GPS_TIMEOUT_MS)) &&
522 (posEstimator.gps.eph < positionEstimationConfig()->max_eph_epv)) {
523 if (posEstimator.gps.epv < positionEstimationConfig()->max_eph_epv) {
524 newFlags |= EST_GPS_XY_VALID | EST_GPS_Z_VALID;
526 else {
527 newFlags |= EST_GPS_XY_VALID;
531 if (sensors(SENSOR_BARO) && ((currentTimeUs - posEstimator.baro.lastUpdateTime) <= MS2US(INAV_BARO_TIMEOUT_MS))) {
532 newFlags |= EST_BARO_VALID;
535 if (sensors(SENSOR_RANGEFINDER) && ((currentTimeUs - posEstimator.surface.lastUpdateTime) <= MS2US(INAV_SURFACE_TIMEOUT_MS))) {
536 newFlags |= EST_SURFACE_VALID;
539 if (sensors(SENSOR_OPFLOW) && posEstimator.flow.isValid && ((currentTimeUs - posEstimator.flow.lastUpdateTime) <= MS2US(INAV_FLOW_TIMEOUT_MS))) {
540 newFlags |= EST_FLOW_VALID;
543 if (posEstimator.est.eph < positionEstimationConfig()->max_eph_epv) {
544 newFlags |= EST_XY_VALID;
547 if (posEstimator.est.epv < positionEstimationConfig()->max_eph_epv) {
548 newFlags |= EST_Z_VALID;
551 return newFlags;
554 static void estimationPredict(estimationContext_t * ctx)
557 /* Prediction step: Z-axis */
558 if ((ctx->newFlags & EST_Z_VALID)) {
559 posEstimator.est.pos.z += posEstimator.est.vel.z * ctx->dt;
560 posEstimator.est.pos.z += posEstimator.imu.accelNEU.z * sq(ctx->dt) / 2.0f;
561 posEstimator.est.vel.z += posEstimator.imu.accelNEU.z * ctx->dt;
564 /* Prediction step: XY-axis */
565 if ((ctx->newFlags & EST_XY_VALID)) {
566 // Predict based on known velocity
567 posEstimator.est.pos.x += posEstimator.est.vel.x * ctx->dt;
568 posEstimator.est.pos.y += posEstimator.est.vel.y * ctx->dt;
570 // If heading is valid, accelNEU is valid as well. Account for acceleration
571 if (navIsHeadingUsable() && navIsAccelerationUsable()) {
572 posEstimator.est.pos.x += posEstimator.imu.accelNEU.x * sq(ctx->dt) / 2.0f;
573 posEstimator.est.pos.y += posEstimator.imu.accelNEU.y * sq(ctx->dt) / 2.0f;
574 posEstimator.est.vel.x += posEstimator.imu.accelNEU.x * ctx->dt;
575 posEstimator.est.vel.y += posEstimator.imu.accelNEU.y * ctx->dt;
580 static bool estimationCalculateCorrection_Z(estimationContext_t * ctx)
582 DEBUG_SET(DEBUG_ALTITUDE, 0, posEstimator.est.pos.z); // Position estimate
583 DEBUG_SET(DEBUG_ALTITUDE, 2, posEstimator.baro.alt); // Baro altitude
584 DEBUG_SET(DEBUG_ALTITUDE, 4, posEstimator.gps.pos.z); // GPS altitude
585 DEBUG_SET(DEBUG_ALTITUDE, 6, accGetVibrationLevel()); // Vibration level
586 DEBUG_SET(DEBUG_ALTITUDE, 1, posEstimator.est.vel.z); // Vertical speed estimate
587 DEBUG_SET(DEBUG_ALTITUDE, 3, posEstimator.imu.accelNEU.z); // Vertical acceleration on earth frame
588 DEBUG_SET(DEBUG_ALTITUDE, 5, posEstimator.gps.vel.z); // GPS vertical speed
589 DEBUG_SET(DEBUG_ALTITUDE, 7, accGetClipCount()); // Clip count
591 bool correctOK = false;
593 //ignore baro if difference is too big, baro is probably wrong
594 const float gpsBaroResidual = ctx->newFlags & EST_GPS_Z_VALID ? fabsf(posEstimator.gps.pos.z - posEstimator.baro.alt) : 0.0f;
595 //fade out the baro to prevent sudden jump
596 const float start_epv = positionEstimationConfig()->max_eph_epv;
597 const float end_epv = positionEstimationConfig()->max_eph_epv * 2.0f;
598 const float wBaro = scaleRangef(constrainf(gpsBaroResidual, start_epv, end_epv), start_epv, end_epv, 1.0f, 0.0f);
599 //use both baro and gps
600 if ((ctx->newFlags & EST_BARO_VALID) && (!positionEstimationConfig()->use_gps_no_baro) && (wBaro > 0.01f)) {
601 timeUs_t currentTimeUs = micros();
603 if (!ARMING_FLAG(ARMED)) {
604 posEstimator.state.baroGroundAlt = posEstimator.est.pos.z;
605 posEstimator.state.isBaroGroundValid = true;
606 posEstimator.state.baroGroundTimeout = currentTimeUs + 250000; // 0.25 sec
608 else {
609 if (posEstimator.est.vel.z > 15) {
610 posEstimator.state.isBaroGroundValid = currentTimeUs > posEstimator.state.baroGroundTimeout ? false: true;
612 else {
613 posEstimator.state.baroGroundTimeout = currentTimeUs + 250000; // 0.25 sec
617 // We might be experiencing air cushion effect during takeoff - use sonar or baro ground altitude to detect it
618 bool isAirCushionEffectDetected = ARMING_FLAG(ARMED) &&
619 (((ctx->newFlags & EST_SURFACE_VALID) && posEstimator.surface.alt < 20.0f && posEstimator.state.isBaroGroundValid) ||
620 ((ctx->newFlags & EST_BARO_VALID) && posEstimator.state.isBaroGroundValid && posEstimator.baro.alt < posEstimator.state.baroGroundAlt));
622 // Altitude
623 const float baroAltResidual = (isAirCushionEffectDetected ? posEstimator.state.baroGroundAlt : posEstimator.baro.alt) - posEstimator.est.pos.z;
624 ctx->estPosCorr.z += wBaro * baroAltResidual * positionEstimationConfig()->w_z_baro_p * ctx->dt;
625 ctx->estVelCorr.z += wBaro * baroAltResidual * sq(positionEstimationConfig()->w_z_baro_p) * ctx->dt;
627 ctx->newEPV = updateEPE(posEstimator.est.epv, ctx->dt, posEstimator.baro.epv, positionEstimationConfig()->w_z_baro_p);
629 // Accelerometer bias
630 if (!isAirCushionEffectDetected) {
631 ctx->accBiasCorr.z -= wBaro * baroAltResidual * sq(positionEstimationConfig()->w_z_baro_p);
634 correctOK = true;
636 if (ctx->newFlags & EST_GPS_Z_VALID) {
637 // Reset current estimate to GPS altitude if estimate not valid
638 if (!(ctx->newFlags & EST_Z_VALID)) {
639 ctx->estPosCorr.z += posEstimator.gps.pos.z - posEstimator.est.pos.z;
640 ctx->estVelCorr.z += posEstimator.gps.vel.z - posEstimator.est.vel.z;
641 ctx->newEPV = posEstimator.gps.epv;
643 else {
644 // Altitude
645 const float gpsAltResudual = posEstimator.gps.pos.z - posEstimator.est.pos.z;
646 const float gpsVelZResudual = posEstimator.gps.vel.z - posEstimator.est.vel.z;
648 ctx->estPosCorr.z += gpsAltResudual * positionEstimationConfig()->w_z_gps_p * ctx->dt;
649 ctx->estVelCorr.z += gpsAltResudual * sq(positionEstimationConfig()->w_z_gps_p) * ctx->dt;
650 ctx->estVelCorr.z += gpsVelZResudual * positionEstimationConfig()->w_z_gps_v * ctx->dt;
651 ctx->newEPV = updateEPE(posEstimator.est.epv, ctx->dt, MAX(posEstimator.gps.epv, gpsAltResudual), positionEstimationConfig()->w_z_gps_p);
653 // Accelerometer bias
654 ctx->accBiasCorr.z -= gpsAltResudual * sq(positionEstimationConfig()->w_z_gps_p);
657 correctOK = true;
660 return correctOK;
663 static bool estimationCalculateCorrection_XY_GPS(estimationContext_t * ctx)
665 if (ctx->newFlags & EST_GPS_XY_VALID) {
666 /* If GPS is valid and our estimate is NOT valid - reset it to GPS coordinates and velocity */
667 if (!(ctx->newFlags & EST_XY_VALID)) {
668 ctx->estPosCorr.x += posEstimator.gps.pos.x - posEstimator.est.pos.x;
669 ctx->estPosCorr.y += posEstimator.gps.pos.y - posEstimator.est.pos.y;
670 ctx->estVelCorr.x += posEstimator.gps.vel.x - posEstimator.est.vel.x;
671 ctx->estVelCorr.y += posEstimator.gps.vel.y - posEstimator.est.vel.y;
672 ctx->newEPH = posEstimator.gps.eph;
674 else {
675 const float gpsPosXResidual = posEstimator.gps.pos.x - posEstimator.est.pos.x;
676 const float gpsPosYResidual = posEstimator.gps.pos.y - posEstimator.est.pos.y;
677 const float gpsVelXResidual = posEstimator.gps.vel.x - posEstimator.est.vel.x;
678 const float gpsVelYResidual = posEstimator.gps.vel.y - posEstimator.est.vel.y;
679 const float gpsPosResidualMag = calc_length_pythagorean_2D(gpsPosXResidual, gpsPosYResidual);
681 //const float gpsWeightScaler = scaleRangef(bellCurve(gpsPosResidualMag, INAV_GPS_ACCEPTANCE_EPE), 0.0f, 1.0f, 0.1f, 1.0f);
682 const float gpsWeightScaler = 1.0f;
684 const float w_xy_gps_p = positionEstimationConfig()->w_xy_gps_p * gpsWeightScaler;
685 const float w_xy_gps_v = positionEstimationConfig()->w_xy_gps_v * sq(gpsWeightScaler);
687 // Coordinates
688 ctx->estPosCorr.x += gpsPosXResidual * w_xy_gps_p * ctx->dt;
689 ctx->estPosCorr.y += gpsPosYResidual * w_xy_gps_p * ctx->dt;
691 // Velocity from coordinates
692 ctx->estVelCorr.x += gpsPosXResidual * sq(w_xy_gps_p) * ctx->dt;
693 ctx->estVelCorr.y += gpsPosYResidual * sq(w_xy_gps_p) * ctx->dt;
695 // Velocity from direct measurement
696 ctx->estVelCorr.x += gpsVelXResidual * w_xy_gps_v * ctx->dt;
697 ctx->estVelCorr.y += gpsVelYResidual * w_xy_gps_v * ctx->dt;
699 // Accelerometer bias
700 ctx->accBiasCorr.x -= gpsPosXResidual * sq(w_xy_gps_p);
701 ctx->accBiasCorr.y -= gpsPosYResidual * sq(w_xy_gps_p);
703 /* Adjust EPH */
704 ctx->newEPH = updateEPE(posEstimator.est.eph, ctx->dt, MAX(posEstimator.gps.eph, gpsPosResidualMag), w_xy_gps_p);
707 return true;
710 return false;
713 static void estimationCalculateGroundCourse(timeUs_t currentTimeUs)
715 UNUSED(currentTimeUs);
716 if (STATE(GPS_FIX) && navIsHeadingUsable()) {
717 uint32_t groundCourse = wrap_36000(RADIANS_TO_CENTIDEGREES(atan2_approx(posEstimator.est.vel.y, posEstimator.est.vel.x)));
718 posEstimator.est.cog = CENTIDEGREES_TO_DECIDEGREES(groundCourse);
723 * Calculate next estimate using IMU and apply corrections from reference sensors (GPS, BARO etc)
724 * Function is called at main loop rate
726 static void updateEstimatedTopic(timeUs_t currentTimeUs)
728 estimationContext_t ctx;
730 /* Calculate dT */
731 ctx.dt = US2S(currentTimeUs - posEstimator.est.lastUpdateTime);
732 posEstimator.est.lastUpdateTime = currentTimeUs;
734 /* If IMU is not ready we can't estimate anything */
735 if (!isImuReady()) {
736 posEstimator.est.eph = positionEstimationConfig()->max_eph_epv + 0.001f;
737 posEstimator.est.epv = positionEstimationConfig()->max_eph_epv + 0.001f;
738 posEstimator.flags = 0;
739 return;
742 /* Calculate new EPH and EPV for the case we didn't update postion */
743 ctx.newEPH = posEstimator.est.eph * ((posEstimator.est.eph <= positionEstimationConfig()->max_eph_epv) ? 1.0f + ctx.dt : 1.0f);
744 ctx.newEPV = posEstimator.est.epv * ((posEstimator.est.epv <= positionEstimationConfig()->max_eph_epv) ? 1.0f + ctx.dt : 1.0f);
745 ctx.newFlags = calculateCurrentValidityFlags(currentTimeUs);
746 vectorZero(&ctx.estPosCorr);
747 vectorZero(&ctx.estVelCorr);
748 vectorZero(&ctx.accBiasCorr);
750 /* AGL estimation - separate process, decouples from Z coordinate */
751 estimationCalculateAGL(&ctx);
753 /* Prediction stage: X,Y,Z */
754 estimationPredict(&ctx);
756 /* Correction stage: Z */
757 const bool estZCorrectOk =
758 estimationCalculateCorrection_Z(&ctx);
760 /* Correction stage: XY: GPS, FLOW */
761 // FIXME: Handle transition from FLOW to GPS and back - seamlessly fly indoor/outdoor
762 const bool estXYCorrectOk =
763 estimationCalculateCorrection_XY_GPS(&ctx) ||
764 estimationCalculateCorrection_XY_FLOW(&ctx);
766 // If we can't apply correction or accuracy is off the charts - decay velocity to zero
767 if (!estXYCorrectOk || ctx.newEPH > positionEstimationConfig()->max_eph_epv) {
768 ctx.estVelCorr.x = (0.0f - posEstimator.est.vel.x) * positionEstimationConfig()->w_xy_res_v * ctx.dt;
769 ctx.estVelCorr.y = (0.0f - posEstimator.est.vel.y) * positionEstimationConfig()->w_xy_res_v * ctx.dt;
772 if (!estZCorrectOk || ctx.newEPV > positionEstimationConfig()->max_eph_epv) {
773 ctx.estVelCorr.z = (0.0f - posEstimator.est.vel.z) * positionEstimationConfig()->w_z_res_v * ctx.dt;
775 // Boost the corrections based on accWeight
776 const float accWeight = navGetAccelerometerWeight();
777 vectorScale(&ctx.estPosCorr, &ctx.estPosCorr, 1.0f/accWeight);
778 vectorScale(&ctx.estVelCorr, &ctx.estVelCorr, 1.0f/accWeight);
779 // Apply corrections
780 vectorAdd(&posEstimator.est.pos, &posEstimator.est.pos, &ctx.estPosCorr);
781 vectorAdd(&posEstimator.est.vel, &posEstimator.est.vel, &ctx.estVelCorr);
783 /* Correct accelerometer bias */
784 if (positionEstimationConfig()->w_acc_bias > 0.0f) {
785 const float accelBiasCorrMagnitudeSq = sq(ctx.accBiasCorr.x) + sq(ctx.accBiasCorr.y) + sq(ctx.accBiasCorr.z);
786 if (accelBiasCorrMagnitudeSq < sq(INAV_ACC_BIAS_ACCEPTANCE_VALUE)) {
787 /* transform error vector from NEU frame to body frame */
788 imuTransformVectorEarthToBody(&ctx.accBiasCorr);
790 /* Correct accel bias */
791 posEstimator.imu.accelBias.x += ctx.accBiasCorr.x * positionEstimationConfig()->w_acc_bias * ctx.dt;
792 posEstimator.imu.accelBias.y += ctx.accBiasCorr.y * positionEstimationConfig()->w_acc_bias * ctx.dt;
793 posEstimator.imu.accelBias.z += ctx.accBiasCorr.z * positionEstimationConfig()->w_acc_bias * ctx.dt;
797 /* Update ground course */
798 estimationCalculateGroundCourse(currentTimeUs);
800 /* Update uncertainty */
801 posEstimator.est.eph = ctx.newEPH;
802 posEstimator.est.epv = ctx.newEPV;
804 // Keep flags for further usage
805 posEstimator.flags = ctx.newFlags;
809 * Examine estimation error and update navigation system if estimate is good enough
810 * Function is called at main loop rate, but updates happen less frequently - at a fixed rate
812 static void publishEstimatedTopic(timeUs_t currentTimeUs)
814 static navigationTimer_t posPublishTimer;
816 /* Position and velocity are published with INAV_POSITION_PUBLISH_RATE_HZ */
817 if (updateTimer(&posPublishTimer, HZ2US(INAV_POSITION_PUBLISH_RATE_HZ), currentTimeUs)) {
818 /* Publish heading update */
819 /* IMU operates in decidegrees while INAV operates in deg*100
820 * Use course over ground when GPS heading valid */
821 int16_t cogValue = isGPSHeadingValid() ? posEstimator.est.cog : attitude.values.yaw;
822 updateActualHeading(navIsHeadingUsable(), DECIDEGREES_TO_CENTIDEGREES(attitude.values.yaw), DECIDEGREES_TO_CENTIDEGREES(cogValue));
824 /* Publish position update */
825 if (posEstimator.est.eph < positionEstimationConfig()->max_eph_epv) {
826 // FIXME!!!!!
827 updateActualHorizontalPositionAndVelocity(true, true, posEstimator.est.pos.x, posEstimator.est.pos.y, posEstimator.est.vel.x, posEstimator.est.vel.y);
829 else {
830 updateActualHorizontalPositionAndVelocity(false, false, posEstimator.est.pos.x, posEstimator.est.pos.y, 0, 0);
833 /* Publish altitude update and set altitude validity */
834 if (posEstimator.est.epv < positionEstimationConfig()->max_eph_epv) {
835 const float gpsCfEstimatedAltitudeError = STATE(GPS_FIX) ? posEstimator.gps.pos.z - posEstimator.est.pos.z : 0;
836 navigationEstimateStatus_e aglStatus = (posEstimator.est.aglQual == SURFACE_QUAL_LOW) ? EST_USABLE : EST_TRUSTED;
837 updateActualAltitudeAndClimbRate(true, posEstimator.est.pos.z, posEstimator.est.vel.z, posEstimator.est.aglAlt, posEstimator.est.aglVel, aglStatus, gpsCfEstimatedAltitudeError);
839 else {
840 updateActualAltitudeAndClimbRate(false, posEstimator.est.pos.z, 0, posEstimator.est.aglAlt, 0, EST_NONE, 0);
843 //Update Blackbox states
844 navEPH = posEstimator.est.eph;
845 navEPV = posEstimator.est.epv;
847 DEBUG_SET(DEBUG_POS_EST, 0, (int32_t) posEstimator.est.pos.x*1000.0F); // Position estimate X
848 DEBUG_SET(DEBUG_POS_EST, 1, (int32_t) posEstimator.est.pos.y*1000.0F); // Position estimate Y
849 if (IS_RC_MODE_ACTIVE(BOXSURFACE) && posEstimator.est.aglQual!=SURFACE_QUAL_LOW){
850 // SURFACE (following) MODE
851 DEBUG_SET(DEBUG_POS_EST, 2, (int32_t) posControl.actualState.agl.pos.z*1000.0F); // Position estimate Z
852 DEBUG_SET(DEBUG_POS_EST, 5, (int32_t) posControl.actualState.agl.vel.z*1000.0F); // Speed estimate VZ
853 } else {
854 DEBUG_SET(DEBUG_POS_EST, 2, (int32_t) posEstimator.est.pos.z*1000.0F); // Position estimate Z
855 DEBUG_SET(DEBUG_POS_EST, 5, (int32_t) posEstimator.est.vel.z*1000.0F); // Speed estimate VZ
857 DEBUG_SET(DEBUG_POS_EST, 3, (int32_t) posEstimator.est.vel.x*1000.0F); // Speed estimate VX
858 DEBUG_SET(DEBUG_POS_EST, 4, (int32_t) posEstimator.est.vel.y*1000.0F); // Speed estimate VY
859 DEBUG_SET(DEBUG_POS_EST, 6, (int32_t) attitude.values.yaw); // Yaw estimate (4 bytes still available here)
860 DEBUG_SET(DEBUG_POS_EST, 7, (int32_t) (posEstimator.flags & 0b1111111)<<20 | // navPositionEstimationFlags fit into 8bits
861 (MIN(navEPH, 1000) & 0x3FF)<<10 |
862 (MIN(navEPV, 1000) & 0x3FF)); // Horizontal and vertical uncertainties (max value = 1000, fit into 20bits)
866 #if defined(NAV_GPS_GLITCH_DETECTION)
867 bool isGPSGlitchDetected(void)
869 return posEstimator.gps.glitchDetected;
871 #endif
873 float getEstimatedAglPosition(void) {
874 return posEstimator.est.aglAlt;
877 bool isEstimatedAglTrusted(void) {
878 return (posEstimator.est.aglQual == SURFACE_QUAL_HIGH) ? true : false;
882 * Initialize position estimator
883 * Should be called once before any update occurs
885 void initializePositionEstimator(void)
887 int axis;
889 posEstimator.est.eph = positionEstimationConfig()->max_eph_epv + 0.001f;
890 posEstimator.est.epv = positionEstimationConfig()->max_eph_epv + 0.001f;
892 posEstimator.imu.lastUpdateTime = 0;
893 posEstimator.gps.lastUpdateTime = 0;
894 posEstimator.baro.lastUpdateTime = 0;
895 posEstimator.surface.lastUpdateTime = 0;
897 posEstimator.est.aglAlt = 0;
898 posEstimator.est.aglVel = 0;
900 posEstimator.est.flowCoordinates[X] = 0;
901 posEstimator.est.flowCoordinates[Y] = 0;
903 posEstimator.imu.accWeightFactor = 0;
905 restartGravityCalibration();
907 for (axis = 0; axis < 3; axis++) {
908 posEstimator.imu.accelBias.v[axis] = 0;
909 posEstimator.est.pos.v[axis] = 0;
910 posEstimator.est.vel.v[axis] = 0;
913 pt1FilterInit(&posEstimator.baro.avgFilter, INAV_BARO_AVERAGE_HZ, 0.0f);
914 pt1FilterInit(&posEstimator.surface.avgFilter, INAV_SURFACE_AVERAGE_HZ, 0.0f);
918 * Update estimator
919 * Update rate: loop rate (>100Hz)
921 void updatePositionEstimator(void)
923 static bool isInitialized = false;
925 if (!isInitialized) {
926 initializePositionEstimator();
927 isInitialized = true;
930 const timeUs_t currentTimeUs = micros();
932 /* Read updates from IMU, preprocess */
933 updateIMUTopic(currentTimeUs);
935 /* Update estimate */
936 updateEstimatedTopic(currentTimeUs);
938 /* Publish estimate */
939 publishEstimatedTopic(currentTimeUs);
942 bool navIsCalibrationComplete(void)
944 return gravityCalibrationComplete();