Skip to content
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
20 changes: 14 additions & 6 deletions GCSViews/SITL.cs
Original file line number Diff line number Diff line change
Expand Up @@ -875,20 +875,22 @@ public async Task StartSwarmSeperate(Firmwares firmware)
var extra = " ";

if (!string.IsNullOrEmpty(config))
extra += @" --defaults """ + config + @",identity.parm"" -P SERIAL0_PROTOCOL=2 -P SERIAL1_PROTOCOL=2 ";
extra += @" --defaults """ + config + @",identity.parm"" ";
else
extra += @" --defaults ""identity.parm"" ";

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} --serial0 tcp:0 {1} -P SYSID_THISMAV={2} ",
" -M{4} -s1 --home {3} --instance {0} --serial0 tcp:0 {1} ",
a, "", a + 1, BuildHomeLocation(home, (int)NUM_heading.Value), model);
}
else
{
extra += String.Format(
" -M{4} -s1 --home {3} --instance {0} --serial0 tcp:0 {1} -P SYSID_THISMAV={2} ",
" -M{4} -s1 --home {3} --instance {0} --serial0 tcp:0 {1} ",
a, "" /*"--serial2 tcpclient:127.0.0.1:" + (5770 + 10 * a)*/, a + 1,
BuildHomeLocation(home, (int)NUM_heading.Value), model);
}
Expand All @@ -900,6 +902,7 @@ public async Task StartSwarmSeperate(Firmwares firmware)
File.WriteAllText(simdir + "identity.parm", String.Format(@"SERIAL0_PROTOCOL=2
SERIAL1_PROTOCOL=2
SYSID_THISMAV={0}
MAV_SYSID={0}
SIM_TERRAIN=0
TERRAIN_ENABLE=0
SCHED_LOOP_RATE=50
Expand Down Expand Up @@ -1021,20 +1024,22 @@ public async void StartSwarmChain()
var extra = " ";

if (!string.IsNullOrEmpty(config))
extra += @" --defaults """ + config + @",identity.parm"" -P SERIAL0_PROTOCOL=2 -P SERIAL1_PROTOCOL=2 ";
extra += @" --defaults """ + config + @",identity.parm"" ";
else
extra += @" --defaults ""identity.parm"" ";

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} --serial0 tcp:0 {1} -P SYSID_THISMAV={2} ",
" -M{4} -s1 --home {3} --instance {0} --serial0 tcp:0 {1} ",
a, "", a + 1, BuildHomeLocation(home, (int)NUM_heading.Value), model);
}
else
{
extra += String.Format(
" -M{4} -s1 --home {3} --instance {0} --serial0 tcp:0 {1} -P SYSID_THISMAV={2} ",
" -M{4} -s1 --home {3} --instance {0} --serial0 tcp:0 {1} ",
a, "--serial2 tcpclient:127.0.0.1:" + (5772 + 10 * a), a + 1,
BuildHomeLocation(home, (int)NUM_heading.Value), model);
}
Expand All @@ -1046,6 +1051,7 @@ public async void StartSwarmChain()
File.WriteAllText(simdir + "identity.parm", String.Format(@"SERIAL0_PROTOCOL=2
SERIAL1_PROTOCOL=2
SYSID_THISMAV={0}
MAV_SYSID={0}
SIM_TERRAIN=0
TERRAIN_ENABLE=0
SCHED_LOOP_RATE=50
Expand Down Expand Up @@ -1076,6 +1082,8 @@ public async void StartSwarmChain()
Path.GetFileName(await exepath).Replace("C:", "/mnt/c").Replace("\\", "/").Replace(".exe", ".elf") + @"""" + " " +
extra.Replace("C:", "/mnt/c").Replace("\\", "/") + " &\nsleep .3\ncd ..\n");

log.InfoFormat("sitl: {0} {1} {2}", exestart.WorkingDirectory, exestart.FileName, exestart.Arguments);

simulator.Add(System.Diagnostics.Process.Start(exestart));
}

Expand Down
Loading