mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_RangeFinder: invalidate param count when changing param tree structure
This commit is contained in:
parent
d7555b4b86
commit
ffe9fa22a1
@ -510,6 +510,9 @@ void RangeFinder::detect_instance(uint8_t instance, uint8_t& serial_instance)
|
|||||||
if (drivers[instance] && state[instance].var_info) {
|
if (drivers[instance] && state[instance].var_info) {
|
||||||
backend_var_info[instance] = state[instance].var_info;
|
backend_var_info[instance] = state[instance].var_info;
|
||||||
AP_Param::load_object_from_eeprom(drivers[instance], backend_var_info[instance]);
|
AP_Param::load_object_from_eeprom(drivers[instance], backend_var_info[instance]);
|
||||||
|
|
||||||
|
// param count could have changed
|
||||||
|
AP_Param::invalidate_count();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user