Skip to content

Commit

Permalink
MAVFtp: speedup uploads #3229
Browse files Browse the repository at this point in the history
  • Loading branch information
meee1 committed Jan 9, 2025
1 parent 491f4fa commit 686f77d
Showing 1 changed file with 22 additions and 14 deletions.
36 changes: 22 additions & 14 deletions ExtLibs/ArduPilot/Mavlink/MAVFtp.cs
Original file line number Diff line number Diff line change
Expand Up @@ -2174,7 +2174,7 @@ public bool kCmdWriteFile(Stream srcfile, string friendlyname, CancellationToken
Exception ex = null;
sub = _mavint.SubscribeToPacketType(MAVLink.MAVLINK_MSG_ID.FILE_TRANSFER_PROTOCOL, message =>
{
Console.WriteLine("G " + DateTime.Now.ToString("O"));
//Console.WriteLine("G " + DateTime.Now.ToString("O"));
if (cancel != null && cancel.IsCancellationRequested)
{
timeout.RetriesCurrent = 999;
Expand Down Expand Up @@ -2222,23 +2222,31 @@ public bool kCmdWriteFile(Stream srcfile, string friendlyname, CancellationToken
timeout.Complete = true;
return true;
}

// send next
payload.offset = (uint32_t) stream.Position;
bytes_read = stream.Read(payload.data, 0, payload.data.Length);
Array.Resize(ref payload.data, bytes_read);
payload.size = (uint8_t) bytes_read;
payload.seq_number = seq_no++;
fileTransferProtocol.payload = payload;
_mavint.sendPacket(fileTransferProtocol, _sysid, _compid);
Progress?.Invoke(friendlyname, (int) ((float) payload.offset / size * 100.0));
timeout.ResetTimeout();
Console.WriteLine("S " + DateTime.Now.ToString("O"));
int burstmax = 8;
if(stream.Position > payload.offset + (rwSize* burstmax))
{
stream.Position = payload.offset;
Array.Resize(ref payload.data, rwSize);
}
for (int burst = 0; burst < burstmax; burst++)
{
// send next
payload.offset = (uint32_t)stream.Position;
bytes_read = stream.Read(payload.data, 0, payload.data.Length);
Array.Resize(ref payload.data, bytes_read);
payload.size = (uint8_t)bytes_read;
payload.seq_number = seq_no++;
fileTransferProtocol.payload = payload;
_mavint.sendPacket(fileTransferProtocol, _sysid, _compid);
Progress?.Invoke(friendlyname + " " + payload.offset, (int)((float)payload.offset / size * 100.0));
timeout.ResetTimeout();
//Console.WriteLine("S " + DateTime.Now.ToString("O"));
}
return true;
}, _sysid, _compid);
// fill buffer
payload.offset = (uint32_t) stream.Position;
payload.data = new byte[rwSize];
payload.data = new byte[200];
bytes_read = stream.Read(payload.data, 0, payload.data.Length);
Array.Resize(ref payload.data, bytes_read);
payload.size = (uint8_t) bytes_read;
Expand Down

0 comments on commit 686f77d

Please sign in to comment.