diff options
author | Lorenz Meier <lm@inf.ethz.ch> | 2014-07-01 14:00:54 +0200 |
---|---|---|
committer | Lorenz Meier <lm@inf.ethz.ch> | 2014-07-01 14:00:54 +0200 |
commit | 4b9f9281f5d2b425f0de83801eb38224395c0f12 (patch) | |
tree | b0a5332543de1e6f4d46901a83c85bfebf6b4795 /src/modules/position_estimator_inav/position_estimator_inav_params.c | |
parent | 5c6a5411288ea181503269a711de2e626ddb5185 (diff) | |
parent | 8f957aeb5f8f7527d1ef2a5583f4de7870c60513 (diff) | |
download | px4-firmware-4b9f9281f5d2b425f0de83801eb38224395c0f12.tar.gz px4-firmware-4b9f9281f5d2b425f0de83801eb38224395c0f12.tar.bz2 px4-firmware-4b9f9281f5d2b425f0de83801eb38224395c0f12.zip |
Merged master into vision_estimate
Diffstat (limited to 'src/modules/position_estimator_inav/position_estimator_inav_params.c')
-rw-r--r-- | src/modules/position_estimator_inav/position_estimator_inav_params.c | 13 |
1 files changed, 10 insertions, 3 deletions
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 c7c1c070c..0d9fbef27 100644 --- a/src/modules/position_estimator_inav/position_estimator_inav_params.c +++ b/src/modules/position_estimator_inav/position_estimator_inav_params.c @@ -1,7 +1,6 @@ /**************************************************************************** * - * Copyright (C) 2013 Anton Babushkin. All rights reserved. - * Author: Anton Babushkin <rk3dov@gmail.com> + * Copyright (c) 2013, 2014 PX4 Development Team. All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -35,6 +34,8 @@ /* * @file position_estimator_inav_params.c * + * @author Anton Babushkin <rk3dov@gmail.com> + * * Parameters for position_estimator_inav */ @@ -46,6 +47,7 @@ PARAM_DEFINE_FLOAT(INAV_W_Z_SONAR, 3.0f); PARAM_DEFINE_FLOAT(INAV_W_XY_GPS_P, 1.0f); PARAM_DEFINE_FLOAT(INAV_W_XY_GPS_V, 2.0f); PARAM_DEFINE_FLOAT(INAV_W_XY_FLOW, 5.0f); +PARAM_DEFINE_FLOAT(INAV_W_XY_RES_V, 0.5f); PARAM_DEFINE_FLOAT(INAV_W_GPS_FLOW, 0.1f); PARAM_DEFINE_FLOAT(INAV_W_ACC_BIAS, 0.05f); PARAM_DEFINE_FLOAT(INAV_FLOW_K, 0.15f); @@ -55,7 +57,8 @@ PARAM_DEFINE_FLOAT(INAV_SONAR_ERR, 0.5f); PARAM_DEFINE_FLOAT(INAV_LAND_T, 3.0f); PARAM_DEFINE_FLOAT(INAV_LAND_DISP, 0.7f); PARAM_DEFINE_FLOAT(INAV_LAND_THR, 0.2f); -PARAM_DEFINE_INT32(CBRK_NO_VISION, 328754); +PARAM_DEFINE_INT32(CBRK_NO_VISION, 0); +PARAM_DEFINE_FLOAT(INAV_DELAY_GPS, 0.2f); int parameters_init(struct position_estimator_inav_param_handles *h) { @@ -65,6 +68,7 @@ int parameters_init(struct position_estimator_inav_param_handles *h) h->w_xy_gps_p = param_find("INAV_W_XY_GPS_P"); h->w_xy_gps_v = param_find("INAV_W_XY_GPS_V"); h->w_xy_flow = param_find("INAV_W_XY_FLOW"); + h->w_xy_res_v = param_find("INAV_W_XY_RES_V"); h->w_gps_flow = param_find("INAV_W_GPS_FLOW"); h->w_acc_bias = param_find("INAV_W_ACC_BIAS"); h->flow_k = param_find("INAV_FLOW_K"); @@ -75,6 +79,7 @@ int parameters_init(struct position_estimator_inav_param_handles *h) h->land_disp = param_find("INAV_LAND_DISP"); h->land_thr = param_find("INAV_LAND_THR"); h->no_vision = param_find("CBRK_NO_VISION"); + h->delay_gps = param_find("INAV_DELAY_GPS"); return OK; } @@ -87,6 +92,7 @@ int parameters_update(const struct position_estimator_inav_param_handles *h, str param_get(h->w_xy_gps_p, &(p->w_xy_gps_p)); param_get(h->w_xy_gps_v, &(p->w_xy_gps_v)); param_get(h->w_xy_flow, &(p->w_xy_flow)); + param_get(h->w_xy_res_v, &(p->w_xy_res_v)); param_get(h->w_gps_flow, &(p->w_gps_flow)); param_get(h->w_acc_bias, &(p->w_acc_bias)); param_get(h->flow_k, &(p->flow_k)); @@ -97,6 +103,7 @@ int parameters_update(const struct position_estimator_inav_param_handles *h, str param_get(h->land_disp, &(p->land_disp)); param_get(h->land_thr, &(p->land_thr)); param_get(h->no_vision, &(p->no_vision)); + param_get(h->delay_gps, &(p->delay_gps)); return OK; } |