Skip to content

Commit 33aa9ec

Browse files
committed
Mock: add high latency option
1 parent 7ba6d35 commit 33aa9ec

File tree

1 file changed

+28
-9
lines changed

1 file changed

+28
-9
lines changed

ExtLibs/Mock/Program.cs

Lines changed: 28 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -47,15 +47,32 @@ static void Main(string[] args)
4747
continue;
4848
}
4949

50-
var sendpacket = mavparse.GenerateMAVLinkPacket20(MAVLink.MAVLINK_MSG_ID.HEARTBEAT,
51-
new MAVLink.mavlink_heartbeat_t()
52-
{
53-
autopilot = (byte) MAVLink.MAV_AUTOPILOT.ARDUPILOTMEGA,
54-
base_mode = (byte) MAVLink.MAV_MODE_FLAG.CUSTOM_MODE_ENABLED,
55-
system_status = (byte) MAVLink.MAV_STATE.ACTIVE,
56-
type = (byte) MAVLink.MAV_TYPE.QUADROTOR
57-
}, false, 1, 1, seqno++);
58-
mavlinkudp.Send(sendpacket, sendpacket.Length, ipEP);
50+
byte[] sendpacket;
51+
52+
if (!HighLatency)
53+
{
54+
55+
sendpacket = mavparse.GenerateMAVLinkPacket20(MAVLink.MAVLINK_MSG_ID.HEARTBEAT,
56+
new MAVLink.mavlink_heartbeat_t()
57+
{
58+
autopilot = (byte)MAVLink.MAV_AUTOPILOT.ARDUPILOTMEGA,
59+
base_mode = (byte)MAVLink.MAV_MODE_FLAG.CUSTOM_MODE_ENABLED,
60+
system_status = (byte)MAVLink.MAV_STATE.ACTIVE,
61+
type = (byte)MAVLink.MAV_TYPE.QUADROTOR
62+
}, false, 1, 1, seqno++);
63+
mavlinkudp.Send(sendpacket, sendpacket.Length, ipEP);
64+
}
65+
else
66+
{
67+
sendpacket = mavparse.GenerateMAVLinkPacket20(MAVLink.MAVLINK_MSG_ID.HIGH_LATENCY2,
68+
new MAVLink.mavlink_high_latency2_t()
69+
{
70+
autopilot = (byte)MAVLink.MAV_AUTOPILOT.ARDUPILOTMEGA, custom_mode = 0,
71+
latitude = (int)(-35 * 1e7),
72+
type = (byte)MAVLink.MAV_TYPE.QUADROTOR
73+
}, false, 1, 1, seqno++);
74+
mavlinkudp.Send(sendpacket, sendpacket.Length, ipEP);
75+
}
5976

6077
//sendpacket = mavparse.GenerateMAVLinkPacket20(MAVLink.MAVLINK_MSG_ID.AUTOPILOT_VERSION,new MAVLink.mavlink_autopilot_version_t(){ }, false, 1, 1, seqno++);
6178
//mavlinkudp.Send(sendpacket, sendpacket.Length, ipEP);
@@ -91,6 +108,8 @@ static void Main(string[] args)
91108
Thread.Sleep(100);
92109
}
93110
}
111+
112+
public static bool HighLatency { get; set; } = false;
94113
}
95114

96115
internal struct mavlink_vfr_hud_EDIT_t

0 commit comments

Comments
 (0)