mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
DataFlash: enable minimal file mode
This adds a "minimal" dataflash mode with a board specific macro. The QURT port uses this to avoid problematic system calls that are buggy in the QURT RTOS With some pending updates to QURT we may be able to remove some (or all) of this
This commit is contained in:
parent
a042845da8
commit
b967140572
@ -17,6 +17,7 @@
|
||||
#if HAL_OS_POSIX_IO
|
||||
#include "DataFlash_File.h"
|
||||
|
||||
#include <AP_Common/AP_Common.h>
|
||||
#include <sys/stat.h>
|
||||
#include <sys/types.h>
|
||||
#include <unistd.h>
|
||||
@ -34,7 +35,7 @@
|
||||
#ifdef __APPLE__
|
||||
#include <sys/param.h>
|
||||
#include <sys/mount.h>
|
||||
#else
|
||||
#elif !DATAFLASH_FILE_MINIMAL
|
||||
#include <sys/statfs.h>
|
||||
#endif
|
||||
|
||||
@ -98,7 +99,7 @@ void DataFlash_File::Init()
|
||||
|
||||
semaphore = hal.util->new_semaphore();
|
||||
if (semaphore == nullptr) {
|
||||
hal.console->printf("Failed to create DataFlash_File semaphore\n");
|
||||
AP_HAL::panic("Failed to create DataFlash_File semaphore");
|
||||
return;
|
||||
}
|
||||
|
||||
@ -122,6 +123,7 @@ void DataFlash_File::Init()
|
||||
_log_directory = custom_dir;
|
||||
}
|
||||
|
||||
#if !DATAFLASH_FILE_MINIMAL
|
||||
ret = stat(_log_directory, &st);
|
||||
if (ret == -1) {
|
||||
ret = mkdir(_log_directory, 0777);
|
||||
@ -130,6 +132,8 @@ void DataFlash_File::Init()
|
||||
hal.console->printf("Failed to create log directory %s\n", _log_directory);
|
||||
return;
|
||||
}
|
||||
#endif
|
||||
|
||||
if (_writebuf != NULL) {
|
||||
free(_writebuf);
|
||||
_writebuf = NULL;
|
||||
@ -166,12 +170,20 @@ void DataFlash_File::Init()
|
||||
|
||||
bool DataFlash_File::file_exists(const char *filename) const
|
||||
{
|
||||
#if DATAFLASH_FILE_MINIMAL
|
||||
int fd = open(filename, O_RDONLY);
|
||||
if (fd == -1) {
|
||||
return false;
|
||||
}
|
||||
close(fd);
|
||||
#else
|
||||
struct stat st;
|
||||
if (stat(filename, &st) == -1) {
|
||||
// hopefully errno==ENOENT. If some error occurs it is
|
||||
// probably better to assume this file exists.
|
||||
return false;
|
||||
}
|
||||
#endif
|
||||
return true;
|
||||
}
|
||||
|
||||
@ -208,11 +220,16 @@ bool DataFlash_File::CardInserted(void)
|
||||
// returns -1 on error
|
||||
int64_t DataFlash_File::disk_space_avail()
|
||||
{
|
||||
#if !DATAFLASH_FILE_MINIMAL
|
||||
struct statfs stats;
|
||||
if (statfs(_log_directory, &stats) < 0) {
|
||||
return -1;
|
||||
}
|
||||
return (((int64_t)stats.f_bavail) * stats.f_bsize);
|
||||
#else
|
||||
// return a fake disk space size
|
||||
return 100*1000*1000UL;
|
||||
#endif
|
||||
}
|
||||
|
||||
// returns the total amount of disk space (in use + available) in
|
||||
@ -220,11 +237,16 @@ int64_t DataFlash_File::disk_space_avail()
|
||||
// returns -1 on error
|
||||
int64_t DataFlash_File::disk_space()
|
||||
{
|
||||
#if !DATAFLASH_FILE_MINIMAL
|
||||
struct statfs stats;
|
||||
if (statfs(_log_directory, &stats) < 0) {
|
||||
return -1;
|
||||
}
|
||||
return (((int64_t)stats.f_blocks) * stats.f_bsize);
|
||||
#else
|
||||
// return fake disk space size
|
||||
return 200*1000*1000UL;
|
||||
#endif
|
||||
}
|
||||
|
||||
// returns the available space in _log_directory as a percentage
|
||||
@ -247,6 +269,9 @@ float DataFlash_File::avail_space_percent()
|
||||
// returns 0 if no log was found
|
||||
uint16_t DataFlash_File::find_oldest_log()
|
||||
{
|
||||
#if DATAFLASH_FILE_MINIMAL
|
||||
return 0;
|
||||
#else
|
||||
if (_cached_oldest_log != 0) {
|
||||
return _cached_oldest_log;
|
||||
}
|
||||
@ -306,8 +331,10 @@ uint16_t DataFlash_File::find_oldest_log()
|
||||
_cached_oldest_log = current_oldest_log;
|
||||
|
||||
return current_oldest_log;
|
||||
#endif
|
||||
}
|
||||
|
||||
#if !DATAFLASH_FILE_MINIMAL
|
||||
void DataFlash_File::Prep_MinSpace()
|
||||
{
|
||||
const uint16_t first_log_to_remove = find_oldest_log();
|
||||
@ -364,13 +391,16 @@ void DataFlash_File::Prep_MinSpace()
|
||||
}
|
||||
} while (log_to_remove != first_log_to_remove);
|
||||
}
|
||||
#endif
|
||||
|
||||
void DataFlash_File::Prep() {
|
||||
if (hal.util->get_soft_armed()) {
|
||||
// do not want to do any filesystem operations while we are e.g. flying
|
||||
return;
|
||||
}
|
||||
#if !DATAFLASH_FILE_MINIMAL
|
||||
Prep_MinSpace();
|
||||
#endif
|
||||
}
|
||||
|
||||
bool DataFlash_File::NeedPrep()
|
||||
@ -419,6 +449,7 @@ void DataFlash_File::EraseAll()
|
||||
{
|
||||
uint16_t log_num;
|
||||
stop_logging();
|
||||
#if !DATAFLASH_FILE_MINIMAL
|
||||
for (log_num=1; log_num<=MAX_LOG_FILES; log_num++) {
|
||||
char *fname = _log_file_name(log_num);
|
||||
if (fname == NULL) {
|
||||
@ -432,7 +463,7 @@ void DataFlash_File::EraseAll()
|
||||
unlink(fname);
|
||||
free(fname);
|
||||
}
|
||||
|
||||
#endif
|
||||
_cached_oldest_log = 0;
|
||||
}
|
||||
|
||||
@ -536,22 +567,24 @@ uint16_t DataFlash_File::find_last_log()
|
||||
if (fname == NULL) {
|
||||
return ret;
|
||||
}
|
||||
FILE *f = ::fopen(fname, "r");
|
||||
int fd = open(fname, O_RDONLY);
|
||||
free(fname);
|
||||
if (f != NULL) {
|
||||
if (fd != -1) {
|
||||
char buf[10];
|
||||
memset(buf, 0, sizeof(buf));
|
||||
// PX4 doesn't have fscanf()
|
||||
if (fread(buf, 1, sizeof(buf)-1, f) > 0) {
|
||||
if (read(fd, buf, sizeof(buf)-1) > 0) {
|
||||
sscanf(buf, "%u", &ret);
|
||||
}
|
||||
fclose(f);
|
||||
close(fd);
|
||||
}
|
||||
return ret;
|
||||
}
|
||||
|
||||
uint32_t DataFlash_File::_get_log_size(const uint16_t log_num) const
|
||||
{
|
||||
#if DATAFLASH_FILE_MINIMAL
|
||||
return 1;
|
||||
#else
|
||||
char *fname = _log_file_name(log_num);
|
||||
if (fname == NULL) {
|
||||
return 0;
|
||||
@ -563,10 +596,14 @@ uint32_t DataFlash_File::_get_log_size(const uint16_t log_num) const
|
||||
}
|
||||
free(fname);
|
||||
return st.st_size;
|
||||
#endif
|
||||
}
|
||||
|
||||
uint32_t DataFlash_File::_get_log_time(const uint16_t log_num) const
|
||||
{
|
||||
#if DATAFLASH_FILE_MINIMAL
|
||||
return 0;
|
||||
#else
|
||||
char *fname = _log_file_name(log_num);
|
||||
if (fname == NULL) {
|
||||
return 0;
|
||||
@ -578,6 +615,7 @@ uint32_t DataFlash_File::_get_log_time(const uint16_t log_num) const
|
||||
}
|
||||
free(fname);
|
||||
return st.st_mtime;
|
||||
#endif
|
||||
}
|
||||
|
||||
/*
|
||||
@ -813,14 +851,19 @@ uint16_t DataFlash_File::start_new_log(void)
|
||||
|
||||
// now update lastlog.txt with the new log number
|
||||
fname = _lastlog_file_name();
|
||||
FILE *f = ::fopen(fname, "w");
|
||||
if (f == NULL) {
|
||||
|
||||
// we avoid fopen()/fprintf() here as it is not available on as many
|
||||
// systems as open/write (specifically the QURT RTOS)
|
||||
int fd = open(fname, O_WRONLY|O_CREAT, 0644);
|
||||
free(fname);
|
||||
if (fd == -1) {
|
||||
return 0xFFFF;
|
||||
}
|
||||
fprintf(f, "%u\r\n", (unsigned)log_num);
|
||||
fclose(f);
|
||||
free(fname);
|
||||
|
||||
char buf[30];
|
||||
snprintf(buf, sizeof(buf), "%u\r\n", (unsigned)log_num);
|
||||
write(fd, buf, strlen(buf));
|
||||
close(fd);
|
||||
|
||||
return log_num;
|
||||
}
|
||||
@ -948,6 +991,7 @@ void DataFlash_File::ListAvailableLogs(AP_HAL::BetterStream *port)
|
||||
}
|
||||
port->printf("\n%u logs\n", (unsigned)num_logs);
|
||||
|
||||
#if !DATAFLASH_FILE_MINIMAL
|
||||
for (uint16_t i=1; i<=num_logs; i++) {
|
||||
uint16_t log_num = _log_num_from_list_entry(i);
|
||||
char *filename = _log_file_name(log_num);
|
||||
@ -968,6 +1012,7 @@ void DataFlash_File::ListAvailableLogs(AP_HAL::BetterStream *port)
|
||||
free(filename);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
port->println();
|
||||
}
|
||||
|
||||
@ -1047,7 +1092,7 @@ void DataFlash_File::_io_timer(void)
|
||||
write.
|
||||
*/
|
||||
BUF_ADVANCEHEAD(_writebuf, nwritten);
|
||||
#if CONFIG_HAL_BOARD != HAL_BOARD_SITL && CONFIG_HAL_BOARD_SUBTYPE != HAL_BOARD_SUBTYPE_LINUX_NONE
|
||||
#if CONFIG_HAL_BOARD != HAL_BOARD_SITL && CONFIG_HAL_BOARD_SUBTYPE != HAL_BOARD_SUBTYPE_LINUX_NONE && CONFIG_HAL_BOARD != HAL_BOARD_QURT
|
||||
::fsync(_write_fd);
|
||||
#endif
|
||||
}
|
||||
|
@ -14,6 +14,18 @@
|
||||
|
||||
#include "DataFlash_Backend.h"
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_QURT
|
||||
/*
|
||||
the QURT port has a limited range of system calls available. It
|
||||
cannot provide all the facilities that DataFlash_File wants. It can
|
||||
provide enough to be useful though, which is what
|
||||
DATAFLASH_FILE_MINIMAL is for
|
||||
*/
|
||||
#define DATAFLASH_FILE_MINIMAL 1
|
||||
#else
|
||||
#define DATAFLASH_FILE_MINIMAL 0
|
||||
#endif
|
||||
|
||||
class DataFlash_File : public DataFlash_Backend
|
||||
{
|
||||
public:
|
||||
|
@ -36,9 +36,11 @@ void DataFlash_Class::Init(const struct LogStructure *structures, uint8_t num_ty
|
||||
DFMessageWriter_DFLogStart *message_writer =
|
||||
new DFMessageWriter_DFLogStart(_firmware_string);
|
||||
if (message_writer != NULL) {
|
||||
#if HAL_OS_POSIX_IO
|
||||
backends[_next_backend] = new DataFlash_File(*this,
|
||||
message_writer,
|
||||
HAL_BOARD_LOG_DIRECTORY);
|
||||
#endif
|
||||
}
|
||||
if (backends[_next_backend] == NULL) {
|
||||
hal.console->printf("Unable to open DataFlash_File");
|
||||
|
Loading…
Reference in New Issue
Block a user