Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

AP_CANManager: use a switch statement to tidy driver allocation #27231

Merged
merged 1 commit into from
Jul 25, 2024
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
11 changes: 6 additions & 5 deletions libraries/AP_CANManager/AP_CANManager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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) {
Expand All @@ -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) {
Expand All @@ -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;
}

Expand Down
Loading