Browse Source

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

apm_2208
Andrew Tridgell 3 years ago committed by Peter Barker
parent
commit
5413893c91
  1. 5
      libraries/AP_RangeFinder/AP_RangeFinder.cpp

5
libraries/AP_RangeFinder/AP_RangeFinder.cpp

@ -175,8 +175,9 @@ RangeFinder::RangeFinder()
} }
void RangeFinder::convert_params(void) { void RangeFinder::convert_params(void) {
if (params[0].type.configured_in_storage()) { if (params[0].type.configured()) {
// _params[0]._type will always be configured in storage after conversion is done the first time // _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; return;
} }

Loading…
Cancel
Save