mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-01 03:04:04 -04:00
AP_Filesystem: FATFS: drop tty check logic
In Standard C, the first three file descriptors are usually standard in, out, and error. However, ArduPilot doesn't have a concept of this and other backends (such as LittleFS) don't bother to reject them. Remove this logic to simplify implementation and allow use of more open files.
This commit is contained in:
parent
9fccccbb3d
commit
7a6861e28d
@ -47,14 +47,6 @@ typedef struct {
|
|||||||
#define MAX_FILES 16
|
#define MAX_FILES 16
|
||||||
static FAT_FILE *file_table[MAX_FILES];
|
static FAT_FILE *file_table[MAX_FILES];
|
||||||
|
|
||||||
static bool isatty_(int fileno)
|
|
||||||
{
|
|
||||||
if (fileno >= 0 && fileno <= 2) {
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
|
|
||||||
/*
|
/*
|
||||||
allocate a file descriptor
|
allocate a file descriptor
|
||||||
*/
|
*/
|
||||||
@ -65,9 +57,6 @@ static int new_file_descriptor(const char *pathname)
|
|||||||
FIL *fh;
|
FIL *fh;
|
||||||
|
|
||||||
for (i=0; i<MAX_FILES; ++i) {
|
for (i=0; i<MAX_FILES; ++i) {
|
||||||
if (isatty_(i)) {
|
|
||||||
continue;
|
|
||||||
}
|
|
||||||
if (file_table[i] == NULL) {
|
if (file_table[i] == NULL) {
|
||||||
stream = (FAT_FILE *) calloc(sizeof(FAT_FILE),1);
|
stream = (FAT_FILE *) calloc(sizeof(FAT_FILE),1);
|
||||||
if (stream == NULL) {
|
if (stream == NULL) {
|
||||||
@ -120,11 +109,6 @@ static int free_file_descriptor(int fileno)
|
|||||||
FAT_FILE *stream;
|
FAT_FILE *stream;
|
||||||
FIL *fh;
|
FIL *fh;
|
||||||
|
|
||||||
if (isatty_( fileno )) {
|
|
||||||
errno = EBADF;
|
|
||||||
return -1;
|
|
||||||
}
|
|
||||||
|
|
||||||
// checks if fileno out of bounds
|
// checks if fileno out of bounds
|
||||||
stream = fileno_to_stream(fileno);
|
stream = fileno_to_stream(fileno);
|
||||||
if (stream == nullptr) {
|
if (stream == nullptr) {
|
||||||
@ -150,11 +134,6 @@ static FIL *fileno_to_fatfs(int fileno)
|
|||||||
FAT_FILE *stream;
|
FAT_FILE *stream;
|
||||||
FIL *fh;
|
FIL *fh;
|
||||||
|
|
||||||
if (isatty_(fileno)) {
|
|
||||||
errno = EBADF;
|
|
||||||
return nullptr;
|
|
||||||
}
|
|
||||||
|
|
||||||
// checks if fileno out of bounds
|
// checks if fileno out of bounds
|
||||||
stream = fileno_to_stream(fileno);
|
stream = fileno_to_stream(fileno);
|
||||||
if (stream == nullptr) {
|
if (stream == nullptr) {
|
||||||
@ -538,9 +517,6 @@ off_t AP_Filesystem_FATFS::lseek(int fileno, off_t position, int whence)
|
|||||||
errno = EMFILE;
|
errno = EMFILE;
|
||||||
return -1;
|
return -1;
|
||||||
}
|
}
|
||||||
if (isatty_(fileno)) {
|
|
||||||
return -1;
|
|
||||||
}
|
|
||||||
|
|
||||||
if (whence == SEEK_END) {
|
if (whence == SEEK_END) {
|
||||||
position += f_size(fh);
|
position += f_size(fh);
|
||||||
|
Loading…
Reference in New Issue
Block a user