mirror of https://github.com/ArduPilot/ardupilot
AP_DAL: correct rangefinder get_backend range check
This commit is contained in:
parent
1bef41b42e
commit
54bae68e02
|
@ -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
|
AP_DAL_RangeFinder_Backend *AP_DAL_RangeFinder::get_backend(uint8_t id) const
|
||||||
{
|
{
|
||||||
if (id >= RANGEFINDER_MAX_INSTANCES) {
|
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;
|
return nullptr;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue