private void StartSITL(string exepath, string model, string homelocation, string extraargs = "", int speedup = 1) { if (String.IsNullOrEmpty(homelocation)) { CustomMessageBox.Show(Strings.Invalid_home_location, Strings.ERROR); return; } // override default model if (cmb_model.Text != "") { model = cmb_model.Text; } string simdir = sitldirectory + model + 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 = String.Format("-M{0} -O{1} -s{2} --uartA tcp:0 {3}", model, homelocation, speedup, extraargs); exestart.WorkingDirectory = simdir; exestart.WindowStyle = ProcessWindowStyle.Minimized; exestart.UseShellExecute = true; simulator = System.Diagnostics.Process.Start(exestart); System.Threading.Thread.Sleep(2000); MainV2.View.ShowScreen(MainV2.View.screens[0].Name); var client = new Comms.TcpSerial(); try { client.client = new TcpClient("127.0.0.1", 5760); MainV2.comPort.BaseStream = client; SITLSEND = new UdpClient("127.0.0.1", 5501); MainV2.instance.doConnect(MainV2.comPort, "preset", "5760"); } catch { CustomMessageBox.Show(Strings.Failed_to_connect_to_SITL_instance, Strings.ERROR); } this.Close(); }
private void StartSITL(string exepath, string model, string homelocation, string extraargs = "", int speedup = 1) { string simdir = sitldirectory + model + Path.DirectorySeparatorChar; Directory.CreateDirectory(simdir); string path = Environment.GetEnvironmentVariable("PATH"); Environment.SetEnvironmentVariable("PATH", simdir + ";" + path, EnvironmentVariableTarget.Process); Environment.SetEnvironmentVariable("HOME", simdir, EnvironmentVariableTarget.Process); ProcessStartInfo exestart = new ProcessStartInfo(); exestart.FileName = exepath; exestart.Arguments = String.Format("-M{0} -O{1} -s{2} {3}", model, homelocation, speedup, extraargs); exestart.WorkingDirectory = simdir; exestart.WindowStyle = ProcessWindowStyle.Minimized; exestart.UseShellExecute = true; simulator = System.Diagnostics.Process.Start(exestart); System.Threading.Thread.Sleep(2000); MainV2.View.ShowScreen(MainV2.View.screens[0].Name); 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); MainV2.instance.doConnect(MainV2.comPort, "preset", "5760"); this.Close(); }
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; for (int a = max; a >= 0; a--) { var extra = ""; 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 { 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; for (int a = max; a >= 0; a--) { var extra = ""; 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 = 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)); }
private void StartSITL(string exepath, string model, string homelocation, string extraargs = "", int speedup = 1) { if (String.IsNullOrEmpty(homelocation)) { CustomMessageBox.Show(Strings.Invalid_home_location, Strings.ERROR); return; } if (!File.Exists(exepath)) { CustomMessageBox.Show(Strings.Failed_to_download_the_SITL_image, Strings.ERROR); return; } // kill old session try { if (simulator != null) { simulator.Kill(); } } catch { } // override default model if (cmb_model.Text != "") { model = cmb_model.Text; } var config = GetDefaultConfig(model); if (!string.IsNullOrEmpty(config)) { extraargs += @" --defaults """ + config + @""""; } extraargs += " " + txt_cmdline.Text + " "; if (chk_wipe.Checked) { extraargs += " --wipe "; } string simdir = sitldirectory + model + 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 = String.Format("-M{0} -O{1} -s{2} --uartA tcp:0 {3}", model, homelocation, speedup, extraargs); exestart.WorkingDirectory = simdir; exestart.WindowStyle = ProcessWindowStyle.Minimized; exestart.UseShellExecute = true; try { simulator = System.Diagnostics.Process.Start(exestart); } catch (Exception ex) { CustomMessageBox.Show("Failed to start the simulator\n" + ex.ToString(), Strings.ERROR); return; } System.Threading.Thread.Sleep(2000); MainV2.View.ShowScreen(MainV2.View.screens[0].Name); var client = new Comms.TcpSerial(); try { 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"); } catch { CustomMessageBox.Show(Strings.Failed_to_connect_to_SITL_instance, Strings.ERROR); return; } }
private void StartSITL(string exepath, string model, string homelocation, string extraargs = "", int speedup = 1) { if (String.IsNullOrEmpty(homelocation)) { CustomMessageBox.Show(Strings.Invalid_home_location, Strings.ERROR); return; } string simdir = sitldirectory + model + Path.DirectorySeparatorChar; Directory.CreateDirectory(simdir); string path = Environment.GetEnvironmentVariable("PATH"); Environment.SetEnvironmentVariable("PATH", simdir + ";" + path, EnvironmentVariableTarget.Process); Environment.SetEnvironmentVariable("HOME", simdir, EnvironmentVariableTarget.Process); ProcessStartInfo exestart = new ProcessStartInfo(); exestart.FileName = exepath; exestart.Arguments = String.Format("-M{0} -O{1} -s{2} {3}", model, homelocation, speedup, extraargs); exestart.WorkingDirectory = simdir; exestart.WindowStyle = ProcessWindowStyle.Minimized; exestart.UseShellExecute = true; simulator = System.Diagnostics.Process.Start(exestart); System.Threading.Thread.Sleep(2000); MainV2.View.ShowScreen(MainV2.View.screens[0].Name); var client = new Comms.TcpSerial(); try { client.client = new TcpClient("127.0.0.1", 5760); MainV2.comPort.BaseStream = client; SITLSEND = new UdpClient("127.0.0.1", 5501); MainV2.instance.doConnect(MainV2.comPort, "preset", "5760"); } catch { CustomMessageBox.Show(Strings.Failed_to_connect_to_SITL_instance, Strings.ERROR); } this.Close(); }
public async void StartSwarmChain() { var max = 10; if (InputBox.Show("how many?", "how many?", ref max) != DialogResult.OK) { return; } // kill old session try { simulator.ForEach(a => { try { a.Kill(); } catch { } }); } catch { } var exepath = CheckandGetSITLImage("ArduCopter.elf"); var model = "+"; var config = await GetDefaultConfig(model); max--; for (int a = (int)max; a >= 0; a--) { var extra = " --disable-fgview -r50"; if (!string.IsNullOrEmpty(config)) { extra += @" --defaults """ + config + @",identity.parm"" -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); File.WriteAllText(simdir + "identity.parm", String.Format(@"SERIAL0_PROTOCOL=2 SERIAL1_PROTOCOL=2 SYSID_THISMAV={0} SIM_TERRAIN=0 TERRAIN_ENABLE=0 SCHED_LOOP_RATE=50 SIM_RATE_HZ=400 SIM_DRIFT_SPEED=0 SIM_DRIFT_TIME=0 ", a + 1)); 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 = await 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" + @"""" + await exepath + @"""" + " " + extra + " &\n"); File.AppendAllText(Settings.GetUserDataDirectory() + "sitl1.sh", "mkdir " + (a + 1) + "\ncd " + (a + 1) + "\n" + @"""../" + Path.GetFileName(await exepath).Replace("C:", "/mnt/c").Replace("\\", "/").Replace(".exe", ".elf") + @"""" + " " + extra.Replace("C:", "/mnt/c").Replace("\\", "/") + " &\nsleep .3\ncd ..\n"); simulator.Add(System.Diagnostics.Process.Start(exestart)); } System.Threading.Thread.Sleep(2000); MainV2.View.ShowScreen(MainV2.View.screens[0].Name); 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", false); try { MainV2.comPort.getParamListAsync((byte)MainV2.comPort.sysidcurrent, (byte)MainV2.comPort.compidcurrent); } catch { } return; } catch { CustomMessageBox.Show(Strings.Failed_to_connect_to_SITL_instance, Strings.ERROR); return; } }
private async void StartSITL(string exepath, string model, string homelocation, string extraargs = "", int speedup = 1) { if (String.IsNullOrEmpty(homelocation)) { CustomMessageBox.Show(Strings.Invalid_home_location, Strings.ERROR); return; } if (!File.Exists(exepath)) { CustomMessageBox.Show(Strings.Failed_to_download_the_SITL_image, Strings.ERROR); return; } // kill old session try { simulator.ForEach(a => { try { a.Kill(); } catch { } }); } catch { } // override default model if (cmb_model.Text != "") { model = cmb_model.Text; } var config = await GetDefaultConfig(model); if (!string.IsNullOrEmpty(config)) { extraargs += @" --defaults """ + config + @""""; } extraargs += " " + txt_cmdline.Text + " "; if (chk_wipe.Checked) { extraargs += " --wipe "; } string simdir = sitldirectory + model + 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 = String.Format("-M{0} -O{1} -s{2} --uartA tcp:0 {3}", model, homelocation, speedup, extraargs); exestart.WorkingDirectory = simdir; exestart.WindowStyle = ProcessWindowStyle.Minimized; Console.WriteLine("sitl: {0} {1} {2}", exestart.WorkingDirectory, exestart.FileName, exestart.Arguments); if (RuntimeInformation.OSArchitecture == Architecture.X64 || RuntimeInformation.OSArchitecture == Architecture.X86) { exestart.UseShellExecute = true; try { simulator.Add(System.Diagnostics.Process.Start(exestart)); } catch (Exception ex) { CustomMessageBox.Show("Failed to start the simulator\n" + ex.ToString(), Strings.ERROR); return; } } else { exestart.UseShellExecute = false; exestart.RedirectStandardOutput = true; exestart.RedirectStandardError = true; try { var proc = System.Diagnostics.Process.Start(exestart); simulator.Add(proc); proc.ErrorDataReceived += (sender, args) => { Console.WriteLine("SITL ERR: " + args.Data); }; proc.OutputDataReceived += (sender, args) => { Console.WriteLine("SITL: " + args.Data); }; proc.Exited += (sender, args) => { Console.WriteLine("SITL EXIT!"); }; proc.BeginOutputReadLine(); proc.BeginErrorReadLine(); } catch (Exception ex) { CustomMessageBox.Show("Failed to start the simulator\n" + ex.ToString(), Strings.ERROR); return; } } await Task.Delay(2000); MainV2.View.ShowScreen(MainV2.View.screens[0].Name); var client = new Comms.TcpSerial(); try { client.client = new TcpClient("127.0.0.1", 5760); MainV2.comPort.BaseStream = client; SITLSEND = new UdpClient("127.0.0.1", 5501); await Task.Delay(200); MainV2.instance.doConnect(MainV2.comPort, "preset", "5760"); } catch { CustomMessageBox.Show(Strings.Failed_to_connect_to_SITL_instance, Strings.ERROR); return; } }
public async Task StartSwarmSeperate(Firmwares firmware) { var max = 10; if (InputBox.Show("how many?", "how many?", ref max) != DialogResult.OK) { return; } // kill old session try { simulator.ForEach(a => { try { a.Kill(); } catch { } }); } catch { } Task <string> exepath; string model = ""; if (firmware == Firmwares.ArduPlane) { exepath = CheckandGetSITLImage("ArduPlane.elf"); model = "plane"; } else if (firmware == Firmwares.ArduRover) { exepath = CheckandGetSITLImage("ArduRover.elf"); model = "rover"; } else // (firmware == Firmwares.ArduCopter2) { exepath = CheckandGetSITLImage("ArduCopter.elf"); model = "+"; } var config = await GetDefaultConfig(model); max--; for (int a = (int)max; a >= 0; a--) { var extra = " --disable-fgview -r50 "; if (!string.IsNullOrEmpty(config)) { extra += @" --defaults """ + config + @",identity.parm"" -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); File.WriteAllText(simdir + "identity.parm", String.Format(@"SERIAL0_PROTOCOL=2 SERIAL1_PROTOCOL=2 SYSID_THISMAV={0} SIM_TERRAIN=0 TERRAIN_ENABLE=0 SCHED_LOOP_RATE=50 SIM_RATE_HZ=400 SIM_DRIFT_SPEED=0 SIM_DRIFT_TIME=0 ", a + 1)); 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 = await exepath; exestart.Arguments = extra; exestart.WorkingDirectory = simdir; exestart.WindowStyle = ProcessWindowStyle.Minimized; exestart.UseShellExecute = true; simulator.Add(System.Diagnostics.Process.Start(exestart)); await Task.Delay(100); } await Task.Delay(2000); MainV2.View.ShowScreen(MainV2.View.screens[0].Name); try { Parallel.For(0, max + 1, (a) => //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); this.InvokeIfRequired(() => { MainV2.instance.doConnect(mav, "preset", "5760", false); }); lock (this) MainV2.Comports.Add(mav); try { _ = mav.getParamListMavftpAsync((byte)mav.sysidcurrent, (byte)mav.compidcurrent); } catch { } } ); return; } catch (Exception ex) { log.Error(ex); CustomMessageBox.Show(Strings.Failed_to_connect_to_SITL_instance + ex.InnerException?.Message, Strings.ERROR); return; } }
private void StartSITL(string exepath, string model, string homelocation, string extraargs = "", int speedup = 1) { if (String.IsNullOrEmpty(homelocation)) { CustomMessageBox.Show(Strings.Invalid_home_location, Strings.ERROR); return; } if (!File.Exists(exepath)) { CustomMessageBox.Show(Strings.Failed_to_download_the_SITL_image, Strings.ERROR); return; } // kill old session try { if (simulator != null) simulator.Kill(); } catch { } // override default model if (cmb_model.Text != "") model = cmb_model.Text; var config = GetDefaultConfig(model); if (!string.IsNullOrEmpty(config)) extraargs += @" --defaults """ + config+@""""; string simdir = sitldirectory + model + 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 = String.Format("-M{0} -O{1} -s{2} --uartA tcp:0 {3}", model, homelocation, speedup, extraargs); exestart.WorkingDirectory = simdir; exestart.WindowStyle = ProcessWindowStyle.Minimized; exestart.UseShellExecute = true; simulator = System.Diagnostics.Process.Start(exestart); System.Threading.Thread.Sleep(2000); MainV2.View.ShowScreen(MainV2.View.screens[0].Name); var client = new Comms.TcpSerial(); try { client.client = new TcpClient("127.0.0.1", 5760); MainV2.comPort.BaseStream = client; SITLSEND = new UdpClient("127.0.0.1", 5501); MainV2.instance.doConnect(MainV2.comPort, "preset", "5760"); } catch { CustomMessageBox.Show(Strings.Failed_to_connect_to_SITL_instance, Strings.ERROR); } }