mirror of https://github.com/ArduPilot/ardupilot
AP_CANManager: use a switch statement to tidy driver allocation
This commit is contained in:
parent
23f628f26b
commit
a0ac6f22df
|
@ -199,8 +199,9 @@ void AP_CANManager::init()
|
|||
}
|
||||
|
||||
// Allocate the set type of Driver
|
||||
switch (drv_type[drv_num]) {
|
||||
#if HAL_ENABLE_DRONECAN_DRIVERS
|
||||
if (drv_type[drv_num] == AP_CAN::Protocol::DroneCAN) {
|
||||
case AP_CAN::Protocol::DroneCAN:
|
||||
_drivers[drv_num] = _drv_param[drv_num]._uavcan = NEW_NOTHROW AP_DroneCAN(drv_num);
|
||||
|
||||
if (_drivers[drv_num] == nullptr) {
|
||||
|
@ -209,10 +210,10 @@ void AP_CANManager::init()
|
|||
}
|
||||
|
||||
AP_Param::load_object_from_eeprom((AP_DroneCAN*)_drivers[drv_num], AP_DroneCAN::var_info);
|
||||
} else
|
||||
break;
|
||||
#endif
|
||||
#if HAL_PICCOLO_CAN_ENABLE
|
||||
if (drv_type[drv_num] == AP_CAN::Protocol::PiccoloCAN) {
|
||||
case AP_CAN::Protocol::PiccoloCAN:
|
||||
_drivers[drv_num] = _drv_param[drv_num]._piccolocan = NEW_NOTHROW AP_PiccoloCAN;
|
||||
|
||||
if (_drivers[drv_num] == nullptr) {
|
||||
|
@ -221,9 +222,9 @@ void AP_CANManager::init()
|
|||
}
|
||||
|
||||
AP_Param::load_object_from_eeprom((AP_PiccoloCAN*)_drivers[drv_num], AP_PiccoloCAN::var_info);
|
||||
} else
|
||||
break;
|
||||
#endif
|
||||
{
|
||||
default:
|
||||
continue;
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue