Skip to content

Commit aa64498

Browse files
committed
FlightPlanner: Hide LOITER RADIUS field when not applicable
1 parent 88b3995 commit aa64498

File tree

1 file changed

+11
-5
lines changed

1 file changed

+11
-5
lines changed

GCSViews/FlightPlanner.cs

Lines changed: 11 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -1403,8 +1403,11 @@ private void CreateAndDisplayOverlay(string overlayId, List<MAVLink.mavlink_miss
14031403
{
14041404
if (TXT_WPRad.Text == "") TXT_WPRad.Text = startupWPradius;
14051405
wpRadius = double.Parse(TXT_WPRad.Text) / CurrentState.multiplieralt;
1406-
if (TXT_loiterrad.Text == "") TXT_loiterrad.Text = "30";
1407-
loiterRadius = double.Parse(TXT_loiterrad.Text) / CurrentState.multiplieralt;
1406+
if (TXT_loiterrad.Visible)
1407+
{
1408+
if (TXT_loiterrad.Text == "") TXT_loiterrad.Text = "30";
1409+
loiterRadius = double.Parse(TXT_loiterrad.Text) / CurrentState.multiplieralt;
1410+
}
14081411
}
14091412
catch (FormatException)
14101413
{
@@ -6263,18 +6266,21 @@ private void setWPParams()
62636266

62646267
try
62656268
{
6266-
TXT_loiterrad.Enabled = false;
6269+
TXT_loiterrad.Visible = false;
6270+
label5.Visible = false;
62676271
if (param.ContainsKey("LOITER_RADIUS"))
62686272
{
62696273
TXT_loiterrad.Text =
62706274
(((double) param["LOITER_RADIUS"] * CurrentState.multiplierdist)).ToString();
6271-
TXT_loiterrad.Enabled = true;
6275+
TXT_loiterrad.Visible = true;
6276+
label5.Visible = true;
62726277
}
62736278
else if (param.ContainsKey("WP_LOITER_RAD"))
62746279
{
62756280
TXT_loiterrad.Text =
62766281
(((double) param["WP_LOITER_RAD"] * CurrentState.multiplierdist)).ToString();
6277-
TXT_loiterrad.Enabled = true;
6282+
TXT_loiterrad.Visible = true;
6283+
label5.Visible = true;
62786284
}
62796285

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

0 commit comments

Comments
 (0)