@@ -27,6 +27,9 @@ public class MAVFtp
2727 /// Identifies Skipped entry from List command
2828 const byte kDirentSkip = ( byte ) 'S' ;
2929
30+ /// max read/write size we will use - low to keep some radios happy
31+ const byte rwSize = 80 ;
32+
3033 private static readonly ILog log = LogManager . GetLogger ( MethodBase . GetCurrentMethod ( ) . DeclaringType ) ;
3134 private readonly byte _compid ;
3235 private readonly MAVLinkInterface _mavint ;
@@ -547,7 +550,7 @@ public enum FTPOpcode : uint8_t
547550 kRspNak
548551 } ;
549552
550- public MemoryStream GetFile ( string file , CancellationTokenSource cancel , bool burst = true , byte readsize = 239 )
553+ public MemoryStream GetFile ( string file , CancellationTokenSource cancel , bool burst = true , byte readsize = rwSize )
551554 {
552555 log . InfoFormat ( "GetFile {0}-{1} {2}" , _sysid , _compid , file ) ;
553556 Progress ? . Invoke ( "Opening file " + file , - 1 ) ;
@@ -681,7 +684,7 @@ public bool kCmdOpenFileRO(string file, out int size, CancellationTokenSource ca
681684 return ans ;
682685 }
683686
684- public MemoryStream kCmdBurstReadFile ( string file , int size , CancellationTokenSource cancel , byte readsize = 239 )
687+ public MemoryStream kCmdBurstReadFile ( string file , int size , CancellationTokenSource cancel , byte readsize = rwSize )
685688 {
686689 RetryTimeout timeout = new RetryTimeout ( ) ;
687690 fileTransferProtocol . target_system = _sysid ;
@@ -1453,7 +1456,7 @@ public bool kCmdOpenFileWO(string file, ref int size, CancellationTokenSource ca
14531456 return ans ;
14541457 }
14551458
1456- public MemoryStream kCmdReadFile ( string file , int size , CancellationTokenSource cancel , byte readsize = 239 )
1459+ public MemoryStream kCmdReadFile ( string file , int size , CancellationTokenSource cancel , byte readsize = rwSize )
14571460 {
14581461 RetryTimeout timeout = new RetryTimeout ( ) ;
14591462 var payload = new FTPPayloadHeader ( )
@@ -2074,7 +2077,7 @@ public bool kCmdWriteFile(byte[] data, uint destoffset, string friendlyname, Can
20742077
20752078 // send next
20762079 payload . offset += ( uint ) payload . data . Length ;
2077- payload . data = data . Skip ( ( int ) payload . offset - ( int ) destoffset ) . Take ( 239 ) . ToArray ( ) ;
2080+ payload . data = data . Skip ( ( int ) payload . offset - ( int ) destoffset ) . Take ( rwSize ) . ToArray ( ) ;
20782081 bytes_read = payload . data . Length ;
20792082 payload . size = ( uint8_t ) bytes_read ;
20802083 payload . seq_number = seq_no ++ ;
@@ -2087,7 +2090,7 @@ public bool kCmdWriteFile(byte[] data, uint destoffset, string friendlyname, Can
20872090 } , _sysid , _compid ) ;
20882091 // fill buffer
20892092 payload . offset = destoffset ;
2090- payload . data = data . Skip ( ( int ) payload . offset - ( int ) destoffset ) . Take ( 239 ) . ToArray ( ) ;
2093+ payload . data = data . Skip ( ( int ) payload . offset - ( int ) destoffset ) . Take ( rwSize ) . ToArray ( ) ;
20912094 bytes_read = payload . data . Length ;
20922095 payload . size = ( uint8_t ) bytes_read ;
20932096 // package it
@@ -2205,7 +2208,7 @@ public bool kCmdWriteFile(Stream srcfile, string friendlyname, CancellationToken
22052208 } , _sysid , _compid ) ;
22062209 // fill buffer
22072210 payload . offset = ( uint32_t ) stream . Position ;
2208- payload . data = new byte [ 239 ] ;
2211+ payload . data = new byte [ rwSize ] ;
22092212 bytes_read = stream . Read ( payload . data , 0 , payload . data . Length ) ;
22102213 Array . Resize ( ref payload . data , bytes_read ) ;
22112214 payload . size = ( uint8_t ) bytes_read ;
@@ -2320,4 +2323,4 @@ public override string ToString()
23202323
23212324 public event Action < string , int > Progress ;
23222325 }
2323- }
2326+ }
0 commit comments