Skip to content
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
17 changes: 10 additions & 7 deletions ExtLibs/ArduPilot/Mavlink/MAVFtp.cs
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,9 @@ public class MAVFtp
/// Identifies Skipped entry from List command
const byte kDirentSkip = (byte) 'S';

/// max read/write size we will use - low to keep some radios happy
const byte rwSize = 80;

private static readonly ILog log = LogManager.GetLogger(MethodBase.GetCurrentMethod().DeclaringType);
private readonly byte _compid;
private readonly MAVLinkInterface _mavint;
Expand Down Expand Up @@ -547,7 +550,7 @@ public enum FTPOpcode : uint8_t
kRspNak
};

public MemoryStream GetFile(string file, CancellationTokenSource cancel, bool burst = true, byte readsize = 239)
public MemoryStream GetFile(string file, CancellationTokenSource cancel, bool burst = true, byte readsize = rwSize)
{
log.InfoFormat("GetFile {0}-{1} {2}", _sysid, _compid, file);
Progress?.Invoke("Opening file " + file, -1);
Expand Down Expand Up @@ -681,7 +684,7 @@ public bool kCmdOpenFileRO(string file, out int size, CancellationTokenSource ca
return ans;
}

public MemoryStream kCmdBurstReadFile(string file, int size, CancellationTokenSource cancel, byte readsize = 239)
public MemoryStream kCmdBurstReadFile(string file, int size, CancellationTokenSource cancel, byte readsize = rwSize)
{
RetryTimeout timeout = new RetryTimeout();
fileTransferProtocol.target_system = _sysid;
Expand Down Expand Up @@ -1453,7 +1456,7 @@ public bool kCmdOpenFileWO(string file, ref int size, CancellationTokenSource ca
return ans;
}

public MemoryStream kCmdReadFile(string file, int size, CancellationTokenSource cancel, byte readsize = 239)
public MemoryStream kCmdReadFile(string file, int size, CancellationTokenSource cancel, byte readsize = rwSize)
{
RetryTimeout timeout = new RetryTimeout();
var payload = new FTPPayloadHeader()
Expand Down Expand Up @@ -2074,7 +2077,7 @@ public bool kCmdWriteFile(byte[] data, uint destoffset, string friendlyname, Can

// send next
payload.offset += (uint) payload.data.Length;
payload.data = data.Skip((int) payload.offset - (int) destoffset).Take(239).ToArray();
payload.data = data.Skip((int) payload.offset - (int) destoffset).Take(rwSize).ToArray();
bytes_read = payload.data.Length;
payload.size = (uint8_t) bytes_read;
payload.seq_number = seq_no++;
Expand All @@ -2087,7 +2090,7 @@ public bool kCmdWriteFile(byte[] data, uint destoffset, string friendlyname, Can
}, _sysid, _compid);
// fill buffer
payload.offset = destoffset;
payload.data = data.Skip((int) payload.offset - (int) destoffset).Take(239).ToArray();
payload.data = data.Skip((int) payload.offset - (int) destoffset).Take(rwSize).ToArray();
bytes_read = payload.data.Length;
payload.size = (uint8_t) bytes_read;
// package it
Expand Down Expand Up @@ -2205,7 +2208,7 @@ public bool kCmdWriteFile(Stream srcfile, string friendlyname, CancellationToken
}, _sysid, _compid);
// fill buffer
payload.offset = (uint32_t) stream.Position;
payload.data = new byte[239];
payload.data = new byte[rwSize];
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 Expand Up @@ -2320,4 +2323,4 @@ public override string ToString()

public event Action<string, int> Progress;
}
}
}