From 142a91ac9abcc888618ec545afd8bd7193f93a82 Mon Sep 17 00:00:00 2001 From: Michael Oborne Date: Tue, 8 Aug 2023 15:51:59 +1000 Subject: [PATCH] LogBrowse: limit impact of many params to 100000 --- ExtLibs/Utilities/DFLogBuffer.cs | 19 +++++++++++++++++++ Log/LogBrowse.cs | 2 +- 2 files changed, 20 insertions(+), 1 deletion(-) diff --git a/ExtLibs/Utilities/DFLogBuffer.cs b/ExtLibs/Utilities/DFLogBuffer.cs index 425278fadf..472dbaf7bd 100644 --- a/ExtLibs/Utilities/DFLogBuffer.cs +++ b/ExtLibs/Utilities/DFLogBuffer.cs @@ -108,12 +108,27 @@ void setlinecount() linestartoffset.Add((uint)(ans.Item2)); lineCount++; + + if (lineCount % 1000000 == 0) + Console.WriteLine("reading lines " + lineCount + " " + ((basestream.Position / (double)length) * 100.0)); } _count = lineCount; // build fmt line database to pre seed the FMT message messageindexline[128].ForEach(a => dflog.FMTLine(this[(int) a])); + + try + { + foreach (var item in dflog.logformat) + { + var id = item.Value.Id; + var type = item.Value.Name; + if(messageindex[id].Count != 0) + Console.WriteLine("Seen " + type + " count " + messageindex[id].Count); + } + } + catch { } } else { @@ -250,6 +265,7 @@ void setlinecount() BuildUnitMultiList(); + int limitcount = 0; // used to set the firmware type foreach (var item in GetEnumeratorType(new[] { @@ -259,6 +275,9 @@ void setlinecount() // must be the string version to do the firmware type detection - binarylog var line = this[(int) item.lineno]; //Console.WriteLine(); + limitcount++; + if (limitcount > 100000) + break; } // try get gps time - when a dfitem is created and no valid gpstime has been establish the messages are parsed to get a valid gpstime diff --git a/Log/LogBrowse.cs b/Log/LogBrowse.cs index e578387c20..830266f5a8 100644 --- a/Log/LogBrowse.cs +++ b/Log/LogBrowse.cs @@ -661,7 +661,7 @@ private void ResetTreeView(List seenmessagetypes, string VehicleType) treeView1.ShowNodeToolTips = true; dataModifierHash = new Hashtable(); - var parmdata = logdata.GetEnumeratorType("PARM").Select(a => + var parmdata = logdata.GetEnumeratorType("PARM").Take(100000).Select(a => new MAVLink.MAVLinkParam(a["Name"], double.Parse(a["Value"], CultureInfo.InvariantCulture), MAVLink.MAV_PARAM_TYPE.REAL32)); MainV2.comPort.MAV.param.Clear();