AP_RangeFinder: fixed use of configured() vs configured_in_storage()

This commit is contained in:
Andrew Tridgell 2022-05-12 08:04:37 +10:00 committed by Peter Barker
parent 72470e290c
commit 5413893c91
1 changed files with 3 additions and 2 deletions

View File

@ -175,8 +175,9 @@ RangeFinder::RangeFinder()
}
void RangeFinder::convert_params(void) {
if (params[0].type.configured_in_storage()) {
// _params[0]._type will always be configured in storage after conversion is done the first time
if (params[0].type.configured()) {
// _params[0]._type will always be configured after conversion is done the first time
// or the user has set a type in a defaults.parm file or via apj tool
return;
}