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

HUD/PrearmStatus: fix failure messages #3250

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.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
4 changes: 2 additions & 2 deletions Controls/PrearmStatus.cs
Original file line number Diff line number Diff line change
Expand Up @@ -16,8 +16,8 @@ public partial class PrearmStatus : Form
{
private static readonly ILog log = LogManager.GetLogger(MethodBase.GetCurrentMethod().DeclaringType);

private DateTime lastRequestTime = DateTime.MinValue;
private DateTime searchTime = DateTime.MinValue;
private DateTime lastRequestTime = DateTime.MaxValue;
private DateTime searchTime = DateTime.MaxValue;
public PrearmStatus()
{
InitializeComponent();
Expand Down
21 changes: 14 additions & 7 deletions ExtLibs/ArduPilot/CurrentState.cs
Original file line number Diff line number Diff line change
Expand Up @@ -174,6 +174,8 @@ public bool prearmstatus
get => connected && (sensors_health.prearm || !sensors_enabled.prearm);
}

private DateTime last_good_prearm = DateTime.MaxValue;

private bool useLocation;

/// <summary>
Expand Down Expand Up @@ -1105,10 +1107,10 @@ public string messageHigh
if (value == null || value == "")
return;
// check against get
_messageHighTime = DateTime.Now;
if (messageHigh == value)
return;
log.Info("messageHigh " + value);
_messageHighTime = DateTime.Now;
_messagehigh = value;
messageHighSeverity = MAVLink.MAV_SEVERITY.EMERGENCY;
}
Expand Down Expand Up @@ -2687,12 +2689,7 @@ private void Parent_OnPacketReceived(object sender, MAVLink.MAVLinkMessage mavLi
messageHigh = "InternalError 0x" + (errors_count1 + (errors_count2 << 16)).ToString("X");
}

if (!sensors_health.prearm && sensors_enabled.prearm && sensors_present.prearm)
{
messageHigh = messages.LastOrDefault(a => a.message.ToLower().Contains("prearm")).message
?.ToString();
}
else if (!sensors_health.gps && sensors_enabled.gps && sensors_present.gps)
if (!sensors_health.gps && sensors_enabled.gps && sensors_present.gps)
{
messageHigh = Strings.BadGPSHealth;
}
Expand Down Expand Up @@ -2768,6 +2765,16 @@ private void Parent_OnPacketReceived(object sender, MAVLink.MAVLinkMessage mavLi
{
messageHigh = Strings.BadAirspeed;
}
else if (!sensors_health.prearm && sensors_enabled.prearm && sensors_present.prearm)
{
messageHigh = messages.LastOrDefault(a =>
a.message.ToLower().Contains("prearm") &&
a.time > last_good_prearm).message?.ToString();
}
if (last_good_prearm > DateTime.Now || sensors_health.prearm || !sensors_enabled.prearm || !sensors_present.prearm)
{
last_good_prearm = DateTime.Now;
}
}

break;
Expand Down