Browse Source

AP_RangeFinder: analog: check for valid pin

gps-1.3.1
Iampete1 3 years ago committed by Andrew Tridgell
parent
commit
f667c098a2
  1. 5
      libraries/AP_RangeFinder/AP_RangeFinder_analog.cpp

5
libraries/AP_RangeFinder/AP_RangeFinder_analog.cpp

@ -63,12 +63,11 @@ bool AP_RangeFinder_analog::detect(AP_RangeFinder_Params &_params) @@ -63,12 +63,11 @@ bool AP_RangeFinder_analog::detect(AP_RangeFinder_Params &_params)
*/
void AP_RangeFinder_analog::update_voltage(void)
{
if (source == nullptr) {
if (source == nullptr || !source->set_pin(params.pin)) {
state.voltage_mv = 0;
set_status(RangeFinder::Status::NotConnected);
return;
}
// cope with changed settings
source->set_pin(params.pin);
if (params.ratiometric) {
state.voltage_mv = source->voltage_average_ratiometric() * 1000U;
} else {

Loading…
Cancel
Save