mirror of https://github.com/ArduPilot/ardupilot
AP_DAL: correct rangefinder get_backend range check
This commit is contained in:
parent
1bef41b42e
commit
54bae68e02
|
@ -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…
Reference in New Issue