AP_DAL: correct rangefinder get_backend range check

This commit is contained in:
Peter Barker 2020-12-01 21:26:07 +11:00 committed by Andrew Tridgell
parent 1bef41b42e
commit 54bae68e02
1 changed files with 4 additions and 1 deletions

View File

@ -116,7 +116,10 @@ bool AP_DAL_RangeFinder::has_orientation(enum Rotation orientation) const
AP_DAL_RangeFinder_Backend *AP_DAL_RangeFinder::get_backend(uint8_t id) const
{
if (id >= RANGEFINDER_MAX_INSTANCES) {
INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);
INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);
return nullptr;
}
if (id >= _RRNH.num_sensors) {
return nullptr;
}