Skip to content
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
136 changes: 86 additions & 50 deletions MAVProxy/modules/mavproxy_adsb.py
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,7 @@

from MAVProxy.modules.lib import mp_module
from MAVProxy.modules.lib import mp_settings
from MAVProxy.modules.lib import mp_util
from pymavlink import mavutil
from PIL import ImageColor

Expand All @@ -27,22 +28,22 @@
104 : 200
}

def get_threat_radius(m):
def get_threat_radius(emitter_type, squawk):

if m.emitter_type == 255:
if emitter_type == 255:
''' objectAvoidance Database item, squawk contains radius in cm'''
return m.squawk * 0.01
return squawk * 0.01
'''get threat radius for an OBC item'''
return obc_radius.get(m.emitter_type,0)
return obc_radius.get(emitter_type,0)


def get_threat_icon(m, default_icon):
def get_threat_icon(emitter_type, default_icon):

if m.emitter_type == 255:
if emitter_type == 255:
''' objectAvoidance Database item, do not draw an icon'''
return None
'''get threat radius for an OBC item, else the true ADSB icon'''
return obc_icons.get(m.emitter_type, default_icon)
return obc_icons.get(emitter_type, default_icon)


class ADSBVehicle(object):
Expand Down Expand Up @@ -82,15 +83,19 @@ def __init__(self, mpstate):
# threat_radius_clear = threat_radius*threat_radius_clear_multiplier
("threat_radius_clear_multiplier", int, 2),
("show_threat_radius_clear", bool, False),
("show_callsign", bool, True),
("traffic_warning", bool, False),
("alt_color1", str, "blue"),
("alt_color2", str, "red"),
("alt_color_thresh", int, 300)])
("alt_color_alt_thresh", int, 300),
("alt_color_dist_thresh", int, 3000)])
self.add_completion_function('(ADSBSETTING)',
self.ADSB_settings.completion)

self.threat_detection_timer = mavutil.periodic_event(2)
self.threat_timeout_timer = mavutil.periodic_event(2)
self.tnow = self.get_time()
self.last_traffic = self.tnow

def cmd_ADSB(self, args):
'''adsb command parser'''
Expand Down Expand Up @@ -191,51 +196,82 @@ def check_threat_timeout(self):
# called:
return

def mavlink_packet(self, m):
'''handle an incoming mavlink packet'''
if m.get_type() == "ADSB_VEHICLE":
id = 'ADSB-' + str(m.ICAO_address)
if id not in self.threat_vehicles.keys(): # check to see if the vehicle is in the dict
# if not then add it
self.threat_vehicles[id] = ADSBVehicle(id=id, state=m.to_dict())
for mp in self.module_matching('map*'):
from MAVProxy.modules.lib import mp_menu
from MAVProxy.modules.mavproxy_map import mp_slipmap
self.threat_vehicles[id].menu_item = mp_menu.MPMenuItem(name=id, returnkey=None)
def add_vehicle(self, state):
'''handle an incoming vehicle packet'''
id = 'ADSB-' + str(state['ICAO_address'])
lat = state['lat']
lon = state['lon']
altitude_km = state['altitude']
callsign = state['callsign']
heading = state['heading']
emitter_type = state['emitter_type']
squawk = state['squawk']

if id not in self.threat_vehicles.keys(): # check to see if the vehicle is in the dict
#print("NEW: ", state)
# if not then add it
self.threat_vehicles[id] = ADSBVehicle(id=id, state=state)
#print("NEW: ", state)
for mp in self.module_matching('map*'):
from MAVProxy.modules.lib import mp_menu
from MAVProxy.modules.mavproxy_map import mp_slipmap
self.threat_vehicles[id].menu_item = mp_menu.MPMenuItem(name=id, returnkey=None)

threat_radius = get_threat_radius(m)
selected_icon = get_threat_icon(m, self.threat_vehicles[id].icon)
threat_radius = get_threat_radius(emitter_type, squawk)
selected_icon = get_threat_icon(emitter_type, self.threat_vehicles[id].icon)

if selected_icon is not None:
# draw the vehicle on the map
popup = mp_menu.MPMenuSubMenu('ADSB', items=[self.threat_vehicles[id].menu_item])
icon = mp.map.icon(selected_icon)
mp.map.add_object(mp_slipmap.SlipIcon(id, (m.lat * 1e-7, m.lon * 1e-7),
icon, layer=3, rotation=m.heading*0.01, follow=False,
trail=mp_slipmap.SlipTrail(colour=(0, 255, 255)),
popup_menu=popup))
if threat_radius > 0:
mp.map.add_object(mp_slipmap.SlipCircle(id+":circle", 3,
(m.lat * 1e-7, m.lon * 1e-7),
threat_radius, (0, 255, 255), linewidth=1))
else: # the vehicle is in the dict
# update the dict entry
self.threat_vehicles[id].update(m.to_dict(), self.get_time())
if selected_icon is not None:
#print("map add ", state)
# draw the vehicle on the map
popup = mp_menu.MPMenuSubMenu('ADSB', items=[self.threat_vehicles[id].menu_item])
icon = mp.map.icon(selected_icon)
mp.map.add_object(mp_slipmap.SlipIcon(id, (lat * 1e-7, lon * 1e-7),
icon, layer=3, rotation=heading*0.01, follow=False,
trail=mp_slipmap.SlipTrail(colour=(0, 255, 255)),
popup_menu=popup))
if threat_radius > 0:
mp.map.add_object(mp_slipmap.SlipCircle(id+":circle", 3,
(lat * 1e-7, lon * 1e-7),
threat_radius, (0, 255, 255), linewidth=1))
else: # the vehicle is in the dict
# update the dict entry
self.threat_vehicles[id].update(state, self.get_time())

for mp in self.module_matching('map*'):
# update the map, labelling alt above/below our alt
GPI = self.master.messages.get("GLOBAL_POSITION_INT", None)
if GPI is None:
return
ref_alt = GPI.alt*0.001
lat_deg = lat * 1.0e-7
lon_deg = lon * 1.0e-7
our_lat_deg = GPI.lat*1.0e-7
our_lon_deg = GPI.lon*1.0e-7

dist = mp_util.gps_distance(our_lat_deg, our_lon_deg, lat_deg, lon_deg)
alt_amsl = altitude_km * 0.001
color = ImageColor.getrgb(self.ADSB_settings.alt_color1)
label = ""
if self.ADSB_settings.show_callsign:
label = "[%s] " % callsign.rstrip()
if alt_amsl > 0:
alt = int(alt_amsl - ref_alt)
label += self.height_string(alt)
if abs(alt) < self.ADSB_settings.alt_color_alt_thresh and dist < self.ADSB_settings.alt_color_dist_thresh:
tnow = self.get_time()
if self.ADSB_settings.traffic_warning and tnow - self.last_traffic > 5:
self.last_traffic = tnow
self.say("traffic")
color = ImageColor.getrgb(self.ADSB_settings.alt_color2)

mp.map.set_position(id, (lat_deg, lon_deg), rotation=heading*0.01, label=label, colour=color)
mp.map.set_position(id+":circle", (lat_deg, lon_deg))

for mp in self.module_matching('map*'):
# update the map, labelling alt above/below our alt
ground_alt = self.module('terrain').ElevationModel.GetElevation(m.lat*1e-7, m.lon*1e-7)
alt_amsl = m.altitude * 0.001
color = ImageColor.getrgb(self.ADSB_settings.alt_color1)
label = None
if alt_amsl > 0:
alt = int(alt_amsl - ground_alt)
label = self.height_string(alt)
if abs(alt) < self.ADSB_settings.alt_color_thresh:
color = ImageColor.getrgb(self.ADSB_settings.alt_color2)

mp.map.set_position(id, (m.lat * 1e-7, m.lon * 1e-7), rotation=m.heading*0.01, label=label, colour=color)
mp.map.set_position(id+":circle", (m.lat * 1e-7, m.lon * 1e-7))
def mavlink_packet(self, m):
'''handle an incoming mavlink packet'''
if m.get_type() == "ADSB_VEHICLE":
state = m.to_dict()
self.add_vehicle(state)

def idle_task(self):
'''called on idle'''
Expand Down