@ -48,11 +48,17 @@
@@ -48,11 +48,17 @@
// Uncomment the line below to get better debug output. Never commit with this left on.
//#define MAVLINK_FTP_DEBUG
constexpr const char MavlinkFTP : : _root_dir [ ] ;
MavlinkFTP : : MavlinkFTP ( Mavlink * mavlink ) :
_session_info { } ,
_utRcvMsgFunc { } ,
_worker_data { } ,
_mavlink ( mavlink )
_mavlink ( mavlink ) ,
_work_buffer1 { nullptr } ,
_work_buffer2 { nullptr } ,
_last_work_buffer_access { 0 }
{
// initialize session
_session_info . fd = - 1 ;
@ -60,6 +66,13 @@ MavlinkFTP::MavlinkFTP(Mavlink *mavlink) :
@@ -60,6 +66,13 @@ MavlinkFTP::MavlinkFTP(Mavlink *mavlink) :
MavlinkFTP : : ~ MavlinkFTP ( )
{
if ( _work_buffer1 ) {
delete [ ] _work_buffer1 ;
}
if ( _work_buffer2 ) {
delete [ ] _work_buffer2 ;
}
}
@ -134,7 +147,6 @@ MavlinkFTP::handle_message(const mavlink_message_t *msg)
@@ -134,7 +147,6 @@ MavlinkFTP::handle_message(const mavlink_message_t *msg)
if ( ftp_request . target_system = = _getServerSystemId ( ) ) {
_process_request ( & ftp_request , msg - > sysid ) ;
return ;
}
}
}
@ -148,6 +160,13 @@ MavlinkFTP::_process_request(mavlink_file_transfer_protocol_t *ftp_req, uint8_t
@@ -148,6 +160,13 @@ MavlinkFTP::_process_request(mavlink_file_transfer_protocol_t *ftp_req, uint8_t
ErrorCode errorCode = kErrNone ;
if ( ! _ensure_buffers_exist ( ) ) {
PX4_ERR ( " Failed to allocate buffers " ) ;
errorCode = kErrFailErrno ;
errno = ENOMEM ;
goto out ;
}
// basic sanity checks; must validate length before use
if ( payload - > size > kMaxDataLength ) {
errorCode = kErrInvalidDataSize ;
@ -250,7 +269,7 @@ out:
@@ -250,7 +269,7 @@ out:
}
}
// Stream download replies are sent through mavlink stream mechanism. Unless we need to Nak.
// Stream download replies are sent through mavlink stream mechanism. Unless we need to Nac k.
if ( ! stream_send | | errorCode ! = kErrNone ) {
// respond to the request
ftp_req - > target_system = target_system_id ;
@ -258,6 +277,21 @@ out:
@@ -258,6 +277,21 @@ out:
}
}
bool MavlinkFTP : : _ensure_buffers_exist ( )
{
_last_work_buffer_access = hrt_absolute_time ( ) ;
if ( ! _work_buffer1 ) {
_work_buffer1 = new char [ _work_buffer1_len ] ;
}
if ( ! _work_buffer2 ) {
_work_buffer2 = new char [ _work_buffer2_len ] ;
}
return _work_buffer1 & & _work_buffer2 ;
}
/// @brief Sends the specified FTP response message out through mavlink
void
MavlinkFTP : : _reply ( mavlink_file_transfer_protocol_t * ftp_req )
@ -283,35 +317,36 @@ MavlinkFTP::_reply(mavlink_file_transfer_protocol_t *ftp_req)
@@ -283,35 +317,36 @@ MavlinkFTP::_reply(mavlink_file_transfer_protocol_t *ftp_req)
MavlinkFTP : : ErrorCode
MavlinkFTP : : _workList ( PayloadHeader * payload , bool list_hidden )
{
char dirPath [ kMaxDataLength ] ;
strncpy ( dirPath , _data_as_cstring ( payload ) , kMaxDataLength ) ;
strncpy ( _work_buffer1 , _root_dir , _work_buffer1_len ) ;
strncpy ( _work_buffer1 + _root_dir_len , _data_as_cstring ( payload ) , _work_buffer1_len - _root_dir_len ) ;
// ensure termination
dirPath [ sizeof ( dirPath ) - 1 ] = ' \0 ' ;
_work_buffer1 [ _work_buffer1_len - 1 ] = ' \0 ' ;
ErrorCode errorCode = kErrNone ;
unsigned offset = 0 ;
DIR * dp = opendir ( dirPath ) ;
DIR * dp = opendir ( _work_buffer1 ) ;
if ( dp = = nullptr ) {
# ifdef MAVLINK_FTP_UNIT_TEST
warnx ( " File open failed " ) ;
# else
_mavlink - > send_statustext_critical ( " FTP: can't open path (file system corrupted?) " ) ;
_mavlink - > send_statustext_critical ( dirPath ) ;
_mavlink - > send_statustext_critical ( _work_buffer1 ) ;
# endif
// this is not an FTP error, abort directory by simulating eof
return kErrEOF ;
}
# ifdef MAVLINK_FTP_DEBUG
warnx ( " FTP: list %s offset %d " , dirPath , payload - > offset ) ;
warnx ( " FTP: list %s offset %d " , _work_buffer1 , payload - > offset ) ;
# endif
struct dirent * result = nullptr ;
// move to the requested offset
int requested_offset = payload - > offset ;
while ( requested_offset - - > 0 & & readdir ( dp ) ) ;
for ( ; ; ) {
@ -325,7 +360,7 @@ MavlinkFTP::_workList(PayloadHeader *payload, bool list_hidden)
@@ -325,7 +360,7 @@ MavlinkFTP::_workList(PayloadHeader *payload, bool list_hidden)
warnx ( " readdir failed " ) ;
# else
_mavlink - > send_statustext_critical ( " FTP: list readdir failure " ) ;
_mavlink - > send_statustext_critical ( dirPath ) ;
_mavlink - > send_statustext_critical ( _work_buffer1 ) ;
# endif
payload - > data [ offset + + ] = kDirentSkip ;
@ -349,7 +384,6 @@ MavlinkFTP::_workList(PayloadHeader *payload, bool list_hidden)
@@ -349,7 +384,6 @@ MavlinkFTP::_workList(PayloadHeader *payload, bool list_hidden)
}
uint32_t fileSize = 0 ;
char buf [ 256 ] ;
char direntType ;
// Determine the directory entry type
@ -363,13 +397,13 @@ MavlinkFTP::_workList(PayloadHeader *payload, bool list_hidden)
@@ -363,13 +397,13 @@ MavlinkFTP::_workList(PayloadHeader *payload, bool list_hidden)
# endif
// For files we get the file size as well
direntType = kDirentFile ;
int ret = snprintf ( buf , sizeof ( buf ) , " %s/%s " , dirPath , result - > d_name ) ;
bool buf_is_ok = ( ( ret > 0 ) & & ( ret < sizeof ( buf ) ) ) ;
int ret = snprintf ( _work_buffer2 , _work_buffer2_len , " %s/%s " , _work_buffer1 , result - > d_name ) ;
bool buf_is_ok = ( ( ret > 0 ) & & ( ret < _work_buffer2_len ) ) ;
if ( buf_is_ok ) {
struct stat st ;
if ( stat ( buf , & st ) = = 0 ) {
if ( stat ( _work_ buffer2 , & st ) = = 0 ) {
fileSize = st . st_size ;
}
}
@ -401,24 +435,24 @@ MavlinkFTP::_workList(PayloadHeader *payload, bool list_hidden)
@@ -401,24 +435,24 @@ MavlinkFTP::_workList(PayloadHeader *payload, bool list_hidden)
if ( direntType = = kDirentSkip ) {
// Skip send only dirent identifier
buf [ 0 ] = ' \0 ' ;
_work_ buffer2 [ 0 ] = ' \0 ' ;
} else if ( direntType = = kDirentFile ) {
// Files send filename and file length
int ret = snprintf ( buf , sizeof ( buf ) , " %s \t %d " , result - > d_name , fileSize ) ;
bool buf_is_ok = ( ( ret > 0 ) & & ( ret < sizeof ( buf ) ) ) ;
int ret = snprintf ( _work_buffer2 , _work_buffer2_len , " %s \t %d " , result - > d_name , fileSize ) ;
bool buf_is_ok = ( ( ret > 0 ) & & ( ret < _work_buffer2_len ) ) ;
if ( ! buf_is_ok ) {
buf [ sizeof ( buf ) - 1 ] = ' \0 ' ;
_work_buffer2 [ _work_buffer2_len - 1 ] = ' \0 ' ;
}
} else {
// Everything else just sends name
strncpy ( buf , result - > d_name , sizeof ( buf ) ) ;
buf [ sizeof ( buf ) - 1 ] = ' \0 ' ;
strncpy ( _work_ buffer2 , result - > d_name , _work_buffer2_len ) ;
_work_buffer2 [ _work_buffer2_len - 1 ] = ' \0 ' ;
}
size_t nameLen = strlen ( buf ) ;
size_t nameLen = strlen ( _work_ buffer2 ) ;
// Do we have room for the name, the one char directory identifier and the null terminator?
if ( ( offset + nameLen + 2 ) > kMaxDataLength ) {
@ -427,9 +461,9 @@ MavlinkFTP::_workList(PayloadHeader *payload, bool list_hidden)
@@ -427,9 +461,9 @@ MavlinkFTP::_workList(PayloadHeader *payload, bool list_hidden)
// Move the data into the buffer
payload - > data [ offset + + ] = direntType ;
strcpy ( ( char * ) & payload - > data [ offset ] , buf ) ;
strcpy ( ( char * ) & payload - > data [ offset ] , _work_ buffer2 ) ;
# ifdef MAVLINK_FTP_DEBUG
printf ( " FTP: list %s %s \n " , dirPath , ( char * ) & payload - > data [ offset - 1 ] ) ;
printf ( " FTP: list %s %s \n " , _work_buffer1 , ( char * ) & payload - > data [ offset - 1 ] ) ;
# endif
offset + = nameLen + 1 ;
}
@ -449,16 +483,17 @@ MavlinkFTP::_workOpen(PayloadHeader *payload, int oflag)
@@ -449,16 +483,17 @@ MavlinkFTP::_workOpen(PayloadHeader *payload, int oflag)
return kErrNoSessionsAvailable ;
}
char * filename = _data_as_cstring ( payload ) ;
strncpy ( _work_buffer1 , _root_dir , _work_buffer1_len ) ;
strncpy ( _work_buffer1 + _root_dir_len , _data_as_cstring ( payload ) , _work_buffer1_len - _root_dir_len ) ;
# ifdef MAVLINK_FTP_DEBUG
warnx ( " FTP: open '%s' " , filename ) ;
warnx ( " FTP: open '%s' " , _work_buffer1 ) ;
# endif
uint32_t fileSize = 0 ;
struct stat st ;
if ( stat ( filename , & st ) ! = 0 ) {
if ( stat ( _work_buffer1 , & st ) ! = 0 ) {
// fail only if requested open for read
if ( oflag & O_RDONLY ) {
return kErrFailErrno ;
@ -471,7 +506,7 @@ MavlinkFTP::_workOpen(PayloadHeader *payload, int oflag)
@@ -471,7 +506,7 @@ MavlinkFTP::_workOpen(PayloadHeader *payload, int oflag)
fileSize = st . st_size ;
// Set mode to 666 incase oflag has O_CREAT
int fd = : : open ( filename , oflag , PX4_O_MODE_666 ) ;
int fd = : : open ( _work_buffer1 , oflag , PX4_O_MODE_666 ) ;
if ( fd < 0 ) {
return kErrFailErrno ;
@ -577,12 +612,12 @@ MavlinkFTP::_workWrite(PayloadHeader *payload)
@@ -577,12 +612,12 @@ MavlinkFTP::_workWrite(PayloadHeader *payload)
MavlinkFTP : : ErrorCode
MavlinkFTP : : _workRemoveFile ( PayloadHeader * payload )
{
char file [ kMaxDataLength ] ;
strncpy ( file , _data_as_cstring ( payload ) , kMaxDataLength ) ;
strncpy ( _work_buffer1 , _root_dir , _work_buffer1_len ) ;
strncpy ( _work_bu ffer1 + _root_d ir_ len , _data_as_cstring ( payload ) , _work_buffer1_len - _root_dir_len ) ;
// ensure termination
file [ sizeof ( file ) - 1 ] = ' \0 ' ;
_work_buffer1 [ _work_buffer1_len - 1 ] = ' \0 ' ;
if ( unlink ( file ) = = 0 ) {
if ( unlink ( _work_buffer1 ) = = 0 ) {
payload - > size = 0 ;
return kErrNone ;
@ -595,19 +630,21 @@ MavlinkFTP::_workRemoveFile(PayloadHeader *payload)
@@ -595,19 +630,21 @@ MavlinkFTP::_workRemoveFile(PayloadHeader *payload)
MavlinkFTP : : ErrorCode
MavlinkFTP : : _workTruncateFile ( PayloadHeader * payload )
{
char file [ kMaxDataLength ] ;
const char temp_file [ ] = PX4_ROOTFSDIR " /fs/microsd/.trunc.tmp " ;
strncpy ( file , _data_as_cstring ( payload ) , kMaxDataLength ) ;
strncpy ( _work_buffer1 , _root_dir , _work_buffer1_len ) ;
strncpy ( _work_buffer1 + _root_dir_len , _data_as_cstring ( payload ) , _work_buffer1_len - _root_dir_len ) ;
// ensure termination
file [ sizeof ( file ) - 1 ] = ' \0 ' ;
_work_buffer1 [ _work_buffer1_len - 1 ] = ' \0 ' ;
payload - > size = 0 ;
// emulate truncate(file, payload->offset) by
// copying to temp and overwrite with O_TRUNC flag.
# ifdef __PX4_NUTTX
// emulate truncate(_work_buffer1, payload->offset) by
// copying to temp and overwrite with O_TRUNC flag (NuttX does not support truncate()).
const char temp_file [ ] = PX4_ROOTFSDIR " /fs/microsd/.trunc.tmp " ;
struct stat st ;
if ( stat ( file , & st ) ! = 0 ) {
if ( stat ( _work_buffer1 , & st ) ! = 0 ) {
return kErrFailErrno ;
}
@ -628,7 +665,7 @@ MavlinkFTP::_workTruncateFile(PayloadHeader *payload)
@@ -628,7 +665,7 @@ MavlinkFTP::_workTruncateFile(PayloadHeader *payload)
} else if ( payload - > offset = = 0 ) {
// 1: truncate all data
int fd = : : open ( file , O_TRUNC | O_WRONLY ) ;
int fd = : : open ( _work_buffer1 , O_TRUNC | O_WRONLY ) ;
if ( fd < 0 ) {
return kErrFailErrno ;
@ -639,7 +676,7 @@ MavlinkFTP::_workTruncateFile(PayloadHeader *payload)
@@ -639,7 +676,7 @@ MavlinkFTP::_workTruncateFile(PayloadHeader *payload)
} else if ( payload - > offset > ( unsigned ) st . st_size ) {
// 2: extend file
int fd = : : open ( file , O_WRONLY ) ;
int fd = : : open ( _work_buffer1 , O_WRONLY ) ;
if ( fd < 0 ) {
return kErrFailErrno ;
@ -657,11 +694,11 @@ MavlinkFTP::_workTruncateFile(PayloadHeader *payload)
@@ -657,11 +694,11 @@ MavlinkFTP::_workTruncateFile(PayloadHeader *payload)
} else {
// 3: truncate
if ( _copy_file ( file , temp_file , payload - > offset ) ! = 0 ) {
if ( _copy_file ( _work_buffer1 , temp_file , payload - > offset ) ! = 0 ) {
return kErrFailErrno ;
}
if ( _copy_file ( temp_file , file , payload - > offset ) ! = 0 ) {
if ( _copy_file ( temp_file , _work_buffer1 , payload - > offset ) ! = 0 ) {
return kErrFailErrno ;
}
@ -671,6 +708,16 @@ MavlinkFTP::_workTruncateFile(PayloadHeader *payload)
@@ -671,6 +708,16 @@ MavlinkFTP::_workTruncateFile(PayloadHeader *payload)
return kErrNone ;
}
# else
int ret = truncate ( _work_buffer1 , payload - > offset ) ;
if ( ret = = 0 ) {
return kErrNone ;
}
return kErrFailErrno ;
# endif /* __PX4_NUTTX */
}
/// @brief Responds to a Terminate command
@ -709,9 +756,6 @@ MavlinkFTP::_workReset(PayloadHeader *payload)
@@ -709,9 +756,6 @@ MavlinkFTP::_workReset(PayloadHeader *payload)
MavlinkFTP : : ErrorCode
MavlinkFTP : : _workRename ( PayloadHeader * payload )
{
char oldpath [ kMaxDataLength ] ;
char newpath [ kMaxDataLength ] ;
char * ptr = _data_as_cstring ( payload ) ;
size_t oldpath_sz = strlen ( ptr ) ;
@ -721,14 +765,15 @@ MavlinkFTP::_workRename(PayloadHeader *payload)
@@ -721,14 +765,15 @@ MavlinkFTP::_workRename(PayloadHeader *payload)
return kErrFailErrno ;
}
strncpy ( oldpath , ptr , kMaxDataLength ) ;
// ensure termination
oldpath [ sizeof ( oldpath ) - 1 ] = ' \0 ' ;
strncpy ( newpath , ptr + oldpath_sz + 1 , kMaxDataLength ) ;
// ensure termination
newpath [ sizeof ( newpath ) - 1 ] = ' \0 ' ;
strncpy ( _work_buffer1 , _root_dir , _work_buffer1_len ) ;
strncpy ( _work_buffer1 + _root_dir_len , ptr , _work_buffer1_len - _root_dir_len ) ;
_work_buffer1 [ _work_buffer1_len - 1 ] = ' \0 ' ; // ensure termination
strncpy ( _work_buffer2 , _root_dir , _work_buffer2_len ) ;
strncpy ( _work_buffer2 + _root_dir_len , ptr + oldpath_sz + 1 , _work_buffer2_len - _root_dir_len ) ;
_work_buffer2 [ _work_buffer2_len - 1 ] = ' \0 ' ; // ensure termination
if ( rename ( oldpath , newpath ) = = 0 ) {
if ( rename ( _work_buffer1 , _work_buffer2 ) = = 0 ) {
payload - > size = 0 ;
return kErrNone ;
@ -741,12 +786,12 @@ MavlinkFTP::_workRename(PayloadHeader *payload)
@@ -741,12 +786,12 @@ MavlinkFTP::_workRename(PayloadHeader *payload)
MavlinkFTP : : ErrorCode
MavlinkFTP : : _workRemoveDirectory ( PayloadHeader * payload )
{
char dir [ kMaxDataLength ] ;
strncpy ( dir , _data_as_cstring ( payload ) , kMaxDataLength ) ;
strncpy ( _work_buffer1 , _root_dir , _work_buffer1_len ) ;
strncpy ( _work_buffer1 + _root_ dir_len , _data_as_cstring ( payload ) , _work_buffer1_len - _root_dir_len ) ;
// ensure termination
dir [ sizeof ( dir ) - 1 ] = ' \0 ' ;
_work_buffer1 [ _work_buffer1_len - 1 ] = ' \0 ' ;
if ( rmdir ( dir ) = = 0 ) {
if ( rmdir ( _work_buffer1 ) = = 0 ) {
payload - > size = 0 ;
return kErrNone ;
@ -759,12 +804,12 @@ MavlinkFTP::_workRemoveDirectory(PayloadHeader *payload)
@@ -759,12 +804,12 @@ MavlinkFTP::_workRemoveDirectory(PayloadHeader *payload)
MavlinkFTP : : ErrorCode
MavlinkFTP : : _workCreateDirectory ( PayloadHeader * payload )
{
char dir [ kMaxDataLength ] ;
strncpy ( dir , _data_as_cstring ( payload ) , kMaxDataLength ) ;
strncpy ( _work_buffer1 , _root_dir , _work_buffer1_len ) ;
strncpy ( _work_buffer1 + _root_ dir_len , _data_as_cstring ( payload ) , _work_buffer1_len - _root_dir_len ) ;
// ensure termination
dir [ sizeof ( dir ) - 1 ] = ' \0 ' ;
_work_buffer1 [ _work_buffer1_len - 1 ] = ' \0 ' ;
if ( mkdir ( dir , S_IRWXU | S_IRWXG | S_IRWXO ) = = 0 ) {
if ( mkdir ( _work_buffer1 , S_IRWXU | S_IRWXG | S_IRWXO ) = = 0 ) {
payload - > size = 0 ;
return kErrNone ;
@ -777,21 +822,21 @@ MavlinkFTP::_workCreateDirectory(PayloadHeader *payload)
@@ -777,21 +822,21 @@ MavlinkFTP::_workCreateDirectory(PayloadHeader *payload)
MavlinkFTP : : ErrorCode
MavlinkFTP : : _workCalcFileCRC32 ( PayloadHeader * payload )
{
char file_buf [ 256 ] ;
uint32_t checksum = 0 ;
ssize_t bytes_read ;
strncpy ( file_buf , _data_as_cstring ( payload ) , kMaxDataLength ) ;
strncpy ( _work_buffer2 , _root_dir , _work_buffer2_len ) ;
strncpy ( _work_buffer2 + _root_dir_len , _data_as_cstring ( payload ) , _work_buffer2_len - _root_dir_len ) ;
// ensure termination
file_buf [ sizeof ( file_buf ) - 1 ] = ' \0 ' ;
_work_buffer2 [ _work_buffer2_len - 1 ] = ' \0 ' ;
int fd = : : open ( file_buf , O_RDONLY ) ;
int fd = : : open ( _work_buffer2 , O_RDONLY ) ;
if ( fd < 0 ) {
return kErrFailErrno ;
}
do {
bytes_read = : : read ( fd , file_buf , sizeof ( file_buf ) ) ;
bytes_read = : : read ( fd , _work_buffer2 , _work_buffer2_len ) ;
if ( bytes_read < 0 ) {
int r_errno = errno ;
@ -800,8 +845,8 @@ MavlinkFTP::_workCalcFileCRC32(PayloadHeader *payload)
@@ -800,8 +845,8 @@ MavlinkFTP::_workCalcFileCRC32(PayloadHeader *payload)
return kErrFailErrno ;
}
checksum = crc32part ( ( uint8_t * ) file_buf , bytes_read , checksum ) ;
} while ( bytes_read = = sizeof ( file_buf ) ) ;
checksum = crc32part ( ( uint8_t * ) _work_buffer2 , bytes_read , checksum ) ;
} while ( bytes_read = = _work_buffer2_len ) ;
: : close ( fd ) ;
@ -831,7 +876,6 @@ MavlinkFTP::_data_as_cstring(PayloadHeader *payload)
@@ -831,7 +876,6 @@ MavlinkFTP::_data_as_cstring(PayloadHeader *payload)
int
MavlinkFTP : : _copy_file ( const char * src_path , const char * dst_path , size_t length )
{
char buff [ 512 ] ;
int src_fd = - 1 , dst_fd = - 1 ;
int op_errno = 0 ;
@ -857,9 +901,9 @@ MavlinkFTP::_copy_file(const char *src_path, const char *dst_path, size_t length
@@ -857,9 +901,9 @@ MavlinkFTP::_copy_file(const char *src_path, const char *dst_path, size_t length
while ( length > 0 ) {
ssize_t bytes_read , bytes_written ;
size_t blen = ( length > sizeof ( buff ) ) ? sizeof ( buff ) : length ;
size_t blen = ( length > _work_buffer2_len ) ? _work_buffer2_len : length ;
bytes_read = : : read ( src_fd , buff , blen ) ;
bytes_read = : : read ( src_fd , _work_ buffer2 , blen ) ;
if ( bytes_read = = 0 ) {
// EOF
@ -871,7 +915,7 @@ MavlinkFTP::_copy_file(const char *src_path, const char *dst_path, size_t length
@@ -871,7 +915,7 @@ MavlinkFTP::_copy_file(const char *src_path, const char *dst_path, size_t length
break ;
}
bytes_written = : : write ( dst_fd , buff , bytes_read ) ;
bytes_written = : : write ( dst_fd , _work_ buffer2 , bytes_read ) ;
if ( bytes_written ! = bytes_read ) {
warnx ( " cp: short write " ) ;
@ -891,6 +935,22 @@ MavlinkFTP::_copy_file(const char *src_path, const char *dst_path, size_t length
@@ -891,6 +935,22 @@ MavlinkFTP::_copy_file(const char *src_path, const char *dst_path, size_t length
void MavlinkFTP : : send ( const hrt_abstime t )
{
if ( _work_buffer1 | | _work_buffer2 ) {
// free the work buffers if they are not used for a while
if ( hrt_elapsed_time ( & _last_work_buffer_access ) > 2000000 ) {
if ( _work_buffer1 ) {
delete [ ] _work_buffer1 ;
_work_buffer1 = nullptr ;
}
if ( _work_buffer2 ) {
delete [ ] _work_buffer2 ;
_work_buffer2 = nullptr ;
}
}
}
// Anything to stream?
if ( ! _session_info . stream_download ) {
return ;