diff --git a/Tools/AP_Bootloader/network.cpp b/Tools/AP_Bootloader/network.cpp index 2a78b199a9604..9b0fe28539cd9 100644 --- a/Tools/AP_Bootloader/network.cpp +++ b/Tools/AP_Bootloader/network.cpp @@ -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-str0getpageaddr(0); diff --git a/libraries/AP_Param/AP_Param.cpp b/libraries/AP_Param/AP_Param.cpp index e3983e2812b9a..e9838d6a98ff9 100644 --- a/libraries/AP_Param/AP_Param.cpp +++ b/libraries/AP_Param/AP_Param.cpp @@ -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 @@ -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) { @@ -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) { diff --git a/libraries/AP_Param/AP_Param.h b/libraries/AP_Param/AP_Param.h index 85d533c1fd148..ddd6f4ce638f9 100644 --- a/libraries/AP_Param/AP_Param.h +++ b/libraries/AP_Param/AP_Param.h @@ -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); /* diff --git a/libraries/AP_ROMFS/AP_ROMFS.cpp b/libraries/AP_ROMFS/AP_ROMFS.cpp index 67adb2313cc53..37b8a7e6b28a5 100644 --- a/libraries/AP_ROMFS/AP_ROMFS.cpp +++ b/libraries/AP_ROMFS/AP_ROMFS.cpp @@ -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) { @@ -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); @@ -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 diff --git a/libraries/AP_ROMFS/AP_ROMFS.h b/libraries/AP_ROMFS/AP_ROMFS.h index 33a7c219fb7f0..e0fecbfa1f415 100644 --- a/libraries/AP_ROMFS/AP_ROMFS.h +++ b/libraries/AP_ROMFS/AP_ROMFS.h @@ -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); /*