public static List<KeyValuePair<int, string>> getModesList(CurrentState cs) { log.Info("getModesList Called"); // ensure we get the correct list MainV2.comPort.MAV.cs.firmware = cs.firmware; Utilities.ParameterMetaDataRepository parm = new ParameterMetaDataRepository(); if (cs.firmware == MainV2.Firmwares.ArduPlane) { var flightModes = parm.GetParameterOptionsInt("FLTMODE1"); flightModes.Add(new KeyValuePair<int,string>(16,"INITIALISING")); return flightModes; } else if (cs.firmware == MainV2.Firmwares.Ateryx) { var flightModes = parm.GetParameterOptionsInt("FLTMODE1"); //same as apm return flightModes; } else if (cs.firmware == MainV2.Firmwares.ArduCopter2 || MainV2.comPort.MAV.cs.firmware == MainV2.Firmwares.ArduHeli) { var flightModes = parm.GetParameterOptionsInt("FLTMODE1"); return flightModes; } else if (cs.firmware == MainV2.Firmwares.ArduRover) { var flightModes = parm.GetParameterOptionsInt("MODE1"); return flightModes; } return null; }
List<string[]> readLog(string fn) { if (logcache.Count > 0) return logcache; List<string[]> list = new List<string[]>(); if (fn.ToLower().EndsWith("tlog")) { MAVLink mine = new MAVLink(); mine.logplaybackfile = new BinaryReader(File.Open(fn, FileMode.Open, FileAccess.Read, FileShare.Read)); mine.logreadmode = true; mine.MAV.packets.Initialize(); // clear CurrentState cs = new CurrentState(); string[] oldvalues = {""}; while (mine.logplaybackfile.BaseStream.Position < mine.logplaybackfile.BaseStream.Length) { byte[] packet = mine.readPacket(); cs.datetime = mine.lastlogread; cs.UpdateCurrentSettings(null, true, mine); // old // line "GPS: 82686250, 1, 8, -34.1406480, 118.5441900, 0.0000, 309.1900, 315.9500, 0.0000, 279.1200" string //Status,Time,NSats,HDop,Lat,Lng,RelAlt,Alt,Spd,GCrs //GPS, 3, 122732, 10, 0.00, -35.3628880, 149.1621961, 808.90, 810.30, 23.30, 94.04 string[] vals = new string[] { "GPS", "3", (cs.datetime.ToUniversalTime() - new DateTime(cs.datetime.Year,cs.datetime.Month,cs.datetime.Day,0,0,0,DateTimeKind.Utc)).TotalMilliseconds.ToString(), cs.satcount.ToString(),cs.gpshdop.ToString(),cs.lat.ToString(),cs.lng.ToString(),cs.alt.ToString(),cs.alt.ToString(),cs.groundspeed.ToString(),cs.yaw.ToString()}; if (oldvalues.Length > 2 && oldvalues[latpos] == vals[latpos] && oldvalues[lngpos] == vals[lngpos] && oldvalues[altpos] == vals[altpos]) continue; oldvalues = vals; list.Add(vals); // 4 5 7 Console.Write((mine.logplaybackfile.BaseStream.Position * 100 / mine.logplaybackfile.BaseStream.Length) + " \r"); } mine.logplaybackfile.Close(); logcache = list; return list; } StreamReader sr = new StreamReader(fn); string lasttime = "0"; while (!sr.EndOfStream) { string line = sr.ReadLine(); if (line.ToLower().StartsWith("gps")) { if (!sr.EndOfStream) { string line2 = sr.ReadLine(); if (line2.ToLower().StartsWith("att")) { line = string.Concat(line, ",", line2); } } string[] vals = line.Split(new char[] {',',':'}); if (lasttime == vals[timepos]) continue; lasttime = vals[timepos]; list.Add(vals); } } sr.Close(); sr.Dispose(); logcache = list; return list; }
private void BUT_redokml_Click(object sender, EventArgs e) { OpenFileDialog openFileDialog1 = new OpenFileDialog(); openFileDialog1.Filter = "*.tlog|*.tlog"; openFileDialog1.FilterIndex = 2; openFileDialog1.RestoreDirectory = true; openFileDialog1.Multiselect = true; try { openFileDialog1.InitialDirectory = Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + @"logs" + Path.DirectorySeparatorChar; } catch { } // incase dir doesnt exist if (openFileDialog1.ShowDialog() == DialogResult.OK) { foreach (string logfile in openFileDialog1.FileNames) { MAVLink mine = new MAVLink(); mine.logplaybackfile = new BinaryReader(File.Open(logfile, FileMode.Open, FileAccess.Read, FileShare.Read)); mine.logreadmode = true; mine.packets.Initialize(); // clear CurrentState cs = new CurrentState(); float oldlatlngalt = 0; while (mine.logplaybackfile.BaseStream.Position < mine.logplaybackfile.BaseStream.Length) { // bar moves to 50 % in this step progressBar1.Value = (int)((float)mine.logplaybackfile.BaseStream.Position / (float)mine.logplaybackfile.BaseStream.Length * 100.0f / 2.0f); progressBar1.Refresh(); byte[] packet = mine.readPacket(); cs.datetime = mine.lastlogread; cs.UpdateCurrentSettings(null, true, mine); try { if (MainV2.talk != null) MainV2.talk.SpeakAsyncCancelAll(); } catch { } // ignore because of this Exception System.PlatformNotSupportedException: No voice installed on the system or none available with the current security setting. if ((float)(cs.lat + cs.lng) != oldlatlngalt && cs.lat != 0 && cs.lng != 0) { Console.WriteLine(cs.lat + " " + cs.lng + " " + cs.alt + " lah " + (float)(cs.lat + cs.lng + cs.alt) + "!=" + oldlatlngalt); CurrentState cs2 = (CurrentState)cs.Clone(); flightdata.Add(cs2); oldlatlngalt = (cs.lat + cs.lng); } } mine.logreadmode = false; mine.logplaybackfile.Close(); mine.logplaybackfile = null; writeKML(logfile + ".kml"); progressBar1.Value = 100; } } }
public void timer() { Control.CheckForIllegalCrossThreadCalls = false; videopos = startlogtime.AddMilliseconds(-startlogtime.Millisecond); hud1.SixteenXNine = true; while (true) { try { // GC.Collect(); // long mem = GC.GetTotalMemory(true) / 1024 / 1024; // Console.WriteLine("mem "+mem); System.Threading.Thread.Sleep(20); // 25 fps // videopos = videopos.AddMilliseconds(1000 / 25); // m_mediaseek = m_FilterGraph as IMediaSeeking; // m_mediapos.put_CurrentPosition((vidpos - startlogtime).TotalSeconds); //m_mediaseek.SetTimeFormat(TimeFormat.MediaTime); //long poscurrent = 0; //long posend = 0; // m_mediaseek.GetPositions(out poscurrent,out posend); DateTime cstimestamp = videopos.AddSeconds(trackBar1.Value).AddMilliseconds(-(videopos.Millisecond % 20)); int tb = trackBar1.Value; if (flightdata.ContainsKey(cstimestamp)) { cs = flightdata[cstimestamp]; } else if (flightdata.ContainsKey(cstimestamp.AddMilliseconds(-20))) { cs = flightdata[cstimestamp.AddMilliseconds(-20)]; } else if (flightdata.ContainsKey(cstimestamp.AddMilliseconds(-40))) { cs = flightdata[cstimestamp.AddMilliseconds(-40)]; } // Console.WriteLine("Update CS"); cs.UpdateCurrentSettings(bindingSource1); } catch (ThreadAbortException) { break; } catch { } } }
List<string[]> readLog(string fn) { List<string[]> list = new List<string[]>(); if (fn.ToLower().EndsWith("tlog")) { MAVLink mine = new MAVLink(); mine.logplaybackfile = new BinaryReader(File.Open(fn, FileMode.Open, FileAccess.Read, FileShare.Read)); mine.logreadmode = true; mine.packets.Initialize(); // clear CurrentState cs = new CurrentState(); string[] oldvalues = {""}; while (mine.logplaybackfile.BaseStream.Position < mine.logplaybackfile.BaseStream.Length) { byte[] packet = mine.readPacket(); cs.datetime = mine.lastlogread; cs.UpdateCurrentSettings(null, true, mine); // line "GPS: 82686250, 1, 8, -34.1406480, 118.5441900, 0.0000, 309.1900, 315.9500, 0.0000, 279.1200" string string[] vals = new string[] { "GPS", (cs.datetime - new DateTime(cs.datetime.Year,cs.datetime.Month,cs.datetime.Day,0,0,0,DateTimeKind.Local)).TotalMilliseconds.ToString(), "1", cs.satcount.ToString(),cs.lat.ToString(),cs.lng.ToString(),"0.0",cs.alt.ToString(),cs.alt.ToString(),"0.0",cs.groundcourse.ToString()}; if (oldvalues.Length > 2 && oldvalues[latpos] == vals[latpos] && oldvalues[lngpos] == vals[lngpos] && oldvalues[altpos] == vals[altpos]) continue; oldvalues = vals; list.Add(vals); // 4 5 7 Console.Write((mine.logplaybackfile.BaseStream.Position * 100 / mine.logplaybackfile.BaseStream.Length) + " \r"); } mine.logplaybackfile.Close(); return list; } StreamReader sr = new StreamReader(fn); string lasttime = "0"; while (!sr.EndOfStream) { string line = sr.ReadLine(); if (line.ToLower().StartsWith("gps")) { string[] vals = line.Split(new char[] {',',':'}); if (lasttime == vals[1]) continue; lasttime = vals[1]; list.Add(vals); } } sr.Close(); sr.Dispose(); return list; }