private void CHK_speecharmdisarm_CheckedChanged(object sender, EventArgs e) { if (startup) { return; } Settings.Instance["speecharmenabled"] = ((CheckBox)sender).Checked.ToString(); if (((CheckBox)sender).Checked) { var speechstring = "Armed"; if (Settings.Instance["speecharm"] != null) { speechstring = Settings.Instance["speecharm"]; } if (DialogResult.Cancel == InputBox.Show("Arm", "What do you want it to say?", ref speechstring)) { return; } Settings.Instance["speecharm"] = speechstring; speechstring = "Disarmed"; if (Settings.Instance["speechdisarm"] != null) { speechstring = Settings.Instance["speechdisarm"]; } if (DialogResult.Cancel == InputBox.Show("Disarmed", "What do you want it to say?", ref speechstring)) { return; } Settings.Instance["speechdisarm"] = speechstring; } }
private void chk_ADSB_CheckedChanged(object sender, EventArgs e) { if (startup) { return; } if (((CheckBox)sender).Checked) { var server = "127.0.0.1"; if (Settings.Instance["adsbserver"] != null) { server = Settings.Instance["adsbserver"]; } if (DialogResult.Cancel == InputBox.Show("Server", "Server IP?", ref server)) { return; } Settings.Instance["adsbserver"] = server; var port = "30003"; if (Settings.Instance["adsbport"] != null) { port = Settings.Instance["adsbport"]; } if (DialogResult.Cancel == InputBox.Show("Server port", "Server port?", ref port)) { return; } Settings.Instance["adsbport"] = port; } Settings.Instance["enableadsb"] = chk_ADSB.Checked.ToString(); MainV2.instance.EnableADSB = chk_ADSB.Checked; }
private void CHK_speechlowspeed_CheckedChanged(object sender, EventArgs e) { if (startup) { return; } Settings.Instance["speechlowspeedenabled"] = ((CheckBox)sender).Checked.ToString(); if (((CheckBox)sender).Checked) { var speechstring = "Low Ground Speed {gsp}"; if (Settings.Instance["speechlowgroundspeed"] != null) { speechstring = Settings.Instance["speechlowgroundspeed"]; } if (DialogResult.Cancel == InputBox.Show("Ground Speed", "What do you want it to say?", ref speechstring)) { return; } Settings.Instance["speechlowgroundspeed"] = speechstring; speechstring = "0"; if (Settings.Instance["speechlowgroundspeedtrigger"] != null) { speechstring = Settings.Instance["speechlowgroundspeedtrigger"]; } if (DialogResult.Cancel == InputBox.Show("speed trigger", "What speed do you want to warn at (m/s)?", ref speechstring)) { return; } Settings.Instance["speechlowgroundspeedtrigger"] = speechstring; speechstring = "Low Air Speed {asp}"; if (Settings.Instance["speechlowairspeed"] != null) { speechstring = Settings.Instance["speechlowairspeed"]; } if (DialogResult.Cancel == InputBox.Show("Air Speed", "What do you want it to say?", ref speechstring)) { return; } Settings.Instance["speechlowairspeed"] = speechstring; speechstring = "0"; if (Settings.Instance["speechlowairspeedtrigger"] != null) { speechstring = Settings.Instance["speechlowairspeedtrigger"]; } if (DialogResult.Cancel == InputBox.Show("speed trigger", "What speed do you want to warn at (m/s)?", ref speechstring)) { return; } Settings.Instance["speechlowairspeedtrigger"] = speechstring; } }
private void CHK_speechbattery_CheckedChanged(object sender, EventArgs e) { if (startup) { return; } Settings.Instance["speechbatteryenabled"] = ((CheckBox)sender).Checked.ToString(); if (((CheckBox)sender).Checked) { var speechstring = "WARNING, Battery at {batv} Volt, {batp} percent"; if (Settings.Instance["speechbattery"] != null) { speechstring = Settings.Instance["speechbattery"].ToString(); } if (DialogResult.Cancel == InputBox.Show("Notification", "What do you want it to say?", ref speechstring)) { return; } Settings.Instance["speechbattery"] = speechstring; speechstring = "9.6"; if (Settings.Instance["speechbatteryvolt"] != null) { speechstring = Settings.Instance["speechbatteryvolt"].ToString(); } if (DialogResult.Cancel == InputBox.Show("Battery Level", "What Voltage do you want to warn at?", ref speechstring)) { return; } Settings.Instance["speechbatteryvolt"] = speechstring; speechstring = "20"; if (Settings.Instance["speechbatterypercent"] != null) { speechstring = Settings.Instance["speechbatterypercent"].ToString(); } if (DialogResult.Cancel == InputBox.Show("Battery Level", "What percentage do you want to warn at?", ref speechstring)) { return; } Settings.Instance["speechbatterypercent"] = speechstring; } }
private void CHK_Password_CheckedChanged(object sender, EventArgs e) { if (startup) { return; } Settings.Instance["password_protect"] = CHK_Password.Checked.ToString(); if (CHK_Password.Checked) { // keep this one local string pw = ""; InputBox.Show("Enter Password", "Please enter a password", ref pw, true); Password.EnterPassword(pw); } }
private void CHK_speechcustom_CheckedChanged(object sender, EventArgs e) { if (startup) { return; } Settings.Instance["speechcustomenabled"] = ((CheckBox)sender).Checked.ToString(); if (((CheckBox)sender).Checked) { var speechstring = "Heading to Waypoint {wpn}, altitude is {alt}, Ground speed is {gsp} "; if (Settings.Instance["speechcustom"] != null) { speechstring = Settings.Instance["speechcustom"].ToString(); } if (DialogResult.Cancel == InputBox.Show("Notification", "What do you want it to say?", ref speechstring)) { return; } Settings.Instance["speechcustom"] = speechstring; } }
private void CHK_speechmode_CheckedChanged(object sender, EventArgs e) { if (startup) { return; } Settings.Instance["speechmodeenabled"] = ((CheckBox)sender).Checked.ToString(); if (((CheckBox)sender).Checked) { var speechstring = "Mode changed to {mode}"; if (Settings.Instance["speechmode"] != null) { speechstring = Settings.Instance["speechmode"].ToString(); } if (DialogResult.Cancel == InputBox.Show("Notification", "What do you want it to say?", ref speechstring)) { return; } Settings.Instance["speechmode"] = speechstring; } }
private void CHK_speechaltwarning_CheckedChanged(object sender, EventArgs e) { if (startup) { return; } Settings.Instance["speechaltenabled"] = ((CheckBox)sender).Checked.ToString(); if (((CheckBox)sender).Checked) { var speechstring = "WARNING, low altitude {alt}"; if (Settings.Instance["speechalt"] != null) { speechstring = Settings.Instance["speechalt"].ToString(); } if (DialogResult.Cancel == InputBox.Show("Notification", "What do you want it to say?", ref speechstring)) { return; } Settings.Instance["speechalt"] = speechstring; speechstring = "2"; if (Settings.Instance["speechaltheight"] != null) { speechstring = Settings.Instance["speechaltheight"].ToString(); } if (DialogResult.Cancel == InputBox.Show("Min Alt", "What altitude do you want to warn at? (relative to home)", ref speechstring)) { return; } Settings.Instance["speechaltheight"] = (double.Parse(speechstring) / CurrentState.multiplieralt).ToString(); // save as m } }
private void BUT_connect_Click(object sender, EventArgs e) { if (comPort.IsOpen) { threadrun = false; comPort.Close(); BUT_connect.Text = Strings.Connect; } else { try { comPort.PortName = CMB_serialport.Text; } catch { CustomMessageBox.Show(Strings.InvalidPortName, Strings.ERROR); return; } try { comPort.BaudRate = int.Parse(CMB_baudrate.Text); } catch { CustomMessageBox.Show(Strings.InvalidBaudRate, Strings.ERROR); return; } try { comPort.Open(); } catch (Exception ex) { CustomMessageBox.Show(Strings.ErrorConnecting + "\n" + ex.ToString(), Strings.ERROR); return; } string alt = "100"; if (MainV2.comPort.MAV.cs.firmware == Firmwares.ArduCopter2) { alt = (10 * CurrentState.multiplierdist).ToString("0"); } else { alt = (100 * CurrentState.multiplierdist).ToString("0"); } if (DialogResult.Cancel == InputBox.Show("Enter Alt", "Enter Alt (relative to home alt)", ref alt)) { return; } intalt = (int)(100 * CurrentState.multiplierdist); if (!int.TryParse(alt, out intalt)) { CustomMessageBox.Show(Strings.InvalidAlt, Strings.ERROR); return; } intalt = (int)(intalt / CurrentState.multiplierdist); t12 = new System.Threading.Thread(new System.Threading.ThreadStart(mainloop)) { IsBackground = true, Name = "followme Input" }; t12.Start(); BUT_connect.Text = Strings.Stop; } }
private void but_graphit_Click(object sender, EventArgs e) { InputBox.Show("Points", "Points of history?", ref history); var form = new Form() { Size = new Size(640, 480) }; var zg1 = new ZedGraphControl() { Dock = DockStyle.Fill }; var path = selectedmsgid.Split('\\'); if (path.Length < 4) { return; } var sysid = int.Parse(path[0].Split(' ')[1]); var compid = int.Parse(path[1].Split(' ')[1]); var msgt = path[2]; var field = path[3]; var msgid = int.Parse(msgt.Split(new[] { '#', ')' })[1]); var msgidfield = field.Split(' ')[0]; var line = new LineItem(msgt.Split(' ')[0] + "." + msgidfield, new RollingPointPairList(history), Color.Red, SymbolType.None); zg1.GraphPane.Title.Text = ""; try { var msginfo = MAVLink.MAVLINK_MESSAGE_INFOS.First(a => a.msgid == msgid); var typeofthing = msginfo.type.GetField( msgidfield); if (typeofthing != null) { var attrib = typeofthing.GetCustomAttributes(false); if (attrib.Length > 0) { zg1.GraphPane.YAxis.Title.Text = attrib.OfType <MAVLink.Units>().First().Unit; } } } catch { } zg1.GraphPane.CurveList.Add(line); zg1.GraphPane.XAxis.Type = AxisType.Date; zg1.GraphPane.XAxis.Scale.Format = "HH:mm:ss.fff"; zg1.GraphPane.XAxis.Scale.MajorUnit = DateUnit.Minute; zg1.GraphPane.XAxis.Scale.MinorUnit = DateUnit.Second; Color[] color = new Color[] { Color.Red, Color.Green, Color.Blue, Color.Black, Color.Violet, Color.Orange }; var timer = new Timer() { Interval = 100 }; EventHandler <MAVLink.MAVLinkMessage> opr = null; opr = (e2, msg) => { if (msg.msgid != msgid) { return; } if (msg.sysid != sysid) { return; } if (msg.compid != compid) { return; } var item = msg.data.GetPropertyOrField(msgidfield); if (item is IEnumerable) { int a = 0; foreach (var subitem in (IEnumerable)item) { if (subitem is IConvertible) { while (zg1.GraphPane.CurveList.Count < (a + 1)) { zg1.GraphPane.CurveList.Add(new LineItem(msgidfield + "[" + a + "]", new RollingPointPairList(history), color[a % color.Length], SymbolType.None)); } zg1.GraphPane.CurveList[a].AddPoint(new XDate(msg.rxtime), ((IConvertible)subitem).ToDouble(null)); a++; } } } else if (item is IConvertible) { line.AddPoint(new XDate(msg.rxtime), ((IConvertible)item).ToDouble(null)); } else { line.AddPoint(new XDate(msg.rxtime), (double)(dynamic)item); } }; mav.OnPacketReceived += opr; mav.OnPacketSent += opr; timer.Tick += (o, args) => { // Make sure the Y axis is rescaled to accommodate actual data zg1.AxisChange(); // Force a redraw zg1.Invalidate(); }; form.Controls.Add(zg1); form.Closing += (o2, args2) => { mav.OnPacketReceived -= opr; mav.OnPacketSent -= opr; }; ThemeManager.ApplyThemeTo(form); form.Show(this); timer.Start(); but_graphit.Enabled = false; }
protected override bool ProcessCmdKey(ref Message msg, Keys keyData) { if (keyData == (Keys.Control | Keys.S)) { var exepath = CheckandGetSITLImage("ArduCopter.elf"); var model = "+"; var config = GetDefaultConfig(model); var max = 10.0; if (InputBox.Show("how many?", "how many?", ref max) != DialogResult.OK) { return(true); } max--; for (int a = (int)max; a >= 0; a--) { var extra = " --disable-fgview -r50"; if (!string.IsNullOrEmpty(config)) { extra += @" --defaults """ + config + @""" -P SERIAL0_PROTOCOL=2 -P SERIAL1_PROTOCOL=2 "; } var home = new PointLatLngAlt(markeroverlay.Markers[0].Position).newpos((double)NUM_heading.Value, a * 4); if (max == a) { extra += String.Format( " -M{4} -s1 --home {3} --instance {0} --uartA tcp:0 {1} -P SYSID_THISMAV={2} ", a, "", a + 1, BuildHomeLocation(home, (int)NUM_heading.Value), model); } else { extra += String.Format( " -M{4} -s1 --home {3} --instance {0} --uartA tcp:0 {1} -P SYSID_THISMAV={2} ", a, "--uartD tcpclient:127.0.0.1:" + (5772 + 10 * a), a + 1, BuildHomeLocation(home, (int)NUM_heading.Value), model); } string simdir = sitldirectory + model + (a + 1) + Path.DirectorySeparatorChar; Directory.CreateDirectory(simdir); string path = Environment.GetEnvironmentVariable("PATH"); Environment.SetEnvironmentVariable("PATH", sitldirectory + ";" + simdir + ";" + path, EnvironmentVariableTarget.Process); Environment.SetEnvironmentVariable("HOME", simdir, EnvironmentVariableTarget.Process); ProcessStartInfo exestart = new ProcessStartInfo(); exestart.FileName = exepath; exestart.Arguments = extra; exestart.WorkingDirectory = simdir; exestart.WindowStyle = ProcessWindowStyle.Minimized; exestart.UseShellExecute = true; File.AppendAllText(Settings.GetUserDataDirectory() + "sitl.bat", "mkdir " + (a + 1) + "\ncd " + (a + 1) + "\n" + @"""" + exepath + @"""" + " " + extra + " &\n"); File.AppendAllText(Settings.GetUserDataDirectory() + "sitl1.sh", "mkdir " + (a + 1) + "\ncd " + (a + 1) + "\n" + @"""../" + Path.GetFileName(exepath).Replace("C:", "/mnt/c").Replace("\\", "/").Replace(".exe", ".elf") + @"""" + " " + extra.Replace("C:", "/mnt/c").Replace("\\", "/") + " &\nsleep .3\ncd ..\n"); Process.Start(exestart); } try { var client = new Comms.TcpSerial(); client.client = new TcpClient("127.0.0.1", 5760); MainV2.comPort.BaseStream = client; SITLSEND = new UdpClient("127.0.0.1", 5501); Thread.Sleep(200); MainV2.instance.doConnect(MainV2.comPort, "preset", "5760"); return(true); } catch { CustomMessageBox.Show(Strings.Failed_to_connect_to_SITL_instance, Strings.ERROR); return(true); } } if (keyData == (Keys.Control | Keys.D)) { var exepath = CheckandGetSITLImage("ArduCopter.elf"); var model = "+"; var config = GetDefaultConfig(model); var max = 10.0; if (InputBox.Show("how many?", "how many?", ref max) != DialogResult.OK) { return(true); } max--; for (int a = (int)max; a >= 0; a--) { var extra = " --disable-fgview -r50 "; if (!string.IsNullOrEmpty(config)) { extra += @" --defaults """ + config + @""" -P SERIAL0_PROTOCOL=2 -P SERIAL1_PROTOCOL=2 "; } var home = new PointLatLngAlt(markeroverlay.Markers[0].Position).newpos((double)NUM_heading.Value, a * 4); if (max == a) { extra += String.Format( " -M{4} -s1 --home {3} --instance {0} --uartA tcp:0 {1} -P SYSID_THISMAV={2} ", a, "", a + 1, BuildHomeLocation(home, (int)NUM_heading.Value), model); } else { extra += String.Format( " -M{4} -s1 --home {3} --instance {0} --uartA tcp:0 {1} -P SYSID_THISMAV={2} ", a, "" /*"--uartD tcpclient:127.0.0.1:" + (5770 + 10 * a)*/, a + 1, BuildHomeLocation(home, (int)NUM_heading.Value), model); } string simdir = sitldirectory + model + (a + 1) + Path.DirectorySeparatorChar; Directory.CreateDirectory(simdir); string path = Environment.GetEnvironmentVariable("PATH"); Environment.SetEnvironmentVariable("PATH", sitldirectory + ";" + simdir + ";" + path, EnvironmentVariableTarget.Process); Environment.SetEnvironmentVariable("HOME", simdir, EnvironmentVariableTarget.Process); ProcessStartInfo exestart = new ProcessStartInfo(); exestart.FileName = exepath; exestart.Arguments = extra; exestart.WorkingDirectory = simdir; exestart.WindowStyle = ProcessWindowStyle.Minimized; exestart.UseShellExecute = true; Process.Start(exestart); } try { for (int a = (int)max; a >= 0; a--) { var mav = new MAVLinkInterface(); var client = new Comms.TcpSerial(); client.client = new TcpClient("127.0.0.1", 5760 + (10 * (a))); mav.BaseStream = client; //SITLSEND = new UdpClient("127.0.0.1", 5501); Thread.Sleep(200); MainV2.instance.doConnect(mav, "preset", "5760"); try { mav.GetParam("SYSID_THISMAV"); mav.setParam("SYSID_THISMAV", a + 1, true); mav.GetParam("FRAME_CLASS"); mav.setParam("FRAME_CLASS", 1, true); } catch { } MainV2.Comports.Add(mav); } return(true); } catch { CustomMessageBox.Show(Strings.Failed_to_connect_to_SITL_instance, Strings.ERROR); return(true); } } return(base.ProcessCmdKey(ref msg, keyData)); }