|
|
|
@ -90,18 +90,10 @@ void AP_BoardConfig_CAN::init()
@@ -90,18 +90,10 @@ void AP_BoardConfig_CAN::init()
|
|
|
|
|
_st_can_debug[i] = (int8_t) _var_info_can[i]._can_debug; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN |
|
|
|
|
px4_setup_canbus(); |
|
|
|
|
#elif CONFIG_HAL_BOARD == HAL_BOARD_LINUX |
|
|
|
|
linux_setup_canbus(); |
|
|
|
|
#endif |
|
|
|
|
setup_canbus(); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN |
|
|
|
|
/*
|
|
|
|
|
setup CANBUS drivers |
|
|
|
|
*/ |
|
|
|
|
void AP_BoardConfig_CAN::px4_setup_canbus(void) |
|
|
|
|
void AP_BoardConfig_CAN::setup_canbus(void) |
|
|
|
|
{ |
|
|
|
|
// Create all drivers that we need
|
|
|
|
|
bool initret = true; |
|
|
|
@ -110,7 +102,13 @@ void AP_BoardConfig_CAN::px4_setup_canbus(void)
@@ -110,7 +102,13 @@ void AP_BoardConfig_CAN::px4_setup_canbus(void)
|
|
|
|
|
|
|
|
|
|
if (drv_num != 0 && drv_num <= MAX_NUMBER_OF_CAN_DRIVERS) { |
|
|
|
|
if (hal.can_mgr[drv_num - 1] == nullptr) { |
|
|
|
|
const_cast <AP_HAL::HAL&> (hal).can_mgr[drv_num - 1] = new PX4::PX4CANManager; |
|
|
|
|
|
|
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN |
|
|
|
|
const_cast <AP_HAL::HAL&> (hal).can_mgr[drv_num - 1] = new PX4::PX4CANManager; |
|
|
|
|
#elif CONFIG_HAL_BOARD == HAL_BOARD_LINUX |
|
|
|
|
const_cast <AP_HAL::HAL&> (hal).can_mgr[drv_num - 1] = new Linux::CANManager; |
|
|
|
|
#endif |
|
|
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
if (hal.can_mgr[drv_num - 1] != nullptr) { |
|
|
|
@ -144,6 +142,7 @@ void AP_BoardConfig_CAN::px4_setup_canbus(void)
@@ -144,6 +142,7 @@ void AP_BoardConfig_CAN::px4_setup_canbus(void)
|
|
|
|
|
} else { |
|
|
|
|
printf("Failed to initialize uavcan interface %d\n\r", i + 1); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
} else { |
|
|
|
|
AP_HAL::panic("Failed to allocate uavcan %d\n\r", i + 1); |
|
|
|
|
} |
|
|
|
@ -160,38 +159,5 @@ void AP_BoardConfig_CAN::px4_setup_canbus(void)
@@ -160,38 +159,5 @@ void AP_BoardConfig_CAN::px4_setup_canbus(void)
|
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
#elif CONFIG_HAL_BOARD == HAL_BOARD_LINUX |
|
|
|
|
void AP_BoardConfig_CAN::linux_setup_canbus(void) { |
|
|
|
|
for (uint8_t i = 0; i < MAX_NUMBER_OF_CAN_INTERFACES; i++) { |
|
|
|
|
|
|
|
|
|
uint8_t drv_num = _var_info_can[i]._driver_number; |
|
|
|
|
|
|
|
|
|
if (drv_num != 0 && drv_num <= MAX_NUMBER_OF_CAN_DRIVERS) { |
|
|
|
|
if (hal.can_mgr[drv_num - 1] == nullptr) { |
|
|
|
|
const_cast <AP_HAL::HAL&> (hal).can_mgr[drv_num - 1] = new Linux::CANManager; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
if (hal.can_mgr[drv_num - 1] != nullptr) { |
|
|
|
|
_var_info_can_protocol[i]._uavcan = new AP_UAVCAN; |
|
|
|
|
if (_var_info_can_protocol[i]._uavcan != nullptr) { |
|
|
|
|
AP_Param::load_object_from_eeprom(_var_info_can_protocol[i]._uavcan, AP_UAVCAN::var_info); |
|
|
|
|
|
|
|
|
|
hal.can_mgr[i]->set_UAVCAN(_var_info_can_protocol[i]._uavcan); |
|
|
|
|
_var_info_can_protocol[i]._uavcan->set_parent_can_mgr(hal.can_mgr[i]);
|
|
|
|
|
|
|
|
|
|
if (!hal.can_mgr[i]->begin(_var_info_can[i]._can_bitrate, i)) { |
|
|
|
|
hal.console->printf("Failed to initialize can_mgr\n"); |
|
|
|
|
} else { |
|
|
|
|
hal.console->printf("can_mgr initialized well\n"); |
|
|
|
|
} |
|
|
|
|
} else { |
|
|
|
|
hal.console->printf("AP_UAVCAN failed to allocate\n"); |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
#endif |
|
|
|
|
#endif |
|
|
|
|
|
|
|
|
|