mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-05 07:28:29 -04:00
AP_ROMFS: added find_size()
This commit is contained in:
parent
7912fcd511
commit
aa7ae2327d
@ -53,7 +53,7 @@ const AP_ROMFS::embedded_file *AP_ROMFS::find_file(const char *name)
|
|||||||
const uint8_t *AP_ROMFS::find_decompress(const char *name, uint32_t &size)
|
const uint8_t *AP_ROMFS::find_decompress(const char *name, uint32_t &size)
|
||||||
{
|
{
|
||||||
const struct embedded_file *f = find_file(name);
|
const struct embedded_file *f = find_file(name);
|
||||||
if (!f) {
|
if (f == nullptr) {
|
||||||
return nullptr;
|
return nullptr;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -146,3 +146,17 @@ const char *AP_ROMFS::dir_list(const char *dirname, uint16_t &ofs)
|
|||||||
}
|
}
|
||||||
return nullptr;
|
return nullptr;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/*
|
||||||
|
find a compressed file and return its size
|
||||||
|
*/
|
||||||
|
bool AP_ROMFS::find_size(const char *name, uint32_t &size)
|
||||||
|
{
|
||||||
|
const struct embedded_file *f = find_file(name);
|
||||||
|
if (f == nullptr) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
size = f->decompressed_size;
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
@ -16,6 +16,9 @@ public:
|
|||||||
// free returned data
|
// free returned data
|
||||||
static void free(const uint8_t *data);
|
static void free(const uint8_t *data);
|
||||||
|
|
||||||
|
// get the size of a file without decompressing
|
||||||
|
static bool find_size(const char *name, uint32_t &size);
|
||||||
|
|
||||||
/*
|
/*
|
||||||
directory listing interface. Start with ofs=0. Returns pathnames
|
directory listing interface. Start with ofs=0. Returns pathnames
|
||||||
that match dirname prefix. Ends with nullptr return when no more
|
that match dirname prefix. Ends with nullptr return when no more
|
||||||
|
Loading…
Reference in New Issue
Block a user