From 63874dfffd8de764b430aa012c47a3a7c536bac5 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 25 Feb 2014 21:10:49 +1100 Subject: [PATCH] AP_NavEKF: set fix type in GPS replay --- libraries/AP_NavEKF/examples/AP_NavEKF/AP_NavEKF.pde | 1 + libraries/AP_NavEKF/examples/AP_NavEKF/LogReader.cpp | 5 +++-- 2 files changed, 4 insertions(+), 2 deletions(-) diff --git a/libraries/AP_NavEKF/examples/AP_NavEKF/AP_NavEKF.pde b/libraries/AP_NavEKF/examples/AP_NavEKF/AP_NavEKF.pde index 924bd30095..7e0a488e5e 100644 --- a/libraries/AP_NavEKF/examples/AP_NavEKF/AP_NavEKF.pde +++ b/libraries/AP_NavEKF/examples/AP_NavEKF/AP_NavEKF.pde @@ -172,6 +172,7 @@ static void read_sensors(uint8_t type) barometer.read(); if (!done_baro_init) { done_baro_init = true; + ::printf("Barometer initialised\n"); barometer.update_calibration(); } } diff --git a/libraries/AP_NavEKF/examples/AP_NavEKF/LogReader.cpp b/libraries/AP_NavEKF/examples/AP_NavEKF/LogReader.cpp index 26722ebc1e..fc3afac119 100644 --- a/libraries/AP_NavEKF/examples/AP_NavEKF/LogReader.cpp +++ b/libraries/AP_NavEKF/examples/AP_NavEKF/LogReader.cpp @@ -285,14 +285,15 @@ bool LogReader::update(uint8_t &type) } memcpy(&msg, data, sizeof(msg)); wait_timestamp(msg.apm_time); - gps->setHIL(msg.apm_time, + gps->setHIL(msg.status==3?GPS::FIX_3D:GPS::FIX_NONE, + msg.apm_time, msg.latitude*1.0e-7f, msg.longitude*1.0e-7f, msg.altitude*1.0e-2f, msg.ground_speed*1.0e-2f, msg.ground_course*1.0e-2f, 0, - msg.status==3?msg.num_sats:0); + msg.num_sats); if (msg.status == 3 && ground_alt_cm == 0) { ground_alt_cm = msg.altitude; }