Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

GCS_MAVLink: ftp receiving messages where size takes into account terminating null #26462

Open
wants to merge 2 commits into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
1 change: 1 addition & 0 deletions libraries/GCS_MAVLink/GCS.h
Expand Up @@ -1009,6 +1009,7 @@ class GCS_MAVLINK
static struct ftp_state ftp;

static void ftp_error(struct pending_ftp &response, FTP_ERROR error); // FTP helper method for packing a NAK
static bool ftp_check_name_len(const struct pending_ftp &request);
static int gen_dir_entry(char *dest, size_t space, const char * path, const struct dirent * entry); // FTP helper for emitting a dir response
static void ftp_list_dir(struct pending_ftp &request, struct pending_ftp &response);

Expand Down
33 changes: 20 additions & 13 deletions libraries/GCS_MAVLink/GCS_FTP.cpp
Expand Up @@ -129,6 +129,17 @@ bool GCS_MAVLINK::send_ftp_reply(const pending_ftp &reply)
return true;
}

bool GCS_MAVLINK::ftp_check_name_len(const struct pending_ftp &request) {
const size_t file_name_len = strnlen((char *)request.data, sizeof(request.data));
if (request.size == 0) {
return false;
}
if (file_name_len == request.size) {
return true;
}
return (request.size - file_name_len == 1) && (request.data[sizeof(request.data) - 1] == 0);
}

void GCS_MAVLINK::ftp_error(struct pending_ftp &response, FTP_ERROR error) {
response.opcode = FTP_OP::Nack;
response.data[0] = static_cast<uint8_t>(error);
Expand Down Expand Up @@ -254,8 +265,7 @@ void GCS_MAVLINK::ftp_worker(void) {
}

// sanity check that our the request looks well formed
const size_t file_name_len = strnlen((char *)request.data, sizeof(request.data));
if ((file_name_len != request.size) || (request.size == 0)) {
if (!ftp_check_name_len(request)) {
ftp_error(reply, FTP_ERROR::InvalidDataSize);
break;
}
Expand Down Expand Up @@ -340,8 +350,7 @@ void GCS_MAVLINK::ftp_worker(void) {
}

// sanity check that our the request looks well formed
const size_t file_name_len = strnlen((char *)request.data, sizeof(request.data));
if ((file_name_len != request.size) || (request.size == 0)) {
if (!ftp_check_name_len(request)) {
ftp_error(reply, FTP_ERROR::InvalidDataSize);
break;
}
Expand Down Expand Up @@ -395,8 +404,7 @@ void GCS_MAVLINK::ftp_worker(void) {
case FTP_OP::CreateDirectory:
{
// sanity check that our the request looks well formed
const size_t file_name_len = strnlen((char *)request.data, sizeof(request.data));
if ((file_name_len != request.size) || (request.size == 0)) {
if (!ftp_check_name_len(request)) {
ftp_error(reply, FTP_ERROR::InvalidDataSize);
break;
}
Expand All @@ -416,8 +424,7 @@ void GCS_MAVLINK::ftp_worker(void) {
case FTP_OP::RemoveFile:
{
// sanity check that our the request looks well formed
const size_t file_name_len = strnlen((char *)request.data, sizeof(request.data));
if ((file_name_len != request.size) || (request.size == 0)) {
if (!ftp_check_name_len(request)) {
ftp_error(reply, FTP_ERROR::InvalidDataSize);
break;
}
Expand All @@ -436,8 +443,7 @@ void GCS_MAVLINK::ftp_worker(void) {
case FTP_OP::CalcFileCRC32:
{
// sanity check that our the request looks well formed
const size_t file_name_len = strnlen((char *)request.data, sizeof(request.data));
if ((file_name_len != request.size) || (request.size == 0)) {
if (!ftp_check_name_len(request)) {
ftp_error(reply, FTP_ERROR::InvalidDataSize);
break;
}
Expand Down Expand Up @@ -548,7 +554,9 @@ void GCS_MAVLINK::ftp_worker(void) {
const size_t len1 = strnlen(filename1, sizeof(request.data)-2);
const char *filename2 = (char*)&request.data[len1+1];
const size_t len2 = strnlen(filename2, sizeof(request.data)-(len1+1));
if (filename1[len1] != 0 || (len1+len2+1 != request.size) || (request.size == 0)) {
const bool is_req_size_consider_tnull = (request.size - (len1+len2) == 2 &&
request.data[sizeof(request.data) - 1] == 0);
if (filename1[len1] != 0 || ((len1+len2+1 != request.size) && !is_req_size_consider_tnull) || (request.size == 0)) {
ftp_error(reply, FTP_ERROR::InvalidDataSize);
break;
}
Expand Down Expand Up @@ -615,9 +623,8 @@ int GCS_MAVLINK::gen_dir_entry(char *dest, size_t space, const char *path, const
void GCS_MAVLINK::ftp_list_dir(struct pending_ftp &request, struct pending_ftp &response) {
response.offset = request.offset; // this should be set for any failure condition for debugging

const size_t directory_name_size = strnlen((char *)request.data, sizeof(request.data));
// sanity check that our the request looks well formed
if ((directory_name_size != request.size) || (request.size == 0)) {
if (!ftp_check_name_len(request)) {
ftp_error(response, FTP_ERROR::InvalidDataSize);
return;
}
Expand Down