aboutsummaryrefslogtreecommitdiff
path: root/src/modules/position_estimator_inav
diff options
context:
space:
mode:
authorJulian Oes <julian@oes.ch>2014-04-26 23:31:15 +0200
committerJulian Oes <julian@oes.ch>2014-04-26 23:31:15 +0200
commite882824ee15e0c5fff58c7f223ec7be181c7af8f (patch)
tree4822b8c3dd2bdd73b993b9c2be4953c6f2af72bb /src/modules/position_estimator_inav
parente8531e8360e4f061f3cd69db90365f64837a7c76 (diff)
downloadpx4-firmware-e882824ee15e0c5fff58c7f223ec7be181c7af8f.tar.gz
px4-firmware-e882824ee15e0c5fff58c7f223ec7be181c7af8f.tar.bz2
px4-firmware-e882824ee15e0c5fff58c7f223ec7be181c7af8f.zip
eph and epv renaming, make this compile again
Diffstat (limited to 'src/modules/position_estimator_inav')
-rw-r--r--src/modules/position_estimator_inav/position_estimator_inav_main.c12
1 files changed, 6 insertions, 6 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 368424853..54c8a7d17 100644
--- a/src/modules/position_estimator_inav/position_estimator_inav_main.c
+++ b/src/modules/position_estimator_inav/position_estimator_inav_main.c
@@ -592,13 +592,13 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
/* hysteresis for GPS quality */
if (gps_valid) {
- if (gps.eph_m > max_eph_epv * 1.5f || gps.epv_m > max_eph_epv * 1.5f || gps.fix_type < 3) {
+ if (gps.eph > max_eph_epv * 1.5f || gps.epv > max_eph_epv * 1.5f || gps.fix_type < 3) {
gps_valid = false;
mavlink_log_info(mavlink_fd, "[inav] GPS signal lost");
}
} else {
- if (gps.eph_m < max_eph_epv && gps.epv_m < max_eph_epv && gps.fix_type >= 3) {
+ if (gps.eph < max_eph_epv && gps.epv < max_eph_epv && gps.fix_type >= 3) {
gps_valid = true;
reset_est = true;
mavlink_log_info(mavlink_fd, "[inav] GPS signal found");
@@ -673,8 +673,8 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
corr_gps[2][1] = 0.0f;
}
- w_gps_xy = min_eph_epv / fmaxf(min_eph_epv, gps.eph_m);
- w_gps_z = min_eph_epv / fmaxf(min_eph_epv, gps.epv_m);
+ w_gps_xy = min_eph_epv / fmaxf(min_eph_epv, gps.eph);
+ w_gps_z = min_eph_epv / fmaxf(min_eph_epv, gps.epv);
}
} else {
@@ -951,8 +951,8 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
global_pos.yaw = local_pos.yaw;
// TODO implement dead-reckoning
- global_pos.eph = gps.eph_m;
- global_pos.epv = gps.epv_m;
+ global_pos.eph = gps.eph;
+ global_pos.epv = gps.epv;
if (vehicle_global_position_pub < 0) {
vehicle_global_position_pub = orb_advertise(ORB_ID(vehicle_global_position), &global_pos);