为了减小通讯,不发心跳包,有通道包,rtk包等,不发心跳也没问题
批量设置参数有问题,临时提交 降低通道发送频率为2次/秒
This commit is contained in:
parent
22b8f46359
commit
471f0ba872
@ -170,6 +170,7 @@ namespace Plane.Copters
|
|||||||
await Task.Delay(_intervalToUpdateFlightTimeSpan).ConfigureAwait(false);
|
await Task.Delay(_intervalToUpdateFlightTimeSpan).ConfigureAwait(false);
|
||||||
}
|
}
|
||||||
});
|
});
|
||||||
|
|
||||||
Task.Run(async () =>
|
Task.Run(async () =>
|
||||||
{
|
{
|
||||||
while (true)
|
while (true)
|
||||||
@ -182,9 +183,10 @@ namespace Plane.Copters
|
|||||||
{
|
{
|
||||||
StatusText = null;
|
StatusText = null;
|
||||||
}
|
}
|
||||||
await Task.Delay(50);
|
await Task.Delay(500); //50
|
||||||
}
|
}
|
||||||
});
|
});
|
||||||
|
|
||||||
Task.Run(async () =>
|
Task.Run(async () =>
|
||||||
{
|
{
|
||||||
var lastHeartbeatCount = HeartbeatCount;
|
var lastHeartbeatCount = HeartbeatCount;
|
||||||
|
@ -221,11 +221,15 @@ namespace Plane.Copters
|
|||||||
var stopwatch = Stopwatch.StartNew();
|
var stopwatch = Stopwatch.StartNew();
|
||||||
while (true)
|
while (true)
|
||||||
{
|
{
|
||||||
for (int ii = 0; ii < 5; ii++)
|
/* for (int ii = 0; ii < 5; ii++)
|
||||||
{
|
{
|
||||||
await _internalCopter.SetParam2Async(paramName, paramValue).ConfigureAwait(false);
|
await _internalCopter.SetParam2Async(paramName, paramValue).ConfigureAwait(false);
|
||||||
await Task.Delay(5).ConfigureAwait(false);
|
await Task.Delay(5).ConfigureAwait(false);
|
||||||
}
|
}
|
||||||
|
*/
|
||||||
|
|
||||||
|
await _internalCopter.SetParam2Async(paramName, paramValue).ConfigureAwait(false);
|
||||||
|
await Task.Delay(5).ConfigureAwait(false);
|
||||||
|
|
||||||
int i = 0;
|
int i = 0;
|
||||||
try
|
try
|
||||||
@ -235,7 +239,7 @@ namespace Plane.Copters
|
|||||||
// await Task.Delay(5).ConfigureAwait(false);
|
// await Task.Delay(5).ConfigureAwait(false);
|
||||||
//}
|
//}
|
||||||
|
|
||||||
if (await _internalCopter.GetParamAsync(paramName, 1000) == paramValue)
|
// if (await _internalCopter.GetParamAsync(paramName, millisecondsTimeout) == paramValue)
|
||||||
{
|
{
|
||||||
i = 1;
|
i = 1;
|
||||||
}
|
}
|
||||||
|
@ -212,7 +212,7 @@ namespace Plane.Copters
|
|||||||
autopilot = (byte)MAVLink.MAV_AUTOPILOT.GENERIC,
|
autopilot = (byte)MAVLink.MAV_AUTOPILOT.GENERIC,
|
||||||
mavlink_version = 3,
|
mavlink_version = 3,
|
||||||
};
|
};
|
||||||
await SendPacketAsync(htb).ConfigureAwait(false); //发心跳包
|
// await SendPacketAsync(htb).ConfigureAwait(false); //发心跳包
|
||||||
#if DEBUG && LOG_PACKETS
|
#if DEBUG && LOG_PACKETS
|
||||||
if (!_sendHeartbeatStopwatch.IsRunning)
|
if (!_sendHeartbeatStopwatch.IsRunning)
|
||||||
{
|
{
|
||||||
|
Loading…
Reference in New Issue
Block a user