@ -1274,7 +1274,7 @@ bool AP_Param::load_all()
@@ -1274,7 +1274,7 @@ bool AP_Param::load_all()
struct Param_header phdr ;
uint16_t ofs = sizeof ( AP_Param : : EEPROM_header ) ;
reload_defaults_file ( ) ;
reload_defaults_file ( false ) ;
while ( ofs < _storage . size ( ) ) {
_storage . read_block ( & phdr , ofs , sizeof ( phdr ) ) ;
@ -1302,12 +1302,14 @@ bool AP_Param::load_all()
@@ -1302,12 +1302,14 @@ bool AP_Param::load_all()
}
/*
reload from hal . util defaults file
* reload from hal . util defaults file or embedded param region
* @ last_pass : if this is the last pass on defaults - unknown parameters are
* ignored but if this is set a warning will be emitted
*/
void AP_Param : : reload_defaults_file ( )
void AP_Param : : reload_defaults_file ( bool last_pass )
{
if ( param_defaults_data . length ! = 0 ) {
load_embedded_param_defaults ( ) ;
load_embedded_param_defaults ( last_pass ) ;
return ;
}
@ -1318,7 +1320,7 @@ void AP_Param::reload_defaults_file()
@@ -1318,7 +1320,7 @@ void AP_Param::reload_defaults_file()
*/
const char * default_file = hal . util - > get_custom_defaults_file ( ) ;
if ( default_file ) {
if ( load_defaults_file ( default_file ) ) {
if ( load_defaults_file ( default_file , last_pass ) ) {
printf ( " Loaded defaults from %s \n " , default_file ) ;
} else {
printf ( " Failed to load defaults from %s \n " , default_file ) ;
@ -1815,7 +1817,7 @@ bool AP_Param::count_defaults_in_file(const char *filename, uint16_t &num_defaul
@@ -1815,7 +1817,7 @@ bool AP_Param::count_defaults_in_file(const char *filename, uint16_t &num_defaul
return true ;
}
bool AP_Param : : read_param_defaults_file ( const char * filename )
bool AP_Param : : read_param_defaults_file ( const char * filename , bool last_pass )
{
FILE * f = fopen ( filename , " r " ) ;
if ( f = = nullptr ) {
@ -1834,8 +1836,13 @@ bool AP_Param::read_param_defaults_file(const char *filename)
@@ -1834,8 +1836,13 @@ bool AP_Param::read_param_defaults_file(const char *filename)
enum ap_var_type var_type ;
AP_Param * vp = find ( pname , & var_type ) ;
if ( ! vp ) {
: : printf ( " Ignored unknown param %s in defaults file %s \n " ,
pname , filename ) ;
if ( last_pass ) {
: : printf ( " Ignored unknown param %s in defaults file %s \n " ,
pname , filename ) ;
hal . console - > printf (
" Ignored unknown param %s in defaults file %s \n " ,
pname , filename ) ;
}
continue ;
}
param_overrides [ idx ] . object_ptr = vp ;
@ -1852,7 +1859,7 @@ bool AP_Param::read_param_defaults_file(const char *filename)
@@ -1852,7 +1859,7 @@ bool AP_Param::read_param_defaults_file(const char *filename)
/*
load a default set of parameters from a file
*/
bool AP_Param : : load_defaults_file ( const char * filename )
bool AP_Param : : load_defaults_file ( const char * filename , bool last_pass )
{
if ( filename = = nullptr ) {
return false ;
@ -1894,7 +1901,7 @@ bool AP_Param::load_defaults_file(const char *filename)
@@ -1894,7 +1901,7 @@ bool AP_Param::load_defaults_file(const char *filename)
for ( char * pname = strtok_r ( mutable_filename , " , " , & saveptr ) ;
pname ! = nullptr ;
pname = strtok_r ( nullptr , " , " , & saveptr ) ) {
if ( ! read_param_defaults_file ( pname ) ) {
if ( ! read_param_defaults_file ( pname , last_pass ) ) {
free ( mutable_filename ) ;
return false ;
}
@ -1957,11 +1964,12 @@ bool AP_Param::count_embedded_param_defaults(uint16_t &count)
@@ -1957,11 +1964,12 @@ bool AP_Param::count_embedded_param_defaults(uint16_t &count)
return true ;
}
/*
load a default set of parameters from a embedded parameter region
* load a default set of parameters from a embedded parameter region
* @ last_pass : if this is the last pass on defaults - unknown parameters are
* ignored but if this is set a warning will be emitted
*/
void AP_Param : : load_embedded_param_defaults ( )
void AP_Param : : load_embedded_param_defaults ( bool last_pass )
{
if ( param_overrides ! = nullptr ) {
free ( param_overrides ) ;
@ -2015,8 +2023,13 @@ void AP_Param::load_embedded_param_defaults()
@@ -2015,8 +2023,13 @@ void AP_Param::load_embedded_param_defaults()
enum ap_var_type var_type ;
AP_Param * vp = find ( pname , & var_type ) ;
if ( ! vp ) {
: : printf ( " Ignored unknown param %s from embedded region (offset=%u) \n " ,
pname , ptr - param_defaults_data . data ) ;
if ( last_pass ) {
: : printf ( " Ignored unknown param %s from embedded region (offset=%u) \n " ,
pname , ptr - param_defaults_data . data ) ;
hal . console - > printf (
" Ignored unknown param %s from embedded region (offset=%u) \n " ,
pname , ptr - param_defaults_data . data ) ;
}
continue ;
}
param_overrides [ idx ] . object_ptr = vp ;