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

Proximity: Fix Proximity UI concurrency issue #3222

Open
wants to merge 1 commit into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
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
12 changes: 10 additions & 2 deletions Controls/ProximityControl.cs
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@ public class ProximityControl : Form

MAVState _parent;
private Proximity.directionState _dS => _parent?.Proximity?.DirectionState;
private bool _drawingInProgress => _parent?.Proximity?.DrawingInProgress ?? false;

private Timer timer1;
private IContainer components;
Expand Down Expand Up @@ -90,6 +91,8 @@ private void Temp_KeyPress(object sender, KeyPressEventArgs e)

private void Temp_Paint(object sender, PaintEventArgs e)
{
if (_parent.Proximity != null)
_parent.Proximity.DrawingInProgress = true;
e.Graphics.Clear(BackColor);

var midx = e.ClipRectangle.Width / 2.0f;
Expand All @@ -111,14 +114,18 @@ private void Temp_Paint(object sender, PaintEventArgs e)
e.Graphics.DrawImage(Resources.quadicon, midx - imw, midy - imw, size, size);
break;
}

if (_dS == null)
{
if (_parent.Proximity != null)
_parent.Proximity.DrawingInProgress = false;
return;
}

Pen redpen = new Pen(Color.Red, 3);
Pen yellowpen = new Pen(Color.Yellow, 3);
var font = new Font(SystemFonts.DefaultFont.FontFamily, SystemFonts.DefaultFont.Size + 2, FontStyle.Bold);

float move = 5;

for (float x = 50f; x <= screenradius; x+=50f)
Expand Down Expand Up @@ -205,6 +212,7 @@ private void Temp_Paint(object sender, PaintEventArgs e)
break;
}
}
_parent.Proximity.DrawingInProgress = false;
}

public new void Show()
Expand Down
33 changes: 19 additions & 14 deletions ExtLibs/ArduPilot/Proximity.cs
Original file line number Diff line number Diff line change
Expand Up @@ -24,8 +24,9 @@ public class Proximity : IDisposable
private byte compid;

public bool DataAvailable { get; set; } = false;
public bool DrawingInProgress { get; set; } = false;

public Proximity(MAVState mavInt, byte sysid, byte compid)
public Proximity(MAVState mavInt, byte sysid, byte compid)
{
this.sysid = sysid;
this.compid = compid;
Expand All @@ -47,6 +48,7 @@ public Proximity(MAVState mavInt, byte sysid, byte compid)

private bool messageReceived(MAVLinkMessage arg)
{
if (DrawingInProgress) return true;
//accept any compid, but filter sysid
if (arg.sysid != _parent.sysid)
return true;
Expand All @@ -64,7 +66,7 @@ private bool messageReceived(MAVLinkMessage arg)
_dS.Add(dist.id, (MAV_SENSOR_ORIENTATION)dist.orientation, dist.current_distance, DateTime.Now, 3);

DataAvailable = true;
}
}
else if (arg.msgid == (uint) MAVLINK_MSG_ID.OBSTACLE_DISTANCE)
{
var dists = arg.ToStructure<mavlink_obstacle_distance_t>();
Expand All @@ -89,7 +91,7 @@ private bool messageReceived(MAVLinkMessage arg)
if(dists.distances[a] == ushort.MaxValue)
continue;
if(dists.distances[a] > dists.max_distance)
continue;
continue;
if(dists.distances[a] < dists.min_distance)
continue;

Expand Down Expand Up @@ -135,7 +137,7 @@ public data(uint id, MAV_SENSOR_ORIENTATION orientation, double distance, DateTi
Distance = distance;
Received = received;
Age = age;
}
}

public data(uint id, double angle, double size, double distance, DateTime received, double age = 1)
{
Expand All @@ -161,20 +163,23 @@ public void Add(uint id, MAV_SENSOR_ORIENTATION orientation, double distance, Da
_dists.Add(new data(id, orientation, distance, received, age));

expire();
}
}

public void Add(uint id, double angle, double size, double distance, DateTime received, double age = 1)
{
var existing = _dists.Where((a) => { return a.SensorId == id && a.Angle == angle; });

foreach (var item in existing.ToList())
lock (this)
{
_dists.Remove(item);
}
var existing = _dists.Where((a) => { return a.SensorId == id && a.Angle == angle; });

_dists.Add(new data(id, angle, size, distance, received, age));
foreach (var item in existing.ToList())
{
_dists.Remove(item);
}

expire();
_dists.Add(new data(id, angle, size, distance, received, age));

expire();
}
}

/// <summary>
Expand Down Expand Up @@ -230,7 +235,7 @@ void expire()
{
for (int a = 0; a < _dists.Count; a++)
{
var expireat = _dists[a].ExpireTime;
var expireat = _dists[a]?.ExpireTime;

if (expireat < DateTime.Now)
{
Expand Down
Loading