forked from Archive/PX4-Autopilot
Fixed mavlink_ftp read
Instead of always reading the max data length, it now properly respects the requested amount of bytes (as per documentation)
This commit is contained in:
parent
8e3ee9f6cd
commit
462b572172
|
@ -572,7 +572,7 @@ MavlinkFTP::_workRead(PayloadHeader *payload)
|
|||
return kErrFailErrno;
|
||||
}
|
||||
|
||||
int bytes_read = ::read(_session_info.fd, &payload->data[0], kMaxDataLength);
|
||||
int bytes_read = ::read(_session_info.fd, &payload->data[0], payload->size);
|
||||
|
||||
if (bytes_read < 0) {
|
||||
// Negative return indicates error other than eof
|
||||
|
|
Loading…
Reference in New Issue