Skip to content

Commit 2111821

Browse files
committed
mavlink: added read size limits on FTP read
thanks to Michael Oborne for spotting this: ArduPilot/MissionPlanner#2784
1 parent 0a65fbb commit 2111821

File tree

1 file changed

+2
-2
lines changed

1 file changed

+2
-2
lines changed

libraries/GCS_MAVLink/GCS_FTP.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -323,7 +323,7 @@ void GCS_MAVLINK::ftp_worker(void) {
323323
}
324324

325325
// fill the buffer
326-
const ssize_t read_bytes = AP::FS().read(ftp.fd, reply.data, request.size);
326+
const ssize_t read_bytes = AP::FS().read(ftp.fd, reply.data, MIN(sizeof(reply.data),request.size));
327327
if (read_bytes == -1) {
328328
ftp_error(reply, FTP_ERROR::FailErrno);
329329
break;
@@ -508,7 +508,7 @@ void GCS_MAVLINK::ftp_worker(void) {
508508
const uint32_t transfer_size = 100;
509509
for (uint32_t i = 0; (i < transfer_size); i++) {
510510
// fill the buffer
511-
const ssize_t read_bytes = AP::FS().read(ftp.fd, reply.data, max_read);
511+
const ssize_t read_bytes = AP::FS().read(ftp.fd, reply.data, MIN(sizeof(reply.data), max_read));
512512
if (read_bytes == -1) {
513513
ftp_error(reply, FTP_ERROR::FailErrno);
514514
break;

0 commit comments

Comments
 (0)