|
27 | 27 | 104 : 200 |
28 | 28 | } |
29 | 29 |
|
30 | | -def get_threat_radius(m): |
| 30 | +def get_threat_radius(emitter_type): |
31 | 31 |
|
32 | | - if m.emitter_type == 255: |
| 32 | + if emitter_type == 255: |
33 | 33 | ''' objectAvoidance Database item, squawk contains radius in cm''' |
34 | 34 | return m.squawk * 0.01 |
35 | 35 | '''get threat radius for an OBC item''' |
36 | | - return obc_radius.get(m.emitter_type,0) |
| 36 | + return obc_radius.get(emitter_type,0) |
37 | 37 |
|
38 | 38 |
|
39 | | -def get_threat_icon(m, default_icon): |
| 39 | +def get_threat_icon(emitter_type, default_icon): |
40 | 40 |
|
41 | | - if m.emitter_type == 255: |
| 41 | + if emitter_type == 255: |
42 | 42 | ''' objectAvoidance Database item, do not draw an icon''' |
43 | 43 | return None |
44 | 44 | '''get threat radius for an OBC item, else the true ADSB icon''' |
45 | | - return obc_icons.get(m.emitter_type, default_icon) |
| 45 | + return obc_icons.get(emitter_type, default_icon) |
46 | 46 |
|
47 | 47 |
|
48 | 48 | class ADSBVehicle(object): |
@@ -192,53 +192,65 @@ def check_threat_timeout(self): |
192 | 192 | # called: |
193 | 193 | return |
194 | 194 |
|
195 | | - def mavlink_packet(self, m): |
196 | | - '''handle an incoming mavlink packet''' |
197 | | - if m.get_type() == "ADSB_VEHICLE": |
198 | | - id = 'ADSB-' + str(m.ICAO_address) |
199 | | - if id not in self.threat_vehicles.keys(): # check to see if the vehicle is in the dict |
200 | | - # if not then add it |
201 | | - self.threat_vehicles[id] = ADSBVehicle(id=id, state=m.to_dict()) |
202 | | - for mp in self.module_matching('map*'): |
203 | | - from MAVProxy.modules.lib import mp_menu |
204 | | - from MAVProxy.modules.mavproxy_map import mp_slipmap |
205 | | - self.threat_vehicles[id].menu_item = mp_menu.MPMenuItem(name=id, returnkey=None) |
| 195 | + def add_vehicle(self, state): |
| 196 | + '''handle an incoming vehicle packet''' |
| 197 | + id = 'ADSB-' + str(state['ICAO_address']) |
| 198 | + lat = state['lat'] |
| 199 | + lon = state['lon'] |
| 200 | + altitude_km = state['altitude'] |
| 201 | + callsign = state['callsign'] |
| 202 | + heading = state['heading'] |
| 203 | + emitter_type = state['emitter_type'] |
| 204 | + |
| 205 | + if id not in self.threat_vehicles.keys(): # check to see if the vehicle is in the dict |
| 206 | + # if not then add it |
| 207 | + self.threat_vehicles[id] = ADSBVehicle(id=id, state=state) |
| 208 | + for mp in self.module_matching('map*'): |
| 209 | + from MAVProxy.modules.lib import mp_menu |
| 210 | + from MAVProxy.modules.mavproxy_map import mp_slipmap |
| 211 | + self.threat_vehicles[id].menu_item = mp_menu.MPMenuItem(name=id, returnkey=None) |
206 | 212 |
|
207 | | - threat_radius = get_threat_radius(m) |
208 | | - selected_icon = get_threat_icon(m, self.threat_vehicles[id].icon) |
| 213 | + threat_radius = get_threat_radius(emitter_type) |
| 214 | + selected_icon = get_threat_icon(emitter_type, self.threat_vehicles[id].icon) |
209 | 215 |
|
210 | | - if selected_icon is not None: |
211 | | - # draw the vehicle on the map |
212 | | - popup = mp_menu.MPMenuSubMenu('ADSB', items=[self.threat_vehicles[id].menu_item]) |
213 | | - icon = mp.map.icon(selected_icon) |
214 | | - mp.map.add_object(mp_slipmap.SlipIcon(id, (m.lat * 1e-7, m.lon * 1e-7), |
215 | | - icon, layer=3, rotation=m.heading*0.01, follow=False, |
216 | | - trail=mp_slipmap.SlipTrail(colour=(0, 255, 255)), |
217 | | - popup_menu=popup)) |
218 | | - if threat_radius > 0: |
219 | | - mp.map.add_object(mp_slipmap.SlipCircle(id+":circle", 3, |
220 | | - (m.lat * 1e-7, m.lon * 1e-7), |
221 | | - threat_radius, (0, 255, 255), linewidth=1)) |
222 | | - else: # the vehicle is in the dict |
223 | | - # update the dict entry |
224 | | - self.threat_vehicles[id].update(m.to_dict(), self.get_time()) |
| 216 | + if selected_icon is not None: |
| 217 | + # draw the vehicle on the map |
| 218 | + popup = mp_menu.MPMenuSubMenu('ADSB', items=[self.threat_vehicles[id].menu_item]) |
| 219 | + icon = mp.map.icon(selected_icon) |
| 220 | + mp.map.add_object(mp_slipmap.SlipIcon(id, (lat * 1e-7, lon * 1e-7), |
| 221 | + icon, layer=3, rotation=heading*0.01, follow=False, |
| 222 | + trail=mp_slipmap.SlipTrail(colour=(0, 255, 255)), |
| 223 | + popup_menu=popup)) |
| 224 | + if threat_radius > 0: |
| 225 | + mp.map.add_object(mp_slipmap.SlipCircle(id+":circle", 3, |
| 226 | + (lat * 1e-7, lon * 1e-7), |
| 227 | + threat_radius, (0, 255, 255), linewidth=1)) |
| 228 | + else: # the vehicle is in the dict |
| 229 | + # update the dict entry |
| 230 | + self.threat_vehicles[id].update(state, self.get_time()) |
| 231 | + |
| 232 | + for mp in self.module_matching('map*'): |
| 233 | + # update the map, labelling alt above/below our alt |
| 234 | + ground_alt = self.module('terrain').ElevationModel.GetElevation(lat*1e-7, lon*1e-7) |
| 235 | + alt_amsl = altitude_km * 0.001 |
| 236 | + color = ImageColor.getrgb(self.ADSB_settings.alt_color1) |
| 237 | + label = "" |
| 238 | + if self.ADSB_settings.show_callsign: |
| 239 | + label = "[%s] " % callsign |
| 240 | + if alt_amsl > 0: |
| 241 | + alt = int(alt_amsl - ground_alt) |
| 242 | + label += self.height_string(alt) |
| 243 | + if abs(alt) < self.ADSB_settings.alt_color_thresh: |
| 244 | + color = ImageColor.getrgb(self.ADSB_settings.alt_color2) |
| 245 | + |
| 246 | + mp.map.set_position(id, (lat * 1e-7, lon * 1e-7), rotation=heading*0.01, label=label, colour=color) |
| 247 | + mp.map.set_position(id+":circle", (lat * 1e-7, lon * 1e-7)) |
225 | 248 |
|
226 | | - for mp in self.module_matching('map*'): |
227 | | - # update the map, labelling alt above/below our alt |
228 | | - ground_alt = self.module('terrain').ElevationModel.GetElevation(m.lat*1e-7, m.lon*1e-7) |
229 | | - alt_amsl = m.altitude * 0.001 |
230 | | - color = ImageColor.getrgb(self.ADSB_settings.alt_color1) |
231 | | - label = "" |
232 | | - if self.ADSB_settings.show_callsign: |
233 | | - label = "[%s] " % m.callsign |
234 | | - if alt_amsl > 0: |
235 | | - alt = int(alt_amsl - ground_alt) |
236 | | - label += self.height_string(alt) |
237 | | - if abs(alt) < self.ADSB_settings.alt_color_thresh: |
238 | | - color = ImageColor.getrgb(self.ADSB_settings.alt_color2) |
239 | | - |
240 | | - mp.map.set_position(id, (m.lat * 1e-7, m.lon * 1e-7), rotation=m.heading*0.01, label=label, colour=color) |
241 | | - mp.map.set_position(id+":circle", (m.lat * 1e-7, m.lon * 1e-7)) |
| 249 | + def mavlink_packet(self, m): |
| 250 | + '''handle an incoming mavlink packet''' |
| 251 | + if m.get_type() == "ADSB_VEHICLE": |
| 252 | + state = m.to_dict() |
| 253 | + self.add_vehicle(state) |
242 | 254 |
|
243 | 255 | def idle_task(self): |
244 | 256 | '''called on idle''' |
|
0 commit comments