[fix] 退出异常调整测试灯光

详细描述

# 类型 包含:
# feat:新功能(feature)
# fix:修补bug
# docs:文档(documentation)
# style: 格式(不影响代码运行的变动)
# refactor:重构(即不是新增功能,也不是修改bug的代码变动)
# test:增加测试
# chore:构建过程或辅助工具的变动
This commit is contained in:
xu 2024-07-02 15:00:29 +08:00
parent ffb95b2e7d
commit 8af733e644
4 changed files with 48 additions and 77 deletions

View File

@ -80,7 +80,8 @@ namespace Plane.Communication
var connectTask = _client.ConnectAsync(_remoteHostname, _remotePort);
if (await Task.WhenAny(connectTask, Task.Delay(5000)) == connectTask)
{
await connectTask.ConfigureAwait(false);
if (_client.Client != null) //需要测试
await connectTask.ConfigureAwait(false);
}
else
{
@ -91,15 +92,27 @@ namespace Plane.Communication
catch (SocketException e)
{
logstr = e.Message;
CloseClient(); // 关闭并清理客户端
}
catch (ObjectDisposedException)
{
CloseClient(); // 关闭并清理客户端
}
catch (Exception)
{
CloseClient(); // 处理其他可能的异常
// throw; // 可选:重新抛出异常,以便调用者知道发生了错误
}
_isBroken = false;
}
_stream = _client.GetStream();
if (_client != null)
_stream = _client.GetStream();
}
private void CloseClient()
{
_client?.Close(); // 如果 _client 不为 null则关闭连接
_client = null; // 将 _client 设置为 null以便垃圾回收器可以回收它
}
private void CreateClientAndConnect()
{

View File

@ -46,7 +46,7 @@ namespace Plane.Communication
// bool bret ;
// bret = _client.Client != null;
// bret = bret && !((_client.Client.Poll(1000, SelectMode.SelectRead) && (_client.Client.Available == 0)) || !_client.Client.Connected);
return _client.Client != null && !((_client.Client.Poll(1000, SelectMode.SelectRead) && (_client.Client.Available == 0)) || !_client.Client.Connected);
return _client != null && _client.Client != null && !((_client.Client.Poll(1000, SelectMode.SelectRead) && (_client.Client.Available == 0)) || !_client.Client.Connected);
}
catch (ObjectDisposedException)
{

View File

@ -439,72 +439,17 @@ namespace Plane.CommunicationManagement
//测试用 灯光间隔1S闪烁
public async Task TestLED(short id, string colorString)
{
MAVLink.mavlink_msg_id_led_control led = new MAVLink.mavlink_msg_id_led_control();
led.target_system = 1;
led.target_component = 1;//(byte)MAVLink.MAV_COMPONENT.MAV_COMP_ID_SYSTEM_CONTROL;;
led.instance = 0;
led.pattern = 0;
led.custom_len = 4; //命令类型——测试灯光
led.custom_bytes = new byte[24];
if (colorString == "") colorString = "330033";
Color color = (Color)ColorConverter.ConvertFromString("#" + colorString);
led.custom_bytes[0] = color.R;
led.custom_bytes[1] = color.G;
led.custom_bytes[2] = color.B;
led.custom_bytes[3] = 3;
byte[] data;
data = MavlinkUtil.StructureToByteArray(led);
byte[] packet = new byte[data.Length + 6 + 2];
packet[0] = MAVLink.MAVLINK_STX;
packet[1] = (byte)(data.Length);
packet[2] = 1;
packet[3] = 255; // this is always 255 - MYGCS
packet[4] = (byte)MAVLink.MAV_COMPONENT.MAV_COMP_ID_MISSIONPLANNER;
packet[5] = MAVLink.MAVLINK_MSG_ID_LED_CONTROL;
int i = 6;
foreach (byte b in data)
{
packet[i] = b;
i++;
}
ushort checksum = MavlinkCRC.crc_calculate(packet, packet[1] + 6);
checksum = MavlinkCRC.crc_accumulate(MAVLink.MAVLINK_MESSAGE_CRCS[MAVLink.MAVLINK_MSG_ID_LED_CONTROL], checksum);
byte ck_a = (byte)(checksum & 0xFF); ///< High byte
byte ck_b = (byte)(checksum >> 8); ///< Low byte
packet[i] = ck_a;
i += 1;
packet[i] = ck_b;
i += 1;
//await WriteCommPacketAsync(id, MavComm.COMM_DOWNLOAD_COMM, packet);
byte[] senddata = packet;
// for (int times = 0; times < 14; times++)
// {
// senddata = senddata.Concat(packet).ToArray();
// }
// byte[] myByteArray = Enumerable.Repeat((byte)0x08, 15).ToArray();
//
// senddata = senddata.Concat(myByteArray).ToArray();
byte[] packet = DoLEDCommandAsync(51, 0, 51);
temp = !temp;
while (temp)
{
Message.Show("测试灯光,长度 = " + senddata.Length);
await WriteCommPacketAsync(id, MavComm.COMM_DOWNLOAD_COMM, senddata);
Message.Show("发送测试灯光");
await WriteCommPacketAsync(id, MavComm.COMM_DOWNLOAD_COMM, packet);
//如果是广播同时发送到广播端口
if ((id==0)&& Recomisopen)
{
await BroadcastSendAsync(packet);
}
await Task.Delay(1000).ConfigureAwait(false);
}
}

View File

@ -22,7 +22,21 @@ namespace Plane.CommunicationManagement
private bool starttime = false;
private bool rtcm_run = false;
private SerialPort RecomPort;
public bool Recomisopen = false;
// public bool Recomisopen = false;
private bool _Recomisopen = false;
public bool Recomisopen
{
get { return _Recomisopen; }
set
{
if (_Recomisopen != value)
{
_Recomisopen = value;
//_RtcmInfoViewModel.SetRTKStatestr();
}
}
}
private IEnumerable<ICopter> _allcopters;
@ -191,7 +205,7 @@ namespace Plane.CommunicationManagement
return GeneratePacket(MAVLink.MAVLINK_MSG_ID_PARAM_REQUEST_READ, req);
}
private byte[] DoLEDCommandAsync()
private byte[] DoLEDCommandAsync(byte red,byte green,byte blue)
{
MAVLink.mavlink_msg_id_led_control led = new MAVLink.mavlink_msg_id_led_control();
led.target_system = 1;
@ -200,11 +214,10 @@ namespace Plane.CommunicationManagement
led.pattern = 0;
led.custom_len = 4;
led.custom_bytes = new byte[24];
led.custom_bytes[0] = 255;
led.custom_bytes[1] = 255;
led.custom_bytes[2] = 255;
led.custom_bytes[3] = 3;
led.custom_bytes[0] = red;
led.custom_bytes[1] = green;
led.custom_bytes[2] = blue;
led.custom_bytes[3] = 3; //持续亮的时间=1/3hz=0.33s
return GeneratePacket(MAVLink.MAVLINK_MSG_ID_LED_CONTROL, led);
}
private byte[] DoThrowoutCommandAsync()
@ -623,7 +636,7 @@ namespace Plane.CommunicationManagement
byte[] batchPacket = null;
GetCopterIds(copters, out copterId, out batchPacket);
byte[] packet = DoLEDCommandAsync();
byte[] packet = DoLEDCommandAsync(255,255,255);
await WriteCommPacketAsync(copterId, MavComm.COMM_DOWNLOAD_COMM, packet, batchPacket).ConfigureAwait(false);
if (Recomisopen&&(copters == null))
await BroadcastSendAsync(packet);
@ -1469,7 +1482,7 @@ namespace Plane.CommunicationManagement
await Task.Delay(1);
}
string last_reserialport="";
public string last_reserialport ="";
public void ReOpenRtcmserial()
{
CloseResendRtcmserial();
@ -1506,7 +1519,6 @@ namespace Plane.CommunicationManagement
public bool OpenResendRtcmserial(string reserialport)
{
last_reserialport = reserialport;
RecomPort = new SerialPort(reserialport);
RecomPort.BaudRate = 57600;
RecomPort.Parity = Parity.None;
@ -1520,6 +1532,7 @@ namespace Plane.CommunicationManagement
{
RecomPort.Open();
Recomisopen = true;
last_reserialport = reserialport;
}
catch (Exception ex)
{