优化通讯数据,为了更多的飞机
This commit is contained in:
parent
6a18c8ac4e
commit
b09020f8ff
@ -53,8 +53,16 @@ namespace Plane.Communication
|
|||||||
|
|
||||||
public void Open()
|
public void Open()
|
||||||
{
|
{
|
||||||
_port.Open();
|
try
|
||||||
_internalIsOpen = true;
|
{
|
||||||
|
_port.Open();
|
||||||
|
_internalIsOpen = true;
|
||||||
|
}
|
||||||
|
catch (Exception ex)
|
||||||
|
{
|
||||||
|
RaiseExceptionThrown(ex);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -22,7 +22,7 @@ namespace Plane.Copters
|
|||||||
{
|
{
|
||||||
switch (StreamType)
|
switch (StreamType)
|
||||||
{
|
{
|
||||||
case MAVLINK_MSG_ID_GPS_RAW_INT:
|
case MAVLINK_MSG_ID_GPS_RAW_INT: //需要
|
||||||
{
|
{
|
||||||
Latitude = _internalCopter.lat;
|
Latitude = _internalCopter.lat;
|
||||||
Longitude = _internalCopter.lng;
|
Longitude = _internalCopter.lng;
|
||||||
@ -41,7 +41,7 @@ namespace Plane.Copters
|
|||||||
|
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case MAVLINK_MSG_ID_ATTITUDE:
|
case MAVLINK_MSG_ID_ATTITUDE: //无用
|
||||||
{
|
{
|
||||||
Roll = _internalCopter.roll;
|
Roll = _internalCopter.roll;
|
||||||
Pitch = _internalCopter.pitch;
|
Pitch = _internalCopter.pitch;
|
||||||
@ -51,7 +51,7 @@ namespace Plane.Copters
|
|||||||
|
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case MAVLINK_MSG_ID_RC_CHANNELS_RAW:
|
case MAVLINK_MSG_ID_RC_CHANNELS_RAW: //只用于显示,可以不要
|
||||||
{
|
{
|
||||||
Channel1 = _internalCopter.ch1in;
|
Channel1 = _internalCopter.ch1in;
|
||||||
Channel2 = _internalCopter.ch2in;
|
Channel2 = _internalCopter.ch2in;
|
||||||
@ -68,10 +68,10 @@ namespace Plane.Copters
|
|||||||
}
|
}
|
||||||
case MAVLINK_MSG_ID_VFR_HUD:
|
case MAVLINK_MSG_ID_VFR_HUD:
|
||||||
{
|
{
|
||||||
Heading = _internalCopter.heading;
|
Heading = _internalCopter.heading; //有用
|
||||||
Altitude = _internalCopter.alt;
|
Altitude = _internalCopter.alt; //有用
|
||||||
AirSpeed = _internalCopter.airspeed;
|
AirSpeed = _internalCopter.airspeed; //没用
|
||||||
GroundSpeed = _internalCopter.groundspeed;
|
GroundSpeed = _internalCopter.groundspeed; //没用
|
||||||
|
|
||||||
RaiseAltitudeChangedIfNeeded();
|
RaiseAltitudeChangedIfNeeded();
|
||||||
|
|
||||||
@ -84,7 +84,7 @@ namespace Plane.Copters
|
|||||||
{
|
{
|
||||||
IsUnlocked = _internalCopter.armed;
|
IsUnlocked = _internalCopter.armed;
|
||||||
Mode = (FlightMode)_internalCopter.mode;
|
Mode = (FlightMode)_internalCopter.mode;
|
||||||
// 林俊清, 20160311, 亿航将闲置的 apname 用作已经切过 GPS 模式的标志。
|
// 林俊清, 20160311, 将闲置的 apname 用作已经切过 GPS 模式的标志。
|
||||||
HasSwitchedToGpsMode = (byte)_internalCopter.apname != 0;
|
HasSwitchedToGpsMode = (byte)_internalCopter.apname != 0;
|
||||||
++HeartbeatCount;
|
++HeartbeatCount;
|
||||||
|
|
||||||
|
@ -130,12 +130,21 @@ namespace Plane.Copters
|
|||||||
|
|
||||||
public async Task GetCopterDataAsync()
|
public async Task GetCopterDataAsync()
|
||||||
{
|
{
|
||||||
await RequestDatastreamAsync(MAVLink.MAV_DATA_STREAM.EXTENDED_STATUS, 10).ConfigureAwait(false); //1电池电压、电流、电量,152-内存、62-导航控制输出、24-GPS数据、42-航点数据
|
//停止所有数据流
|
||||||
await RequestDatastreamAsync(MAVLink.MAV_DATA_STREAM.EXTRA1, 5).ConfigureAwait(false); // 请求 飞行姿态 roll、pitch、yaw、rollspeed、pitchspeed、yawspeed--- 30
|
await StopGetDatastreamAsync(MAVLink.MAV_DATA_STREAM.ALL, 0).ConfigureAwait(false);
|
||||||
await RequestDatastreamAsync(MAVLink.MAV_DATA_STREAM.EXTRA2, 10).ConfigureAwait(false); // 请求vfr airspeed(空速)、groundspeed(地速)、alt(高度)、climb(爬升率)、heading(头朝向)、throttle(实际油门) ---74
|
//需要电池电压,电流,GPS数据
|
||||||
await RequestDatastreamAsync(MAVLink.MAV_DATA_STREAM.RC_CHANNELS, 1).ConfigureAwait(false); // 请求 通道数据
|
|
||||||
await RequestDatastreamAsync(MAVLink.MAV_DATA_STREAM.RAW_SENSORS, ratesensors).ConfigureAwait(false); // 请求 传感器原始值
|
|
||||||
|
|
||||||
|
await RequestDatastreamAsync(MAVLink.MAV_DATA_STREAM.EXTENDED_STATUS, 5).ConfigureAwait(false); //10 1电池电压、电流、电量,152-内存、62-导航控制输出、24-GPS数据、42-航点数据
|
||||||
|
//不需要姿态信息
|
||||||
|
// await RequestDatastreamAsync(MAVLink.MAV_DATA_STREAM.EXTRA1, 1).ConfigureAwait(false); //5 请求 飞行姿态 roll、pitch、yaw、rollspeed、pitchspeed、yawspeed--- 30
|
||||||
|
//需要高度和机头朝向数据
|
||||||
|
await RequestDatastreamAsync(MAVLink.MAV_DATA_STREAM.EXTRA2, 5).ConfigureAwait(false); //10 请求vfr airspeed(空速)、groundspeed(地速)、alt(高度)、climb(爬升率)、heading(头朝向)、throttle(实际油门) ---74
|
||||||
|
//不需要通道数据
|
||||||
|
//await RequestDatastreamAsync(MAVLink.MAV_DATA_STREAM.RC_CHANNELS, 1).ConfigureAwait(false); //1 请求 通道数据
|
||||||
|
//不需要原始数据
|
||||||
|
// await RequestDatastreamAsync(MAVLink.MAV_DATA_STREAM.RAW_SENSORS, ratesensors).ConfigureAwait(false); // 请求 传感器原始值
|
||||||
|
|
||||||
|
/* //已经停止所有数据了,不用单独停止
|
||||||
// Disable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, NAV_CONTROLLER_OUTPUT. |
|
// Disable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, NAV_CONTROLLER_OUTPUT. |
|
||||||
await StopGetDatastreamAsync(MAVLink.MAV_DATA_STREAM.RAW_CONTROLLER, 0).ConfigureAwait(false);
|
await StopGetDatastreamAsync(MAVLink.MAV_DATA_STREAM.RAW_CONTROLLER, 0).ConfigureAwait(false);
|
||||||
// Disable LOCAL_POSITION, GLOBAL_POSITION/GLOBAL_POSITION_INT messages. |
|
// Disable LOCAL_POSITION, GLOBAL_POSITION/GLOBAL_POSITION_INT messages. |
|
||||||
@ -144,6 +153,12 @@ namespace Plane.Copters
|
|||||||
await StopGetDatastreamAsync(MAVLink.MAV_DATA_STREAM.EXTRA3, 0).ConfigureAwait(false);
|
await StopGetDatastreamAsync(MAVLink.MAV_DATA_STREAM.EXTRA3, 0).ConfigureAwait(false);
|
||||||
// Disable Plane Stream
|
// Disable Plane Stream
|
||||||
await StopGetDatastreamAsync(MAVLink.MAV_DATA_STREAM.GHOST_STREAM, 0).ConfigureAwait(false);
|
await StopGetDatastreamAsync(MAVLink.MAV_DATA_STREAM.GHOST_STREAM, 0).ConfigureAwait(false);
|
||||||
|
// Disable RAW_SENSORS
|
||||||
|
await StopGetDatastreamAsync(MAVLink.MAV_DATA_STREAM.RAW_SENSORS, 0).ConfigureAwait(false); //
|
||||||
|
// 5 Disable MSG_ATTITUDE roll、pitch、yaw、rollspeed、pitchspeed、yawspeed-- - 30
|
||||||
|
await StopGetDatastreamAsync(MAVLink.MAV_DATA_STREAM.EXTRA1, 0).ConfigureAwait(false); //
|
||||||
|
*/
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
private async void StartCommunication()
|
private async void StartCommunication()
|
||||||
@ -178,7 +193,7 @@ namespace Plane.Copters
|
|||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
// if (heatbeatSend.Second != DateTime.Now.Second)
|
// if (heatbeatSend.Second != DateTime.Now.Second)
|
||||||
if (heatbeatSend.AddMilliseconds(200) <= DateTime.Now)
|
if (heatbeatSend.AddMilliseconds(1000) <= DateTime.Now)
|
||||||
{
|
{
|
||||||
var htb = new MAVLink.mavlink_heartbeat_t()
|
var htb = new MAVLink.mavlink_heartbeat_t()
|
||||||
{
|
{
|
||||||
@ -232,29 +247,40 @@ namespace Plane.Copters
|
|||||||
{
|
{
|
||||||
PacketReceived?.Invoke(this, new PacketReceivedEventArgs(packet));
|
PacketReceived?.Invoke(this, new PacketReceivedEventArgs(packet));
|
||||||
var handled = true;
|
var handled = true;
|
||||||
|
Debug.WriteLine(packet[5],"收到数据类型");
|
||||||
switch (packet[5])
|
switch (packet[5])
|
||||||
{
|
{
|
||||||
case MAVLink.MAVLINK_MSG_ID_HEARTBEAT: //0
|
case MAVLink.MAVLINK_MSG_ID_HEARTBEAT: //0
|
||||||
AnalyzeHeartbeatPacket(packet);
|
AnalyzeHeartbeatPacket(packet);
|
||||||
break;
|
break;
|
||||||
case MAVLink.MAVLINK_MSG_ID_RADIO:
|
case MAVLink.MAVLINK_MSG_ID_SYS_STATUS: //1
|
||||||
|
AnalyzeSysStatusPacket(packet);
|
||||||
|
break;
|
||||||
|
case MAVLink.MAVLINK_MSG_ID_GPS_RAW_INT: //24
|
||||||
|
AnalyzeGpsRawIntPacket(packet);
|
||||||
|
break;
|
||||||
|
case MAVLink.MAVLINK_MSG_ID_VFR_HUD: //74
|
||||||
|
AnalyzeVfrHudPacket(packet);
|
||||||
|
break;
|
||||||
|
case MAVLink.MAVLINK_MSG_ID_STATUSTEXT: //253
|
||||||
|
AnalyzeStatusTextPacket(packet);
|
||||||
|
break;
|
||||||
|
|
||||||
|
////以上为基本数据,
|
||||||
|
|
||||||
|
case MAVLink.MAVLINK_MSG_ID_RADIO: //109
|
||||||
AnalyzeRadioPacket(packet);
|
AnalyzeRadioPacket(packet);
|
||||||
break;
|
break;
|
||||||
case MAVLink.MAVLINK_MSG_ID_PARAM_VALUE: //22
|
case MAVLink.MAVLINK_MSG_ID_PARAM_VALUE: //22
|
||||||
AnalyzeParamValuePacket(packet);
|
AnalyzeParamValuePacket(packet);
|
||||||
break;
|
break;
|
||||||
case MAVLink.MAVLINK_MSG_ID_SYS_STATUS: //1
|
|
||||||
AnalyzeSysStatusPacket(packet);
|
|
||||||
break;
|
|
||||||
case MAVLink.MAVLINK_MSG_ID_MEMINFO: //152
|
case MAVLink.MAVLINK_MSG_ID_MEMINFO: //152
|
||||||
AnalyzeMemInfoPacket(packet);
|
AnalyzeMemInfoPacket(packet);
|
||||||
break;
|
break;
|
||||||
case MAVLink.MAVLINK_MSG_ID_MISSION_CURRENT: //42
|
case MAVLink.MAVLINK_MSG_ID_MISSION_CURRENT: //42
|
||||||
AnalyzeMissionCurrentPacket(packet);
|
AnalyzeMissionCurrentPacket(packet);
|
||||||
break;
|
break;
|
||||||
case MAVLink.MAVLINK_MSG_ID_GPS_RAW_INT: //24
|
|
||||||
AnalyzeGpsRawIntPacket(packet);
|
|
||||||
break;
|
|
||||||
case MAVLink.MAVLINK_MSG_ID_GLOBAL_POSITION_INT: //33
|
case MAVLink.MAVLINK_MSG_ID_GLOBAL_POSITION_INT: //33
|
||||||
AnalyzeGlobalPositionIntPacket(packet);
|
AnalyzeGlobalPositionIntPacket(packet);
|
||||||
break;
|
break;
|
||||||
@ -264,24 +290,20 @@ namespace Plane.Copters
|
|||||||
case MAVLink.MAVLINK_MSG_ID_ATTITUDE: //30
|
case MAVLink.MAVLINK_MSG_ID_ATTITUDE: //30
|
||||||
AnalyzeAttitudePacket(packet);
|
AnalyzeAttitudePacket(packet);
|
||||||
break;
|
break;
|
||||||
case MAVLink.MAVLINK_MSG_ID_VFR_HUD: //74
|
|
||||||
AnalyzeVfrHudPacket(packet);
|
|
||||||
break;
|
|
||||||
case MAVLink.MAVLINK_MSG_ID_RC_CHANNELS_RAW: //35
|
case MAVLink.MAVLINK_MSG_ID_RC_CHANNELS_RAW: //35
|
||||||
AnalyzeRCChannelsRawPacket(packet);
|
AnalyzeRCChannelsRawPacket(packet);
|
||||||
break;
|
break;
|
||||||
case MAVLink.MAVLINK_MSG_ID_RAW_IMU:
|
case MAVLink.MAVLINK_MSG_ID_RAW_IMU: //没有用27
|
||||||
AnalyzeRawImuPacket(packet);
|
AnalyzeRawImuPacket(packet);
|
||||||
break;
|
break;
|
||||||
case MAVLink.MAVLINK_MSG_ID_SCALED_IMU2:
|
case MAVLink.MAVLINK_MSG_ID_SCALED_IMU2: //没有用 116
|
||||||
AnalyzeScaledImu2Packet(packet);
|
AnalyzeScaledImu2Packet(packet);
|
||||||
break;
|
break;
|
||||||
case MAVLink.MAVLINK_MSG_ID_SENSOR_OFFSETS:
|
case MAVLink.MAVLINK_MSG_ID_SENSOR_OFFSETS: //150
|
||||||
AnalyzeSensorOffsetsPacket(packet);
|
AnalyzeSensorOffsetsPacket(packet);
|
||||||
break;
|
break;
|
||||||
case MAVLink.MAVLINK_MSG_ID_STATUSTEXT:
|
|
||||||
AnalyzeStatusTextPacket(packet);
|
|
||||||
break;
|
|
||||||
default:
|
default:
|
||||||
handled = false;
|
handled = false;
|
||||||
UnhandledPacketReceived?.Invoke(this, new PacketReceivedEventArgs(packet));
|
UnhandledPacketReceived?.Invoke(this, new PacketReceivedEventArgs(packet));
|
||||||
|
Loading…
Reference in New Issue
Block a user