Skip to content

Commit

Permalink
FlightData: add set loiter rad #932
Browse files Browse the repository at this point in the history
  • Loading branch information
meee1 committed Apr 1, 2016
1 parent cb7ebaf commit ccacc70
Show file tree
Hide file tree
Showing 3 changed files with 793 additions and 1,739 deletions.
41 changes: 28 additions & 13 deletions GCSViews/FlightData.Designer.cs

Some generated files are not rendered by default. Learn more about how customized files appear on GitHub.

22 changes: 21 additions & 1 deletion GCSViews/FlightData.cs
Expand Up @@ -2046,9 +2046,15 @@ private void FlightData_ParentChanged(object sender, EventArgs e)
&& (float) MainV2.comPort.MAV.param["ARSPD_USE"] == 0)
{
modifyandSetSpeed.Value = (decimal) (float) MainV2.comPort.MAV.param["TRIM_THROTTLE"];
// percent
// percent
modifyandSetSpeed.ButtonText = Strings.ChangeThrottle;
}

if (MainV2.comPort.MAV.param.ContainsKey("LOITER_RAD"))
modifyandSetLoiterRad.Value = (decimal) (float) MainV2.comPort.MAV.param["LOITER_RAD"];

if (MainV2.comPort.MAV.param.ContainsKey("WP_LOITER_RAD"))
modifyandSetLoiterRad.Value = (decimal) (float) MainV2.comPort.MAV.param["WP_LOITER_RAD"];
}

void cam_camimage(Image camimage)
Expand Down Expand Up @@ -4118,5 +4124,19 @@ private void PointCameraCoordsToolStripMenuItem1_Click(object sender, EventArgs
CustomMessageBox.Show(Strings.InvalidField, Strings.ERROR);
}
}

private void modifyandSetLoiterRad_Click(object sender, EventArgs e)
{
int newrad = (int)modifyandSetLoiterRad.Value;

try
{
MainV2.comPort.setParam(new[] { "LOITER_RAD", "WP_LOITER_RAD" },newrad / CurrentState.multiplierdist);
}
catch
{
CustomMessageBox.Show(Strings.ErrorCommunicating, Strings.ERROR);
}
}
}
}

0 comments on commit ccacc70

Please sign in to comment.