2020-11-12 20:02:21 -04:00
|
|
|
/*
|
|
|
|
This program is free software: you can redistribute it and/or modify
|
|
|
|
it under the terms of the GNU General Public License as published by
|
|
|
|
the Free Software Foundation, either version 3 of the License, or
|
|
|
|
(at your option) any later version.
|
|
|
|
|
|
|
|
This program is distributed in the hope that it will be useful,
|
|
|
|
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
|
|
|
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
|
|
|
GNU General Public License for more details.
|
|
|
|
|
|
|
|
You should have received a copy of the GNU General Public License
|
|
|
|
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
|
|
|
*/
|
|
|
|
|
2021-06-08 22:59:23 -03:00
|
|
|
#include <AP_HAL/AP_HAL.h>
|
2020-11-12 20:02:21 -04:00
|
|
|
#include "AP_Filesystem.h"
|
|
|
|
|
2021-06-08 22:59:23 -03:00
|
|
|
extern const AP_HAL::HAL& hal;
|
|
|
|
|
2020-11-12 20:02:21 -04:00
|
|
|
/*
|
2024-02-23 18:09:37 -04:00
|
|
|
Load a file's contents into memory. Returned object must be `delete`d to free
|
|
|
|
the data. The data is guaranteed to be null-terminated such that it can be
|
|
|
|
treated as a string.
|
2020-11-12 20:02:21 -04:00
|
|
|
*/
|
|
|
|
FileData *AP_Filesystem_Backend::load_file(const char *filename)
|
|
|
|
{
|
|
|
|
struct stat st;
|
|
|
|
if (stat(filename, &st) != 0) {
|
|
|
|
return nullptr;
|
|
|
|
}
|
2024-05-26 22:24:11 -03:00
|
|
|
FileData *fd = NEW_NOTHROW FileData(this);
|
2020-11-12 20:02:21 -04:00
|
|
|
if (fd == nullptr) {
|
|
|
|
return nullptr;
|
|
|
|
}
|
2024-02-23 18:09:37 -04:00
|
|
|
// add one byte for null termination; ArduPilot's malloc will zero it.
|
|
|
|
void *data = malloc(st.st_size+1);
|
2020-11-12 20:02:21 -04:00
|
|
|
if (data == nullptr) {
|
|
|
|
delete fd;
|
|
|
|
return nullptr;
|
|
|
|
}
|
|
|
|
int d = open(filename, O_RDONLY);
|
|
|
|
if (d == -1) {
|
|
|
|
free(data);
|
|
|
|
delete fd;
|
|
|
|
return nullptr;
|
|
|
|
}
|
|
|
|
if (read(d, data, st.st_size) != st.st_size) {
|
|
|
|
close(d);
|
|
|
|
free(data);
|
|
|
|
delete fd;
|
|
|
|
return nullptr;
|
|
|
|
}
|
|
|
|
close(d);
|
2024-02-23 18:09:37 -04:00
|
|
|
fd->length = st.st_size; // length does not include our added termination
|
2020-11-12 20:02:21 -04:00
|
|
|
fd->data = (const uint8_t *)data;
|
|
|
|
return fd;
|
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
unload a FileData object
|
|
|
|
*/
|
|
|
|
void AP_Filesystem_Backend::unload_file(FileData *fd)
|
|
|
|
{
|
|
|
|
if (fd->data != nullptr) {
|
|
|
|
free(const_cast<uint8_t *>(fd->data));
|
|
|
|
fd->data = nullptr;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2021-06-08 22:59:23 -03:00
|
|
|
// return true if file operations are allowed
|
|
|
|
bool AP_Filesystem_Backend::file_op_allowed(void) const
|
|
|
|
{
|
|
|
|
if (!hal.util->get_soft_armed() || !hal.scheduler->in_main_thread()) {
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
2020-11-12 20:02:21 -04:00
|
|
|
/*
|
|
|
|
destructor for FileData
|
|
|
|
*/
|
|
|
|
FileData::~FileData()
|
|
|
|
{
|
|
|
|
if (backend != nullptr) {
|
|
|
|
((AP_Filesystem_Backend *)backend)->unload_file(this);
|
|
|
|
}
|
|
|
|
}
|
2021-06-08 22:59:23 -03:00
|
|
|
|