Ejemplo n.º 1
0
        public async Task Load(string file, ProgressUtility progress)
        {
            this.file      = file;
            this.startTime = DateTime.MinValue;
            this.duration  = TimeSpan.Zero;
            DateTime lastTime = DateTime.MinValue;

            await Task.Run(() =>
            {
                this.msgs = new List <ULog.Message>();

                using (Stream s = File.OpenRead(file))
                {
                    BinaryReader reader = new BinaryReader(s);
                    this.reader         = reader;
                    ReadFileHeader();

                    while (s.Position < s.Length)
                    {
                        progress.ShowProgress(0, s.Length, s.Position);

                        try
                        {
                            Message msg = ReadMessage();
                            if (msg != null)
                            {
                                msgs.Add(msg);
                            }
                        }
                        catch
                        {
                            // stop here then.
                            break;
                        }
                    }
                    this.reader = null;
                }

                CreateSchema();
            });

            this.duration = lastTime - startTime;
        }
Ejemplo n.º 2
0
 private void ReportProgress()
 {
     progress.ShowProgress(0, fileStream.Length, fileStream.Position);
 }
Ejemplo n.º 3
0
        public async Task Load(string file, ProgressUtility progress)
        {
            this.file = file;
            string ext = System.IO.Path.GetExtension(file).ToLowerInvariant();

            if (ext == ".bin")
            {
                this.logType = LogType.binFile;
            }
            else if (ext == ".px4log")
            {
                this.logType = LogType.px4logFile;
            }

            bool hasStartTime = false;

            this.startTime = DateTime.MinValue;

            List <LogEntry> rows = new List <LogEntry>();

            await Task.Run(() =>
            {
                using (Stream s = File.OpenRead(file))
                {
                    BinaryReader reader     = new BinaryReader(s);
                    PX4BinaryLog log        = new PX4BinaryLog(this.logType);
                    log.GenerateParser      = false;
                    DateTime?gpsStartTime   = null;
                    ulong gpsAbsoluteOffset = 0;
                    ulong logStartTime      = 0;

                    while (s.Position < s.Length)
                    {
                        progress.ShowProgress(0, s.Length, s.Position);

                        LogEntry row = log.ReadMessageObjects(s) as LogEntry;
                        if (row == null)
                        {
                            // has no system clock value yet, so skip it.
                            continue;
                        }

                        if (!hasStartTime && log.CurrentTime != 0)
                        {
                            hasStartTime   = true;
                            logStartTime   = log.CurrentTime;
                            this.startTime = GetTime(log.CurrentTime);
                        }
                        if (!gpsStartTime.HasValue && row.Name == "GPS")
                        {
                            ulong time = row.GetField <ulong>("GPSTime");
                            if (time > 0)
                            {
                                // ok, we got a real GPS time
                                gpsStartTime = GetTime(time);
                                // backtrack and fix up initial rows.
                                if (hasStartTime)
                                {
                                    // compute offset from PX4 boot time (which is the log.CurrentTime) and the absolute GPS real time clock
                                    // so we can add this offset to PX4 log.CurrentTime so all our times from here on out are in real time.
                                    gpsStartTime = gpsStartTime.Value.AddMilliseconds((double)logStartTime - (double)log.CurrentTime);
                                }
                                ulong linuxEpochMicroseconds = ((ulong)(gpsStartTime.Value.ToUniversalTime() - new DateTime(1970, 1, 1)).TotalMilliseconds * 1000);
                                gpsAbsoluteOffset            = linuxEpochMicroseconds - logStartTime;
                                this.startTime = gpsStartTime.Value;
                                // and fix existing log entries
                                foreach (LogEntry e in rows)
                                {
                                    // add GPS absolute offset to the timestamp.
                                    e.Timestamp += gpsAbsoluteOffset;
                                }
                                hasStartTime = true;
                            }
                        }

                        if (gpsStartTime.HasValue)
                        {
                            // add GPS absolute offset to the timestamp.
                            row.Timestamp += gpsAbsoluteOffset;
                        }

                        rows.Add(row);

                        if (row.Format.Name == "PARM")
                        {
                            string name = row.GetField <string>("Name");
                            float value = row.GetField <float>("Value");
                            Debug.WriteLine("{0}={1}", name, value);
                        }
                    }
                    if (log.CurrentTime != 0)
                    {
                        DateTime endTime = GetTime(log.CurrentTime + gpsAbsoluteOffset);
                        this.duration    = endTime - startTime;
                        Debug.WriteLine("StartTime={0}, EndTime={1}, Duration={2}", startTime.ToString(), endTime.ToString(), duration.ToString());
                    }

                    CreateSchema(log);
                }
            });

            this.data = rows;
        }
Ejemplo n.º 4
0
        private void OnMavlinkMessageReceived(object sender, MavLinkMessage e)
        {
            if (currentFlightLog != null && !pauseRecording)
            {
                currentFlightLog.AddMessage(e);
            }

            switch (e.MsgId)
            {
            case MAVLink.MAVLINK_MSG_ID.ATTITUDE_QUATERNION:
            {
                var payload = (MAVLink.mavlink_attitude_quaternion_t)e.TypedPayload;
                var q       = new System.Windows.Media.Media3D.Quaternion(payload.q1, payload.q2, payload.q3, payload.q4);
                UiDispatcher.RunOnUIThread(() =>
                    {
                        //ModelViewer.ModelAttitude = initialAttitude * q;
                    });
                break;
            }

            case MAVLink.MAVLINK_MSG_ID.ATTITUDE:
            {
                var        payload = (MAVLink.mavlink_attitude_t)e.TypedPayload;
                Quaternion y       = new Quaternion(new Vector3D(0, 0, 1), -payload.yaw * 180 / Math.PI);
                Quaternion x       = new Quaternion(new Vector3D(1, 0, 0), payload.pitch * 180 / Math.PI);
                Quaternion z       = new Quaternion(new Vector3D(0, 1, 0), payload.roll * 180 / Math.PI);
                UiDispatcher.RunOnUIThread(() =>
                    {
                        ModelViewer.ModelAttitude = initialAttitude * (y * x * z);
                    });
                break;
            }

            case MAVLink.MAVLINK_MSG_ID.HIL_STATE_QUATERNION:
            {
                var        payload = (MAVLink.mavlink_hil_state_quaternion_t)e.TypedPayload;
                Quaternion q       = new Quaternion(payload.attitude_quaternion[0],
                                                    payload.attitude_quaternion[1],
                                                    payload.attitude_quaternion[2],
                                                    payload.attitude_quaternion[3]);
                UiDispatcher.RunOnUIThread(() =>
                    {
                        ModelViewer.ModelAttitude = initialAttitude * q;
                    });
                break;
            }

            case MAVLink.MAVLINK_MSG_ID.GLOBAL_POSITION_INT:
            {
                var payload = (MAVLink.mavlink_global_position_int_t)e.TypedPayload;
                UiDispatcher.RunOnUIThread(() =>
                    {
                        MapLocation((double)payload.lat / 1e7, (double)payload.lon / 1e7);
                    });
                break;
            }

            case MAVLink.MAVLINK_MSG_ID.SERIAL_CONTROL:
            {
                var ctrl = (MAVLink.mavlink_serial_control_t)e.TypedPayload;
                if (ctrl.count > 0)
                {
                    string text = System.Text.Encoding.ASCII.GetString(ctrl.data, 0, ctrl.count);
                    UiDispatcher.RunOnUIThread(() =>
                        {
                            SystemConsole.Write(text);
                        });
                }
                break;
            }

            case MAVLink.MAVLINK_MSG_ID.DATA_TRANSMISSION_HANDSHAKE:
                if (showImageStream)
                {
                    var p = (MAVLink.mavlink_data_transmission_handshake_t)e.TypedPayload;
                    incoming_image.size           = p.size;
                    incoming_image.packets        = p.packets;
                    incoming_image.payload        = p.payload;
                    incoming_image.quality        = p.jpg_quality;
                    incoming_image.type           = p.type;
                    incoming_image.width          = p.width;
                    incoming_image.height         = p.height;
                    incoming_image.start          = Environment.TickCount;
                    incoming_image.packetsArrived = 0;
                    incoming_image.data           = new byte[incoming_image.size];
                }
                break;

            case MAVLink.MAVLINK_MSG_ID.ENCAPSULATED_DATA:
                if (showImageStream)
                {
                    var img = (MAVLink.mavlink_encapsulated_data_t)e.TypedPayload;

                    int  seq = img.seqnr;
                    uint pos = (uint)seq * (uint)incoming_image.payload;

                    // Check if we have a valid transaction
                    if (incoming_image.packets == 0 || incoming_image.size == 0)
                    {
                        // not expecting an image?
                        incoming_image.packetsArrived = 0;
                        break;
                    }

                    uint available = (uint)incoming_image.payload;
                    if (pos + available > incoming_image.size)
                    {
                        available = incoming_image.size - pos;
                    }
                    Array.Copy(img.data, 0, incoming_image.data, pos, available);

                    progress.ShowProgress(0, incoming_image.size, pos + available);

                    ++incoming_image.packetsArrived;
                    //Debug.WriteLine("packet {0} of {1}, position {2} of {3}", incoming_image.packetsArrived, incoming_image.packets,
                    //    pos + available, incoming_image.size);

                    // emit signal if all packets arrived
                    if (pos + available >= incoming_image.size)
                    {
                        // Restart state machine
                        incoming_image.packets        = 0;
                        incoming_image.packetsArrived = 0;
                        byte[] saved = incoming_image.data;
                        incoming_image.data = null;

                        UiDispatcher.RunOnUIThread(() =>
                        {
                            progress.ShowProgress(0, 0, 0);
                            ShowImage(saved);
                        });
                    }
                }
                break;
            }
        }
        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(() =>
            {
                // MAVLINK_MSG_ID
                using (Stream s = File.OpenRead(file))
                {
                    BinaryReader reader = new BinaryReader(s);
                    while (s.Position < s.Length)
                    {
                        progress.ShowProgress(0, s.Length, s.Position);

                        try
                        {
                            MavLinkMessage header = new MavLinkMessage();
                            header.ReadHeader(reader);

                            while (!header.IsValid())
                            {
                                // hmm. looks like a bad record, so now what?
                                header.ShiftHeader(reader);
                            }

                            int read = s.Read(msgBuf, 0, header.Length);
                            if (read == header.Length)
                            {
                                header.Crc = reader.ReadUInt16();

                                if (!header.IsValidCrc(msgBuf, read))
                                {
                                    continue;
                                }

                                Type msgType = MAVLink.MAVLINK_MESSAGE_INFO[(int)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;
                                    first     = false;
                                }
                            }
                        }
                        catch
                        {
                            // try and continue...
                        }
                    }
                }
                handle.Free();
            });

            this.duration = lastTime - startTime;
        }
Ejemplo n.º 6
0
        public async Task Load(string fileName, ProgressUtility progress)
        {
            flights.Clear();
            // CSV doesn't have realtime clock, so go with the file date instead.
            this.startTime = File.GetLastWriteTime(fileName);

            // time (us)
            int min = int.MaxValue;
            int max = int.MinValue;


            await Task.Run(() =>
            {
                using (Stream s = File.OpenRead(fileName))
                {
                    XmlNameTable nametable = new NameTable();
                    using (XmlCsvReader reader = new XmlCsvReader(s, System.Text.Encoding.UTF8, new Uri(fileName), nametable))
                    {
                        progress.ShowProgress(0, s.Length, s.Position);
                        reader.FirstRowHasColumnNames = true;
                        data = XDocument.Load(reader);

                        this.schema = new LogItemSchema()
                        {
                            Name = "CsvDataLog", Type = "Root"
                        };

                        // create the schema
                        List <LogItemSchema> children = new List <Model.LogItemSchema>();
                        foreach (String name in reader.ColumnNames)
                        {
                            children.Add(new LogItemSchema()
                            {
                                Name = name, Parent = this.schema
                            });
                        }

                        this.schema.ChildItems = children;

                        progress.ShowProgress(0, s.Length, s.Position);
                    }
                }

                foreach (var e in data.Root.Elements())
                {
                    int?i = GetTimeMicroseconds(e);
                    if (i.HasValue)
                    {
                        if (i.Value < min)
                        {
                            min = i.Value;
                        }
                        if (i > max)
                        {
                            max = i.Value;
                        }
                    }
                }
            });

            // this log has no absolute UTC time, only ticks since board was booted, so we make up a start time.
            DateTime end    = this.startTime.AddMilliseconds((max - min) / 1000);
            var      flight = new Flight()
            {
                Log = this, StartTime = this.startTime, Duration = end - this.startTime
            };

            this.duration = end - this.startTime;
            this.flights.Add(flight);
        }
Ejemplo n.º 7
0
        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;
        }
Ejemplo n.º 8
0
        public async Task Load(string fileName, ProgressUtility progress)
        {
            flights.Clear();
            // CSV doesn't have realtime clock, so go with the file date instead.
            this.startTime = File.GetLastWriteTime(fileName);

            // time (ms)
            long min = long.MaxValue;
            long max = long.MinValue;

            await Task.Run(() =>
            {
                timeElementName = null;
                using (Stream s = File.OpenRead(fileName))
                {
                    Dictionary <string, LogItemSchema> map = new Dictionary <string, LogItemSchema>();
                    XmlNameTable nametable = new NameTable();
                    using (XmlCsvReader reader = new XmlCsvReader(s, System.Text.Encoding.UTF8, new Uri(fileName), nametable))
                    {
                        reader.FirstRowHasColumnNames = true;
                        reader.ColumnsAsAttributes    = true;
                        while (reader.Read())
                        {
                            progress.ShowProgress(0, s.Length, s.Position);
                            if (this.schema == null)
                            {
                                // create the schema
                                this.schema = new LogItemSchema()
                                {
                                    Name = "CsvLog", Type = "Root"
                                };
                                LogItemSchema row = null;

                                foreach (String name in reader.ColumnNames)
                                {
                                    if (timeElementName == null && (name.ToLower().Contains("time") || name.ToLower().Contains("ticks")))
                                    {
                                        timeElementName = name;
                                    }

                                    if (name.Contains(":"))
                                    {
                                        // then we have sub-parts.
                                        int pos             = name.IndexOf(":");
                                        string key          = name.Substring(0, pos);
                                        string field        = name.Substring(pos + 1);
                                        LogItemSchema group = null;
                                        if (!map.ContainsKey(key))
                                        {
                                            group = new LogItemSchema()
                                            {
                                                Name = key, Type = key
                                            };
                                            this.schema.AddChild(group);
                                            map[key] = group;
                                        }
                                        else
                                        {
                                            group = map[key];
                                        }
                                        var leaf = new LogItemSchema()
                                        {
                                            Name = field, Type = "Double"
                                        };
                                        group.AddChild(leaf);
                                        map[name] = leaf;
                                    }
                                    else
                                    {
                                        if (row == null)
                                        {
                                            row = new LogItemSchema()
                                            {
                                                Name = "Other", Type = "Other"
                                            };
                                            this.schema.AddChild(row);
                                        }
                                        var leaf = new LogItemSchema()
                                        {
                                            Name = name, Type = "Double"
                                        };
                                        row.AddChild(leaf);
                                        map[name] = leaf;
                                    }
                                }
                            }

                            if (reader.NodeType == XmlNodeType.Element && reader.LocalName == "row")
                            {
                                // read a row
                                long time    = GetTicks(reader);
                                min          = Math.Min(min, time);
                                max          = Math.Max(max, time);
                                LogEntry row = new Model.LogEntry()
                                {
                                    Name = "Other", Timestamp = (ulong)time
                                };
                                log.Add(row);
                                Dictionary <string, LogEntry> groups = new Dictionary <string, LogEntry>();

                                if (reader.MoveToFirstAttribute())
                                {
                                    do
                                    {
                                        string name = XmlConvert.DecodeName(reader.LocalName);
                                        LogItemSchema itemSchema = map[name];
                                        LogEntry e = row;
                                        if (name.Contains(":"))
                                        {
                                            // then we have sub-parts.
                                            int pos      = name.IndexOf(":");
                                            string key   = name.Substring(0, pos);
                                            string field = name.Substring(pos + 1);
                                            if (!groups.ContainsKey(key))
                                            {
                                                e = new LogEntry()
                                                {
                                                    Name = key, Timestamp = (ulong)time
                                                };
                                                groups[key] = e;
                                                log.Add(e);
                                            }
                                            else
                                            {
                                                e = groups[key];
                                            }
                                            name = field;
                                        }

                                        string value = reader.Value;
                                        double d     = 0;
                                        if (double.TryParse(value, out d))
                                        {
                                            e.SetField(name, d);
                                        }
                                        else
                                        {
                                            if (!string.IsNullOrEmpty(value))
                                            {
                                                // not a number.
                                                itemSchema.Type = "String";
                                                e.SetField(name, value);
                                            }
                                        }
                                    }while (reader.MoveToNextAttribute());
                                    reader.MoveToElement();
                                }
                            }
                        }
                    }
                }
            });

            // this log has no absolute UTC time, only ticks since board was booted, so we make up a start time.
            DateTime end    = this.startTime.AddMilliseconds((max - min) / 1000);
            var      flight = new Flight()
            {
                Log = this, StartTime = this.startTime, Duration = end - this.startTime
            };

            this.duration = end - this.startTime;
            this.flights.Add(flight);
        }