Skip to content

Commit 8e21277

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 5c7185b commit 8e21277

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
@@ -179,6 +179,8 @@ public bool prearmstatus
179179
get => connected && (sensors_health.prearm || !sensors_enabled.prearm);
180180
}
181181

182+
private DateTime last_good_prearm = DateTime.MaxValue;
183+
182184
private bool useLocation;
183185

184186
/// <summary>
@@ -1228,10 +1230,10 @@ public string messageHigh
12281230
if (value == null || value == "")
12291231
return;
12301232
// check against get
1233+
_messageHighTime = DateTime.Now;
12311234
if (messageHigh == value)
12321235
return;
12331236
log.Info("messageHigh " + value);
1234-
_messageHighTime = DateTime.Now;
12351237
_messagehigh = value;
12361238
messageHighSeverity = MAVLink.MAV_SEVERITY.EMERGENCY;
12371239
}
@@ -2874,12 +2876,7 @@ private void Parent_OnPacketReceived(object sender, MAVLink.MAVLinkMessage mavLi
28742876
messageHigh = "InternalError 0x" + (errors_count1 + (errors_count2 << 16)).ToString("X");
28752877
}
28762878

2877-
if (!sensors_health.prearm && sensors_enabled.prearm && sensors_present.prearm)
2878-
{
2879-
messageHigh = messages.LastOrDefault(a => a.message.ToLower().Contains("prearm")).message
2880-
?.ToString();
2881-
}
2882-
else if (!sensors_health.gps && sensors_enabled.gps && sensors_present.gps)
2879+
if (!sensors_health.gps && sensors_enabled.gps && sensors_present.gps)
28832880
{
28842881
messageHigh = Strings.BadGPSHealth;
28852882
}
@@ -2955,6 +2952,16 @@ private void Parent_OnPacketReceived(object sender, MAVLink.MAVLinkMessage mavLi
29552952
{
29562953
messageHigh = Strings.BadAirspeed;
29572954
}
2955+
else if (!sensors_health.prearm && sensors_enabled.prearm && sensors_present.prearm)
2956+
{
2957+
messageHigh = messages.LastOrDefault(a =>
2958+
a.message.ToLower().Contains("prearm") &&
2959+
a.time > last_good_prearm).message?.ToString();
2960+
}
2961+
if (last_good_prearm > DateTime.Now || sensors_health.prearm || !sensors_enabled.prearm || !sensors_present.prearm)
2962+
{
2963+
last_good_prearm = DateTime.Now;
2964+
}
29582965
}
29592966

29602967
break;

0 commit comments

Comments
 (0)