forked from ArduPilot/MissionPlanner
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathProgram.cs
99 lines (79 loc) · 3.72 KB
/
Program.cs
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
using System;
using System.IO;
using System.Linq;
using System.Net;
using System.Net.Sockets;
using System.Threading;
using MavlinkMessagePlugin;
namespace Mock
{
class Program
{
static void Main(string[] args)
{
var mavlinkudp = new UdpClient(14550);
var mavparse = new MAVLink.MavlinkParse();
var seqno = 0;
IPEndPoint ipEP = new IPEndPoint(IPAddress.Any, 0);
var oldlist = MAVLink.MAVLINK_MESSAGE_INFOS.ToList();
oldlist.Add(new MAVLink.message_info(27499, "VFR_HUD_EDIT", 20, 20, 20, typeof(mavlink_vfr_hud_EDIT_t)));
MAVLink.MAVLINK_MESSAGE_INFOS = oldlist.ToArray();
while (true)
{
while (mavlinkudp.Available > 0)
{
ipEP = new IPEndPoint(IPAddress.Any, 0);
try
{
var rawpacket = mavlinkudp.Receive(ref ipEP);
var packet = mavparse.ReadPacket(new MemoryStream(rawpacket));
Console.WriteLine(packet);
}
catch
{
continue;
}
}
if (ipEP.Address == IPAddress.Any)
{
Thread.Sleep(100);
continue;
}
var sendpacket = mavparse.GenerateMAVLinkPacket20(MAVLink.MAVLINK_MSG_ID.HEARTBEAT,
new MAVLink.mavlink_heartbeat_t()
{
autopilot = (byte) MAVLink.MAV_AUTOPILOT.ARDUPILOTMEGA,
base_mode = (byte) MAVLink.MAV_MODE_FLAG.CUSTOM_MODE_ENABLED,
system_status = (byte) MAVLink.MAV_STATE.ACTIVE,
type = (byte) MAVLink.MAV_TYPE.QUADROTOR
}, false, 1, 1, seqno++);
mavlinkudp.Send(sendpacket, sendpacket.Length, ipEP);
//sendpacket = mavparse.GenerateMAVLinkPacket20(MAVLink.MAVLINK_MSG_ID.AUTOPILOT_VERSION,new MAVLink.mavlink_autopilot_version_t(){ }, false, 1, 1, seqno++);
//mavlinkudp.Send(sendpacket, sendpacket.Length, ipEP);
sendpacket = mavparse.GenerateMAVLinkPacket20(MAVLink.MAVLINK_MSG_ID.AHRS,
new MAVLink.mavlink_ahrs_t()
{ }, false, 1, 1, seqno++);
mavlinkudp.Send(sendpacket, sendpacket.Length, ipEP);
sendpacket = mavparse.GenerateMAVLinkPacket20(MAVLink.MAVLINK_MSG_ID.ATTITUDE,
new MAVLink.mavlink_attitude_t()
{pitch = 0, roll = 0, yaw = 0, time_boot_ms = (uint)DateTime.Now.Ticks}, false, 1, 1, seqno++);
mavlinkudp.Send(sendpacket, sendpacket.Length, ipEP);
sendpacket = mavparse.GenerateMAVLinkPacket20(MAVLink.MAVLINK_MSG_ID.GLOBAL_POSITION_INT,
new MAVLink.mavlink_global_position_int_t()
{
lat = (int) (-35 * 1e7), lon = (int) (117.89 * 1e7), alt = (40 * 1000), hdg = 45 * 100,
time_boot_ms = (uint) DateTime.Now.Ticks
}, false, 1, 1, seqno++);
mavlinkudp.Send(sendpacket, sendpacket.Length, ipEP);
sendpacket = mavparse.GenerateMAVLinkPacket20(MAVLink.MAVLINK_MSG_ID.PARAM_VALUE,
new MAVLink.mavlink_param_value_t()
{param_count = 0, param_index = 0, param_type = 0, param_value = 0}, false, 1, 1, seqno++);
mavlinkudp.Send(sendpacket, sendpacket.Length, ipEP);
Thread.Sleep(100);
}
}
}
internal struct mavlink_vfr_hud_EDIT_t
{
}
}