Skip to content

Commit

Permalink
FlightPlanner: Hide LOITER RADIUS field when not applicable
Browse files Browse the repository at this point in the history
  • Loading branch information
tatsuy committed Mar 14, 2024
1 parent e6e44d6 commit f6eaf8c
Showing 1 changed file with 11 additions and 5 deletions.
16 changes: 11 additions & 5 deletions GCSViews/FlightPlanner.cs
Original file line number Diff line number Diff line change
Expand Up @@ -1403,8 +1403,11 @@ private void CreateAndDisplayOverlay(string overlayId, List<MAVLink.mavlink_miss
{
if (TXT_WPRad.Text == "") TXT_WPRad.Text = startupWPradius;
wpRadius = double.Parse(TXT_WPRad.Text) / CurrentState.multiplieralt;
if (TXT_loiterrad.Text == "") TXT_loiterrad.Text = "30";
loiterRadius = double.Parse(TXT_loiterrad.Text) / CurrentState.multiplieralt;
if (TXT_loiterrad.Visible)
{
if (TXT_loiterrad.Text == "") TXT_loiterrad.Text = "30";
loiterRadius = double.Parse(TXT_loiterrad.Text) / CurrentState.multiplieralt;
}
}
catch (FormatException)
{
Expand Down Expand Up @@ -6263,18 +6266,21 @@ private void setWPParams()

try
{
TXT_loiterrad.Enabled = false;
TXT_loiterrad.Visible = false;
label5.Visible = false;
if (param.ContainsKey("LOITER_RADIUS"))
{
TXT_loiterrad.Text =
(((double) param["LOITER_RADIUS"] * CurrentState.multiplierdist)).ToString();
TXT_loiterrad.Enabled = true;
TXT_loiterrad.Visible = true;
label5.Visible = true;
}
else if (param.ContainsKey("WP_LOITER_RAD"))
{
TXT_loiterrad.Text =
(((double) param["WP_LOITER_RAD"] * CurrentState.multiplierdist)).ToString();
TXT_loiterrad.Enabled = true;
TXT_loiterrad.Visible = true;
label5.Visible = true;
}

log.Info("param LOITER_RADIUS " + TXT_loiterrad.Text);
Expand Down

0 comments on commit f6eaf8c

Please sign in to comment.