mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
GCS_MAVLink: rename emit_dir_entry to gen_dir_entry
comment from Sid
This commit is contained in:
parent
e5321b6201
commit
00549d13fa
@ -681,7 +681,7 @@ private:
|
|||||||
static struct ftp_state ftp;
|
static struct ftp_state ftp;
|
||||||
|
|
||||||
static void ftp_error(struct pending_ftp &response, FTP_ERROR error); // FTP helper method for packing a NAK
|
static void ftp_error(struct pending_ftp &response, FTP_ERROR error); // FTP helper method for packing a NAK
|
||||||
static int emit_dir_entry(char *dest, size_t space, const char * path, const struct dirent * entry); // FTP helper for emitting a dir response
|
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);
|
static void ftp_list_dir(struct pending_ftp &request, struct pending_ftp &response);
|
||||||
|
|
||||||
bool ftp_init(void);
|
bool ftp_init(void);
|
||||||
|
@ -500,7 +500,7 @@ void GCS_MAVLINK::ftp_worker(void) {
|
|||||||
}
|
}
|
||||||
|
|
||||||
// calculates how much string length is needed to fit this in a list response
|
// calculates how much string length is needed to fit this in a list response
|
||||||
int GCS_MAVLINK::emit_dir_entry(char *dest, size_t space, const char *path, const struct dirent * entry) {
|
int GCS_MAVLINK::gen_dir_entry(char *dest, size_t space, const char *path, const struct dirent * entry) {
|
||||||
const bool is_file = entry->d_type == DT_REG;
|
const bool is_file = entry->d_type == DT_REG;
|
||||||
|
|
||||||
if (space < 3) {
|
if (space < 3) {
|
||||||
@ -557,7 +557,7 @@ void GCS_MAVLINK::ftp_list_dir(struct pending_ftp &request, struct pending_ftp &
|
|||||||
}
|
}
|
||||||
|
|
||||||
// check how much space would be needed to emit the listing
|
// check how much space would be needed to emit the listing
|
||||||
const int needed_space = emit_dir_entry((char *)response.data, sizeof(request.data), (char *)request.data, entry);
|
const int needed_space = gen_dir_entry((char *)response.data, sizeof(request.data), (char *)request.data, entry);
|
||||||
|
|
||||||
if (needed_space < 0 || needed_space > (int)sizeof(request.data)) {
|
if (needed_space < 0 || needed_space > (int)sizeof(request.data)) {
|
||||||
continue;
|
continue;
|
||||||
@ -571,7 +571,7 @@ void GCS_MAVLINK::ftp_list_dir(struct pending_ftp &request, struct pending_ftp &
|
|||||||
struct dirent *entry;
|
struct dirent *entry;
|
||||||
while ((entry = AP::FS().readdir(dir))) {
|
while ((entry = AP::FS().readdir(dir))) {
|
||||||
// figure out if we can fit the file
|
// figure out if we can fit the file
|
||||||
const int required_space = emit_dir_entry((char *)(response.data + index), sizeof(response.data) - index, (char *)request.data, entry);
|
const int required_space = gen_dir_entry((char *)(response.data + index), sizeof(response.data) - index, (char *)request.data, entry);
|
||||||
|
|
||||||
// couldn't ever send this so drop it
|
// couldn't ever send this so drop it
|
||||||
if (required_space < 0) {
|
if (required_space < 0) {
|
||||||
|
Loading…
Reference in New Issue
Block a user