mirror of https://github.com/ArduPilot/ardupilot
Tools: make check_var_info void
Given all the callers die anyway, make it void
This commit is contained in:
parent
33599bd79c
commit
65915441b6
|
@ -532,10 +532,8 @@ void AP_Periph_FW::load_parameters(void)
|
|||
{
|
||||
AP_Param::setup_sketch_defaults();
|
||||
|
||||
if (!AP_Param::check_var_info()) {
|
||||
hal.console->printf("Bad parameter table\n");
|
||||
AP_HAL::panic("Bad parameter table");
|
||||
}
|
||||
AP_Param::check_var_info();
|
||||
|
||||
if (!g.format_version.load() ||
|
||||
g.format_version != Parameters::k_format_version) {
|
||||
// erase all parameters
|
||||
|
|
|
@ -90,9 +90,8 @@ const AP_Param::Info ReplayVehicle::var_info[] = {
|
|||
|
||||
void ReplayVehicle::load_parameters(void)
|
||||
{
|
||||
if (!AP_Param::check_var_info()) {
|
||||
AP_HAL::panic("Bad parameter table");
|
||||
}
|
||||
AP_Param::check_var_info();
|
||||
|
||||
StorageManager::erase();
|
||||
AP_Param::erase_all();
|
||||
// Load all auto-loaded EEPROM variables - also registers thread
|
||||
|
|
Loading…
Reference in New Issue