Skip to content

Commit

Permalink
MainV2: convert Now to UtcNow
Browse files Browse the repository at this point in the history
MAVLinkInterface: convert Now to UtcNow
  • Loading branch information
meee1 committed Jul 11, 2024
1 parent c91c197 commit 779648a
Show file tree
Hide file tree
Showing 4 changed files with 42 additions and 36 deletions.
2 changes: 1 addition & 1 deletion ExtLibs/ArduPilot/CurrentState.cs
Original file line number Diff line number Diff line change
Expand Up @@ -4340,7 +4340,7 @@ public void UpdateCurrentSettings(Action<CurrentState> bs, bool updatenow,
//check if valid mavinterface
if (parent != null && parent.packetsnotlost != 0)
{
if ((DateTime.Now - MAV.lastvalidpacket).TotalSeconds > 10)
if ((DateTime.UtcNow - MAV.lastvalidpacket).TotalSeconds > 10)
linkqualitygcs = 0;
else
linkqualitygcs =
Expand Down
8 changes: 4 additions & 4 deletions ExtLibs/ArduPilot/Mavlink/MAVLinkInterface.cs
Original file line number Diff line number Diff line change
Expand Up @@ -1640,7 +1640,7 @@ public async Task<bool> setParamAsync(byte sysid, byte compid, string paramname,

log.Info("setParam gotback " + st + " : " + MAVlist[sysid, compid].param[st]);

lastparamset = DateTime.Now;
lastparamset = DateTime.UtcNow;

// check if enabeling this param has added subparams, queue on gui thread
if (currentparamcount < par.param_count)
Expand Down Expand Up @@ -5024,7 +5024,7 @@ public async Task<MAVLinkMessage> readPacketAsync()
}
else if (logreadmode && MAVlist[sysid, compid].packetlosttimer.AddSeconds(5) < lastlogread)
{
MAVlist[sysid, compid].packetlosttimer = lastlogread;
MAVlist[sysid, compid].packetlosttimer = lastlogread.ToUniversalTime();
MAVlist[sysid, compid].packetslost = (MAVlist[sysid, compid].packetslost * 0.8f);
MAVlist[sysid, compid].packetsnotlost = (MAVlist[sysid, compid].packetsnotlost * 0.8f);
}
Expand Down Expand Up @@ -5340,7 +5340,7 @@ public async Task<MAVLinkMessage> readPacketAsync()
if (Settings.Instance["autoParamCommit"] == null ||
Settings.Instance.GetBoolean("autoParamCommit") == true)
{
if (lastparamset != DateTime.MinValue && lastparamset.AddSeconds(10) < DateTime.Now)
if (lastparamset != DateTime.MinValue && lastparamset.AddSeconds(10) < DateTime.UtcNow)
{
lastparamset = DateTime.MinValue;

Expand All @@ -5362,7 +5362,7 @@ public async Task<MAVLinkMessage> readPacketAsync()
}

// update last valid packet receive time
MAVlist[sysid, compid].lastvalidpacket = DateTime.Now;
MAVlist[sysid, compid].lastvalidpacket = DateTime.UtcNow;

return message;
}
Expand Down
2 changes: 1 addition & 1 deletion ExtLibs/ArduPilot/Mavlink/MAVState.cs
Original file line number Diff line number Diff line change
Expand Up @@ -265,7 +265,7 @@ public void Dispose()
}

/// <summary>
/// time seen of last mavlink packet
/// time seen of last mavlink packet UTC
/// </summary>
public DateTime lastvalidpacket { get; set; }

Expand Down
66 changes: 36 additions & 30 deletions MainV2.cs
Original file line number Diff line number Diff line change
Expand Up @@ -461,6 +461,9 @@ public static bool speechEnable
public static bool speech_armed_only = false;
public static bool speechEnabled()
{
if (speechEngine == null)
return false;

if (!speechEnable) {
return false;
}
Expand Down Expand Up @@ -519,7 +522,7 @@ public static bool sitl
/// <summary>
/// track the last heartbeat sent
/// </summary>
private DateTime heatbeatSend = DateTime.Now;
private DateTime heatbeatSend = DateTime.UtcNow;

/// <summary>
/// used to call anything as needed.
Expand All @@ -531,15 +534,18 @@ public static bool sitl
public static MainSwitcher View;

/// <summary>
/// store the time we first connect
/// store the time we first connect UTC
/// </summary>
DateTime connecttime = DateTime.Now;

DateTime nodatawarning = DateTime.Now;
DateTime OpenTime = DateTime.Now;

DateTime connecttime = DateTime.UtcNow;
/// <summary>
/// no data repeat interval UTC
/// </summary>
DateTime nodatawarning = DateTime.UtcNow;

DateTime connectButtonUpdate = DateTime.Now;
/// <summary>
/// update the connect button UTC
/// </summary>
DateTime connectButtonUpdate = DateTime.UtcNow;

/// <summary>
/// declared here if i want a "single" instance of the form
Expand Down Expand Up @@ -1590,7 +1596,7 @@ public void doConnect(MAVLinkInterface comPort, string portname, string baud, bo
} // soft fail

// reset connect time - for timeout functions
connecttime = DateTime.Now;
connecttime = DateTime.UtcNow;

// do the connect
comPort.Open(false, skipconnectcheck, showui);
Expand Down Expand Up @@ -2533,7 +2539,7 @@ private async void joysticksend()
/// </summary>
private void UpdateConnectIcon()
{
if ((DateTime.Now - connectButtonUpdate).Milliseconds > 500)
if ((DateTime.UtcNow - connectButtonUpdate).Milliseconds > 500)
{
// Console.WriteLine(DateTime.Now.Millisecond);
if (comPort.BaseStream.IsOpen)
Expand Down Expand Up @@ -2572,7 +2578,7 @@ private void UpdateConnectIcon()
}
}

connectButtonUpdate = DateTime.Now;
connectButtonUpdate = DateTime.UtcNow;
}
}

Expand Down Expand Up @@ -2721,7 +2727,7 @@ private async void SerialReader()
}

// 30 seconds interval speech options
if (speechEnabled() && speechEngine != null && (DateTime.Now - speechcustomtime).TotalSeconds > 30 &&
if (speechEnabled() && (DateTime.UtcNow - speechcustomtime).TotalSeconds > 30 &&
(MainV2.comPort.logreadmode || comPort.BaseStream.IsOpen))
{
if (MainV2.speechEngine.IsReady)
Expand All @@ -2732,7 +2738,7 @@ private async void SerialReader()
"" + Settings.Instance["speechcustom"]));
}

speechcustomtime = DateTime.Now;
speechcustomtime = DateTime.UtcNow;
}

// speech for battery alerts
Expand Down Expand Up @@ -2765,7 +2771,7 @@ private async void SerialReader()
}

// speech for airspeed alerts
if (speechEnabled() && speechEngine != null && (DateTime.Now - speechlowspeedtime).TotalSeconds > 10 &&
if (speechEnabled() && (DateTime.UtcNow - speechlowspeedtime).TotalSeconds > 10 &&
(MainV2.comPort.logreadmode || comPort.BaseStream.IsOpen))
{
if (Settings.Instance.GetBoolean("speechlowspeedenabled") == true &&
Expand All @@ -2781,7 +2787,7 @@ private async void SerialReader()
MainV2.speechEngine.SpeakAsync(
ArduPilot.Common.speechConversion(comPort.MAV,
"" + Settings.Instance["speechlowairspeed"]));
speechlowspeedtime = DateTime.Now;
speechlowspeedtime = DateTime.UtcNow;
}
}
else if (MainV2.comPort.MAV.cs.groundspeed < warngroundspeed)
Expand All @@ -2791,18 +2797,18 @@ private async void SerialReader()
MainV2.speechEngine.SpeakAsync(
ArduPilot.Common.speechConversion(comPort.MAV,
"" + Settings.Instance["speechlowgroundspeed"]));
speechlowspeedtime = DateTime.Now;
speechlowspeedtime = DateTime.UtcNow;
}
}
else
{
speechlowspeedtime = DateTime.Now;
speechlowspeedtime = DateTime.UtcNow;
}
}
}

// speech altitude warning - message high warning
if (speechEnabled() && speechEngine != null &&
if (speechEnabled() &&
(MainV2.comPort.logreadmode || comPort.BaseStream.IsOpen))
{
float warnalt = float.MaxValue;
Expand Down Expand Up @@ -2860,13 +2866,13 @@ private async void SerialReader()
}

// attenuate the link qualty over time
if ((DateTime.Now - MainV2.comPort.MAV.lastvalidpacket).TotalSeconds >= 1)
if ((DateTime.UtcNow - MainV2.comPort.MAV.lastvalidpacket).TotalSeconds >= 1)
{
if (linkqualitytime.Second != DateTime.Now.Second)
if (linkqualitytime.Second != DateTime.UtcNow.Second)
{
MainV2.comPort.MAV.cs.linkqualitygcs =
(ushort) (MainV2.comPort.MAV.cs.linkqualitygcs * 0.8f);
linkqualitytime = DateTime.Now;
linkqualitytime = DateTime.UtcNow;

// force redraw if there are no other packets are being read
this.BeginInvokeIfRequired(
Expand All @@ -2876,20 +2882,20 @@ private async void SerialReader()
}

// data loss warning - wait min of 3 seconds, ignore first 30 seconds of connect, repeat at 5 seconds interval
if ((DateTime.Now - MainV2.comPort.MAV.lastvalidpacket).TotalSeconds > 3
&& (DateTime.Now - connecttime).TotalSeconds > 30
&& (DateTime.Now - nodatawarning).TotalSeconds > 5
if ((DateTime.UtcNow - MainV2.comPort.MAV.lastvalidpacket).TotalSeconds > 3
&& (DateTime.UtcNow - connecttime).TotalSeconds > 30
&& (DateTime.UtcNow - nodatawarning).TotalSeconds > 5
&& (MainV2.comPort.logreadmode || comPort.BaseStream.IsOpen)
&& MainV2.comPort.MAV.cs.armed)
{
var msg = "WARNING No Data for " + (int)(DateTime.Now - MainV2.comPort.MAV.lastvalidpacket).TotalSeconds + " Seconds";
var msg = "WARNING No Data for " + (int)(DateTime.UtcNow - MainV2.comPort.MAV.lastvalidpacket).TotalSeconds + " Seconds";
MainV2.comPort.MAV.cs.messageHigh = msg;
if (speechEnabled() && speechEngine != null)
if (speechEnabled())
{
if (MainV2.speechEngine.IsReady)
{
MainV2.speechEngine.SpeakAsync(msg);
nodatawarning = DateTime.Now;
nodatawarning = DateTime.UtcNow;
}
}
}
Expand Down Expand Up @@ -2969,7 +2975,7 @@ private async void SerialReader()
}

// send a hb every seconds from gcs to ap
if (heatbeatSend.Second != DateTime.Now.Second)
if (heatbeatSend.Second != DateTime.UtcNow.Second)
{
MAVLink.mavlink_heartbeat_t htb = new MAVLink.mavlink_heartbeat_t()
{
Expand All @@ -2990,7 +2996,7 @@ private async void SerialReader()
try
{
// poll only when not armed
if (!port.MAV.cs.armed && DateTime.Now > connecttime.AddSeconds(60))
if (!port.MAV.cs.armed && DateTime.UtcNow > connecttime.AddSeconds(60))
{
port.getParamPoll();
port.getParamPoll();
Expand Down Expand Up @@ -3076,7 +3082,7 @@ private async void SerialReader()
}
}

heatbeatSend = DateTime.Now;
heatbeatSend = DateTime.UtcNow;
}

// if not connected or busy, sleep and loop
Expand Down

0 comments on commit 779648a

Please sign in to comment.