mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_CANManager: fixed use of CANSensor on multiple ports
we should not increment _num_drivers if we don't have a driver yet
This commit is contained in:
parent
3b7207a5e4
commit
6ed4eca57f
@ -186,8 +186,7 @@ void AP_CANManager::init()
|
||||
continue;
|
||||
}
|
||||
|
||||
_num_drivers++;
|
||||
if (_num_drivers > HAL_MAX_CAN_PROTOCOL_DRIVERS) {
|
||||
if (_num_drivers >= HAL_MAX_CAN_PROTOCOL_DRIVERS) {
|
||||
// We are exceeding number of drivers,
|
||||
// this can't be happening time to panic
|
||||
AP_BoardConfig::config_error("Max number of CAN Drivers exceeded\n\r");
|
||||
@ -247,6 +246,8 @@ void AP_CANManager::init()
|
||||
continue;
|
||||
}
|
||||
|
||||
_num_drivers++;
|
||||
|
||||
// Hook this interface to the selected Driver Type
|
||||
_drivers[drv_num]->add_interface(iface);
|
||||
log_text(AP_CANManager::LOG_INFO, LOG_TAG, "Adding Interface %d to Driver %d", i + 1, drv_num + 1);
|
||||
|
Loading…
Reference in New Issue
Block a user