From ec04eba61c136471f8864278c72343df8f61db16 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 2 Apr 2014 07:49:58 +1100 Subject: [PATCH] Replay: handle multiple GPS sensors --- Tools/Replay/LogReader.cpp | 36 ++++++++++++++++++++++++++++++++++-- 1 file changed, 34 insertions(+), 2 deletions(-) diff --git a/Tools/Replay/LogReader.cpp b/Tools/Replay/LogReader.cpp index 836c9006df..fe07cc9517 100644 --- a/Tools/Replay/LogReader.cpp +++ b/Tools/Replay/LogReader.cpp @@ -382,11 +382,13 @@ bool LogReader::update(uint8_t &type) Vector3f vel(msg.ground_speed*0.01f*cosf(msg.ground_course*0.01f), msg.ground_speed*0.01f*sinf(msg.ground_course*0.01f), msg.vel_z); - gps.setHIL((AP_GPS::GPS_Status)msg.status, + gps.setHIL(0, (AP_GPS::GPS_Status)msg.status, msg.apm_time, loc, vel, - msg.num_sats); + msg.num_sats, + msg.hdop, + msg.vel_z != 0); if (msg.status == 3 && ground_alt_cm == 0) { ground_alt_cm = msg.altitude; } @@ -394,6 +396,36 @@ bool LogReader::update(uint8_t &type) break; } + case LOG_GPS2_MSG: { + struct log_GPS2 msg; + if(sizeof(msg) != f.length) { + printf("Bad GPS2 length\n"); + exit(1); + } + memcpy(&msg, data, sizeof(msg)); + wait_timestamp(msg.apm_time); + Location loc; + loc.lat = msg.latitude; + loc.lng = msg.longitude; + loc.alt = msg.altitude; + loc.options = 0; + + Vector3f vel(msg.ground_speed*0.01f*cosf(msg.ground_course*0.01f), + msg.ground_speed*0.01f*sinf(msg.ground_course*0.01f), + msg.vel_z); + gps.setHIL(1, (AP_GPS::GPS_Status)msg.status, + msg.apm_time, + loc, + vel, + msg.num_sats, + msg.hdop, + msg.vel_z != 0); + if (msg.status == 3 && ground_alt_cm == 0) { + ground_alt_cm = msg.altitude; + } + break; + } + case LOG_SIMSTATE_MSG: { struct log_AHRS msg; if(sizeof(msg) != f.length) {