Skip to content

Commit

Permalink
Refactor ADS-B input support in Mission Planner (#3251)
Browse files Browse the repository at this point in the history
* Fix ADSB: heading, speed & callsign, fix unit conv

* Add Squawk codes to SBS-1 decode

* Debug-filled functional 1Hz ADS-B

* Send less planes faster if less are in radius

* Fix ADS-B unit conversions, fix internal API, add velocities

* Use ADS-B ThreatLevel from MAV

* Clean up old planes from our internal memory

* Add ADS-B Collision risk to tooltip

* Fix ADS-B radius render errors

* Improve collision risk tooltip wording

* Pass source to UpdatePlanePosition

* Only update threat level when necessary, fix messages

* Shorten ADS-B loop, simplify code

* Remove log lines

* Only show tooltips on hover for ADSB

* Fix scaling bugs & add user-agent

* Fix merge issue

* Improve ADSB HTTP logic, rate limiting, default to adsb.lol
  • Loading branch information
MUSTARDTIGERFPV authored Jul 30, 2024
1 parent e900cb1 commit eefd216
Show file tree
Hide file tree
Showing 8 changed files with 484 additions and 220 deletions.
22 changes: 14 additions & 8 deletions ExtLibs/ArduPilot/Mavlink/MAVLinkInterface.cs
Original file line number Diff line number Diff line change
Expand Up @@ -5122,15 +5122,21 @@ public async Task<MAVLinkMessage> readPacketAsync()
var id = adsb.ICAO_address.ToString("X5");

if (_UpdateADSBPlanePosition != null)
_UpdateADSBPlanePosition(this, new adsb.PointLatLngAltHdg(adsb.lat / 1e7,
_UpdateADSBPlanePosition(this, new adsb.PointLatLngAltHdg(
adsb.lat / 1e7,
adsb.lon / 1e7,
adsb.altitude / 1000.0, adsb.heading * 0.01f, adsb.hor_velocity * 0.01f, id,
DateTime.Now)
{
CallSign = Encoding.UTF8.GetString(adsb.callsign),
Squawk = adsb.squawk,
Raw = adsb
}
adsb.altitude / 1000,
adsb.heading * 0.01f,
adsb.hor_velocity,
id,
DateTime.Now
)
{
CallSign = Encoding.UTF8.GetString(adsb.callsign),
Squawk = adsb.squawk,
Raw = adsb,
VerticalSpeed = adsb.ver_velocity,
}
);
}

Expand Down
16 changes: 14 additions & 2 deletions ExtLibs/Maps/GMapMarkerQuad.cs
Original file line number Diff line number Diff line change
Expand Up @@ -198,26 +198,38 @@ public override void OnRender(IGraphics g)
double width =
(Overlay.Control.MapProvider.Projection.GetDistance(Overlay.Control.FromLocalToLatLng(0, 0),
Overlay.Control.FromLocalToLatLng(Overlay.Control.Width, 0)) * 1000.0);
// size of a square meter in pixels on our map
double m2pixelwidth = Overlay.Control.Width / width;

GPoint loc = new GPoint((int) (LocalPosition.X - (m2pixelwidth * warn * 2)), LocalPosition.Y);

var markerDimension = (int)Math.Abs(loc.X - LocalPosition.X);
if (markerDimension == 0)
{
return;
}

if (m2pixelwidth > 0.001 && warn > 0)
g.DrawArc(Pens.Orange,
new System.Drawing.Rectangle(
LocalPosition.X - Offset.X - (int) (Math.Abs(loc.X - LocalPosition.X) / 2),
LocalPosition.Y - Offset.Y - (int) Math.Abs(loc.X - LocalPosition.X) / 2,
(int) Math.Abs(loc.X - LocalPosition.X), (int) Math.Abs(loc.X - LocalPosition.X)), 0,
markerDimension, markerDimension), 0,
360);

loc = new GPoint((int) (LocalPosition.X - (m2pixelwidth * danger * 2)), LocalPosition.Y);
markerDimension = (int)Math.Abs(loc.X - LocalPosition.X);
if (markerDimension == 0)
{
return;
}

if (m2pixelwidth > 0.001 && danger > 0)
g.DrawArc(Pens.Red,
new System.Drawing.Rectangle(
LocalPosition.X - Offset.X - (int) (Math.Abs(loc.X - LocalPosition.X) / 2),
LocalPosition.Y - Offset.Y - (int) Math.Abs(loc.X - LocalPosition.X) / 2,
(int) Math.Abs(loc.X - LocalPosition.X), (int) Math.Abs(loc.X - LocalPosition.X)), 0,
markerDimension, markerDimension), 0,
360);
}
}
Expand Down
17 changes: 17 additions & 0 deletions ExtLibs/Utilities/Download.cs
Original file line number Diff line number Diff line change
Expand Up @@ -321,6 +321,23 @@ public static async Task<string> GetAsync(string uri)
return await Task.Run(() => (content));
}

public struct HTTPResult
{
public string content;
public HttpStatusCode status;
}

/// <summary>
/// Perform a GET request and return the content and status code
/// </summary>
public static async Task<HTTPResult> GetAsyncWithStatus(string uri)
{
var httpClient = new HttpClient();
var response = await httpClient.GetAsync(uri);
var content = await response.Content.ReadAsStringAsync();
return await Task.Run(() => (new HTTPResult() { content = content, status = response.StatusCode }));
}

public static event EventHandler<HttpRequestMessage> RequestModification;

public static async Task<bool> getFilefromNetAsync(string url, string saveto, Action<int, string> status = null)
Expand Down
3 changes: 3 additions & 0 deletions ExtLibs/Utilities/PointLatLngAlt.cs
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,9 @@ public class PointLatLngAlt: IComparable
public static readonly PointLatLngAlt Zero = new PointLatLngAlt();
public double Lat { get; set; } = 0;
public double Lng { get; set; } = 0;
/// <summary>
/// Altitude in meters
/// </summary>
public double Alt { get; set; } = 0;
public string Tag { get; set; } = "";
public string Tag2 { get; set; } = "";
Expand Down
Loading

0 comments on commit eefd216

Please sign in to comment.