aboutsummaryrefslogtreecommitdiff
path: root/apps/gps
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2012-11-12 17:36:17 +0100
committerLorenz Meier <lm@inf.ethz.ch>2012-11-12 17:36:17 +0100
commit66e806754ba17c127cd9fa657b0bad5d0b2015a3 (patch)
treee7119b7da4d144a8724f1c145f10ca891a76604a /apps/gps
parent2c12802f25cef99da345493d01c54c7c39602ccc (diff)
downloadpx4-firmware-66e806754ba17c127cd9fa657b0bad5d0b2015a3.tar.gz
px4-firmware-66e806754ba17c127cd9fa657b0bad5d0b2015a3.tar.bz2
px4-firmware-66e806754ba17c127cd9fa657b0bad5d0b2015a3.zip
Fixed GPS status detection
Diffstat (limited to 'apps/gps')
-rw-r--r--apps/gps/mtk.c7
-rw-r--r--apps/gps/ubx.c11
2 files changed, 10 insertions, 8 deletions
diff --git a/apps/gps/mtk.c b/apps/gps/mtk.c
index 374280d28..604dba05c 100644
--- a/apps/gps/mtk.c
+++ b/apps/gps/mtk.c
@@ -418,10 +418,11 @@ void *mtk_watchdog_loop(void *args)
mtk_gps->satellite_info_available = 0;
// global_data_send_subsystem_info(&mtk_present_enabled_healthy);
mavlink_log_info(mavlink_fd, "[gps] MTK custom binary module found, status ok\n");
- mtk_healthy = true;
- mtk_fail_count = 0;
- once_ok = true;
}
+
+ mtk_healthy = true;
+ mtk_fail_count = 0;
+ once_ok = true;
}
usleep(MTK_WATCHDOG_WAIT_TIME_MICROSECONDS);
diff --git a/apps/gps/ubx.c b/apps/gps/ubx.c
index 03ae622a1..21e917bf8 100644
--- a/apps/gps/ubx.c
+++ b/apps/gps/ubx.c
@@ -272,7 +272,8 @@ int ubx_parse(uint8_t b, char *gps_rx_buffer)
ubx_gps->timestamp = hrt_absolute_time();
ubx_gps->counter++;
-
+ ubx_gps->s_variance = packet->sAcc;
+ ubx_gps->p_variance = packet->pAcc;
//pthread_mutex_lock(ubx_mutex);
ubx_state->last_message_timestamps[NAV_SOL - 1] = hrt_absolute_time();
@@ -785,10 +786,6 @@ void *ubx_watchdog_loop(void *args)
sleep(1);
} else {
- /* gps healthy */
- ubx_success_count++;
- ubx_healthy = true;
- ubx_fail_count = 0;
if (!ubx_healthy && ubx_success_count == UBX_HEALTH_SUCCESS_COUNTER_LIMIT) {
//printf("[gps] ublox UBX module status ok (baud=%d)\r\n", current_gps_speed);
@@ -799,6 +796,10 @@ void *ubx_watchdog_loop(void *args)
once_ok = true;
}
+ /* gps healthy */
+ ubx_success_count++;
+ ubx_healthy = true;
+ ubx_fail_count = 0;
}
usleep(UBX_WATCHDOG_WAIT_TIME_MICROSECONDS);