Revert "通信模块协议的添加和修改"
添加千寻Rtk类型
提交之前未add的文件
This reverts commit d46804bc23
.
This commit is contained in:
parent
d46804bc23
commit
2464022801
@ -0,0 +1,8 @@
|
||||
namespace Plane.Copters
|
||||
{
|
||||
public enum CopterLocationType
|
||||
{
|
||||
GPS,
|
||||
RTK
|
||||
}
|
||||
}
|
17
PlaneGcsSdk.Contract_Shared/Copters/ICopterAttribute.cs
Normal file
17
PlaneGcsSdk.Contract_Shared/Copters/ICopterAttribute.cs
Normal file
@ -0,0 +1,17 @@
|
||||
using System;
|
||||
using System.Collections.Generic;
|
||||
using System.Text;
|
||||
|
||||
namespace Plane.Copters
|
||||
{
|
||||
/// <summary>
|
||||
/// 定义用于设置飞行器部分可编辑的属性
|
||||
/// </summary>
|
||||
public partial interface ICopterAttribute
|
||||
{
|
||||
/// <summary>
|
||||
/// 飞行器摆放时地面的相对高度
|
||||
/// </summary>
|
||||
float GroundAlt { get; set; }
|
||||
}
|
||||
}
|
74
PlaneGcsSdk_Shared/Communication/TcpClientWithTimeout.cs
Normal file
74
PlaneGcsSdk_Shared/Communication/TcpClientWithTimeout.cs
Normal file
@ -0,0 +1,74 @@
|
||||
using System;
|
||||
using System.Net.Sockets;
|
||||
using System.Threading;
|
||||
|
||||
/// <summary>
|
||||
/// TcpClientWithTimeout 用来设置一个带连接超时功能的类
|
||||
/// 使用者可以设置毫秒级的等待超时时间 (1000=1second)
|
||||
/// 例如:
|
||||
/// TcpClient connection = new TcpClientWithTimeout('127.0.0.1',80,1000).Connect();
|
||||
/// </summary>
|
||||
public class TcpClientWithTimeout
|
||||
{
|
||||
protected string _hostname;
|
||||
protected int _port;
|
||||
protected int _timeout_milliseconds;
|
||||
protected TcpClient connection;
|
||||
protected bool connected;
|
||||
protected Exception exception;
|
||||
|
||||
public TcpClientWithTimeout(string hostname, int port, int timeout_milliseconds)
|
||||
{
|
||||
_hostname = hostname;
|
||||
_port = port;
|
||||
_timeout_milliseconds = timeout_milliseconds;
|
||||
}
|
||||
public TcpClient Connect()
|
||||
{
|
||||
// kick off the thread that tries to connect
|
||||
connected = false;
|
||||
exception = null;
|
||||
Thread thread = new Thread(new ThreadStart(BeginConnect));
|
||||
thread.IsBackground = true; // 作为后台线程处理
|
||||
// 不会占用机器太长的时间
|
||||
thread.Start();
|
||||
|
||||
// 等待如下的时间
|
||||
thread.Join(_timeout_milliseconds);
|
||||
|
||||
if (connected == true)
|
||||
{
|
||||
// 如果成功就返回TcpClient对象
|
||||
thread.Abort();
|
||||
return connection;
|
||||
}
|
||||
if (exception != null)
|
||||
{
|
||||
// 如果失败就抛出错误
|
||||
thread.Abort();
|
||||
throw exception;
|
||||
}
|
||||
else
|
||||
{
|
||||
// 同样地抛出错误
|
||||
thread.Abort();
|
||||
string message = string.Format("TcpClient connection to {0}:{1} timed out",
|
||||
_hostname, _port);
|
||||
throw new TimeoutException(message);
|
||||
}
|
||||
}
|
||||
protected void BeginConnect()
|
||||
{
|
||||
try
|
||||
{
|
||||
connection = new TcpClient(_hostname, _port);
|
||||
// 标记成功,返回调用者
|
||||
connected = true;
|
||||
}
|
||||
catch (Exception ex)
|
||||
{
|
||||
// 标记失败
|
||||
exception = ex;
|
||||
}
|
||||
}
|
||||
}
|
66
PlaneGcsSdk_Shared/Communication/TimeOutSocket.cs
Normal file
66
PlaneGcsSdk_Shared/Communication/TimeOutSocket.cs
Normal file
@ -0,0 +1,66 @@
|
||||
using System;
|
||||
using System.Collections.Generic;
|
||||
using System.Net.Sockets;
|
||||
using System.Text;
|
||||
using System.Threading;
|
||||
|
||||
namespace Plane.Communication
|
||||
{
|
||||
class TimeOutSocket
|
||||
{
|
||||
private static bool IsConnectionSuccessful = false;
|
||||
private static Exception socketexception;
|
||||
private static ManualResetEvent TimeoutObject = new ManualResetEvent(false);
|
||||
|
||||
public static TcpClient Connect(string serverip, int serverport, int timeoutMSec)
|
||||
{
|
||||
TimeoutObject.Reset();
|
||||
socketexception = null;
|
||||
|
||||
TcpClient tcpclient = new TcpClient();
|
||||
|
||||
tcpclient.BeginConnect(serverip, serverport,
|
||||
new AsyncCallback(CallBackMethod), tcpclient);
|
||||
|
||||
if (TimeoutObject.WaitOne(timeoutMSec, false))
|
||||
{
|
||||
if (IsConnectionSuccessful)
|
||||
{
|
||||
return tcpclient;
|
||||
}
|
||||
else
|
||||
{
|
||||
throw socketexception;
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
tcpclient.Close();
|
||||
throw new TimeoutException("TimeOut Exception");
|
||||
}
|
||||
}
|
||||
private static void CallBackMethod(IAsyncResult asyncresult)
|
||||
{
|
||||
try
|
||||
{
|
||||
IsConnectionSuccessful = false;
|
||||
TcpClient tcpclient = asyncresult.AsyncState as TcpClient;
|
||||
|
||||
if (tcpclient.Client != null)
|
||||
{
|
||||
tcpclient.EndConnect(asyncresult);
|
||||
IsConnectionSuccessful = true;
|
||||
}
|
||||
}
|
||||
catch (Exception ex)
|
||||
{
|
||||
IsConnectionSuccessful = false;
|
||||
socketexception = ex;
|
||||
}
|
||||
finally
|
||||
{
|
||||
TimeoutObject.Set();
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
@ -154,19 +154,10 @@ namespace Plane.CommunicationManagement
|
||||
break;
|
||||
|
||||
case MavComm.COMM_GET_COPTERS_COUNT:
|
||||
dealData = packet.Skip(18).ToArray();
|
||||
dealData = packet.Skip(16).ToArray();
|
||||
AnalyzeCopterInfosPacket(dealData);
|
||||
break;
|
||||
|
||||
case MavComm.COMM_GET_CURR_SYS_PARM:
|
||||
dealData = packet.Skip(18).ToArray();
|
||||
Analyze_curr_sys_parm_Packet(dealData);
|
||||
break;
|
||||
|
||||
case MavComm.COMM_SET_CURR_SYS_PARM:
|
||||
|
||||
break;
|
||||
|
||||
case MavComm.COMM_NOTIFICATION:
|
||||
short messageType = BitConverter.ToInt16(packet, 10);
|
||||
dealData = packet.Skip(12).ToArray();
|
||||
|
@ -49,72 +49,6 @@ namespace Plane.CommunicationManagement
|
||||
return GeneratePacket(MAVLink.MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE, rc);
|
||||
}
|
||||
|
||||
/// <summary>
|
||||
/// 设置飞机上通信模块的回传功率
|
||||
/// </summary>
|
||||
/// <returns></returns>
|
||||
public async Task SetCopterCommBackPower(short id, byte power)
|
||||
{
|
||||
byte[] data = new byte[12];
|
||||
short num = (0x5 << 12) ^ 1;
|
||||
byte frequencyPoint = 16;
|
||||
int frequencyValue = 0x50;
|
||||
|
||||
Array.Copy(BitConverter.GetBytes(num), 0, data, 0, 2); //广播个数
|
||||
Array.Copy(BitConverter.GetBytes(id), 0, data, 2, 2); //小批量 当前只对1个采用小批量模式广播
|
||||
data[4] = 0x00;
|
||||
data[5] = 0xFC;
|
||||
data[6] = power;
|
||||
data[7] = frequencyPoint;
|
||||
Array.Copy(BitConverter.GetBytes(frequencyValue), 0, data, 8, 4);
|
||||
|
||||
await WriteCommPacketAsync(0, MavComm.COMM_SET_BACK_POWER, data).ConfigureAwait(false);
|
||||
}
|
||||
|
||||
public async Task GetCurr_Sys_Parm()
|
||||
{
|
||||
configurationData = null;
|
||||
configData1 = null;
|
||||
configData2 = null;
|
||||
|
||||
byte[] data = new byte[2];
|
||||
data = BitConverter.GetBytes((short)0x0000);
|
||||
await WriteCommPacketAsync(0, MavComm.COMM_GET_CURR_SYS_PARM, data).ConfigureAwait(false);
|
||||
|
||||
await Task.Delay(100);
|
||||
|
||||
data = BitConverter.GetBytes((short)0x0001);
|
||||
await WriteCommPacketAsync(0, MavComm.COMM_GET_CURR_SYS_PARM, data).ConfigureAwait(false);
|
||||
}
|
||||
|
||||
public async Task SetCurr_Sys_Parm()
|
||||
{
|
||||
if (configurationData == null) return;
|
||||
|
||||
byte[] data = new byte[configurationData.Length + 2];
|
||||
|
||||
Array.Copy(BitConverter.GetBytes((short)configurationData.Length), data, 2);
|
||||
Array.Copy(configurationData,0, data, 2, configurationData.Length);
|
||||
|
||||
await WriteCommPacketAsync(0, MavComm.COMM_SET_CURR_SYS_PARM, data).ConfigureAwait(false);
|
||||
}
|
||||
|
||||
public async Task SetCommCount(short count, short startNum)
|
||||
{
|
||||
byte[] data = new byte[4];
|
||||
Array.Copy(BitConverter.GetBytes(count), 0, data, 0, 2);
|
||||
Array.Copy(BitConverter.GetBytes(startNum), 0, data, 2, 2);
|
||||
|
||||
await WriteCommPacketAsync(0, MavComm.COMM_SET_MAV_COUNT, data).ConfigureAwait(false);
|
||||
}
|
||||
|
||||
|
||||
/// <summary>
|
||||
/// 写入航点
|
||||
/// </summary>
|
||||
/// <param name="id">飞机ID</param>
|
||||
/// <param name="missions">航点列表</param>
|
||||
/// <returns></returns>
|
||||
public async Task<bool> WriteMissionListAsync(short id, List<IMission> missions)
|
||||
{
|
||||
missions.Insert(0, PLCopter.PRE_TAKE_OFF_MISSION);
|
||||
@ -226,22 +160,6 @@ namespace Plane.CommunicationManagement
|
||||
await WriteCommPacketAsync(copterId, MavComm.COMM_DOWNLOAD_COMM, data, batchPacket).ConfigureAwait(false);
|
||||
}
|
||||
|
||||
/// <summary>
|
||||
/// 返航偏移
|
||||
/// </summary>
|
||||
/// <param name="copters"></param>
|
||||
/// <returns></returns>
|
||||
public async Task RLTOffsetAsync(float lat, float lng, IEnumerable<ICopter> copters = null)
|
||||
{
|
||||
short copterId = 0;
|
||||
byte[] batchPacket = null;
|
||||
GetCopterIds(copters, out copterId, out batchPacket);
|
||||
|
||||
byte[] data = DoCommandAsync(MAVLink.MAV_CMD.DO_SET_HOME, 2, 0, 0, lat, lng, 0, 0);
|
||||
|
||||
await WriteCommPacketAsync(copterId, MavComm.COMM_DOWNLOAD_COMM, data, batchPacket).ConfigureAwait(false);
|
||||
}
|
||||
|
||||
/// <summary>
|
||||
/// LED闪烁白灯
|
||||
/// </summary>
|
||||
@ -648,7 +566,54 @@ namespace Plane.CommunicationManagement
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
int inject_seq_no = 0;
|
||||
public async Task InjectGpsRTCMDataAsync(byte[] data, int length)
|
||||
{
|
||||
MAVLink.mavlink_gps_rtcm_data_t gps = new MAVLink.mavlink_gps_rtcm_data_t();
|
||||
var msglen = 180;
|
||||
|
||||
// if (length > msglen * 4)
|
||||
// log.Error("Message too large " + length);
|
||||
|
||||
// number of packets we need, including a termination packet if needed
|
||||
var nopackets = (length % msglen) == 0 ? length / msglen + 1 : (length / msglen) + 1;
|
||||
|
||||
if (nopackets >= 4)
|
||||
nopackets = 4;
|
||||
|
||||
// flags = isfrag(1)/frag(2)/seq(5)
|
||||
|
||||
for (int a = 0; a < nopackets; a++)
|
||||
{
|
||||
// check if its a fragment
|
||||
if (nopackets > 1)
|
||||
gps.flags = 1;
|
||||
else
|
||||
gps.flags = 0;
|
||||
|
||||
// add fragment number
|
||||
gps.flags += (byte)((a & 0x3) << 1);
|
||||
|
||||
// add seq number
|
||||
gps.flags += (byte)((inject_seq_no & 0x1f) << 3);
|
||||
|
||||
// create the empty buffer
|
||||
gps.data = new byte[msglen];
|
||||
|
||||
// calc how much data we are copying
|
||||
int copy = Math.Min(length - a * msglen, msglen);
|
||||
|
||||
// copy the data
|
||||
Array.Copy(data, a * msglen, gps.data, 0, copy);
|
||||
|
||||
// set the length
|
||||
gps.len = (byte)copy;
|
||||
byte[] packet = GeneratePacket(MAVLink.MAVLINK_MSG_ID_GPS_RTCM_DATA, gps);
|
||||
await WriteCommPacketAsync(0, MavComm.COMM_DOWNLOAD_COMM, packet).ConfigureAwait(false);
|
||||
} }
|
||||
|
||||
|
||||
|
||||
|
||||
public byte[] GenerateRTKPacketAsync<TMavlinkPacket>(byte messageType, TMavlinkPacket indata, int rtklength)
|
||||
{
|
||||
@ -657,6 +622,7 @@ namespace Plane.CommunicationManagement
|
||||
|
||||
data = MavlinkUtil.StructureToByteArray(indata);
|
||||
|
||||
|
||||
byte[] packet = new byte[rtkdataleng + 6 + 2];
|
||||
|
||||
packet[0] = MAVLink.MAVLINK_STX;
|
||||
@ -773,15 +739,7 @@ namespace Plane.CommunicationManagement
|
||||
else
|
||||
BatchByte = BatchByte.Concat(tempByte).ToArray();
|
||||
}
|
||||
short byteNum = (short)(BatchByte.Length / 2);
|
||||
short length = (short)((0x5 << 12) ^ byteNum);
|
||||
byte[] ret = new byte[2+ BatchByte.Length];
|
||||
|
||||
Array.Copy(BitConverter.GetBytes(length), ret, 2);
|
||||
|
||||
Array.Copy(BatchByte, 0, ret, 2, BatchByte.Length);
|
||||
|
||||
return ret;
|
||||
return BatchByte;
|
||||
}
|
||||
|
||||
private void GetCopterIds(IEnumerable<ICopter> copters, out short copterId, out byte[] batchPacket)
|
||||
@ -791,10 +749,9 @@ namespace Plane.CommunicationManagement
|
||||
|
||||
if (copters != null)
|
||||
{
|
||||
//为提高通信稳定性,无论1架还是多架全部改为小批量广播
|
||||
//if (copters.Count() == 1)
|
||||
// copterId = short.Parse(copters.FirstOrDefault().Id);
|
||||
//else
|
||||
if (copters.Count() == 1)
|
||||
copterId = short.Parse(copters.FirstOrDefault().Id);
|
||||
else
|
||||
{
|
||||
batchPacket = BatchCopterIdData(copters);
|
||||
}
|
||||
|
@ -21,9 +21,6 @@ namespace Plane.CommunicationManagement
|
||||
public event EventHandler<CommunicationConnectEventArgs> CommunicationConnected;
|
||||
private Dictionary<int, CommWriteMissinState> missionWriteState = new Dictionary<int, CommWriteMissinState>();
|
||||
private static readonly object MissinLocker = new object();
|
||||
private byte[] configData1 = null;
|
||||
private byte[] configData2 = null;
|
||||
private byte[] configurationData = null;
|
||||
|
||||
public Dictionary<int, CommWriteMissinState> MissionWriteState
|
||||
{
|
||||
@ -141,8 +138,6 @@ namespace Plane.CommunicationManagement
|
||||
|
||||
}
|
||||
|
||||
|
||||
|
||||
private void AnalyzeCopterInfosPacket(byte[] buffer)
|
||||
{
|
||||
ushort beginNum = BitConverter.ToUInt16(buffer, 0);
|
||||
@ -180,35 +175,6 @@ namespace Plane.CommunicationManagement
|
||||
}
|
||||
}
|
||||
|
||||
private void Analyze_curr_sys_parm_Packet(byte[] buffer)
|
||||
{
|
||||
Message.Show($"buffer length = {buffer.Length}");
|
||||
short num = BitConverter.ToInt16(buffer, 0);
|
||||
short offset = BitConverter.ToInt16(buffer, 2);
|
||||
short curLength = BitConverter.ToInt16(buffer, 4);
|
||||
short allLength = BitConverter.ToInt16(buffer, 6);
|
||||
|
||||
if (num == 0)
|
||||
{
|
||||
configData1 = new byte[curLength];
|
||||
Array.Copy(buffer, 8, configData1, 0, curLength);
|
||||
Message.Show($"part0 长度={curLength}, 总长{allLength}");
|
||||
}
|
||||
else if (num == 1)
|
||||
{
|
||||
configData2 = new byte[curLength];
|
||||
Array.Copy(buffer, 8, configData2, 0, curLength);
|
||||
Message.Show($"part1 长度={curLength}, 总长{allLength}");
|
||||
}
|
||||
|
||||
if (configData1 != null && configData2 != null)
|
||||
{
|
||||
Message.Show("合成数据");
|
||||
configurationData = new byte[configData1.Length + configData2.Length];
|
||||
configurationData = configData1.Concat(configData2).ToArray();
|
||||
}
|
||||
}
|
||||
|
||||
private void AnalyzeComm4RetrunPacket(short copterId, byte[] buffer)
|
||||
{
|
||||
byte[] packet = buffer.Take(28).ToArray();
|
||||
|
@ -34,7 +34,9 @@ namespace Plane.Protocols
|
||||
|
||||
//public static readonly byte[] MAVLINK_MESSAGE_CRCS = new byte[] {50, 124, 137, 0, 237, 217, 104, 119, 0, 0, 0, 89, 0, 0, 0, 0, 0, 0, 0, 0, 214, 159, 220, 168, 24, 23, 170, 144, 67, 115, 39, 246, 185, 104, 237, 244, 222, 212, 9, 254, 230, 28, 28, 132, 221, 232, 11, 153, 41, 39, 214, 223, 141, 33, 15, 3, 100, 24, 239, 238, 30, 240, 183, 130, 130, 118, 148, 21, 0, 243, 124, 0, 0, 0, 20, 0, 152, 143, 0, 0, 127, 106, 0, 0, 0, 0, 0, 0, 0, 231, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 175, 102, 158, 208, 56, 93, 211, 108, 32, 185, 235, 93, 124, 124, 119, 4, 76, 128, 56, 116, 134, 237, 203, 250, 87, 203, 220, 0, 0, 0, 29, 223, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 177, 241, 15, 134, 219, 208, 188, 84, 22, 19, 21, 134, 0, 78, 68, 189, 127, 154, 21, 21, 144, 1, 234, 73, 181, 22, 83, 167, 138, 234, 240, 47, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 59, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 204, 49, 170, 44, 83, 46, 0 };
|
||||
//public static readonly byte[] MAVLINK_MESSAGE_CRCS = new byte[] { 50, 124, 137, 0, 237, 217, 104, 119, 0, 0, 0, 89, 0, 0, 0, 0, 0, 0, 0, 0, 214, 159, 220, 168, 24, 23, 170, 144, 67, 115, 39, 246, 185, 104, 237, 244, 222, 212, 9, 254, 230, 28, 28, 132, 221, 232, 11, 153, 41, 39, 214, 223, 141, 33, 15, 3, 100, 24, 239, 238, 30, 240, 183, 130, 130, 118, 148, 21, 0, 243, 124, 0, 0, 0, 20, 0, 152, 143, 0, 0, 127, 106, 0, 0, 0, 0, 0, 0, 0, 231, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 175, 102, 158, 208, 56, 93, 211, 108, 32, 185, 235, 93, 124, 124, 119, 4, 76, 128, 56, 116, 134, 237, 203, 250, 87, 203, 220, 0, 0, 0, 29, 223, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 177, 241, 15, 134, 219, 208, 188, 84, 22, 19, 21, 134, 0, 78, 68, 189, 127, 154, 21, 21, 144, 1, 234, 73, 181, 22, 83, 167, 138, 234, 240, 47, 0, 0, 0, 0, 0, 0, 0, 72, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 59, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 204, 49, 170, 44, 83, 46, 0 };
|
||||
public static readonly byte[] MAVLINK_MESSAGE_CRCS = new byte[] { 50, 124, 137, 0, 237, 217, 104, 119, 0, 0, 0, 89, 0, 0, 0, 0, 0, 0, 0, 0, 214, 159, 220, 168, 24, 23, 170, 144, 67, 115, 39, 246, 185, 104, 237, 244, 222, 212, 9, 254, 230, 28, 28, 132, 221, 232, 11, 153, 41, 39, 214, 223, 141, 33, 15, 3, 100, 24, 239, 238, 30, 240, 183, 130, 130, 118, 148, 21, 0, 243, 124, 0, 0, 0, 20, 0, 152, 143, 0, 0, 127, 106, 0, 0, 0, 0, 0, 0, 0, 231, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 175, 102, 158, 208, 56, 93, 211, 108, 32, 185, 235, 93, 124, 124, 119, 4, 76, 128, 56, 116, 134, 237, 203, 250, 87, 203, 220, 0, 0, 0, 29, 223, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 177, 241, 15, 134, 219, 208, 188, 84, 22, 19, 21, 134, 0, 78, 68, 189, 127, 154, 21, 21, 144, 1, 234, 73, 181, 22, 83, 167, 138, 234, 240, 47, 0, 0, 0, 0, 85, 0, 0, 72, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 59, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 204, 49, 170, 44, 83, 46, 0 };
|
||||
//public static readonly byte[] MAVLINK_MESSAGE_CRCS = new byte[] { 50, 124, 137, 0, 237, 217, 104, 119, 0, 0, 0, 89, 0, 0, 0, 0, 0, 0, 0, 0, 214, 159, 220, 168, 24, 23, 170, 144, 67, 115, 39, 246, 185, 104, 237, 244, 222, 212, 9, 254, 230, 28, 28, 132, 221, 232, 11, 153, 41, 39, 214, 223, 141, 33, 15, 3, 100, 24, 239, 238, 30, 240, 183, 130, 130, 118, 148, 21, 0, 243, 124, 0, 0, 0, 20, 0, 152, 143, 0, 0, 127, 106, 0, 0, 0, 0, 0, 0, 0, 231, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 175, 102, 158, 208, 56, 93, 211, 108, 32, 185, 235, 93, 124, 124, 119, 4, 76, 128, 56, 116, 134, 237, 203, 250, 87, 203, 220, 0, 0, 0, 29, 223, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 177, 241, 15, 134, 219, 208, 188, 84, 22, 19, 21, 134, 0, 78, 68, 189, 127, 154, 21, 21, 144, 1, 234, 73, 181, 22, 83, 167, 138, 234, 240, 47, 0, 0, 0, 0, 85, 0, 0, 72, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 59, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 204, 49, 170, 44, 83, 46, 0 };
|
||||
public static readonly byte[] MAVLINK_MESSAGE_CRCS = new byte[] { 50, 124, 137, 0, 237, 217, 104, 119, 0, 0, 0, 89, 0, 0, 0, 0, 0, 0, 0, 0, 214, 159, 220, 168, 24, 23, 170, 144, 67, 115, 39, 246, 185, 104, 237, 244, 222, 212, 9, 254, 230, 28, 28, 132, 221, 232, 11, 153, 41, 39, 214, 223, 141, 33, 15, 3, 100, 24, 239, 238, 30, 240, 183, 130, 130, 118, 148, 21, 0, 243, 124, 0, 0, 0, 20, 0, 152, 143, 0, 0, 127, 106, 0, 0, 0, 0, 0, 0, 0, 231, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 175, 102, 158, 208, 56, 93, 211, 108, 32, 185, 235, 93, 124, 124, 119, 4, 76, 128, 56, 116, 134, 237, 203, 250, 87, 203, 220, 0, 0, 0, 29, 223, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 177, 241, 15, 134, 219, 208, 188, 84, 22, 19, 21, 134, 0, 78, 68, 189, 127, 154, 21, 21, 144, 1, 234, 73, 181, 22, 83, 167, 138, 234, 240, 47, 0, 0, 0, 0, 85, 0, 0, 72, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 59, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 35, 35, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 204, 49, 170, 44, 83, 46, 0 };
|
||||
|
||||
//public static Type[] MAVLINK_MESSAGE_INFO = new Type[] { typeof(mavlink_heartbeat_t), typeof(mavlink_sys_status_t), typeof(mavlink_system_time_t), null, typeof(mavlink_ping_t), typeof(mavlink_change_operator_control_t), typeof(mavlink_change_operator_control_ack_t), typeof(mavlink_auth_key_t), null, null, null, typeof(mavlink_set_mode_t), null, null, null, null, null, null, null, null, typeof(mavlink_param_request_read_t), typeof(mavlink_param_request_list_t), typeof(mavlink_param_value_t), typeof(mavlink_param_set_t), typeof(mavlink_gps_raw_int_t), typeof(mavlink_gps_status_t), typeof(mavlink_scaled_imu_t), typeof(mavlink_raw_imu_t), typeof(mavlink_raw_pressure_t), typeof(mavlink_scaled_pressure_t), typeof(mavlink_attitude_t), typeof(mavlink_attitude_quaternion_t), typeof(mavlink_local_position_ned_t), typeof(mavlink_global_position_int_t), typeof(mavlink_rc_channels_scaled_t), typeof(mavlink_rc_channels_raw_t), typeof(mavlink_servo_output_raw_t), typeof(mavlink_mission_request_partial_list_t), typeof(mavlink_mission_write_partial_list_t), typeof(mavlink_mission_item_t), typeof(mavlink_mission_request_t), typeof(mavlink_mission_set_current_t), typeof(mavlink_mission_current_t), typeof(mavlink_mission_request_list_t), typeof(mavlink_mission_count_t), typeof(mavlink_mission_clear_all_t), typeof(mavlink_mission_item_reached_t), typeof(mavlink_mission_ack_t), typeof(mavlink_set_gps_global_origin_t), typeof(mavlink_gps_global_origin_t), typeof(mavlink_set_local_position_setpoint_t), typeof(mavlink_local_position_setpoint_t), typeof(mavlink_global_position_setpoint_int_t), typeof(mavlink_set_global_position_setpoint_int_t), typeof(mavlink_safety_set_allowed_area_t), typeof(mavlink_safety_allowed_area_t), typeof(mavlink_set_roll_pitch_yaw_thrust_t), typeof(mavlink_set_roll_pitch_yaw_speed_thrust_t), typeof(mavlink_roll_pitch_yaw_thrust_setpoint_t), typeof(mavlink_roll_pitch_yaw_speed_thrust_setpoint_t), typeof(mavlink_set_quad_motors_setpoint_t), typeof(mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t), typeof(mavlink_nav_controller_output_t), typeof(mavlink_set_quad_swarm_led_roll_pitch_yaw_thrust_t), typeof(mavlink_state_correction_t), null, typeof(mavlink_request_data_stream_t), typeof(mavlink_data_stream_t), null, typeof(mavlink_manual_control_t), typeof(mavlink_rc_channels_override_t), null, null, null, typeof(mavlink_vfr_hud_t), null, typeof(mavlink_command_long_t), typeof(mavlink_command_ack_t), null, null, typeof(mavlink_roll_pitch_yaw_rates_thrust_setpoint_t), typeof(mavlink_manual_setpoint_t), null, null, null, null, null, null, null, typeof(mavlink_local_position_ned_system_global_offset_t), typeof(mavlink_hil_state_t), typeof(mavlink_hil_controls_t), typeof(mavlink_hil_rc_inputs_raw_t), null, null, null, null, null, null, null, typeof(mavlink_optical_flow_t), typeof(mavlink_global_vision_position_estimate_t), typeof(mavlink_vision_position_estimate_t), typeof(mavlink_vision_speed_estimate_t), typeof(mavlink_vicon_position_estimate_t), typeof(mavlink_highres_imu_t), null, null, null, null, typeof(mavlink_file_transfer_start_t), typeof(mavlink_file_transfer_dir_list_t), typeof(mavlink_file_transfer_res_t), null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, typeof(mavlink_battery_status_t), typeof(mavlink_setpoint_8dof_t), typeof(mavlink_setpoint_6dof_t), typeof(mavlink_sensor_offsets_t), typeof(mavlink_set_mag_offsets_t), typeof(mavlink_meminfo_t), typeof(mavlink_ap_adc_t), typeof(mavlink_digicam_configure_t), typeof(mavlink_digicam_control_t), typeof(mavlink_mount_configure_t), typeof(mavlink_mount_control_t), typeof(mavlink_mount_status_t), null, typeof(mavlink_fence_point_t), typeof(mavlink_fence_fetch_point_t), typeof(mavlink_fence_status_t), typeof(mavlink_ahrs_t), typeof(mavlink_simstate_t), typeof(mavlink_hwstatus_t), typeof(mavlink_radio_t), typeof(mavlink_limits_status_t), typeof(mavlink_wind_t), typeof(mavlink_data16_t), typeof(mavlink_data32_t), typeof(mavlink_data64_t), typeof(mavlink_data96_t), typeof(mavlink_rangefinder_t), null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, typeof(mavlink_rc_mobile_control_t), typeof(mavlink_set_pair_t), null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, typeof(mavlink_memory_vect_t), typeof(mavlink_debug_vect_t), typeof(mavlink_named_value_float_t), typeof(mavlink_named_value_int_t), typeof(mavlink_statustext_t), typeof(mavlink_debug_t), null };
|
||||
public static Type[] MAVLINK_MESSAGE_INFO = new Type[] { typeof(mavlink_heartbeat_t), typeof(mavlink_sys_status_t), typeof(mavlink_system_time_t), null, typeof(mavlink_ping_t), typeof(mavlink_change_operator_control_t), typeof(mavlink_change_operator_control_ack_t), typeof(mavlink_auth_key_t), null, null, null, typeof(mavlink_set_mode_t), null, null, null, null, null, null, null, null, typeof(mavlink_param_request_read_t), typeof(mavlink_param_request_list_t), typeof(mavlink_param_value_t), typeof(mavlink_param_set_t), typeof(mavlink_gps_raw_int_t), typeof(mavlink_gps_status_t), typeof(mavlink_scaled_imu_t), typeof(mavlink_raw_imu_t), typeof(mavlink_raw_pressure_t), typeof(mavlink_scaled_pressure_t), typeof(mavlink_attitude_t), typeof(mavlink_attitude_quaternion_t), typeof(mavlink_local_position_ned_t), typeof(mavlink_global_position_int_t), typeof(mavlink_rc_channels_scaled_t), typeof(mavlink_rc_channels_raw_t), typeof(mavlink_servo_output_raw_t), typeof(mavlink_mission_request_partial_list_t), typeof(mavlink_mission_write_partial_list_t), typeof(mavlink_mission_item_t), typeof(mavlink_mission_request_t), typeof(mavlink_mission_set_current_t), typeof(mavlink_mission_current_t), typeof(mavlink_mission_request_list_t), typeof(mavlink_mission_count_t), typeof(mavlink_mission_clear_all_t), typeof(mavlink_mission_item_reached_t), typeof(mavlink_mission_ack_t), typeof(mavlink_set_gps_global_origin_t), typeof(mavlink_gps_global_origin_t), typeof(mavlink_set_local_position_setpoint_t), typeof(mavlink_local_position_setpoint_t), typeof(mavlink_global_position_setpoint_int_t), typeof(mavlink_set_global_position_setpoint_int_t), typeof(mavlink_safety_set_allowed_area_t), typeof(mavlink_safety_allowed_area_t), typeof(mavlink_set_roll_pitch_yaw_thrust_t), typeof(mavlink_set_roll_pitch_yaw_speed_thrust_t), typeof(mavlink_roll_pitch_yaw_thrust_setpoint_t), typeof(mavlink_roll_pitch_yaw_speed_thrust_setpoint_t), typeof(mavlink_set_quad_motors_setpoint_t), typeof(mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t), typeof(mavlink_nav_controller_output_t), typeof(mavlink_set_quad_swarm_led_roll_pitch_yaw_thrust_t), typeof(mavlink_state_correction_t), null, typeof(mavlink_request_data_stream_t), typeof(mavlink_data_stream_t), null, typeof(mavlink_manual_control_t), typeof(mavlink_rc_channels_override_t), null, null, null, typeof(mavlink_vfr_hud_t), null, typeof(mavlink_command_long_t), typeof(mavlink_command_ack_t), null, null, typeof(mavlink_roll_pitch_yaw_rates_thrust_setpoint_t), typeof(mavlink_manual_setpoint_t), null, null, null, null, null, null, null, typeof(mavlink_local_position_ned_system_global_offset_t), typeof(mavlink_hil_state_t), typeof(mavlink_hil_controls_t), typeof(mavlink_hil_rc_inputs_raw_t), null, null, null, null, null, null, null, typeof(mavlink_optical_flow_t), typeof(mavlink_global_vision_position_estimate_t), typeof(mavlink_vision_position_estimate_t), typeof(mavlink_vision_speed_estimate_t), typeof(mavlink_vicon_position_estimate_t), typeof(mavlink_highres_imu_t), null, null, null, null, typeof(mavlink_file_transfer_start_t), typeof(mavlink_file_transfer_dir_list_t), typeof(mavlink_file_transfer_res_t), null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, typeof(mavlink_battery_status_t), typeof(mavlink_setpoint_8dof_t), typeof(mavlink_setpoint_6dof_t), typeof(mavlink_sensor_offsets_t), typeof(mavlink_set_mag_offsets_t), typeof(mavlink_meminfo_t), typeof(mavlink_ap_adc_t), typeof(mavlink_digicam_configure_t), typeof(mavlink_digicam_control_t), typeof(mavlink_mount_configure_t), typeof(mavlink_mount_control_t), typeof(mavlink_mount_status_t), null, typeof(mavlink_fence_point_t), typeof(mavlink_fence_fetch_point_t), typeof(mavlink_fence_status_t), typeof(mavlink_ahrs_t), typeof(mavlink_simstate_t), typeof(mavlink_hwstatus_t), typeof(mavlink_radio_t), typeof(mavlink_limits_status_t), typeof(mavlink_wind_t), typeof(mavlink_data16_t), typeof(mavlink_data32_t), typeof(mavlink_data64_t), typeof(mavlink_data96_t), typeof(mavlink_rangefinder_t), null, null, null, null, null, null, null, null, null, null, null, null, typeof(mavlink_msg_id_led_control), null, null, null, null, null, null, null, null, null, null, null, null, null, typeof(mavlink_rc_mobile_control_t), typeof(mavlink_set_pair_t), null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, typeof(mavlink_memory_vect_t), typeof(mavlink_debug_vect_t), typeof(mavlink_named_value_float_t), typeof(mavlink_named_value_int_t), typeof(mavlink_statustext_t), typeof(mavlink_debug_t), null };
|
||||
|
||||
@ -3079,6 +3081,20 @@ namespace Plane.Protocols
|
||||
public Int16 version;
|
||||
}
|
||||
|
||||
public const byte MAVLINK_MSG_ID_GPS_RTCM_DATA = 233;
|
||||
[StructLayout(LayoutKind.Sequential, Pack = 1, Size = 182)]
|
||||
///<summary> RTCM message for injecting into the onboard GPS (used for DGPS) </summary>
|
||||
public struct mavlink_gps_rtcm_data_t
|
||||
{
|
||||
/// <summary> LSB: 1 means message is fragmented, next 2 bits are the fragment ID, the remaining 5 bits are used for the sequence ID. Messages are only to be flushed to the GPS when the entire message has been reconstructed on the autopilot. The fragment ID specifies which order the fragments should be assembled into a buffer, while the sequence ID is used to detect a mismatch between different buffers. The buffer is considered fully reconstructed when either all 4 fragments are present, or all the fragments before the first fragment with a non full payload is received. This management is used to ensure that normal GPS operation doesn't corrupt RTCM data, and to recover from a unreliable transport delivery order. </summary>
|
||||
public byte flags;
|
||||
/// <summary> data length </summary>
|
||||
public byte len;
|
||||
/// <summary> RTCM message (may be fragmented) </summary>
|
||||
[MarshalAs(UnmanagedType.ByValArray, SizeConst = 180)]
|
||||
public byte[] data;
|
||||
|
||||
};
|
||||
|
||||
public const byte MAVLINK_MSG_ID_MEMORY_VECT = 249;
|
||||
[StructLayout(LayoutKind.Sequential, Pack = 1, Size = 36)]
|
||||
|
@ -84,21 +84,6 @@ namespace Plane.Protocols
|
||||
/// </summary>
|
||||
public const short COMM_UPDATE_COPTER_MODULE = 0xFD;
|
||||
|
||||
/// <summary>
|
||||
/// 修改飞机回传功率
|
||||
/// </summary>
|
||||
public const short COMM_SET_BACK_POWER = 0x00FA;
|
||||
|
||||
/// <summary>
|
||||
/// 读取当前配置信息
|
||||
/// </summary>
|
||||
public const short COMM_GET_CURR_SYS_PARM = 0x00CC;
|
||||
|
||||
/// <summary>
|
||||
/// 改写当前配置信息
|
||||
/// </summary>
|
||||
public const short COMM_SET_CURR_SYS_PARM = 0x00EC;
|
||||
|
||||
#endregion
|
||||
|
||||
public enum CommMode
|
||||
|
Loading…
Reference in New Issue
Block a user