MAVLinkMessage readlogPacketMavlink()
{
byte[] datearray = new byte[8];
bool missingtimestamp = false;
if (logplaybackfile.BaseStream is FileStream)
{
if (((FileStream) _logplaybackfile.BaseStream).Name.ToLower().EndsWith(".rlog"))
missingtimestamp = true;
}
if (!missingtimestamp)
{
int tem = logplaybackfile.BaseStream.Read(datearray, 0, datearray.Length);
Array.Reverse(datearray);
DateTime date1 = new DateTime(1970, 1, 1, 0, 0, 0, DateTimeKind.Utc);
UInt64 dateint = BitConverter.ToUInt64(datearray, 0);
try
{
// array is reversed above
if (datearray[7] == 254 || datearray[7] == 253)
{
//rewind 8bytes
logplaybackfile.BaseStream.Seek(-8, SeekOrigin.Current);
}
else
{
if ((dateint/1000/1000/60/60) < 9999999)
{
date1 = date1.AddMilliseconds(dateint/1000);
lastlogread = date1.ToLocalTime();
}
}
}
catch
{
}
}
byte[] temp = new byte[0];
byte byte0 = 0;
byte byte1 = 0;
byte byte2 = 0;
var filelength = logplaybackfile.BaseStream.Length;
var filepos = logplaybackfile.BaseStream.Position;
if(filelength == filepos)
return MAVLinkMessage.Invalid;
int length = 5;
int a = 0;
while (a < length)
{
if (filelength == filepos)
return MAVLinkMessage.Invalid;
var tempb = (byte) logplaybackfile.ReadByte();
filepos++;
switch (a)
{
case 0:
byte0 = tempb;
if (byte0 != 'U' && byte0 != 254 && byte0 != 253)
{
log.DebugFormat("logread - lost sync byte {0} pos {1}", byte0,
logplaybackfile.BaseStream.Position);
// seek to next valid
do
{
byte0 = logplaybackfile.ReadByte();
}
while (byte0 != 'U' && byte0 != 254 && byte0 != 253);
a = 1;
continue;
}
break;
case 1:
byte1 = tempb;
// handle length
{
int headerlength = byte0 == MAVLINK_STX ? 9 : 5;
int headerlengthstx = headerlength + 1;
length = byte1 + headerlengthstx + 2; // header + 2 checksum
}
break;
case 2:
byte2 = tempb;
// handle signing and mavlink2
if (byte0 == MAVLINK_STX)
{
if ((byte2 & MAVLINK_IFLAG_SIGNED) > 0)
length += MAVLINK_SIGNATURE_BLOCK_LEN;
}
// handle rest
{
temp = new byte[length];
temp[0] = byte0;
temp[1] = byte1;
temp[2] = byte2;
var readto = a + 1;
var readlength = length - (a + 1);
logplaybackfile.Read(temp, readto, readlength);
a = length;
}
break;
}
a++;
}
MAVLinkMessage tmp = new MAVLinkMessage(temp);
MAVlist[tmp.sysid, tmp.compid].cs.datetime = lastlogread;
return tmp;
}