Browse Source

MAVLink: Fix FTP file path handling

This was a real issue for long paths and not a flight safety issue for regular users, but could have been an issue for developers trying to use FTP on very deep nested file systems
sbg
Lorenz Meier 8 years ago committed by Beat Küng
parent
commit
4fcb4cf0fd
  1. 18
      src/modules/mavlink/mavlink_ftp.cpp

18
src/modules/mavlink/mavlink_ftp.cpp

@ -303,6 +303,8 @@ MavlinkFTP::_workList(PayloadHeader *payload, bool list_hidden)
{ {
char dirPath[kMaxDataLength]; char dirPath[kMaxDataLength];
strncpy(dirPath, _data_as_cstring(payload), kMaxDataLength); strncpy(dirPath, _data_as_cstring(payload), kMaxDataLength);
// ensure termination
dirPath[sizeof(dirPath) - 1] = '\0';
ErrorCode errorCode = kErrNone; ErrorCode errorCode = kErrNone;
unsigned offset = 0; unsigned offset = 0;
@ -418,7 +420,7 @@ MavlinkFTP::_workList(PayloadHeader *payload, bool list_hidden)
} else { } else {
// Everything else just sends name // Everything else just sends name
strncpy(buf, result->d_name, sizeof(buf)); strncpy(buf, result->d_name, sizeof(buf));
buf[sizeof(buf) - 1] = 0; buf[sizeof(buf) - 1] = '\0';
} }
size_t nameLen = strlen(buf); size_t nameLen = strlen(buf);
@ -582,6 +584,8 @@ MavlinkFTP::_workRemoveFile(PayloadHeader *payload)
{ {
char file[kMaxDataLength]; char file[kMaxDataLength];
strncpy(file, _data_as_cstring(payload), kMaxDataLength); strncpy(file, _data_as_cstring(payload), kMaxDataLength);
// ensure termination
file[sizeof(file) - 1] = '\0';
if (unlink(file) == 0) { if (unlink(file) == 0) {
payload->size = 0; payload->size = 0;
@ -599,6 +603,8 @@ MavlinkFTP::_workTruncateFile(PayloadHeader *payload)
char file[kMaxDataLength]; char file[kMaxDataLength];
const char temp_file[] = PX4_ROOTFSDIR"/fs/microsd/.trunc.tmp"; const char temp_file[] = PX4_ROOTFSDIR"/fs/microsd/.trunc.tmp";
strncpy(file, _data_as_cstring(payload), kMaxDataLength); strncpy(file, _data_as_cstring(payload), kMaxDataLength);
// ensure termination
file[sizeof(file) - 1] = '\0';
payload->size = 0; payload->size = 0;
// emulate truncate(file, payload->offset) by // emulate truncate(file, payload->offset) by
@ -721,7 +727,11 @@ MavlinkFTP::_workRename(PayloadHeader *payload)
} }
strncpy(oldpath, ptr, kMaxDataLength); strncpy(oldpath, ptr, kMaxDataLength);
// ensure termination
oldpath[sizeof(oldpath) - 1] = '\0';
strncpy(newpath, ptr + oldpath_sz + 1, kMaxDataLength); strncpy(newpath, ptr + oldpath_sz + 1, kMaxDataLength);
// ensure termination
newpath[sizeof(newpath) - 1] = '\0';
if (rename(oldpath, newpath) == 0) { if (rename(oldpath, newpath) == 0) {
payload->size = 0; payload->size = 0;
@ -738,6 +748,8 @@ MavlinkFTP::_workRemoveDirectory(PayloadHeader *payload)
{ {
char dir[kMaxDataLength]; char dir[kMaxDataLength];
strncpy(dir, _data_as_cstring(payload), kMaxDataLength); strncpy(dir, _data_as_cstring(payload), kMaxDataLength);
// ensure termination
dir[sizeof(dir) - 1] = '\0';
if (rmdir(dir) == 0) { if (rmdir(dir) == 0) {
payload->size = 0; payload->size = 0;
@ -754,6 +766,8 @@ MavlinkFTP::_workCreateDirectory(PayloadHeader *payload)
{ {
char dir[kMaxDataLength]; char dir[kMaxDataLength];
strncpy(dir, _data_as_cstring(payload), kMaxDataLength); strncpy(dir, _data_as_cstring(payload), kMaxDataLength);
// ensure termination
dir[sizeof(dir) - 1] = '\0';
if (mkdir(dir, S_IRWXU | S_IRWXG | S_IRWXO) == 0) { if (mkdir(dir, S_IRWXU | S_IRWXG | S_IRWXO) == 0) {
payload->size = 0; payload->size = 0;
@ -772,6 +786,8 @@ MavlinkFTP::_workCalcFileCRC32(PayloadHeader *payload)
uint32_t checksum = 0; uint32_t checksum = 0;
ssize_t bytes_read; ssize_t bytes_read;
strncpy(file_buf, _data_as_cstring(payload), kMaxDataLength); strncpy(file_buf, _data_as_cstring(payload), kMaxDataLength);
// ensure termination
file_buf[sizeof(file_buf) - 1] = '\0';
int fd = ::open(file_buf, O_RDONLY); int fd = ::open(file_buf, O_RDONLY);

Loading…
Cancel
Save