Skip to content

Commit

Permalink
FlightData: Add action for MAV_CMD_CONTROL_HIGH_LATENCY
Browse files Browse the repository at this point in the history
  • Loading branch information
stephendade authored and meee1 committed Dec 14, 2022
1 parent 7ac221f commit fa0e386
Show file tree
Hide file tree
Showing 2 changed files with 30 additions and 1 deletion.
15 changes: 15 additions & 0 deletions ExtLibs/ArduPilot/Mavlink/MAVLinkInterface.cs
Original file line number Diff line number Diff line change
Expand Up @@ -2388,6 +2388,21 @@ public bool doDFUBoot(byte sysid, byte compid)
return true;
}

/// <summary>
/// Control high latency mode
/// </summary>
/// <param name="onoff">true to enable, false to disable</param>
/// <returns></returns>
public bool doHighLatency(bool onoff= false)
{
int param1 = onoff ? 1 : 0;

var ans1 = doCommand((byte)sysidcurrent, (byte)compidcurrent, MAV_CMD.CONTROL_HIGH_LATENCY,
param1, 0, 0, 0, 0, 0, 0);

return ans1;
}

/// <summary>
/// reboot the vehicle
/// </summary>
Expand Down
16 changes: 15 additions & 1 deletion GCSViews/FlightData.cs
Original file line number Diff line number Diff line change
Expand Up @@ -180,7 +180,9 @@ public enum actions
Battery_Reset,
ADSB_Out_Ident,
Scripting_cmd_stop_and_restart,
Scripting_cmd_stop
Scripting_cmd_stop,
HighLatency_Enable,
HighLatency_Disable
}

private Dictionary<int, string> NIC_table = new Dictionary<int, string>()
Expand Down Expand Up @@ -1710,6 +1712,18 @@ private void BUTactiondo_Click(object sender, EventArgs e)
((Control) sender).Enabled = true;
return;
}
if (CMB_action.Text == actions.HighLatency_Enable.ToString())
{
MainV2.comPort.doHighLatency(true);
((Control)sender).Enabled = true;
return;
}
if (CMB_action.Text == actions.HighLatency_Disable.ToString())
{
MainV2.comPort.doHighLatency(false);
((Control)sender).Enabled = true;
return;
}

if (CMB_action.Text == actions.Battery_Reset.ToString())
{
Expand Down

0 comments on commit fa0e386

Please sign in to comment.