Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

ADSB: Multi-vehicle compatibility and revamp #952

Open
wants to merge 1 commit into
base: master
Choose a base branch
from

Conversation

stephendade
Copy link
Contributor

Modernisation of the ADSB Module:

  • Able to take in ADSB feeds from all connected vehicles
  • Will print on console if any vehicles are too close (defined by threat_radius) to ADSB objects
  • "In range" detection changed to being the same as ArduPilot (separate horizontal and vertical thresholds)

Copy link
Contributor

@peterbarker peterbarker left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Light review only.

I think we generally try to avoid doing processing-heavy stuff in the mavlink callback; the idle callback may suffer latency but that's because it's more important to continue to process mavlink than process all of the content - thus the original structure.

def mavlink_packet(self, m):
'''handle an incoming mavlink packet'''
if m.get_type() == "ADSB_VEHICLE":
id = 'ADSB-' + str(m.ICAO_address)
label = str(m.callsign) + "/" + str(int(m.altitude * 0.001)) + "m"
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This can be moved into where the we construct the ADSBVehicle

Comment on lines 151 to 152
threat_radius_xy = get_threat_radius(self.threat_vehicles[id].state) if self.ADSB_settings.threat_radius_xy == 0 else self.ADSB_settings.threat_radius_xy
threat_radius_z = get_threat_radius(self.threat_vehicles[id].state) if self.ADSB_settings.threat_radius_z == 0 else self.ADSB_settings.threat_radius_z
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

It seems very odd looking inside threat_vehicles before we construct and add a vehicle if it doesn't exist.

Further, just because you can doesn't mean you should; these would be better written out as multiple lines.

Comment on lines 151 to 152
threat_radius_xy = get_threat_radius(self.threat_vehicles[id].state) if self.ADSB_settings.threat_radius_xy == 0 else self.ADSB_settings.threat_radius_xy
threat_radius_z = get_threat_radius(self.threat_vehicles[id].state) if self.ADSB_settings.threat_radius_z == 0 else self.ADSB_settings.threat_radius_z
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

These settings need clarification; it looks like they're override values rather than default values. So name them appropriately if that's the case...
self.ADSB_settings.threat_radius_z_override

We should also not be using radius_z - it's not a radius :-)

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())
self.threat_vehicles[id] = ADSBVehicle(id, m, threat_radius_xy, threat_radius_z)
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This should probably end up creating the vehicle with a default radius, and then common code below this point updating it from the received message.

@stephendade
Copy link
Contributor Author

I've fixed it up - now using a similar approach to the AIS module.

Copy link
Contributor

@peterbarker peterbarker left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This looks OK but I'll want to test it a chunk locally.

Comment on lines 62 to 63
self.isThreat = False
self.onMap = False
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Now using a mix of different variable-name styles; let's be consistent with the original format.


self.add_command('adsb', self.cmd_ADSB, "adsb control",
["<status>", "set (ADSBSETTING)"])

self.ADSB_settings = mp_settings.MPSettings([("timeout", int, 5), # seconds
("threat_radius", int, 200), # meters
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This will break existing users. We should accept threat_radius as an argument and if it is set to something other than None then we should use its value in preference to the xy and z overrides

@peterbarker
Copy link
Contributor

Testing went well, but I have (re)discovered that you really don't want multiple vehicles that are able to see each other's ADSB_VEHICLE messages.

@stephendade
Copy link
Contributor Author

I've fixed up the variable naming and re-added threat_radius. If threat_radius is 0, then the xy/z overrides will be used instead.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

None yet

2 participants