mirror of https://github.com/ArduPilot/ardupilot
AP_CANManager: set _driver_type_cache for *all* ifaces
This commit is contained in:
parent
e21063522d
commit
2bbd7d8d91
|
@ -215,14 +215,8 @@ void AP_CANManager::init()
|
||||||
AP_Param::load_object_from_eeprom((AP_DroneCAN*)_drivers[drv_num], AP_DroneCAN::var_info);
|
AP_Param::load_object_from_eeprom((AP_DroneCAN*)_drivers[drv_num], AP_DroneCAN::var_info);
|
||||||
} else
|
} else
|
||||||
#endif
|
#endif
|
||||||
if (drv_type[drv_num] == Driver_Type_KDECAN) {
|
|
||||||
#if AP_KDECAN_ENABLED
|
|
||||||
// cache the driver type so we can detect that it is in the params via get_driver_type().
|
|
||||||
// Normally it is cached after init but this driver's init is handled by CANSensor later on
|
|
||||||
_driver_type_cache[drv_num] = drv_type[drv_num];
|
|
||||||
#endif
|
|
||||||
} else if (drv_type[drv_num] == Driver_Type_PiccoloCAN) {
|
|
||||||
#if HAL_PICCOLO_CAN_ENABLE
|
#if HAL_PICCOLO_CAN_ENABLE
|
||||||
|
if (drv_type[drv_num] == Driver_Type_PiccoloCAN) {
|
||||||
_drivers[drv_num] = _drv_param[drv_num]._piccolocan = new AP_PiccoloCAN;
|
_drivers[drv_num] = _drv_param[drv_num]._piccolocan = new AP_PiccoloCAN;
|
||||||
|
|
||||||
if (_drivers[drv_num] == nullptr) {
|
if (_drivers[drv_num] == nullptr) {
|
||||||
|
@ -231,9 +225,10 @@ void AP_CANManager::init()
|
||||||
}
|
}
|
||||||
|
|
||||||
AP_Param::load_object_from_eeprom((AP_PiccoloCAN*)_drivers[drv_num], AP_PiccoloCAN::var_info);
|
AP_Param::load_object_from_eeprom((AP_PiccoloCAN*)_drivers[drv_num], AP_PiccoloCAN::var_info);
|
||||||
|
} else
|
||||||
#endif
|
#endif
|
||||||
} else if (drv_type[drv_num] == Driver_Type_CANTester) {
|
|
||||||
#if HAL_NUM_CAN_IFACES > 1 && !HAL_MINIMIZE_FEATURES && HAL_ENABLE_CANTESTER
|
#if HAL_NUM_CAN_IFACES > 1 && !HAL_MINIMIZE_FEATURES && HAL_ENABLE_CANTESTER
|
||||||
|
if (drv_type[drv_num] == Driver_Type_CANTester) {
|
||||||
_drivers[drv_num] = _drv_param[drv_num]._testcan = new CANTester;
|
_drivers[drv_num] = _drv_param[drv_num]._testcan = new CANTester;
|
||||||
|
|
||||||
if (_drivers[drv_num] == nullptr) {
|
if (_drivers[drv_num] == nullptr) {
|
||||||
|
@ -241,8 +236,9 @@ void AP_CANManager::init()
|
||||||
continue;
|
continue;
|
||||||
}
|
}
|
||||||
AP_Param::load_object_from_eeprom((CANTester*)_drivers[drv_num], CANTester::var_info);
|
AP_Param::load_object_from_eeprom((CANTester*)_drivers[drv_num], CANTester::var_info);
|
||||||
|
} else
|
||||||
#endif
|
#endif
|
||||||
} else {
|
{
|
||||||
continue;
|
continue;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -256,6 +252,11 @@ void AP_CANManager::init()
|
||||||
|
|
||||||
for (uint8_t drv_num = 0; drv_num < HAL_MAX_CAN_PROTOCOL_DRIVERS; drv_num++) {
|
for (uint8_t drv_num = 0; drv_num < HAL_MAX_CAN_PROTOCOL_DRIVERS; drv_num++) {
|
||||||
//initialise all the Drivers
|
//initialise all the Drivers
|
||||||
|
|
||||||
|
// Cache the driver type, initialized or not, so we can detect that it is in the params at boot via get_driver_type().
|
||||||
|
// This allows drivers that are initialized by CANSensor instead of CANManager to know if they should init or not
|
||||||
|
_driver_type_cache[drv_num] = drv_type[drv_num];
|
||||||
|
|
||||||
if (_drivers[drv_num] == nullptr) {
|
if (_drivers[drv_num] == nullptr) {
|
||||||
continue;
|
continue;
|
||||||
}
|
}
|
||||||
|
@ -272,9 +273,6 @@ void AP_CANManager::init()
|
||||||
}
|
}
|
||||||
|
|
||||||
_drivers[drv_num]->init(drv_num, enable_filter);
|
_drivers[drv_num]->init(drv_num, enable_filter);
|
||||||
// Finally initialise driver type, this will be used
|
|
||||||
// to find and reference protocol drivers
|
|
||||||
_driver_type_cache[drv_num] = drv_type[drv_num];
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
#else
|
#else
|
||||||
|
|
Loading…
Reference in New Issue