Skip to content

Commit

Permalink
bug fix.
Browse files Browse the repository at this point in the history
1. 修复无法读取微信传送的只读文件的bug.
2. 增加读取损坏文件的稳定性.
  • Loading branch information
cfrpg committed Mar 3, 2024
1 parent ba582c6 commit 07b723f
Show file tree
Hide file tree
Showing 4 changed files with 120 additions and 32 deletions.
8 changes: 5 additions & 3 deletions src/SharpBladeFlightAnalyzer/Controls/LogPageControl.xaml.cs
Original file line number Diff line number Diff line change
Expand Up @@ -259,7 +259,8 @@ private void exportAcmiBtn_Click(object sender, RoutedEventArgs e)
}
DataField[] posData = new DataField[3];
DataField[] attData = new DataField[3];
int id = logFile.FormatList["vehicle_global_position"].SubscribedID[0];
//int id = logFile.FormatList["vehicle_global_position"].SubscribedID[0];
int id = logFile.FormatList["vehicle_gps_position"].SubscribedID[0];
posData[0] = logFile.MessageDict[id].FieldDict["lon"];
posData[1] = logFile.MessageDict[id].FieldDict["lat"];
posData[2] = logFile.MessageDict[id].FieldDict["alt"];
Expand Down Expand Up @@ -288,7 +289,8 @@ private void exportAcmiBtn_Click(object sender, RoutedEventArgs e)
var posTimes = posData[0].Timestamps;
var attTimes = attData[0].Timestamps;
sw.WriteLine("#{0}", Math.Min(posTimes[0], attTimes[0]));
sw.WriteLine("101,T={0}|{1}|{2}", posData[0].Values[0], posData[1].Values[0], posData[2].Values[0]);
//sw.WriteLine("101,T={0}|{1}|{2}", posData[0].Values[0], posData[1].Values[0], posData[2].Values[0]);
sw.WriteLine("101,T={0}|{1}|{2}", posData[0].Values[0]/1E7, posData[1].Values[0] / 1E7, posData[2].Values[0] / 1E3);
hdg = attData[2].Values[0] * 57.29577951;
while (pospos < posTimes.Count || attpos < attTimes.Count)
{
Expand Down Expand Up @@ -317,7 +319,7 @@ private void exportAcmiBtn_Click(object sender, RoutedEventArgs e)
//Update pos
sw.WriteLine("#" + posTimes[pospos].ToString());

sw.WriteLine("101,T={0}|{1}|{2}|{3}|{4}|{5}", posData[0].Values[pospos], posData[1].Values[pospos], posData[2].Values[pospos], attFilter[0] * 57.29577951, attFilter[1] * 57.29577951, hdg);
sw.WriteLine("101,T={0}|{1}|{2}|{3}|{4}|{5}", posData[0].Values[pospos] / 1E7, posData[1].Values[pospos] / 1E7, posData[2].Values[pospos] / 1E3, attFilter[0] * 57.29577951, attFilter[1] * 57.29577951, hdg);
pospos++;
}
else
Expand Down
4 changes: 4 additions & 0 deletions src/SharpBladeFlightAnalyzer/LoadViewModel.cs
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,8 @@ public class LoadViewModel : INotifyPropertyChanged

Visibility visibility;

bool loadFailed;


public double MaxProgress
{
Expand Down Expand Up @@ -47,5 +49,7 @@ public Visibility Visibility
PropertyChanged?.Invoke(this, new PropertyChangedEventArgs("Visibility"));
}
}

public bool LoadFailed { get => loadFailed; set => loadFailed = value; }
}
}
59 changes: 35 additions & 24 deletions src/SharpBladeFlightAnalyzer/MainWindow.xaml.cs
Original file line number Diff line number Diff line change
Expand Up @@ -216,30 +216,28 @@ private void Window_Drop(object sender, DragEventArgs e)
return;
if(e.Data.GetDataPresent(DataFormats.FileDrop))
{
string[] files = (string[])e.Data.GetData(DataFormats.FileDrop);

startLoadFile(files[0]);

string[] files = (string[])e.Data.GetData(DataFormats.FileDrop);
startLoadFile(files[0]);
}
}

private void loadFile(string path)
{
ULogFile f = new ULogFile();
if (f.Load(path, fieldConfigs))
{
LogPageControl lpc = new LogPageControl(f, this);
lpc.addFieldBtn.Click += AddFieldBtn_Click;
TabPage page = new TabPage();
page.Header = f.File.Name;
//private void loadFile(string path)
//{
// ULogFile f = new ULogFile();
// if (f.Load(path, fieldConfigs))
// {
// LogPageControl lpc = new LogPageControl(f, this);
// lpc.addFieldBtn.Click += AddFieldBtn_Click;
// TabPage page = new TabPage();
// page.Header = f.File.Name;

page.Content = lpc;
page.DisposableContent = f;
mainTabControl.Items.Insert(mainTabControl.Items.Count - 1, page);
mainTabControl.SelectedIndex = mainTabControl.Items.Count - 2;
currentPage = lpc;
}
}
// page.Content = lpc;
// page.DisposableContent = f;
// mainTabControl.Items.Insert(mainTabControl.Items.Count - 1, page);
// mainTabControl.SelectedIndex = mainTabControl.Items.Count - 2;
// currentPage = lpc;
// }
//}

private void startLoadFile(string path)
{
Expand All @@ -249,20 +247,31 @@ private void startLoadFile(string path)
Thread uiThread = new Thread(new ParameterizedThreadStart(updateUI));
uiThread.IsBackground = true;
uiThread.Start(path);

}

private void updateUI(object o)
{
string path = (string)o;
lvm.LoadFailed = false;
Thread loadThread= new Thread(new ParameterizedThreadStart(loadingFile));
loadThread.IsBackground = true;
lvm.CurrProgress = 0;
lvm.Visibility = Visibility.Visible;
lvm.CurrProgress = 0;
ULogFile f = new ULogFile();
loadThread.Start(new Tuple<ULogFile, string>(f, path));
Thread.Sleep(20);
while(f.TotalSize<0)
{
Thread.Sleep(20);
if(lvm.LoadFailed)
{
Dispatcher.Invoke(() => ShowMessageBox("无法打开文件"));

isloading = false;
return;
}
}

lvm.MaxProgress = f.TotalSize;
lvm.Visibility = Visibility.Visible;
while (true)
{
lvm.CurrProgress = f.CurrPos;
Expand Down Expand Up @@ -292,6 +301,8 @@ private void loadingFile(object o)
Tuple<ULogFile, string> args = (Tuple<ULogFile, string>)o;
ULogFile f = args.Item1;
bool res = f.Load(args.Item2, fieldConfigs);
if (res == false)
lvm.LoadFailed = true;
}

private void Window_Loaded(object sender, RoutedEventArgs e)
Expand Down
81 changes: 76 additions & 5 deletions src/SharpBladeFlightAnalyzer/ULogFile.cs
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,7 @@ public class ULogFile :IDisposable
{
private static Dictionary<string, int> typeSize;
public static DateTime UnixStartTime = new DateTime(1970, 1, 1, 0, 0, 0, 0);
const string AllMsgTypes = "BFIMPQARDLCSO";

UInt64 timestamp;
byte version;
Expand Down Expand Up @@ -103,7 +104,7 @@ public FileInfo File
public List<MessageViewModel> MessageList { get => messageList; set => messageList = value; }
public Dictionary<string, MessageFormat> FormatList { get => formatList; set => formatList = value; }
public Dictionary<int, Message> MessageDict { get => messageDict; set => messageDict = value; }
public long TotalSize { get => reader.BaseStream.Length; }
public long TotalSize { get => reader == null ? -1 : reader.BaseStream.Length; }

public long CurrPos { get => currLoadPos; }
public bool ReadCompleted { get => readCompleted; set => readCompleted = value; }
Expand All @@ -122,8 +123,16 @@ public ULogFile()

public bool Load(string path, Dictionary<string, FieldConfig> fieldConfigs)
{
file = new FileInfo(path);
reader = new BinaryReader(new FileStream(path, FileMode.Open));
file = new FileInfo(path);
try
{
reader = new BinaryReader(new FileStream(path,FileMode.Open,FileAccess.Read));
}
catch
{
return false;
}

byte[] buff = reader.ReadBytes(8);
if (buff[0] != 0x55)
return false;
Expand Down Expand Up @@ -224,6 +233,7 @@ private bool readMessage()
{
if (reader.BaseStream.Length - reader.BaseStream.Position < 3)
return false;
long pos = reader.BaseStream.Position;
ushort size = reader.ReadUInt16();
byte msgtype = reader.ReadByte();
if (reader.BaseStream.Length - reader.BaseStream.Position < size)
Expand Down Expand Up @@ -275,11 +285,30 @@ private bool readMessage()
case 79://O
res = readDropoutMark(size);
break;

default:
Debug.WriteLine("Unknow message type:{0},at {1}, size {2}.", msgtype, reader.BaseStream.Position,size);
if (msgtype == 0 && size==0)
{
int blanklen = 0;
while (reader.BaseStream.Position != reader.BaseStream.Length)
{
byte b = reader.ReadByte();
if (b == 0)
blanklen++;
else
break;
}
Debug.WriteLine("Suspected blank data:at {0}, len {1}.", pos, blanklen);
}
Debug.WriteLine("Unknow message type:{0},at {1}, size {2}.", msgtype, pos, size);
byte[] tmp= reader.ReadBytes(size);
res = false;
errmsg = "未知日志消息类型:" + msgtype.ToString();
Debug.WriteLine("Try to find the next package.");
if (!findNextData())
{
errmsg = "文件末端损坏";
}
break;
}

Expand All @@ -301,6 +330,48 @@ private bool readMessage()

return res;
}

private bool checkData(int thrd)
{
long posbackup = reader.BaseStream.Position;

for(int i=0;i<thrd;i++)
{
if (reader.BaseStream.Length - reader.BaseStream.Position < 3)
return false;
ushort len = reader.ReadUInt16();
char msg = Convert.ToChar(reader.ReadByte());
if (reader.BaseStream.Length - reader.BaseStream.Position < len)
return false;
if (!AllMsgTypes.Contains(msg))
return false;
byte[] tmp = reader.ReadBytes(len);
}
reader.BaseStream.Position = posbackup;
return true;
}

private bool findNextData()
{
while(!checkData(3))
{
while(true)
{
if (reader.BaseStream.Length - reader.BaseStream.Position < 3)
return false;
ushort len = reader.ReadUInt16();
char msg = Convert.ToChar(reader.ReadByte());
if (AllMsgTypes.Contains(msg))
{
reader.BaseStream.Position -= 3;
break;
}
reader.BaseStream.Position -= 2;
}
}
Debug.WriteLine("Find avalible data at {0}.", reader.BaseStream.Position);
return true;
}
private void expendDefinition()
{
bool alldone = false;
Expand Down Expand Up @@ -483,7 +554,7 @@ private bool readParameter(ushort msglen,bool def)
parameters[i].SystemDefaultValue = v;
if ((defaultType & 0x02) != 0)
parameters[i].AirframeDefaultValue = v;
}
}
}
}
return true;
Expand Down

0 comments on commit 07b723f

Please sign in to comment.