Skip to content

Commit

Permalink
DFLogBuffer: add this[string type, string col]
Browse files Browse the repository at this point in the history
  • Loading branch information
meee1 committed Dec 16, 2019
1 parent 511e0f2 commit fe9a781
Show file tree
Hide file tree
Showing 2 changed files with 169 additions and 98 deletions.
214 changes: 124 additions & 90 deletions ExtLibs/Utilities/BinaryLog.cs
Original file line number Diff line number Diff line change
Expand Up @@ -275,7 +275,7 @@ void logEntryFMT(byte packettype, Stream br)
length = logfmt.length,
type = logfmt.type,
name = ASCIIEncoding.ASCII.GetString(logfmt.name).Trim(new char[] { '\0' }),
format = ASCIIEncoding.ASCII.GetString(logfmt.format).Trim(new char[] { '\0' }),
format = ASCIIEncoding.ASCII.GetString(logfmt.format).Trim(new char[] { '\0' })
};

return;
Expand Down Expand Up @@ -356,6 +356,33 @@ public object[] ReadMessageObjects(Stream br, long length)
}
}

public (int offset, char coltype, int typesize) GetColumnOffset(byte packettype, int colno)
{
string format = "";
string name = "";
int size = 0;

if (packettypecache[packettype].length != 0)
{
var fmt = packettypecache[packettype];
name = fmt.name;
format = fmt.format;
size = fmt.length;
}

var offset = 0;
var a = 0;
foreach (var ch in format)
{
if (a == colno)
break;
offset += (int) Enum.Parse(typeof(TypeSize), ch.ToString());
a++;
}

return (offset, format[colno], (int) Enum.Parse(typeof(TypeSize), format[colno].ToString()));
}

object[] logEntryObjects(byte packettype, Stream br)
{
lock (locker)
Expand Down Expand Up @@ -455,99 +482,106 @@ private object[] ProcessMessageObjects(byte[] message, string name, string forma

foreach (char ch in form)
{
switch (ch)
{
case 'b':
answer.Add((sbyte) message[offset]);
offset++;
break;
case 'B':
answer.Add(message[offset]);
offset++;
break;
case 'h':
answer.Add(BitConverter.ToInt16(message, offset));
offset += 2;
break;
case 'H':
answer.Add(BitConverter.ToUInt16(message, offset));
offset += 2;
break;
case 'i':
answer.Add(BitConverter.ToInt32(message, offset));
offset += 4;
break;
case 'I':
answer.Add(BitConverter.ToUInt32(message, offset));
offset += 4;
break;
case 'q':
answer.Add(BitConverter.ToInt64(message, offset));
offset += 8;
break;
case 'Q':
answer.Add(BitConverter.ToUInt64(message, offset));
offset += 8;
break;
case 'f':
answer.Add(BitConverter.ToSingle(message, offset));
offset += 4;
break;
case 'd':
answer.Add(BitConverter.ToDouble(message, offset));
offset += 8;
break;
case 'c':
answer.Add((BitConverter.ToInt16(message, offset)/100.0));
offset += 2;
break;
case 'C':
answer.Add((BitConverter.ToUInt16(message, offset)/100.0));
offset += 2;
break;
case 'e':
answer.Add((BitConverter.ToInt32(message, offset)/100.0));
offset += 4;
break;
case 'E':
answer.Add((BitConverter.ToUInt32(message, offset)/100.0));
offset += 4;
break;
case 'L':
answer.Add(((double) BitConverter.ToInt32(message, offset)/10000000.0));
offset += 4;
break;
case 'n':
answer.Add(ASCIIEncoding.ASCII.GetString(message, offset, 4).Trim(new char[] {'\0'}));
offset += 4;
break;
case 'N':
answer.Add(ASCIIEncoding.ASCII.GetString(message, offset, 16).Trim(new char[] {'\0'}));
offset += 16;
break;
case 'M':
int modeno = message[offset];
string mode = onFlightMode?.Invoke(_firmware, modeno);
if (mode == null)
mode = modeno.ToString();
answer.Add(mode);
offset++;
break;
case 'Z':
answer.Add(ASCIIEncoding.ASCII.GetString(message, offset, 64).Trim(new char[] {'\0'}));
offset += 64;
break;
case 'a':
answer.Add(new UnionArray(message.Skip(offset).Take(64).ToArray()));
offset += 2 * 32;
break;
default:
return null;
}
var temp = GetObjectFromMessage(ch, message, offset);
answer.Add(temp);
offset += (int)Enum.Parse(typeof(TypeSize), ch.ToString());
}
return answer.ToArray();
}

public object GetObjectFromMessage(char type, byte[] message, int offset)
{
switch (type)
{
case 'b':
return ((sbyte)message[offset]);
offset++;
break;
case 'B':
return (message[offset]);
offset++;
break;
case 'h':
return (BitConverter.ToInt16(message, offset));
offset += 2;
break;
case 'H':
return (BitConverter.ToUInt16(message, offset));
offset += 2;
break;
case 'i':
return (BitConverter.ToInt32(message, offset));
offset += 4;
break;
case 'I':
return (BitConverter.ToUInt32(message, offset));
offset += 4;
break;
case 'q':
return (BitConverter.ToInt64(message, offset));
offset += 8;
break;
case 'Q':
return (BitConverter.ToUInt64(message, offset));
offset += 8;
break;
case 'f':
return (BitConverter.ToSingle(message, offset));
offset += 4;
break;
case 'd':
return (BitConverter.ToDouble(message, offset));
offset += 8;
break;
case 'c':
return ((BitConverter.ToInt16(message, offset) / 100.0));
offset += 2;
break;
case 'C':
return ((BitConverter.ToUInt16(message, offset) / 100.0));
offset += 2;
break;
case 'e':
return ((BitConverter.ToInt32(message, offset) / 100.0));
offset += 4;
break;
case 'E':
return ((BitConverter.ToUInt32(message, offset) / 100.0));
offset += 4;
break;
case 'L':
return (((double)BitConverter.ToInt32(message, offset) / 10000000.0));
offset += 4;
break;
case 'n':
return (ASCIIEncoding.ASCII.GetString(message, offset, 4).Trim(new char[] { '\0' }));
offset += 4;
break;
case 'N':
return (ASCIIEncoding.ASCII.GetString(message, offset, 16).Trim(new char[] { '\0' }));
offset += 16;
break;
case 'M':
int modeno = message[offset];
string mode = onFlightMode?.Invoke(_firmware, modeno);
if (mode == null)
mode = modeno.ToString();
return (mode);
offset++;
break;
case 'Z':
return (ASCIIEncoding.ASCII.GetString(message, offset, 64).Trim(new char[] { '\0' }));
offset += 64;
break;
case 'a':
return (new UnionArray(message.Skip(offset).Take(64).ToArray()));
offset += 2 * 32;
break;
default:
return null;
}
}

public enum TypeSize
{
a = 2*32,
Expand Down
53 changes: 45 additions & 8 deletions ExtLibs/Utilities/DFLogBuffer.cs
Original file line number Diff line number Diff line change
Expand Up @@ -106,11 +106,7 @@ void setlinecount()
_count = lineCount;

// build fmt line database to pre seed the FMT message
int amax = Math.Min(2000, _count - 1);
for (int a = 0; a < amax; a++)
{
dflog.GetDFItemFromLine(this[a].ToString(), a);
}
messageindexline[128].ForEach(a => dflog.FMTLine(this[(int) a]));
}
else
{
Expand Down Expand Up @@ -240,15 +236,15 @@ void setlinecount()
"MSG", "PARM"
}))
{
Console.WriteLine(item.raw.ToJSON(Formatting.None));
//Console.WriteLine(item.raw.ToJSON(Formatting.None));
}

// 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
// here we just force the parsing of gps messages to get the valid board time to gps time offset
int gpsa = 0;
foreach (var item in GetEnumeratorType(new[]
{
"GPS", "GPS2"
"GPS", "GPS2", "GPSB"
}))
{
gpsa++;
Expand Down Expand Up @@ -318,6 +314,46 @@ private void BuildUnitMultiList()
public Dictionary<char, string> Unit { get; set; } = new Dictionary<char, string>();
public Dictionary<char, string> Mult { get; set; } = new Dictionary<char, string>();

public IEnumerable<object> this[string type, string col]
{
get
{
// get the ids for the passed in types
List<long> slist = new List<long>();

byte typeid = 0;
int colindex = 0;

if (dflog.logformat.ContainsKey(type))
{
typeid = (byte) dflog.logformat[type].Id;
colindex = dflog.FindMessageOffset(type, col);

foreach (var item in messageindexline[typeid])
{
slist.Add(item);
}
}

var coloffset = binlog.GetColumnOffset(typeid, colindex);

foreach (var indexin in slist)
{
var index = (int)indexin;
long startoffset = linestartoffset[index];

startoffset += coloffset.offset;
byte[] buffer = new byte[coloffset.typesize];
lock (locker)
{
basestream.Seek(startoffset, SeekOrigin.Begin);
basestream.Read(buffer, 0, buffer.Length);
}

yield return binlog.GetObjectFromMessage(coloffset.coltype, buffer, 0);
}
}
}
public DFLog.DFItem this[long indexin]
{
get
Expand Down Expand Up @@ -466,7 +502,8 @@ public bool IsReadOnly
}
}

slist.Sort();
if(types.Length > 1)
slist.Sort();

// work through list of lines
foreach (var l in slist)
Expand Down

0 comments on commit fe9a781

Please sign in to comment.