public async Task Load(string file, ProgressUtility progress) { this.file = file; this.startTime = DateTime.MinValue; this.duration = TimeSpan.Zero; bool first = true; // QT time is milliseconds from the following epoch. byte[] msgBuf = new byte[256]; GCHandle handle = GCHandle.Alloc(msgBuf, GCHandleType.Pinned); IntPtr ptr = handle.AddrOfPinnedObject(); DateTime lastTime = DateTime.MinValue; await Task.Run(() => { long length = 0; // MAVLINK_MSG_ID using (Stream s = File.OpenRead(file)) { length = s.Length; BinaryReader reader = new BinaryReader(s); while (s.Position < length) { progress.ShowProgress(0, length, s.Position); try { MavLinkMessage header = new MavLinkMessage(); header.ReadHeader(reader); int read = s.Read(msgBuf, 0, header.Length); if (read == header.Length) { header.Crc = reader.ReadUInt16(); bool checkCrc = true; if ((int)header.MsgId == MAVLink.mavlink_telemetry.MessageId) { if (header.Crc == 0) // telemetry has no crc. { checkCrc = false; continue; } } if (checkCrc && !header.IsValidCrc(msgBuf, read)) { continue; } Type msgType = MavLinkMessage.GetMavlinkType((uint)header.MsgId); if (msgType != null) { // convert to proper mavlink structure. header.TypedPayload = Marshal.PtrToStructure(ptr, msgType); } Message message = AddMessage(header); if (first) { startTime = message.Timestamp; startTicks = message.Ticks; first = false; } } } catch { // try and continue... } } } progress.ShowProgress(0, length, length); handle.Free(); }); this.duration = lastTime - startTime; }
internal Message AddMessage(MavLinkMessage e) { if (this.data == null) { this.data = new List <Message>(); } DateTime time = epoch.AddMilliseconds((double)e.Time / (double)1000); Message msg = new Model.MavlinkLog.Message() { Msg = e, Timestamp = time, Ticks = e.Time }; if (e.TypedPayload == null) { Type msgType = MavLinkMessage.GetMavlinkType((uint)e.MsgId); if (msgType != null) { byte[] msgBuf = new byte[256]; GCHandle handle = GCHandle.Alloc(msgBuf, GCHandleType.Pinned); IntPtr ptr = handle.AddrOfPinnedObject(); // convert to proper mavlink structure. msg.TypedValue = Marshal.PtrToStructure(ptr, msgType); handle.Free(); } } else { msg.TypedValue = e.TypedPayload; } lock (data) { this.data.Add(msg); if (msg.TypedValue is MAVLink.mavlink_param_value_t) { MAVLink.mavlink_param_value_t param = (MAVLink.mavlink_param_value_t)msg.TypedValue; string name = ConvertToString(param.param_id); parameters[name] = param; Debug.WriteLine("{0}={1}", name, param.param_value); } } if (msg.TypedValue != null) { CreateSchema(msg.TypedValue); } lock (queryEnumerators) { foreach (var q in queryEnumerators) { q.Add(msg); } } return(msg); }