diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index bb718961cd..60ccf10986 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -1206,6 +1206,10 @@ groups: field: w_xy_res_v min: 0 max: 10 + - name: inav_w_xyz_acc_p + field: w_xyz_acc_p + min: 0 + max: 1 - name: inav_w_acc_bias field: w_acc_bias min: 0 diff --git a/src/main/navigation/navigation.h b/src/main/navigation/navigation.h index 6a7c9d19e9..7916dbb746 100755 --- a/src/main/navigation/navigation.h +++ b/src/main/navigation/navigation.h @@ -114,6 +114,7 @@ typedef struct positionEstimationConfig_s { float w_xy_res_v; float w_acc_bias; // Weight (cutoff frequency) for accelerometer bias estimation. 0 to disable. + float w_xyz_acc_p; float max_eph_epv; // Max estimated position error acceptable for estimation (cm) float baro_epv; // Baro position error diff --git a/src/main/navigation/navigation_pos_estimator.c b/src/main/navigation/navigation_pos_estimator.c index cf9445786d..cfd8f12807 100755 --- a/src/main/navigation/navigation_pos_estimator.c +++ b/src/main/navigation/navigation_pos_estimator.c @@ -53,7 +53,7 @@ navigationPosEstimator_t posEstimator; -PG_REGISTER_WITH_RESET_TEMPLATE(positionEstimationConfig_t, positionEstimationConfig, PG_POSITION_ESTIMATION_CONFIG, 3); +PG_REGISTER_WITH_RESET_TEMPLATE(positionEstimationConfig_t, positionEstimationConfig, PG_POSITION_ESTIMATION_CONFIG, 4); PG_RESET_TEMPLATE(positionEstimationConfig_t, positionEstimationConfig, // Inertial position estimator parameters @@ -66,6 +66,8 @@ PG_RESET_TEMPLATE(positionEstimationConfig_t, positionEstimationConfig, .max_surface_altitude = 200, + .w_xyz_acc_p = 1.0f, + .w_z_baro_p = 0.35f, .w_z_surface_p = 3.500f, @@ -433,6 +435,12 @@ static bool navIsHeadingUsable(void) } } +float navGetAccelerometerWeight(void) +{ + // TODO(digitalentity): consider accelerometer health in weight calculation + return positionEstimationConfig()->w_xyz_acc_p; +} + static uint32_t calculateCurrentValidityFlags(timeUs_t currentTimeUs) { /* Figure out if we have valid position data from our data sources */ @@ -474,11 +482,13 @@ static uint32_t calculateCurrentValidityFlags(timeUs_t currentTimeUs) static void estimationPredict(estimationContext_t * ctx) { + const float accWeight = navGetAccelerometerWeight(); + /* Prediction step: Z-axis */ if ((ctx->newFlags & EST_Z_VALID)) { posEstimator.est.pos.z += posEstimator.est.vel.z * ctx->dt; - posEstimator.est.pos.z += posEstimator.imu.accelNEU.z * sq(ctx->dt) / 2.0f; - posEstimator.est.vel.z += posEstimator.imu.accelNEU.z * ctx->dt; + posEstimator.est.pos.z += posEstimator.imu.accelNEU.z * sq(ctx->dt) / 2.0f * accWeight; + posEstimator.est.vel.z += posEstimator.imu.accelNEU.z * ctx->dt * sq(accWeight); } /* Prediction step: XY-axis */ @@ -489,10 +499,10 @@ static void estimationPredict(estimationContext_t * ctx) // If heading is valid, accelNEU is valid as well. Account for acceleration if (navIsHeadingUsable() && navIsAccelerationUsable()) { - posEstimator.est.pos.x += posEstimator.imu.accelNEU.x * sq(ctx->dt) / 2.0f; - posEstimator.est.pos.y += posEstimator.imu.accelNEU.y * sq(ctx->dt) / 2.0f; - posEstimator.est.vel.x += posEstimator.imu.accelNEU.x * ctx->dt; - posEstimator.est.vel.y += posEstimator.imu.accelNEU.y * ctx->dt; + posEstimator.est.pos.x += posEstimator.imu.accelNEU.x * sq(ctx->dt) / 2.0f * accWeight; + posEstimator.est.pos.y += posEstimator.imu.accelNEU.y * sq(ctx->dt) / 2.0f * accWeight; + posEstimator.est.vel.x += posEstimator.imu.accelNEU.x * ctx->dt * sq(accWeight); + posEstimator.est.vel.y += posEstimator.imu.accelNEU.y * ctx->dt * sq(accWeight); } } } diff --git a/src/main/navigation/navigation_pos_estimator_agl.c b/src/main/navigation/navigation_pos_estimator_agl.c index 21c09909de..0a97507204 100644 --- a/src/main/navigation/navigation_pos_estimator_agl.c +++ b/src/main/navigation/navigation_pos_estimator_agl.c @@ -149,9 +149,10 @@ void estimationCalculateAGL(estimationContext_t * ctx) } // Update estimate + const float accWeight = navGetAccelerometerWeight(); posEstimator.est.aglAlt += posEstimator.est.aglVel * ctx->dt; - posEstimator.est.aglAlt += posEstimator.imu.accelNEU.z * sq(ctx->dt) / 2.0f; - posEstimator.est.aglVel += posEstimator.imu.accelNEU.z * ctx->dt; + posEstimator.est.aglAlt += posEstimator.imu.accelNEU.z * sq(ctx->dt) / 2.0f * accWeight; + posEstimator.est.aglVel += posEstimator.imu.accelNEU.z * ctx->dt * sq(accWeight); // Apply correction if (posEstimator.est.aglQual == SURFACE_QUAL_HIGH) { diff --git a/src/main/navigation/navigation_pos_estimator_private.h b/src/main/navigation/navigation_pos_estimator_private.h index 46c1550978..19e3f83fde 100644 --- a/src/main/navigation/navigation_pos_estimator_private.h +++ b/src/main/navigation/navigation_pos_estimator_private.h @@ -182,5 +182,5 @@ typedef struct { extern float updateEPE(const float oldEPE, const float dt, const float newEPE, const float w); extern void estimationCalculateAGL(estimationContext_t * ctx); extern bool estimationCalculateCorrection_XY_FLOW(estimationContext_t * ctx); - +extern float navGetAccelerometerWeight(void);