From 094dd9d769b748869db9db8a345c16531ffeccc8 Mon Sep 17 00:00:00 2001 From: Paul Riseborough Date: Wed, 22 Jun 2016 15:48:45 +1000 Subject: [PATCH] Replay: Fix bug preventing use of IMT data during replay --- Tools/Replay/Replay.cpp | 2 -- 1 file changed, 2 deletions(-) diff --git a/Tools/Replay/Replay.cpp b/Tools/Replay/Replay.cpp index 70c373bd19..8745046fd8 100644 --- a/Tools/Replay/Replay.cpp +++ b/Tools/Replay/Replay.cpp @@ -399,9 +399,7 @@ bool Replay::find_log_info(struct log_information &info) if (streq(type, "PARM") && streq(reader.last_parm_name, "SCHED_LOOP_RATE")) { // get rate directly from parameters info.update_rate = reader.last_parm_value; - return true; } - if (strlen(clock_source) == 0) { // If you want to add a clock source, also add it to // handle_msg and handle_log_format_msg, above. Note that