Skip to content

Commit

Permalink
FlightPlanner: Simultaneous display when not connected to vehicle
Browse files Browse the repository at this point in the history
  • Loading branch information
tatsuy committed Mar 14, 2024
1 parent f6eaf8c commit fb8f977
Showing 1 changed file with 36 additions and 7 deletions.
43 changes: 36 additions & 7 deletions GCSViews/FlightPlanner.cs
Original file line number Diff line number Diff line change
Expand Up @@ -107,6 +107,9 @@ private void but_mincommands_Click(object sender, System.EventArgs e)
private bool grid;
private List<int> groupmarkers = new List<int>();
private List<List<Locationwp>> history = new List<List<Locationwp>>();
private List<Locationwp> wpCommandList = new List<Locationwp>();
private List<Locationwp> fenceCommandList = new List<Locationwp>();
private List<Locationwp> rallyCommandList = new List<Locationwp>();
private bool isMouseClickOffMenu;
private bool isMouseDown;
private bool isMouseDraging;
Expand Down Expand Up @@ -1417,15 +1420,26 @@ private void CreateAndDisplayOverlay(string overlayId, List<MAVLink.mavlink_miss
}
try
{
var commandlist = GetCommandList();
if (isEditable)
{
var commandlist = GetCommandList();
overlay.CreateOverlay(home, commandlist, wpRadius, loiterRadius, CurrentState.multiplieralt);
// Store command list for waypoints, fences, and rally points
if (overlayId == "wp") wpCommandList = commandlist;
else if (overlayId == "fence") fenceCommandList = commandlist;
else if (overlayId == "rally") rallyCommandList = commandlist;
}
else
{
overlay.CreateOverlay(home, points.Select(a => (Locationwp)a).ToList(), wpRadius, loiterRadius, CurrentState.multiplieralt);
if (MainV2.comPort.BaseStream.IsOpen) commandlist = points.Select(a => (Locationwp)a).ToList();
else
{
// Use the stored command list if not connected to vehicle
if (overlayId == "wp") commandlist = wpCommandList;
else if (overlayId == "fence") commandlist = fenceCommandList;
else if (overlayId == "rally") commandlist = rallyCommandList;
}
}
overlay.CreateOverlay(home, commandlist, wpRadius, loiterRadius, CurrentState.multiplieralt);
}
catch (FormatException)
{
Expand Down Expand Up @@ -2101,16 +2115,22 @@ public void Cmb_missiontype_SelectedIndexChanged(object sender, EventArgs e)
if (rally.Count() > 0) MainMap.Overlays.Remove(rally.First());

// update the displayed items
// if connected to a vehicle, display the vehicle's items; otherwise, display local items
if ((MAVLink.MAV_MISSION_TYPE) cmb_missiontype.SelectedValue == MAVLink.MAV_MISSION_TYPE.RALLY)
{
BUT_Add.Visible = false;
processToScreen(MainV2.comPort.MAV.rallypoints.Select(a => (Locationwp) a.Value).ToList());

if (MainV2.comPort.BaseStream.IsOpen)
processToScreen(MainV2.comPort.MAV.rallypoints.Select(a => (Locationwp) a.Value).ToList());
else
processToScreen(rallyCommandList);
}
else if ((MAVLink.MAV_MISSION_TYPE) cmb_missiontype.SelectedValue == MAVLink.MAV_MISSION_TYPE.FENCE)
{
BUT_Add.Visible = false;
processToScreen(MainV2.comPort.MAV.fencepoints.Select(a => (Locationwp) a.Value).ToList());
if (MainV2.comPort.BaseStream.IsOpen)
processToScreen(MainV2.comPort.MAV.fencepoints.Select(a => (Locationwp) a.Value).ToList());
else
processToScreen(fenceCommandList);

Common.MessageShowAgain("FlightPlan Fence", "Please use the Polygon drawing tool to draw " +
"Inclusion and Exclusion areas (round circle to the left)," +
Expand All @@ -2120,7 +2140,16 @@ public void Cmb_missiontype_SelectedIndexChanged(object sender, EventArgs e)
else
{
BUT_Add.Visible = true;
processToScreen(MainV2.comPort.MAV.wps.Select(a => (Locationwp) a.Value).ToList());
if (MainV2.comPort.BaseStream.IsOpen)
processToScreen(MainV2.comPort.MAV.wps.Select(a => (Locationwp) a.Value).ToList());
else
{
if (wpCommandList.Count > 0)
// insert a dummy home point
wpCommandList.Insert(0, new Locationwp().Set(0, 0, 0, 0));

processToScreen(wpCommandList);
}
}

writeKML();
Expand Down

0 comments on commit fb8f977

Please sign in to comment.