Skip to content

Commit 53259e0

Browse files
committed
AP_CANManager: use a switch statement to tidy driver allocation
1 parent 364419b commit 53259e0

File tree

1 file changed

+6
-5
lines changed

1 file changed

+6
-5
lines changed

libraries/AP_CANManager/AP_CANManager.cpp

Lines changed: 6 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -199,8 +199,9 @@ void AP_CANManager::init()
199199
}
200200

201201
// Allocate the set type of Driver
202+
switch (drv_type[drv_num]) {
202203
#if HAL_ENABLE_DRONECAN_DRIVERS
203-
if (drv_type[drv_num] == AP_CAN::Protocol::DroneCAN) {
204+
case AP_CAN::Protocol::DroneCAN:
204205
_drivers[drv_num] = _drv_param[drv_num]._uavcan = NEW_NOTHROW AP_DroneCAN(drv_num);
205206

206207
if (_drivers[drv_num] == nullptr) {
@@ -209,10 +210,10 @@ void AP_CANManager::init()
209210
}
210211

211212
AP_Param::load_object_from_eeprom((AP_DroneCAN*)_drivers[drv_num], AP_DroneCAN::var_info);
212-
} else
213+
break;
213214
#endif
214215
#if HAL_PICCOLO_CAN_ENABLE
215-
if (drv_type[drv_num] == AP_CAN::Protocol::PiccoloCAN) {
216+
case AP_CAN::Protocol::PiccoloCAN:
216217
_drivers[drv_num] = _drv_param[drv_num]._piccolocan = NEW_NOTHROW AP_PiccoloCAN;
217218

218219
if (_drivers[drv_num] == nullptr) {
@@ -221,9 +222,9 @@ void AP_CANManager::init()
221222
}
222223

223224
AP_Param::load_object_from_eeprom((AP_PiccoloCAN*)_drivers[drv_num], AP_PiccoloCAN::var_info);
224-
} else
225+
break;
225226
#endif
226-
{
227+
default:
227228
continue;
228229
}
229230

0 commit comments

Comments
 (0)