mirror of https://github.com/ArduPilot/ardupilot
AP_CANManager: correct array bounds used for sanity check
both of these are currently HAL_MAX_CAN_PROTOCOL_DRIVERS in length
This commit is contained in:
parent
43a4160487
commit
565e3f0175
|
@ -77,7 +77,7 @@ public:
|
||||||
// return driver for index i
|
// return driver for index i
|
||||||
AP_CANDriver* get_driver(uint8_t i) const
|
AP_CANDriver* get_driver(uint8_t i) const
|
||||||
{
|
{
|
||||||
if (i < HAL_NUM_CAN_IFACES) {
|
if (i < ARRAY_SIZE(_drivers)) {
|
||||||
return _drivers[i];
|
return _drivers[i];
|
||||||
}
|
}
|
||||||
return nullptr;
|
return nullptr;
|
||||||
|
@ -97,7 +97,7 @@ public:
|
||||||
// return driver type index i
|
// return driver type index i
|
||||||
AP_CAN::Protocol get_driver_type(uint8_t i) const
|
AP_CAN::Protocol get_driver_type(uint8_t i) const
|
||||||
{
|
{
|
||||||
if (i < HAL_NUM_CAN_IFACES) {
|
if (i < ARRAY_SIZE(_driver_type_cache)) {
|
||||||
return _driver_type_cache[i];
|
return _driver_type_cache[i];
|
||||||
}
|
}
|
||||||
return AP_CAN::Protocol::None;
|
return AP_CAN::Protocol::None;
|
||||||
|
|
Loading…
Reference in New Issue