Browse Source

AP_DAL: correct rangefinder get_backend range check

zr-v5.1
Peter Barker 4 years ago committed by Andrew Tridgell
parent
commit
54bae68e02
  1. 3
      libraries/AP_DAL/AP_DAL_RangeFinder.cpp

3
libraries/AP_DAL/AP_DAL_RangeFinder.cpp

@ -119,6 +119,9 @@ AP_DAL_RangeFinder_Backend *AP_DAL_RangeFinder::get_backend(uint8_t id) const @@ -119,6 +119,9 @@ AP_DAL_RangeFinder_Backend *AP_DAL_RangeFinder::get_backend(uint8_t id) const
INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);
return nullptr;
}
if (id >= _RRNH.num_sensors) {
return nullptr;
}
return _backend[id];
}

Loading…
Cancel
Save