aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorLorenz Meier <lorenz@px4.io>2015-01-23 20:26:50 +0100
committerLorenz Meier <lorenz@px4.io>2015-01-23 20:26:50 +0100
commitba54deefc929ca670ae725cb772a8fe574f74742 (patch)
treed54bac920277192c9df8e65308b9a4c3a14e943c
parentb14e849fc4bcf81bbffd47064e2850a929652f6d (diff)
parent0632d882bb734ac52ff5f7f5d1dc7930046e4600 (diff)
downloadpx4-firmware-ba54deefc929ca670ae725cb772a8fe574f74742.tar.gz
px4-firmware-ba54deefc929ca670ae725cb772a8fe574f74742.tar.bz2
px4-firmware-ba54deefc929ca670ae725cb772a8fe574f74742.zip
Merge pull request #1397 from dyeldandi/vz
Adding vertical (Z) velocity to inav estimator
-rw-r--r--src/modules/position_estimator_inav/position_estimator_inav_main.c3
-rw-r--r--src/modules/position_estimator_inav/position_estimator_inav_params.c12
-rw-r--r--src/modules/position_estimator_inav/position_estimator_inav_params.h2
3 files changed, 17 insertions, 0 deletions
diff --git a/src/modules/position_estimator_inav/position_estimator_inav_main.c b/src/modules/position_estimator_inav/position_estimator_inav_main.c
index 39294e3c0..86764d620 100644
--- a/src/modules/position_estimator_inav/position_estimator_inav_main.c
+++ b/src/modules/position_estimator_inav/position_estimator_inav_main.c
@@ -872,6 +872,7 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
float w_xy_gps_p = params.w_xy_gps_p * w_gps_xy;
float w_xy_gps_v = params.w_xy_gps_v * w_gps_xy;
float w_z_gps_p = params.w_z_gps_p * w_gps_z;
+ float w_z_gps_v = params.w_z_gps_v * w_gps_z;
float w_xy_vision_p = params.w_xy_vision_p;
float w_xy_vision_v = params.w_xy_vision_v;
@@ -902,6 +903,7 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
if (use_gps_z) {
accel_bias_corr[2] -= corr_gps[2][0] * w_z_gps_p * w_z_gps_p;
+ accel_bias_corr[2] -= corr_gps[2][1] * w_z_gps_v;
}
/* transform error vector from NED frame to body frame */
@@ -986,6 +988,7 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
epv = fminf(epv, gps.epv);
inertial_filter_correct(corr_gps[2][0], dt, z_est, 0, w_z_gps_p);
+ inertial_filter_correct(corr_gps[2][1], dt, z_est, 1, w_z_gps_v);
}
if (use_vision_z) {
diff --git a/src/modules/position_estimator_inav/position_estimator_inav_params.c b/src/modules/position_estimator_inav/position_estimator_inav_params.c
index b7f6509d7..5387b7e87 100644
--- a/src/modules/position_estimator_inav/position_estimator_inav_params.c
+++ b/src/modules/position_estimator_inav/position_estimator_inav_params.c
@@ -64,6 +64,17 @@ PARAM_DEFINE_FLOAT(INAV_W_Z_BARO, 0.5f);
PARAM_DEFINE_FLOAT(INAV_W_Z_GPS_P, 0.005f);
/**
+ * Z velocity weight for GPS
+ *
+ * Weight (cutoff frequency) for GPS altitude velocity measurements.
+ *
+ * @min 0.0
+ * @max 10.0
+ * @group Position Estimator INAV
+ */
+PARAM_DEFINE_FLOAT(INAV_W_Z_GPS_V, 0.0f);
+
+/**
* Z axis weight for vision
*
* Weight (cutoff frequency) for vision altitude measurements. vision altitude data is very noisy and should be used only as slow correction for baro offset.
@@ -281,6 +292,7 @@ int parameters_init(struct position_estimator_inav_param_handles *h)
{
h->w_z_baro = param_find("INAV_W_Z_BARO");
h->w_z_gps_p = param_find("INAV_W_Z_GPS_P");
+ h->w_z_gps_v = param_find("INAV_W_Z_GPS_V");
h->w_z_vision_p = param_find("INAV_W_Z_VIS_P");
h->w_z_sonar = param_find("INAV_W_Z_SONAR");
h->w_xy_gps_p = param_find("INAV_W_XY_GPS_P");
diff --git a/src/modules/position_estimator_inav/position_estimator_inav_params.h b/src/modules/position_estimator_inav/position_estimator_inav_params.h
index d0a65e42e..51bbda412 100644
--- a/src/modules/position_estimator_inav/position_estimator_inav_params.h
+++ b/src/modules/position_estimator_inav/position_estimator_inav_params.h
@@ -44,6 +44,7 @@
struct position_estimator_inav_params {
float w_z_baro;
float w_z_gps_p;
+ float w_z_gps_v;
float w_z_vision_p;
float w_z_sonar;
float w_xy_gps_p;
@@ -68,6 +69,7 @@ struct position_estimator_inav_params {
struct position_estimator_inav_param_handles {
param_t w_z_baro;
param_t w_z_gps_p;
+ param_t w_z_gps_v;
param_t w_z_vision_p;
param_t w_z_sonar;
param_t w_xy_gps_p;