Skip to content

Commit 5d61601

Browse files
committed
HUD/PrearmStatus: fix failure messages
When prearm checks are failing, the HUD displays the last failure message, even if that message is very stale. This changes it so it displays the latest failure message since the last time it passed the prearm check. The prearm failure messages were also moved to the lowest priority, so that they would not mask other sensor failures. The PrearmStatus window had a similar problem, where it would show all failure messages briefly when it first launched, instead of the latest relevant ones. Also, a drive-by fix of where the messageHigh setter function sets the _messageHighTime variable, which was causing flickers.
1 parent 5a6d4f9 commit 5d61601

File tree

2 files changed

+16
-9
lines changed

2 files changed

+16
-9
lines changed

Controls/PrearmStatus.cs

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -16,8 +16,8 @@ public partial class PrearmStatus : Form
1616
{
1717
private static readonly ILog log = LogManager.GetLogger(MethodBase.GetCurrentMethod().DeclaringType);
1818

19-
private DateTime lastRequestTime = DateTime.MinValue;
20-
private DateTime searchTime = DateTime.MinValue;
19+
private DateTime lastRequestTime = DateTime.MaxValue;
20+
private DateTime searchTime = DateTime.MaxValue;
2121
public PrearmStatus()
2222
{
2323
InitializeComponent();

ExtLibs/ArduPilot/CurrentState.cs

Lines changed: 14 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -174,6 +174,8 @@ public bool prearmstatus
174174
get => connected && (sensors_health.prearm || !sensors_enabled.prearm);
175175
}
176176

177+
private DateTime last_good_prearm = DateTime.MaxValue;
178+
177179
private bool useLocation;
178180

179181
/// <summary>
@@ -1098,10 +1100,10 @@ public string messageHigh
10981100
if (value == null || value == "")
10991101
return;
11001102
// check against get
1103+
_messageHighTime = DateTime.Now;
11011104
if (messageHigh == value)
11021105
return;
11031106
log.Info("messageHigh " + value);
1104-
_messageHighTime = DateTime.Now;
11051107
_messagehigh = value;
11061108
messageHighSeverity = MAVLink.MAV_SEVERITY.EMERGENCY;
11071109
}
@@ -2680,12 +2682,7 @@ private void Parent_OnPacketReceived(object sender, MAVLink.MAVLinkMessage mavLi
26802682
messageHigh = "InternalError 0x" + (errors_count1 + (errors_count2 << 16)).ToString("X");
26812683
}
26822684

2683-
if (!sensors_health.prearm && sensors_enabled.prearm && sensors_present.prearm)
2684-
{
2685-
messageHigh = messages.LastOrDefault(a => a.message.ToLower().Contains("prearm")).message
2686-
?.ToString();
2687-
}
2688-
else if (!sensors_health.gps && sensors_enabled.gps && sensors_present.gps)
2685+
if (!sensors_health.gps && sensors_enabled.gps && sensors_present.gps)
26892686
{
26902687
messageHigh = Strings.BadGPSHealth;
26912688
}
@@ -2761,6 +2758,16 @@ private void Parent_OnPacketReceived(object sender, MAVLink.MAVLinkMessage mavLi
27612758
{
27622759
messageHigh = Strings.BadAirspeed;
27632760
}
2761+
else if (!sensors_health.prearm && sensors_enabled.prearm && sensors_present.prearm)
2762+
{
2763+
messageHigh = messages.LastOrDefault(a =>
2764+
a.message.ToLower().Contains("prearm") &&
2765+
a.time > last_good_prearm).message?.ToString();
2766+
}
2767+
if (last_good_prearm > DateTime.Now || sensors_health.prearm || !sensors_enabled.prearm || !sensors_present.prearm)
2768+
{
2769+
last_good_prearm = DateTime.Now;
2770+
}
27642771
}
27652772

27662773
break;

0 commit comments

Comments
 (0)