forked from ArduPilot/MissionPlanner
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathTerrainFollow.cs
167 lines (135 loc) · 5.83 KB
/
TerrainFollow.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
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
using log4net;
using System;
using System.Collections.Generic;
using System.Linq;
using System.Reflection;
using System.Text;
using System.Threading;
namespace MissionPlanner.Utilities
{
public class TerrainFollow
{
private static readonly ILog log = LogManager.GetLogger(MethodBase.GetCurrentMethod().DeclaringType);
bool issending = false;
MAVLink.MAVLinkMessage lastmessage;
MAVLink.mavlink_terrain_request_t lastrequest;
private static ManualResetEvent mre = new ManualResetEvent(false);
private IMAVLinkInterface _interface;
public TerrainFollow(IMAVLinkInterface inInterface)
{
_interface = inInterface;
log.Info("OnPacketReceived to packets");
_interface.OnPacketReceived += _interface_OnPacketReceived;
}
private void _interface_OnPacketReceived(object sender, MAVLink.MAVLinkMessage e)
{
if(e.msgid == (uint)MAVLink.MAVLINK_MSG_ID.TERRAIN_REQUEST
|| e.msgid == (uint)MAVLink.MAVLINK_MSG_ID.TERRAIN_REPORT)
{
ReceivedPacket(e);
}
}
~TerrainFollow()
{
_interface.OnPacketReceived -= _interface_OnPacketReceived;
}
public void UnSub()
{
log?.Info("OnPacketReceived remove to packets");
_interface.OnPacketReceived -= _interface_OnPacketReceived;
}
private bool ReceivedPacket(MAVLink.MAVLinkMessage rawpacket)
{
if (rawpacket.msgid == (byte) MAVLink.MAVLINK_MSG_ID.TERRAIN_REQUEST)
{
MAVLink.mavlink_terrain_request_t packet =
rawpacket.ToStructure<MAVLink.mavlink_terrain_request_t>();
if (issending)
return false;
lastmessage = rawpacket;
lastrequest = packet;
log.Info("received TERRAIN_REQUEST " + packet.lat/1e7 + " " + packet.lon/1e7 + " space " +
packet.grid_spacing + " " + Convert.ToString((long) packet.mask, 2));
// reset state to block
mre.Reset();
System.Threading.ThreadPool.QueueUserWorkItem(QueueSendGrid);
// wait for thread to start
mre.WaitOne();
}
else if (rawpacket.msgid == (byte) MAVLink.MAVLINK_MSG_ID.TERRAIN_REPORT)
{
MAVLink.mavlink_terrain_report_t packet =
rawpacket.ToStructure<MAVLink.mavlink_terrain_report_t>();
//log.Info("received TERRAIN_REPORT " + packet.lat / 1e7 + " " + packet.lon / 1e7 + " " + packet.loaded + " " + packet.pending);
}
return false;
}
private void QueueSendGrid(object nothing)
{
issending = true;
// trigger start
mre.Set();
try
{
// 8 across - 7 down
// cycle though the bitmask to check what we need to send (8*7)
for (byte i = 0; i < 56; i++)
{
// check to see if the ap requested this box.
if ((lastrequest.mask & ((ulong) 1 << i)) > 0)
{
// get the requested lat and lon
double lat = lastrequest.lat/1e7;
double lon = lastrequest.lon/1e7;
// get the distance between grids
int bitgridspacing = lastrequest.grid_spacing*4;
// get the new point, based on our current bit.
var newplla = new PointLatLngAlt(lat, lon).gps_offset(bitgridspacing*(i%8),
bitgridspacing*(int) Math.Floor(i/8.0));
// send a 4*4 grid, based on the lat lon of the bitmask
SendGrid(newplla.Lat, newplla.Lng, lastrequest.grid_spacing, i);
// 12hz = (43+6) * 12 = 588 bps
System.Threading.Thread.Sleep(1000/12);
}
}
}
catch (Exception ex)
{
log.Error(ex);
}
finally
{
issending = false;
}
}
void SendGrid(double lat, double lon, ushort grid_spacing, byte bit)
{
log.Info("SendGrid " + lat + " " + lon + " space " + grid_spacing + " bit " + bit);
MAVLink.mavlink_terrain_data_t resp = new MAVLink.mavlink_terrain_data_t();
resp.grid_spacing = grid_spacing;
resp.lat = lastrequest.lat;
resp.lon = lastrequest.lon;
resp.gridbit = bit;
resp.data = new short[16];
for (int i = 0; i < (4*4); i++)
{
int x = i%4;
int y = i/4;
PointLatLngAlt plla = new PointLatLngAlt(lat, lon).gps_offset(x*grid_spacing, y*grid_spacing);
var alt = srtm.getAltitude(plla.Lat, plla.Lng);
// check where the alt returned came from.
if (alt.currenttype == srtm.tiletype.invalid)
return;
resp.data[i] = (short) alt.alt;
}
_interface.sendPacket(resp, lastmessage.sysid, lastmessage.compid);
}
public void checkTerrain(double lat, double lon)
{
MAVLink.mavlink_terrain_check_t packet = new MAVLink.mavlink_terrain_check_t();
packet.lat = (int) (lat*1e7);
packet.lon = (int) (lon*1e7);
_interface.sendPacket(packet, _interface.sysidcurrent, _interface.compidcurrent);
}
}
}