diff --git a/Plane.FormationCreator/App.xaml b/Plane.FormationCreator/App.xaml
index 736d16d..37220a8 100644
--- a/Plane.FormationCreator/App.xaml
+++ b/Plane.FormationCreator/App.xaml
@@ -41,6 +41,12 @@
+
+
diff --git a/Plane.FormationCreator/App.xaml.cs b/Plane.FormationCreator/App.xaml.cs
index 1682c13..720dc6d 100644
--- a/Plane.FormationCreator/App.xaml.cs
+++ b/Plane.FormationCreator/App.xaml.cs
@@ -120,6 +120,8 @@ namespace Plane.FormationCreator
MainWindow = new MainWindow();
MainWindow.Show();
+
+
try
{
/* by panxu tcp 不使用了 --使用TCP监听在自动获取IP的情况下,刚开始会导致界面无响应,过一会就好
diff --git a/Plane.FormationCreator/Formation/FlightTaskManager.cs b/Plane.FormationCreator/Formation/FlightTaskManager.cs
index 14c1b8b..69a19b5 100644
--- a/Plane.FormationCreator/Formation/FlightTaskManager.cs
+++ b/Plane.FormationCreator/Formation/FlightTaskManager.cs
@@ -425,13 +425,13 @@ namespace Plane.FormationCreator.Formation
foreach (string line in lines)
{
string[] parameters = line.Split(' ');
- string id = parameters[0];
+ int id = Convert.ToInt32(parameters[0])+1;
string frame = parameters[1];
string[] point = new string[3];
point[0] = parameters[2]; //左右 经度
point[1] = parameters[3]; //上下 高度
point[2] = parameters[4]; //前后 纬度
- PointDic.Add(Convert.ToInt32(id), point);
+ PointDic.Add(id, point);
}
diff --git a/Plane.FormationCreator/Formation/RtcmManager.cs b/Plane.FormationCreator/Formation/RtcmManager.cs
new file mode 100644
index 0000000..39c4f46
--- /dev/null
+++ b/Plane.FormationCreator/Formation/RtcmManager.cs
@@ -0,0 +1,432 @@
+using GalaSoft.MvvmLight;
+using Microsoft.Practices.ServiceLocation;
+using Plane.CommunicationManagement;
+using Plane.Util;
+using Plane.Windows.IniHelper;
+using Plane.Windows.Messages;
+using System;
+using System.Collections;
+using System.Collections.Generic;
+using System.Collections.ObjectModel;
+using System.Linq;
+using System.Text;
+using System.Threading;
+using System.Threading.Tasks;
+using System.Windows.Media;
+using System.Windows.Threading;
+
+namespace Plane.FormationCreator.Formation
+{
+ public class RtcmManager: ObservableObject
+ {
+ private rtcm3 rtcm = new rtcm3();
+ private Hashtable msgseen = new Hashtable();
+
+ private ICommsSerial comPort;
+ private CommModuleManager _commModuleManager = CommModuleManager.Instance;
+ public ObservableCollection rtcmInfoList { get; } = new ObservableCollection();
+
+ private bool _rtcmthreadrun = false;
+ public bool Rtcmthreadrun
+ {
+ get { return _rtcmthreadrun; }
+ set { Set(nameof(Rtcmthreadrun), ref _rtcmthreadrun, value); }
+ }
+
+ private int bps;
+ private int bpsusefull;
+
+ private int _bps = 0;
+ public int Bps
+ {
+ get { return _bps; }
+ set { Set(nameof(Bps), ref _bps, value); }
+ }
+
+ private int _bpsusefull = 0;
+ public int Bpsusefull
+ {
+ get { return _bpsusefull; }
+ set { Set(nameof(Bpsusefull), ref _bpsusefull, value); }
+ }
+
+ private string _messages_seen = "";
+ public string Messages_seen
+ {
+ get { return _messages_seen; }
+ set { Set(nameof(Messages_seen), ref _messages_seen, value); }
+ }
+
+
+ private DateTime baseTime = DateTime.Now;
+ private DateTime gpsTime = DateTime.Now;
+ private DateTime glonassTime = DateTime.Now;
+ private DateTime beidouTime = DateTime.Now;
+
+ private bool _baseState = false;
+ public bool BaseState
+ {
+ get { return _baseState; }
+ set { Set(nameof(BaseState), ref _baseState, value); }
+ }
+
+ private bool _gpsState = false;
+ public bool GpsState
+ {
+ get { return _gpsState; }
+ set { Set(nameof(GpsState), ref _gpsState, value); }
+ }
+
+ private bool _glonassState = false;
+ public bool GlonassState
+ {
+ get { return _glonassState; }
+ set { Set(nameof(GlonassState), ref _glonassState, value); }
+ }
+
+ private bool _beidouState = false;
+ public bool BeidouState
+ {
+ get { return _beidouState; }
+ set { Set(nameof(BeidouState), ref _beidouState, value); }
+ }
+
+ private double _stationLat;
+ public double StationLat
+ {
+ get { return _stationLat; }
+ set { Set(nameof(StationLat), ref _stationLat, value); }
+ }
+
+ private double _stationLng;
+ public double StationLng
+ {
+ get { return _stationLng; }
+ set { Set(nameof(StationLng), ref _stationLng, value); }
+ }
+
+ private double _stationAlt;
+ public double StationAlt
+ {
+ get { return _stationAlt; }
+ set { Set(nameof(StationAlt), ref _stationAlt, value); }
+ }
+
+ private string _stationTime;
+ public string StationTime
+ {
+ get { return _stationTime; }
+ set { Set(nameof(StationTime), ref _stationTime, value); }
+ }
+
+ private DispatcherTimer dispatcherTimer = null;
+ public RtcmManager()
+ {
+ rtcm.ObsMessage += Rtcm_ObsMessage;
+ dispatcherTimer = new DispatcherTimer();
+ dispatcherTimer.Tick += new EventHandler(OnTimedEvent);
+ dispatcherTimer.Interval = new TimeSpan(0, 0, 1);
+ dispatcherTimer.Start();
+ }
+
+ private void OnTimedEvent(object sender, EventArgs e)
+ {
+ BaseState = baseTime > DateTime.Now;
+ GpsState = gpsTime > DateTime.Now;
+ GlonassState = glonassTime > DateTime.Now;
+ BeidouState = beidouTime > DateTime.Now;
+
+ Bps = bps;
+ Bpsusefull = bpsusefull;
+ bps = 0;
+ bpsusefull = 0;
+
+ StringBuilder sb = new StringBuilder();
+ try
+ {
+ foreach (var item in msgseen.Keys)
+ {
+ sb.Append(item + "=" + msgseen[item] + " ");
+ }
+ }
+ catch
+ {}
+ Messages_seen = sb.ToString();
+ }
+
+
+
+ private void Rtcm_ObsMessage(object sender, EventArgs e)
+ {
+ List obs = sender as List;
+ if (obs.Count == 0) return;
+
+ List partRtcmInfos;
+ partRtcmInfos = rtcmInfoList.Where(o => o.Sys == obs[0].sys).ToList();
+ while (partRtcmInfos.Count() < obs.Count)
+ {
+ RtcmInfo newInfo = new RtcmInfo();
+ rtcmInfoList.Add(newInfo);
+ partRtcmInfos.Add(newInfo);
+
+ }
+
+ while (partRtcmInfos.Count() > obs.Count)
+ {
+ RtcmInfo lastInfo = partRtcmInfos[partRtcmInfos.Count - 1];
+ rtcmInfoList.Remove(lastInfo);
+ partRtcmInfos.Remove(lastInfo);
+ }
+
+ if (partRtcmInfos.Count() == obs.Count)
+ {
+ for (int i = 0; i < obs.Count; i++)
+ {
+ partRtcmInfos[i].Sys = obs[i].sys;
+ partRtcmInfos[i].Prn = obs[i].prn;
+ partRtcmInfos[i].Snr = obs[i].snr;
+ }
+ }
+
+ }
+
+ public string[] GetPortNames()
+ {
+ return SerialPort.GetPortNames();
+ }
+
+ public async Task Open(string CMB_serialport)
+ {
+ if (CMB_serialport == "") return;
+
+ switch(CMB_serialport)
+ {
+ case "千寻":
+ //检测原点
+ FlightTaskManager _flightTaskManager = ServiceLocator.Current.GetInstance();
+ if (_flightTaskManager.OriginLat == 0 && _flightTaskManager.OriginLng == 0)
+ {
+ Alert.Show("作为参照的原点未设置,无法发送RTCM!", "提示");
+ return;
+ }
+
+ //千寻账号
+ string messagetips = "格式:http://差分账号:差分密码@域名:端口/坐标系\r\n例如:http://account:password@rtk.ntrip.qxwz.com:8002/RTCM32_GGB";
+ string url = "";
+ IniFiles inifilse = new IniFiles();
+ url = inifilse.IniReadvalue("Default", "RTKurl");
+ if (PlaneMessageBox.OnShow(messagetips, "发送RTK", ref url) == false) return;
+ inifilse.IniWritevalue("Default", "RTKurl", url);
+
+ //构造
+ comPort = new CommsNTRIP(url, _flightTaskManager.OriginLat, _flightTaskManager.OriginLng);
+ break;
+ default:
+ comPort = new SerialPort();
+ comPort.PortName = CMB_serialport;
+ comPort.BaudRate = 57600;
+ break;
+ }
+ msgseen.Clear();
+ comPort.Open();
+ if (comPort.IsOpen)
+ {
+ Rtcmthreadrun = true;
+ await RtcmLoop();
+ }
+ }
+
+ public async Task Close()
+ {
+ Rtcmthreadrun = false;
+ comPort.Close();
+ await Task.Delay(1);
+ }
+
+ private async Task RtcmLoop()
+ {
+ int reconnecttimeout = 10;
+ DateTime lastrecv = DateTime.MinValue;
+ while (Rtcmthreadrun)
+ {
+ try
+ {
+ try
+ {
+ if ((DateTime.Now - lastrecv).TotalSeconds > reconnecttimeout || !comPort.IsOpen)
+ {
+ if (comPort is CommsNTRIP)
+ {
+ }
+ else
+ {
+ comPort.Close();
+ comPort.Open();
+ }
+ // reset timer
+ lastrecv = DateTime.Now;
+ }
+ }
+ catch { }
+
+ if (!comPort.IsOpen)
+ {
+ return;
+ }
+
+ //rtcm size=180
+ byte[] buffer = new byte[180];
+
+ int read = comPort.Read(buffer, 0, Math.Min(buffer.Length, comPort.BytesToRead));
+ if (read > 0)
+ lastrecv = DateTime.Now;
+
+ bps += read;
+ for (int a = 0; a < read; a++)
+ {
+ int seenmsg = -1;
+ // rtcm
+ if ((seenmsg = rtcm.Read(buffer[a])) > 0)
+ {
+ bpsusefull += rtcm.length;
+ Message.Show($"{DateTime.Now.ToString("HH-mm-ss:fff")} rtcm.length = {rtcm.length}");
+ await _commModuleManager.InjectGpsRTCMDataAsync(rtcm.packet, rtcm.length);
+
+ string msgname = "Rtcm" + seenmsg;
+
+ if (!msgseen.ContainsKey(msgname))
+ msgseen[msgname] = 0;
+ msgseen[msgname] = (int)msgseen[msgname] + 1;
+
+ await ExtractBasePos(seenmsg);
+ //await seenRTCM(seenmsg);
+ }
+ }
+ await Task.Delay(10);
+ }
+ catch(Exception ex)
+ {
+ Message.Show(ex.Message);
+ }
+ }
+ }
+
+
+ private async Task ExtractBasePos(int seen)
+ {
+ try
+ {
+ if (seen == 1005)
+ {
+ var basepos = new rtcm3.type1005();
+ basepos.Read(rtcm.packet);
+ var pos = basepos.ecefposition;
+ double[] baseposllh = new double[3];
+ rtcm3.ecef2pos(pos, ref baseposllh);
+
+
+ StationLat = baseposllh[0] * rtcm3.R2D;
+ StationLng = baseposllh[1] * rtcm3.R2D;
+ StationAlt = baseposllh[2];
+ StationTime = DateTime.Now.ToString("HH:mm:ss");
+
+ }
+ else if (seen == 1006)
+ {
+ var basepos = new rtcm3.type1006();
+ basepos.Read(rtcm.packet);
+ var pos = basepos.ecefposition;
+ double[] baseposllh = new double[3];
+ rtcm3.ecef2pos(pos, ref baseposllh);
+
+ StationLat = baseposllh[0] * rtcm3.R2D;
+ StationLng = baseposllh[1] * rtcm3.R2D;
+ StationAlt = baseposllh[2];
+ StationTime = DateTime.Now.ToString("HH:mm:ss");
+ }
+
+ switch (seen)
+ {
+ case 1001:
+ case 1002:
+ case 1003:
+ case 1004:
+ case 1071:
+ case 1072:
+ case 1073:
+ case 1074:
+ case 1075:
+ case 1076:
+ case 1077:
+ gpsTime = DateTime.Now.AddSeconds(5);
+ break;
+ case 1005:
+ case 1006:
+ case 4072: // ublox moving base
+ baseTime = DateTime.Now.AddSeconds(20);
+ break;
+ case 1009:
+ case 1010:
+ case 1011:
+ case 1012:
+ case 1081:
+ case 1082:
+ case 1083:
+ case 1084:
+ case 1085:
+ case 1086:
+ case 1087:
+ glonassTime = DateTime.Now.AddSeconds(5);
+ break;
+ case 1121:
+ case 1122:
+ case 1123:
+ case 1124:
+ case 1125:
+ case 1126:
+ case 1127:
+ beidouTime = DateTime.Now.AddSeconds(5);
+ break;
+ default:
+ break;
+ }
+ }
+ catch (Exception ex)
+ {
+ Message.Show(ex.Message);
+ }
+ await Task.Delay(1);
+
+ }
+ }
+
+ public class RtcmInfo: ObservableObject
+ {
+ private char sys;
+ private byte prn;
+ private byte snr;
+
+ public RtcmInfo()
+ {
+
+ }
+
+ public char Sys
+ {
+ get { return sys; }
+ set { Set(nameof(Sys), ref sys, value); }
+ }
+
+ public byte Prn
+ {
+ get { return prn; }
+ set { Set(nameof(Prn), ref prn, value); }
+ }
+
+ public byte Snr
+ {
+ get { return snr; }
+ set { Set(nameof(Snr), ref snr, value); }
+ }
+ }
+}
diff --git a/Plane.FormationCreator/MainWindow.xaml.cs b/Plane.FormationCreator/MainWindow.xaml.cs
index 263c1ed..f1f6bc8 100644
--- a/Plane.FormationCreator/MainWindow.xaml.cs
+++ b/Plane.FormationCreator/MainWindow.xaml.cs
@@ -34,13 +34,20 @@ namespace Plane.FormationCreator
InitializeComponent();
this.DataContext = ServiceLocator.Current.GetInstance();
-
+
+ DateTime dateTimeClose = DateTime.Parse("2019-12-7");
+ if (DateTime.UtcNow > dateTimeClose)
+ {
+ MessageBox.Show("软件过旧,请更新!");
+ Application.Current.Shutdown();
+ throw new NotImplementedException();
+ }
//ShowConnectDialog();
//if (_copterManager.CoptersForControlling.Count <= 0)
//{
// //App.Current.Shutdown();
//}
-
+
}
private CommModuleManager _commModuleManager = CommModuleManager.Instance;
private CopterManager _copterManager = ServiceLocator.Current.GetInstance();
diff --git a/Plane.FormationCreator/Plane.FormationCreator.csproj b/Plane.FormationCreator/Plane.FormationCreator.csproj
index 53e7b4c..761caa5 100644
--- a/Plane.FormationCreator/Plane.FormationCreator.csproj
+++ b/Plane.FormationCreator/Plane.FormationCreator.csproj
@@ -182,6 +182,7 @@
+
@@ -195,6 +196,10 @@
+
+ Component
+
+
@@ -208,6 +213,7 @@
+
@@ -241,6 +247,9 @@
ModifyTaskView.xaml
+
+ RtcmInfoView.xaml
+
SetCoptersPutView.xaml
@@ -375,6 +384,10 @@
Designer
MSBuild:Compile
+
+ Designer
+ MSBuild:Compile
+
Designer
MSBuild:Compile
diff --git a/Plane.FormationCreator/PlaneMessageBox.xaml b/Plane.FormationCreator/PlaneMessageBox.xaml
index 125651b..da712b4 100644
--- a/Plane.FormationCreator/PlaneMessageBox.xaml
+++ b/Plane.FormationCreator/PlaneMessageBox.xaml
@@ -12,7 +12,7 @@
Title="PlaneMessageBox" Height="200" Width="600"
MinHeight="200" MinWidth="600"
MaxHeight="200" MaxWidth="600"
- WindowStyle="ToolWindow" Visibility="Visible" ShowMinButton="False" ShowMaxRestoreButton="False" ShowCloseButton="False" IsCloseButtonEnabled="False" IsMinButtonEnabled="False" IsMaxRestoreButtonEnabled="False" IsWindowDraggable="False"
+ WindowStyle="ToolWindow" Visibility="Visible" ShowMinButton="False" ShowMaxRestoreButton="False" ShowCloseButton="False" IsCloseButtonEnabled="False" IsMinButtonEnabled="False" IsMaxRestoreButtonEnabled="False" IsWindowDraggable="True" Background="#FF2D2D2D" BorderBrush="#FF099EF3"
>
diff --git a/Plane.FormationCreator/ServiceLocatorConfigurer.cs b/Plane.FormationCreator/ServiceLocatorConfigurer.cs
index b4d1add..712241c 100644
--- a/Plane.FormationCreator/ServiceLocatorConfigurer.cs
+++ b/Plane.FormationCreator/ServiceLocatorConfigurer.cs
@@ -35,6 +35,7 @@ namespace Plane.FormationCreator
_container.Register();
_container.Register();
_container.Register();
+ _container.Register();
_container.Register(() => new LocalFileLogger(new DebugLogger()));
@@ -45,6 +46,7 @@ namespace Plane.FormationCreator
_container.Register();
_container.Register();
+ _container.Register();
_container.Register();
}
diff --git a/Plane.FormationCreator/Util/CommNTRIP.cs b/Plane.FormationCreator/Util/CommNTRIP.cs
index cb68455..4bd9def 100644
--- a/Plane.FormationCreator/Util/CommNTRIP.cs
+++ b/Plane.FormationCreator/Util/CommNTRIP.cs
@@ -1,46 +1,141 @@
using System;
using System.Collections.Generic;
-using System.Diagnostics;
-using System.IO;
-using System.Linq;
-using System.Net.Sockets;
+using System.ComponentModel;
+using System.Reflection;
using System.Text;
-using System.Threading.Tasks;
+using System.IO.Ports;
+using System.Threading;
+using System.Net; // dns, ip address
+using System.Net.Sockets; // tcplistner
+using System.IO;
+using System.Runtime.InteropServices;
+using System.Text.RegularExpressions;
namespace Plane.Util
{
- public class CommNTRIP: IDisposable
+ public class CommsNTRIP : ICommsSerial, IDisposable
{
public TcpClient client = new TcpClient();
+ IPEndPoint RemoteIpEndPoint = new IPEndPoint(IPAddress.Any, 0);
private Uri remoteUri;
- double Lat = 40.0910757034397;
- double Lng = 116.27734627295;
- double alt = 0;
+
+ public double lat = 0;
+ public double lng = 0;
+ public double alt = 0;
+
int retrys = 3;
- DateTime _lastnmea = DateTime.MinValue;
- public string Port { get; set; }
private string host;
-
+ public int WriteBufferSize { get; set; }
+ public int WriteTimeout { get; set; }
+ public bool RtsEnable { get; set; }
+ private string url;
- private static int bytes = 0;
- private static int bps = 0;
- public int ReadTimeout
+ public Stream BaseStream
{
- get;
- set;
+ get { return client.GetStream(); }
}
- public CommNTRIP(string url, double lat, double lng)
+ public CommsNTRIP(string url, double lat, double lng)
{
- remoteUri = new Uri(url);
- this.Lat = lat;
- this.Lng = lng;
+ this.url = url;
+ this.lat = lat;
+ this.lng = lng;
ReadTimeout = 500;
}
- public void doConnect()
+ public void toggleDTR()
+ {
+ }
+
+ public string Port { get; set; }
+
+ public int ReadTimeout
+ {
+ get; // { return client.ReceiveTimeout; }
+ set; // { client.ReceiveTimeout = value; }
+ }
+
+ public int ReadBufferSize { get; set; }
+
+ public int BaudRate { get; set; }
+ public StopBits StopBits { get; set; }
+ public Parity Parity { get; set; }
+ public int DataBits { get; set; }
+
+ public string PortName { get; set; }
+
+ public int BytesToRead
+ {
+ get
+ {
+ /*Console.WriteLine(DateTime.Now.Millisecond + " tcp btr " + (client.Available + rbuffer.Length - rbufferread));*/
+ SendNMEA();
+ return (int)client.Available;
+ }
+ }
+
+ public int BytesToWrite
+ {
+ get { return 0; }
+ }
+
+ public bool IsOpen
+ {
+ get
+ {
+ try
+ {
+ return client.Client.Connected;
+ }
+ catch
+ {
+ return false;
+ }
+ }
+ }
+
+ public bool DtrEnable { get; set; }
+
+ public void Open()
+ {
+ if (client.Client.Connected)
+ {
+ return;
+ }
+
+
+ /*string url = "";*/
+
+
+ int count = url.Split('@').Length - 1;
+
+ if (count > 1)
+ {
+ var regex = new Regex("@");
+ url = regex.Replace(url, "%40", 1);
+ }
+
+ url = url.Replace("ntrip://", "http://");
+
+ remoteUri = new Uri(url);
+
+ doConnect();
+ }
+
+ private byte[] TcpKeepAlive(bool On_Off, uint KeepaLiveTime, uint KeepaLiveInterval)
+ {
+ byte[] InValue = new byte[12];
+
+ Array.ConstrainedCopy(BitConverter.GetBytes(Convert.ToUInt32(On_Off)), 0, InValue, 0, 4);
+ Array.ConstrainedCopy(BitConverter.GetBytes(KeepaLiveTime), 0, InValue, 4, 4);
+ Array.ConstrainedCopy(BitConverter.GetBytes(KeepaLiveInterval), 0, InValue, 8, 4);
+
+ return InValue;
+ }
+
+ private void doConnect()
{
string usernamePassword = remoteUri.UserInfo;
string userpass2 = Uri.UnescapeDataString(usernamePassword);
@@ -67,133 +162,54 @@ namespace Plane.Util
+ "Connection: close\r\n\r\n";
sw.Write(line);
+
sw.Flush();
- line = sr.ReadLine();
+ line = sr.ReadLine();
- Console.WriteLine(line);
if (!line.Contains("200"))
{
client.Dispose();
+
client = new TcpClient();
+
throw new Exception("Bad ntrip Responce\n\n" + line);
}
+ // vrs may take up to 60+ seconds to respond
SendNMEA();
VerifyConnected();
}
- public int Read(byte[] readto, int offset, int length)
- {
- VerifyConnected();
-
- SendNMEA();
-
- try
- {
- if (length < 1) { return 0; }
-
- return client.Client.Receive(readto, offset, length, SocketFlags.Partial);
- }
- catch { throw new Exception("ntrip Socket Closed"); }
- }
-
+ DateTime _lastnmea = DateTime.MinValue;
private void SendNMEA()
{
- if (Lat != 0 || Lng != 0)
+ if (lat != 0 || lng != 0)
{
if (_lastnmea.AddSeconds(30) < DateTime.Now)
{
- double latdms = (int)Lat + ((Lat - (int)Lat) * .6f);
- double lngdms = (int)Lng + ((Lng - (int)Lng) * .6f);
+ double latdms = (int)lat + ((lat - (int)lat) * .6f);
+ double lngdms = (int)lng + ((lng - (int)lng) * .6f);
var line = string.Format(System.Globalization.CultureInfo.InvariantCulture,
"$GP{0},{1:HHmmss.ff},{2},{3},{4},{5},{6},{7},{8},{9},{10},{11},{12},{13},{14}", "GGA",
- DateTime.Now.ToUniversalTime(), Math.Abs(latdms * 100).ToString("0000.00"), Lat < 0 ? "S" : "N",
- Math.Abs(lngdms * 100).ToString("00000.00"), Lng < 0 ? "W" : "E", 1, 10,
+ DateTime.Now.ToUniversalTime(), Math.Abs(latdms * 100).ToString("0000.00"), lat < 0 ? "S" : "N",
+ Math.Abs(lngdms * 100).ToString("00000.00"), lng < 0 ? "W" : "E", 1, 10,
1, alt.ToString("0.00"), "M", 0, "M", "0.0", "0");
string checksum = GetChecksum(line);
WriteLine(line + "*" + checksum);
+
_lastnmea = DateTime.Now;
}
}
+
}
- public int BytesToRead
- {
- get
- {
- /*Console.WriteLine(DateTime.Now.Millisecond + " tcp btr " + (client.Available + rbuffer.Length - rbufferread));*/
- SendNMEA();
- return (int)client.Available;
- }
- }
-
- void VerifyConnected()
- {
- if (!IsOpen)
- {
- try
- {
- client.Dispose();
- client = new TcpClient();
- }
- catch { }
-
- // this should only happen if we have established a connection in the first place
- if (client != null && retrys > 0)
- {
- doConnect();
- retrys--;
- }
-
- throw new Exception("The ntrip is closed");
- }
- }
-
- public bool IsOpen
- {
- get
- {
- try
- {
- return client.Client.Connected;
- }
- catch
- {
- return false;
- }
- }
- }
-
- public void WriteLine(string line)
- {
- VerifyConnected();
- line = line + "\r\n";
- Write(line);
- }
-
- public void Write(string line)
- {
- VerifyConnected();
- byte[] data = new System.Text.ASCIIEncoding().GetBytes(line);
- Write(data, 0, data.Length);
- }
-
- public void Write(byte[] write, int offset, int length)
- {
- VerifyConnected();
- try
- {
- client.Client.Send(write, length, SocketFlags.None);
- }
- catch { }//throw new Exception("Comport / Socket Closed"); }
- }
-
+ // Calculates the checksum for a sentence
string GetChecksum(string sentence)
{
// Loop through all chars to get a checksum
@@ -227,30 +243,151 @@ namespace Plane.Util
return Checksum.ToString("X2");
}
- private byte[] TcpKeepAlive(bool On_Off, uint KeepaLiveTime, uint KeepaLiveInterval)
+ void VerifyConnected()
{
- byte[] InValue = new byte[12];
-
- Array.ConstrainedCopy(BitConverter.GetBytes(Convert.ToUInt32(On_Off)), 0, InValue, 0, 4);
- Array.ConstrainedCopy(BitConverter.GetBytes(KeepaLiveTime), 0, InValue, 4, 4);
- Array.ConstrainedCopy(BitConverter.GetBytes(KeepaLiveInterval), 0, InValue, 8, 4);
-
- return InValue;
- }
-
- protected virtual void Dispose(bool disposing)
- {
- if (disposing)
+ if (!IsOpen)
{
- this.Close();
- client = null;
+ try
+ {
+ client.Dispose();
+ client = new TcpClient();
+ }
+ catch { }
+
+ // this should only happen if we have established a connection in the first place
+ if (client != null && retrys > 0)
+ {
+ doConnect();
+ retrys--;
+ }
+
+ throw new Exception("The ntrip is closed");
}
}
- public void Dispose()
+ public int Read(byte[] readto, int offset, int length)
{
- Dispose(true);
- GC.SuppressFinalize(this);
+ VerifyConnected();
+
+ SendNMEA();
+
+ try
+ {
+ if (length < 1) { return 0; }
+
+ return client.Client.Receive(readto, offset, length, SocketFlags.Partial);
+ /*
+ byte[] temp = new byte[length];
+ clientbuf.Read(temp, 0, length);
+
+ temp.CopyTo(readto, offset);
+
+ return length;*/
+ }
+ catch { throw new Exception("ntrip Socket Closed"); }
+ }
+
+ public int ReadByte()
+ {
+ VerifyConnected();
+ int count = 0;
+ while (this.BytesToRead == 0)
+ {
+ System.Threading.Thread.Sleep(1);
+ if (count > ReadTimeout)
+ throw new Exception("ntrip Timeout on read");
+ count++;
+ }
+ byte[] buffer = new byte[1];
+ Read(buffer, 0, 1);
+ return buffer[0];
+ }
+
+ public int ReadChar()
+ {
+ return ReadByte();
+ }
+
+ public string ReadExisting()
+ {
+ VerifyConnected();
+ byte[] data = new byte[client.Available];
+ if (data.Length > 0)
+ Read(data, 0, data.Length);
+
+ string line = Encoding.ASCII.GetString(data, 0, data.Length);
+
+ return line;
+ }
+
+ public void WriteLine(string line)
+ {
+ VerifyConnected();
+ line = line + "\r\n";
+ Write(line);
+ }
+
+ public void Write(string line)
+ {
+ VerifyConnected();
+ byte[] data = new System.Text.ASCIIEncoding().GetBytes(line);
+ Write(data, 0, data.Length);
+ }
+
+ public void Write(byte[] write, int offset, int length)
+ {
+ VerifyConnected();
+ try
+ {
+ client.Client.Send(write, length, SocketFlags.None);
+ }
+ catch { }//throw new Exception("Comport / Socket Closed"); }
+ }
+
+ public void DiscardInBuffer()
+ {
+ VerifyConnected();
+ int size = (int)client.Available;
+ byte[] crap = new byte[size];
+ Read(crap, 0, size);
+ }
+
+ public string ReadLine()
+ {
+ byte[] temp = new byte[4000];
+ int count = 0;
+ int timeout = 0;
+
+ while (timeout <= 100)
+ {
+ if (!this.IsOpen) { break; }
+ if (this.BytesToRead > 0)
+ {
+ byte letter = (byte)this.ReadByte();
+
+ temp[count] = letter;
+
+ if (letter == '\n') // normal line
+ {
+ break;
+ }
+
+
+ count++;
+ if (count == temp.Length)
+ break;
+ timeout = 0;
+ }
+ else
+ {
+ timeout++;
+ System.Threading.Thread.Sleep(5);
+ }
+ }
+
+ Array.Resize(ref temp, count + 1);
+
+ return Encoding.ASCII.GetString(temp, 0, temp.Length);
}
public void Close()
@@ -272,6 +409,23 @@ namespace Plane.Util
catch { }
client = new TcpClient();
- }
+ }
+
+ protected virtual void Dispose(bool disposing)
+ {
+ if (disposing)
+ {
+ // dispose managed resources
+ this.Close();
+ client = null;
+ }
+ // free native resources
+ }
+
+ public void Dispose()
+ {
+ Dispose(true);
+ GC.SuppressFinalize(this);
+ }
}
}
diff --git a/Plane.FormationCreator/Util/ICommsSerial.cs b/Plane.FormationCreator/Util/ICommsSerial.cs
new file mode 100644
index 0000000..b044af1
--- /dev/null
+++ b/Plane.FormationCreator/Util/ICommsSerial.cs
@@ -0,0 +1,59 @@
+using System;
+using System.Collections.Generic;
+using System.Text;
+using System.IO.Ports;
+using System.IO;
+using System.Reflection;
+
+namespace Plane.Util
+{
+
+ public interface ICommsSerial
+ {
+ // from serialport class
+ // Methods
+ void Close();
+ void DiscardInBuffer();
+ //void DiscardOutBuffer();
+ void Open();
+ int Read(byte[] buffer, int offset, int count);
+ //int Read(char[] buffer, int offset, int count);
+ int ReadByte();
+ int ReadChar();
+ string ReadExisting();
+ string ReadLine();
+ //string ReadTo(string value);
+ void Write(string text);
+ void Write(byte[] buffer, int offset, int count);
+ //void Write(char[] buffer, int offset, int count);
+ void WriteLine(string text);
+
+ void toggleDTR();
+
+ // Properties
+ Stream BaseStream { get; }
+ int BaudRate { get; set; }
+ //bool BreakState { get; set; }
+ int BytesToRead { get; }
+ int BytesToWrite { get; }
+ //bool CDHolding { get; }
+ //bool CtsHolding { get; }
+ int DataBits { get; set; }
+ //bool DiscardNull { get; set; }
+ //bool DsrHolding { get; }
+ bool DtrEnable { get; set; }
+ //Encoding Encoding { get; set; }
+ //Handshake Handshake { get; set; }
+ bool IsOpen { get; }
+ //string NewLine { get; set; }
+ Parity Parity { get; set; }
+ //byte ParityReplace { get; set; }
+ string PortName { get; set; }
+ int ReadBufferSize { get; set; }
+ int ReadTimeout { get; set; }
+ bool RtsEnable { get; set; }
+ StopBits StopBits { get; set; }
+ int WriteBufferSize { get; set; }
+ int WriteTimeout { get; set; }
+ }
+}
diff --git a/Plane.FormationCreator/ViewModels/ControlPanelViewModel.cs b/Plane.FormationCreator/ViewModels/ControlPanelViewModel.cs
index 3839811..9140b69 100644
--- a/Plane.FormationCreator/ViewModels/ControlPanelViewModel.cs
+++ b/Plane.FormationCreator/ViewModels/ControlPanelViewModel.cs
@@ -864,15 +864,16 @@ namespace Plane.FormationCreator.ViewModels
RTKState = "RTK数据发送中";
RTKbtntxt = "停止RTK";
await SaveRTKcomvalue();
+ await _commModuleManager.StartRtcmLoop();
await Task.Run(async () =>
{
+ Message.Show("RTK数据开始发送");
//读取RTK数据循环
rtcm3 rtcm3 = new rtcm3();
while (trkthreadrun)
{
//读入RTK数据
var packet = await ReadRTKPacketAsync().ConfigureAwait(false);
-
if (packet != null && packet.Length > 0)
{
@@ -886,8 +887,7 @@ namespace Plane.FormationCreator.ViewModels
// rtcm
if ((seenmsg = rtcm3.Read(packet[a])) > 0)
{
- //Console.WriteLine($"{DateTime.Now.ToLongTimeString()}---rtcm3.length = {rtcm3.length}");
- //Message.Show($"{DateTime.Now.ToString("HH:mm:ss fff")}---rtcm3.length = {rtcm3.length}");
+ Message.Show($"{DateTime.Now.ToString("HH:mm:ss fff")}---rtcm3.length = {rtcm3.length}");
await _commModuleManager.InjectGpsRTCMDataAsync(rtcm3.packet, rtcm3.length);
}
}
@@ -912,7 +912,7 @@ namespace Plane.FormationCreator.ViewModels
}
}
-
+
private ICommand _SendRTCMCommand;
public ICommand SendRTCMCommand
{
@@ -940,16 +940,15 @@ namespace Plane.FormationCreator.ViewModels
RTKState = "RTK数据发送中";
NTRIPbtntxt = "停止RTCM";
Alert.Show("RTCM数据开始发送", "提示", MessageBoxButton.OK, MessageBoxImage.Information);
-
+
+ await _commModuleManager.StartRtcmLoop();
await Task.Run(async () =>
{
-
-
-
+ Message.Show("RTK数据开始发送");
//string url = "http://qxarpz003:1dc880b@rtk.ntrip.qxwz.com:8002/RTCM32_GGB";
- CommNTRIP commNTRIP = new CommNTRIP(url, _flightTaskManager.OriginLat, _flightTaskManager.OriginLng);
+ CommsNTRIP commNTRIP = new CommsNTRIP(url, _flightTaskManager.OriginLat, _flightTaskManager.OriginLng);
rtcm3 rtcm3 = new rtcm3();
- commNTRIP.doConnect();
+ commNTRIP.Open();
//读取RTK数据循环
while (rtcmthreadrun)
{
@@ -967,7 +966,9 @@ namespace Plane.FormationCreator.ViewModels
// rtcm
if ((seenmsg = rtcm3.Read(buffer[a])) > 0)
{
- //Message.Show($"{DateTime.Now.ToString("HH:mm:ss fff")}---rtcm3.length = {rtcm3.length}");
+ //rtcmDatas.Add(rtcm3.packet);
+ //await SendRtcmData();
+ Message.Show($"{DateTime.Now.ToString("HH:mm:ss fff")}---rtcm3.length = {rtcm3.length}");
await _commModuleManager.InjectGpsRTCMDataAsync(rtcm3.packet, rtcm3.length);
}
}
@@ -984,6 +985,25 @@ namespace Plane.FormationCreator.ViewModels
}
}
+ private RtcmInfoView rtcmInfoView;
+ private ICommand _OpenRtcmManageCommand;
+ public ICommand OpenRtcmManageCommand
+ {
+ get
+ {
+ return _OpenRtcmManageCommand ?? (_OpenRtcmManageCommand = new RelayCommand(() =>
+ {
+ RtcmInfoView.GetInstance().Show();
+ RtcmInfoView.GetInstance().Activate();
+ // if (rtcmInfoView == null)
+ // {
+ // rtcmInfoView = new RtcmInfoView();
+ // }
+ // rtcmInfoView.Show();
+ }));
+ }
+ }
+
rtcm3 rtcm3 = new rtcm3();
private async Task AnalysisRendRrcmData(byte[] buffer, int length)
{
@@ -1000,9 +1020,6 @@ namespace Plane.FormationCreator.ViewModels
}
-
-
-
private ICommand _LandCommand;
public ICommand LandCommand
{
@@ -1401,18 +1418,6 @@ namespace Plane.FormationCreator.ViewModels
return missions;
}
-
-
-
-
-
-
-
-
-
-
-
-
private ICommand _FlagCommand;
public ICommand FlagCommand
{
diff --git a/Plane.FormationCreator/ViewModels/RtcmInfoViewModel.cs b/Plane.FormationCreator/ViewModels/RtcmInfoViewModel.cs
new file mode 100644
index 0000000..6ee6264
--- /dev/null
+++ b/Plane.FormationCreator/ViewModels/RtcmInfoViewModel.cs
@@ -0,0 +1,87 @@
+using GalaSoft.MvvmLight;
+using GalaSoft.MvvmLight.Command;
+using Plane.FormationCreator.Formation;
+using Plane.Windows.Messages;
+using System;
+using System.Collections.Generic;
+using System.Collections.ObjectModel;
+using System.Linq;
+using System.Text;
+using System.Threading.Tasks;
+using System.Windows.Input;
+
+namespace Plane.FormationCreator.ViewModels
+{
+ public class RtcmInfoViewModel: ViewModelBase
+ {
+ private RtcmManager _rtcmManager;
+
+ public RtcmManager RtcmManager { get { return _rtcmManager; } }
+
+ public ObservableCollection serialPorts { get; } = new ObservableCollection();
+
+ private string _serialPortsSelectdValue;
+ public string SerialPortsSelectdValue
+ {
+
+ get { return _serialPortsSelectdValue; }
+ set { Set(nameof(SerialPortsSelectdValue), ref _serialPortsSelectdValue, value); }
+
+ }
+
+ public RtcmInfoViewModel(RtcmManager rtcmManager)
+ {
+ _rtcmManager = rtcmManager;
+ string[] commports = _rtcmManager.GetPortNames();
+ foreach (var item in commports)
+ {
+ serialPorts.Add(item);
+ }
+ serialPorts.Add("千寻");
+ SerialPortsSelectdValue = serialPorts[0];
+ }
+
+
+
+ public void RefreshPorts()
+ {
+ string lastSelectValue = SerialPortsSelectdValue;
+ serialPorts.Clear();
+ string[] commports = _rtcmManager.GetPortNames();
+ foreach (var item in commports)
+ {
+ serialPorts.Add(item);
+ }
+ serialPorts.Add("千寻");
+ if (serialPorts.Contains(lastSelectValue))
+ SerialPortsSelectdValue = lastSelectValue;
+ }
+
+ private ICommand _ConnectRtcmCommand;
+ public ICommand ConnectRtcmCommand
+ {
+ get
+ {
+ return _ConnectRtcmCommand ?? (_ConnectRtcmCommand = new RelayCommand(async() =>
+ {
+ if (!_rtcmManager.Rtcmthreadrun)
+ await _rtcmManager.Open(SerialPortsSelectdValue);
+ else
+ await _rtcmManager.Close();
+ }));
+ }
+ }
+
+ private ICommand _ClearRtcmCommand;
+ public ICommand ClearRtcmCommand
+ {
+ get
+ {
+ return _ClearRtcmCommand ?? (_ClearRtcmCommand = new RelayCommand(async () =>
+ {
+ await Task.Delay(1);
+ }));
+ }
+ }
+ }
+}
diff --git a/Plane.FormationCreator/Views/ControlPanelView.xaml b/Plane.FormationCreator/Views/ControlPanelView.xaml
index 9b228e4..57fd7ec 100644
--- a/Plane.FormationCreator/Views/ControlPanelView.xaml
+++ b/Plane.FormationCreator/Views/ControlPanelView.xaml
@@ -142,8 +142,10 @@
Command="{Binding SendRTKCommand}" />
+ Command="{Binding SendRTCMCommand}"/>
+
+
+
+ />
@@ -380,7 +380,7 @@
Grid.Row="1"
Grid.ColumnSpan="2"
MinHeight="100"
- Height="Auto"
+ Height="Auto"
MaxHeight="280"
ScrollViewer.VerticalScrollBarVisibility="Visible"
ScrollViewer.HorizontalScrollBarVisibility="Hidden"
diff --git a/Plane.FormationCreator/Views/RtcmInfoView.xaml b/Plane.FormationCreator/Views/RtcmInfoView.xaml
new file mode 100644
index 0000000..75014cf
--- /dev/null
+++ b/Plane.FormationCreator/Views/RtcmInfoView.xaml
@@ -0,0 +1,119 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/Plane.FormationCreator/Views/RtcmInfoView.xaml.cs b/Plane.FormationCreator/Views/RtcmInfoView.xaml.cs
new file mode 100644
index 0000000..fe3cd6d
--- /dev/null
+++ b/Plane.FormationCreator/Views/RtcmInfoView.xaml.cs
@@ -0,0 +1,56 @@
+using MahApps.Metro.Controls;
+using Microsoft.Practices.ServiceLocation;
+using Plane.FormationCreator.ViewModels;
+using System;
+using System.Collections.Generic;
+using System.Linq;
+using System.Text;
+using System.Threading.Tasks;
+using System.Windows;
+using System.Windows.Controls;
+using System.Windows.Data;
+using System.Windows.Documents;
+using System.Windows.Input;
+using System.Windows.Media;
+using System.Windows.Media.Imaging;
+using System.Windows.Navigation;
+using System.Windows.Shapes;
+
+namespace Plane.FormationCreator.Views
+{
+ ///
+ /// RtcmInfoView.xaml 的交互逻辑
+ ///
+ public partial class RtcmInfoView : MetroWindow
+ {
+ private static RtcmInfoView staticInstance = null;
+ public static RtcmInfoView GetInstance()
+ {
+ if (staticInstance == null)
+ {
+ staticInstance = new RtcmInfoView();
+ }
+ return staticInstance;
+ }
+
+
+ RtcmInfoViewModel _rtcmInfoViewModel = ServiceLocator.Current.GetInstance();
+ public RtcmInfoView()
+ {
+ InitializeComponent();
+ this.DataContext = _rtcmInfoViewModel;
+ this.Closed += WindowOnClosed;
+ }
+
+ private void ComboBox_DropDownOpened(object sender, EventArgs e)
+ {
+ _rtcmInfoViewModel.RefreshPorts();
+
+ }
+
+ private void WindowOnClosed(object sender, System.EventArgs e)
+ {
+ staticInstance = null;
+ }
+ }
+}