Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

AP_ROMFS: remove requirement that returned buffer is null-terminated #26184

Closed
wants to merge 4 commits into from
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
24 changes: 12 additions & 12 deletions Tools/AP_Bootloader/network.cpp
Expand Up @@ -307,40 +307,40 @@ BL_Network::web_var BL_Network::variables[] = {
/*
substitute variables of the form {VARNAME}
*/
char *BL_Network::substitute_vars(const char *str, uint32_t size)
char *BL_Network::substitute_vars(const char *buf, uint32_t size)
{
// assume 1024 is enough room for new variables
char *result = (char *)malloc(strlen(str) + 1024);
char *result = (char *)malloc(size + 1024);
if (result == nullptr) {
return nullptr;
}
char *p = result;
const char *str0 = str;
while (*str && str-str0<size) {
if (*str != '{') {
*p++ = *str++;
const char *buf0 = buf;
while (buf-buf0<size && *buf) {
if (*buf != '{') {
*p++ = *buf++;
continue;
}
char *q = strchr(str+1, '}');
char *q = (char*)memchr((const void*)(buf+1), '}', size-(buf+1-buf0));
if (q == nullptr) {
*p++ = *str++;
*p++ = *buf++;
continue;
}
const uint32_t len = (q - str)-1;
const uint32_t len = (q - buf)-1;
bool found = false;
for (auto &v : variables) {
if (strlen(v.name) == len && strncmp(v.name, str+1, len) == 0) {
if (strlen(v.name) == len && strncmp(v.name, buf+1, len) == 0) {
found = true;
strcpy(p, v.value);
p += strlen(v.value);
str = q+1;
buf = q+1;
break;
}
}
if (found) {
continue;
}
*p++ = *str++;
*p++ = *buf++;
}
*p = '\0';
return result;
Expand Down
7 changes: 0 additions & 7 deletions Tools/ardupilotwaf/embed.py
Expand Up @@ -32,21 +32,14 @@ def embed_file(out, f, idx, embedded_name, uncompressed):
write_encode(out, '__EXTFLASHFUNC__ static const uint8_t ap_romfs_%u[] = {' % idx)

if uncompressed:
# terminate if there's not already an existing null. we don't add it to
# the contents to avoid storing the wrong length
null_terminate = 0 not in contents
b = contents
else:
# compress it (max level, max window size, raw stream, max mem usage)
z = zlib.compressobj(level=9, method=zlib.DEFLATED, wbits=-15, memLevel=9)
b = z.compress(contents)
b += z.flush()
# decompressed data will be null terminated at runtime, nothing to do here
null_terminate = False

write_encode(out, ",".join(str(c) for c in b))
if null_terminate:
write_encode(out, ",0")
write_encode(out, '};\n\n');
return crc, len(contents)

Expand Down
3 changes: 0 additions & 3 deletions libraries/AP_HAL_ChibiOS/Util.cpp
Expand Up @@ -304,9 +304,6 @@ Util::FlashBootloader Util::flash_bootloader()
}
#endif

// make sure size is multiple of 32
fw_size = (fw_size + 31U) & ~31U;

bool uptodate = true;
const uint32_t addr = hal.flash->getpageaddr(0);

Expand Down
14 changes: 7 additions & 7 deletions libraries/AP_Param/AP_Param.cpp
Expand Up @@ -1627,15 +1627,15 @@ void AP_Param::load_defaults_file_from_romfs(const char *default_file, bool last
// filename without the prefix:
const char *trimmed_filename = &default_file[strlen(prefix)];

uint32_t string_length;
const uint8_t *text = AP_ROMFS::find_decompress(trimmed_filename, string_length);
if (text == nullptr) {
uint32_t data_length;
const uint8_t *data = AP_ROMFS::find_decompress(trimmed_filename, data_length);
if (data == nullptr) {
return;
}

load_param_defaults((const char*)text, string_length, last_pass);
load_param_defaults((const char*)data, data_length, last_pass);

AP_ROMFS::free(text);
AP_ROMFS::free(data);

}
#endif // HAL_HAVE_AP_ROMFS_EMBEDDED_H
Expand Down Expand Up @@ -2372,7 +2372,7 @@ bool AP_Param::load_defaults_file(const char *filename, bool last_pass)

#if AP_PARAM_MAX_EMBEDDED_PARAM > 0 || (!AP_FILESYSTEM_FILE_READING_ENABLED && defined(HAL_HAVE_AP_ROMFS_EMBEDDED_H))
/*
count the number of parameter defaults present in supplied string
count the number of parameter defaults present in supplied buffer
*/
bool AP_Param::count_param_defaults(const volatile char *ptr, int32_t length, uint16_t &count)
{
Expand Down Expand Up @@ -2429,7 +2429,7 @@ void AP_Param::load_embedded_param_defaults(bool last_pass)
#endif // AP_PARAM_MAX_EMBEDDED_PARAM > 0

/*
* load parameter defaults from supplied string
* load parameter defaults from supplied buffer
*/
void AP_Param::load_param_defaults(const volatile char *ptr, int32_t length, bool last_pass)
{
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_Param/AP_Param.h
Expand Up @@ -750,7 +750,7 @@ class AP_Param
// load an @ROMFS defaults.parm using ROMFS API:
static void load_defaults_file_from_romfs(const char *filename, bool lastpass);

// load defaults from supplied string:
// load defaults from supplied buffer:
static void load_param_defaults(const volatile char *ptr, int32_t length, bool last_pass);

/*
Expand Down
13 changes: 4 additions & 9 deletions libraries/AP_ROMFS/AP_ROMFS.cpp
Expand Up @@ -45,10 +45,8 @@ const AP_ROMFS::embedded_file *AP_ROMFS::find_file(const char *name)
}

/*
find a compressed file and uncompress it. Space for decompressed data comes
from malloc. Caller must be careful to free the resulting data after use. The
file data buffer is guaranteed to contain at least one null (though it may be
at buf[size]).
Find the named file and return its decompressed data and size. Caller must
call AP_ROMFS::free() on the return value after use to free it.
*/
const uint8_t *AP_ROMFS::find_decompress(const char *name, uint32_t &size)
{
Expand All @@ -61,14 +59,11 @@ const uint8_t *AP_ROMFS::find_decompress(const char *name, uint32_t &size)
size = f->decompressed_size;
return f->contents;
#else
uint8_t *decompressed_data = (uint8_t *)malloc(f->decompressed_size+1);
uint8_t *decompressed_data = (uint8_t *)malloc(f->decompressed_size);
if (!decompressed_data) {
return nullptr;
}

// explicitly null-terminate the data
decompressed_data[f->decompressed_size] = 0;

TINF_DATA *d = (TINF_DATA *)malloc(sizeof(TINF_DATA));
if (!d) {
::free(decompressed_data);
Expand Down Expand Up @@ -100,7 +95,7 @@ const uint8_t *AP_ROMFS::find_decompress(const char *name, uint32_t &size)
#endif
}

// free returned data
// free decompressed file data
void AP_ROMFS::free(const uint8_t *data)
{
#ifndef HAL_ROMFS_UNCOMPRESSED
Expand Down
8 changes: 3 additions & 5 deletions libraries/AP_ROMFS/AP_ROMFS.h
Expand Up @@ -7,13 +7,11 @@

class AP_ROMFS {
public:
// find a file and de-compress, assumning gzip format. The
// decompressed data will be allocated with malloc(). You must
// call AP_ROMFS::free() on the return value after use. The next byte after
// the file data is guaranteed to be null.
// Find the named file and return its decompressed data and size. Caller
// must call AP_ROMFS::free() on the return value after use to free it.
static const uint8_t *find_decompress(const char *name, uint32_t &size);

// free returned data
// free decompressed file data
static void free(const uint8_t *data);

/*
Expand Down