Skip to content

Commit

Permalink
MainV2: async readPacket
Browse files Browse the repository at this point in the history
  • Loading branch information
meee1 committed May 4, 2020
1 parent 8fda52f commit 8fe3001
Show file tree
Hide file tree
Showing 15 changed files with 93 additions and 78 deletions.
8 changes: 5 additions & 3 deletions Controls/MAVLinkInspector.cs
Original file line number Diff line number Diff line change
@@ -1,8 +1,10 @@
using MissionPlanner.Utilities;
using Microsoft.Scripting.Utils;
using MissionPlanner.Utilities;
using System;
using System.ComponentModel;
using System.Drawing;
using System.Linq;
using System.Text;
using System.Windows.Forms;
using ZedGraph;

Expand Down Expand Up @@ -143,11 +145,11 @@ private void MavOnOnPacketReceived(object o, MAVLink.MAVLinkMessage linkMessage)

if (field.Name == "param_id") // param_value
{
value = new String((char[])value2);
value = Encoding.ASCII.GetString((byte[])value2);
}
else if (field.Name == "text") // statustext
{
value = new String((char[])value);
value = Encoding.ASCII.GetString((byte[])value2);
}
else
{
Expand Down
15 changes: 8 additions & 7 deletions Controls/OSDVideo.cs
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,7 @@
using System.IO;
using System.Runtime.InteropServices;
using System.Threading;
using System.Threading.Tasks;
using System.Windows.Forms;

namespace MissionPlanner
Expand Down Expand Up @@ -128,9 +129,9 @@ private void loadconfig()
}
}

private void startup()
private async Task startup()
{
dolog();
await dolog().ConfigureAwait(true);

if (DSplugin)
{
Expand Down Expand Up @@ -271,7 +272,7 @@ private void StartCapture()
}
}

void dolog()
async Task dolog()
{
flightdata.Clear();

Expand All @@ -290,7 +291,7 @@ void dolog()
mine.logreadmode = true;
mine.speechenabled = false;

mine.readPacket();
await mine.readPacketAsync().ConfigureAwait(true);

startlogtime = mine.lastlogread;

Expand All @@ -300,7 +301,7 @@ void dolog()

while (mine.logplaybackfile.BaseStream.Position < mine.logplaybackfile.BaseStream.Length)
{
MAVLink.MAVLinkMessage packet = mine.readPacket();
MAVLink.MAVLinkMessage packet = await mine.readPacketAsync().ConfigureAwait(true);

cs.datetime = mine.lastlogread;

Expand Down Expand Up @@ -618,7 +619,7 @@ private String GetCurrentFilePath(Control ctl)
return ctl.Text.Substring(0, ctl.Text.LastIndexOf("\\") + 1);
}

private void BUT_start_Click(object sender, EventArgs e)
private async void BUT_start_Click(object sender, EventArgs e)
{
saveconfig();
try
Expand Down Expand Up @@ -655,7 +656,7 @@ private void BUT_start_Click(object sender, EventArgs e)

//newManager.Close();

startup();
await startup().ConfigureAwait(true);

this.MaximumSize = this.Size;
this.MinimumSize = this.Size;
Expand Down
9 changes: 8 additions & 1 deletion ExtLibs/Utilities/DFLogBuffer.cs
Original file line number Diff line number Diff line change
Expand Up @@ -172,6 +172,9 @@ void setlinecount()
{
try
{
if(item.items == null || item.items.Length == 0)
continue;

FMT[int.Parse(item["Type"])] = (
int.Parse(item["Length"].Trim()),
item["Name"].Trim(),
Expand All @@ -188,6 +191,9 @@ void setlinecount()
{
try
{
if (item.items == null || item.items.Length == 0)
continue;

FMTU[int.Parse(item["FmtType"])] =
new Tuple<string, string>(item["UnitIds"].Trim(), item["MultIds"].Trim());

Expand Down Expand Up @@ -243,7 +249,8 @@ void setlinecount()
}))
{
// must be the string version to do the firmware type detection - binarylog
Console.WriteLine(this[(int) item.lineno]);
var line = this[(int) item.lineno];
//Console.WriteLine();
}

// try get gps time - when a dfitem is created and no valid gpstime has been establish the messages are parsed to get a valid gpstime
Expand Down
4 changes: 2 additions & 2 deletions ExtLibs/Xamarin/Xamarin/GCSViews/FlightData.xaml.cs
Original file line number Diff line number Diff line change
Expand Up @@ -695,7 +695,7 @@ private void gMapControl1_OnPositionChanged(PointLatLng point)
bool playingLog;
List<PointLatLng> trackPoints = new List<PointLatLng>();

private void mainloop()
private async void mainloop()
{
if (threadrun == true)
return;
Expand Down Expand Up @@ -774,7 +774,7 @@ private void mainloop()
try
{
if (!MainV2.comPort.giveComport)
MainV2.comPort.readPacket();
await MainV2.comPort.readPacketAsync().ConfigureAwait(false);

// update currentstate of sysids on the port
foreach (var MAV in MainV2.comPort.MAVlist)
Expand Down
5 changes: 3 additions & 2 deletions ExtLibs/Xamarin/Xamarin/Linked/MainV2.cs
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,7 @@
using System.Collections.Generic;
using System.Linq;
using System.Threading;
using System.Threading.Tasks;
using log4net;
using MissionPlanner.Comms;

Expand Down Expand Up @@ -74,7 +75,7 @@ public static ISpeech speechEngine
///
/// and can't fall out
/// </summary>
internal void SerialReader()
internal async Task SerialReader()
{
if (serialThread == true)
return;
Expand Down Expand Up @@ -461,7 +462,7 @@ internal void SerialReader()
{
try
{
port.readPacket();
await port.readPacketAsync().ConfigureAwait(false);
}
catch (Exception ex)
{
Expand Down
2 changes: 1 addition & 1 deletion ExtLibs/wasm/Pages/Tlog.razor
Original file line number Diff line number Diff line change
Expand Up @@ -285,7 +285,7 @@
{
var param = (MAVLink.mavlink_param_value_t) packet.data;

Console.WriteLine("{0} {1}", new String(param.param_id), param.param_value);
Console.WriteLine("{0} {1}", Encoding.ASCII.GetString(param.param_id), param.param_value);
}

return true;
Expand Down
10 changes: 5 additions & 5 deletions ExtLibs/wasm/Pages/Websocket.razor
Original file line number Diff line number Diff line change
Expand Up @@ -501,17 +501,17 @@
var txt = (MAVLink.mavlink_statustext_t) packet.data;
if (txt.severity >= (byte) MAVLink.MAV_SEVERITY.NOTICE)
{
Toaster.Info(new String(txt.text).TrimUnPrintable());
Toaster.Info(Encoding.ASCII.GetString(txt.text).TrimUnPrintable());
}
else if (txt.severity >= (byte) MAVLink.MAV_SEVERITY.WARNING)
{
Toaster.Warning(new String(txt.text).TrimUnPrintable());
SpeechSynthesis.Speak(new String(txt.text).TrimUnPrintable());
Toaster.Warning(Encoding.ASCII.GetString(txt.text).TrimUnPrintable());
SpeechSynthesis.Speak(Encoding.ASCII.GetString(txt.text).TrimUnPrintable());
}
else if (txt.severity >= (byte) MAVLink.MAV_SEVERITY.EMERGENCY)
{
Toaster.Error(new String(txt.text).TrimUnPrintable());
SpeechSynthesis.Speak(new String(txt.text).TrimUnPrintable());
Toaster.Error(Encoding.ASCII.GetString(txt.text).TrimUnPrintable());
SpeechSynthesis.Speak(Encoding.ASCII.GetString(txt.text).TrimUnPrintable());
}
}

Expand Down
4 changes: 2 additions & 2 deletions GCSViews/ConfigurationView/ConfigHWCompass.cs
Original file line number Diff line number Diff line change
Expand Up @@ -359,7 +359,7 @@ private void CHK_enablecompass_CheckedChanged(object sender, EventArgs e)
}
}

private void BUT_MagCalibrationLog_Click(object sender, EventArgs e)
private async void BUT_MagCalibrationLog_Click(object sender, EventArgs e)
{
var minthro = "30";
if (DialogResult.Cancel ==
Expand All @@ -369,7 +369,7 @@ private void BUT_MagCalibrationLog_Click(object sender, EventArgs e)
var ans = 0;
int.TryParse(minthro, out ans);

MagCalib.ProcessLog(ans);
await MagCalib.ProcessLog(ans).ConfigureAwait(true);
}

private void CHK_autodec_CheckedChanged(object sender, EventArgs e)
Expand Down
13 changes: 7 additions & 6 deletions GCSViews/ConfigurationView/ConfigTerminal.cs
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,7 @@
using System.Reflection;
using System.Text;
using System.Threading;
using System.Threading.Tasks;
using System.Windows.Forms;
using SerialPort = MissionPlanner.Comms.SerialPort;

Expand Down Expand Up @@ -345,7 +346,7 @@ private void setcomport()
}
}

private void start_Terminal(bool px4)
private async Task start_Terminal(bool px4)
{
setcomport();

Expand Down Expand Up @@ -390,7 +391,7 @@ private void start_Terminal(bool px4)
mine.BaseStream.Open();

// check if we are a mavlink stream
var buffer = mine.readPacket();
var buffer = await mine.readPacketAsync().ConfigureAwait(true);

if (buffer.Length > 0)
{
Expand Down Expand Up @@ -700,7 +701,7 @@ private void BUT_logbrowse_Click(object sender, EventArgs e)
logbrowse.Show();
}

private void BUT_RebootAPM_Click(object sender, EventArgs e)
private async void BUT_RebootAPM_Click(object sender, EventArgs e)
{
if (comPort.IsOpen)
{
Expand All @@ -720,11 +721,11 @@ private void BUT_RebootAPM_Click(object sender, EventArgs e)
}

if (CMB_boardtype.Text.Contains("APM"))
start_Terminal(false);
await start_Terminal(false).ConfigureAwait(true);
if (CMB_boardtype.Text.Contains("PX4"))
start_Terminal(true);
await start_Terminal(true).ConfigureAwait(true);
if (CMB_boardtype.Text.Contains("VRX"))
start_Terminal(true);
await start_Terminal(true).ConfigureAwait(true);
if (CMB_boardtype.Text.Contains("SSH"))
{
term = new SSHTerminal(TXT_terminal);
Expand Down
4 changes: 2 additions & 2 deletions GCSViews/FlightData.cs
Original file line number Diff line number Diff line change
Expand Up @@ -2716,7 +2716,7 @@ private void loadFileToolStripMenuItem_Click(object sender, EventArgs e)
POI.POILoad();
}

private void mainloop()
private async void mainloop()
{
threadrun = true;
EndPoint Remote = new IPEndPoint(IPAddress.Any, 0);
Expand Down Expand Up @@ -2820,7 +2820,7 @@ private void mainloop()
try
{
if (!MainV2.comPort.giveComport)
MainV2.comPort.readPacket();
await MainV2.comPort.readPacketAsync().ConfigureAwait(false);

// update currentstate of sysids on the port
foreach (var MAV in MainV2.comPort.MAVlist)
Expand Down
15 changes: 8 additions & 7 deletions Log/LogIndex.cs
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,7 @@ void createFileList(object directory)

private void queueRunner(object nothing)
{
Parallel.ForEach(files, file => { ProcessFile(file); });
Parallel.ForEach(files, async (file) => { await ProcessFile(file).ConfigureAwait(false); });

Loading.ShowLoading("Populating Data", this);

Expand All @@ -65,15 +65,15 @@ private void queueRunner(object nothing)
Loading.Close();
}

private void ProcessFile(string file)
private async Task ProcessFile(string file)
{
if (File.Exists(file))
processbg(file);
await processbg(file).ConfigureAwait(false);
}

List<object> logs = new List<object>();
int a = 0;
void processbg(string file)
async Task processbg(string file)
{
a++;
Loading.ShowLoading(a + "/" + files.Count + " " + file, this);
Expand Down Expand Up @@ -109,7 +109,8 @@ void processbg(string file)
try
{
mine.logplaybackfile =
new BinaryReader(File.Open(file, FileMode.Open, FileAccess.Read, FileShare.Read));
new BinaryReader(new BufferedStream(
File.Open(file, FileMode.Open, FileAccess.Read, FileShare.Read), 1024 * 1024 * 5));
}
catch (Exception ex)
{
Expand Down Expand Up @@ -150,7 +151,7 @@ void processbg(string file)
// abandon last 100 bytes
while (mine.logplaybackfile.BaseStream.Position < (length - 100))
{
var packet = mine.readPacket();
var packet = await mine.readPacketAsync().ConfigureAwait(false);

// gcs
if (packet.sysid == 255)
Expand Down Expand Up @@ -179,7 +180,7 @@ void processbg(string file)
}
else if (file.ToLower().EndsWith(".bin") || file.ToLower().EndsWith(".log"))
{
using (DFLogBuffer colbuf = new DFLogBuffer(File.OpenRead(file)))
using (DFLogBuffer colbuf = new DFLogBuffer(new BufferedStream(File.OpenRead(file), 1024 * 1024 * 5)))
{
PointLatLngAlt lastpos = null;
DateTime start = DateTime.MinValue;
Expand Down
Loading

0 comments on commit 8fe3001

Please sign in to comment.