25 #if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN 26 #include <sys/types.h> 32 #elif CONFIG_HAL_BOARD == HAL_BOARD_LINUX 34 #elif CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS 45 #if MAX_NUMBER_OF_CAN_INTERFACES > 0 48 AP_SUBGROUPINFO(_var_info_can[0],
"P1_", 1, AP_BoardConfig_CAN, AP_BoardConfig_CAN::CAN_if_var_info),
51 #if MAX_NUMBER_OF_CAN_INTERFACES > 1 54 AP_SUBGROUPINFO(_var_info_can[1],
"P2_", 2, AP_BoardConfig_CAN, AP_BoardConfig_CAN::CAN_if_var_info),
57 #if MAX_NUMBER_OF_CAN_INTERFACES > 2 60 AP_SUBGROUPINFO(_var_info_can[2],
"P3_", 3, AP_BoardConfig_CAN, AP_BoardConfig_CAN::CAN_if_var_info),
63 #if MAX_NUMBER_OF_CAN_DRIVERS > 0 66 AP_SUBGROUPINFO(_var_info_can_protocol[0],
"D1_", 4, AP_BoardConfig_CAN, AP_BoardConfig_CAN::CAN_driver_var_info),
69 #if MAX_NUMBER_OF_CAN_DRIVERS > 1 72 AP_SUBGROUPINFO(_var_info_can_protocol[1],
"D2_", 5, AP_BoardConfig_CAN, AP_BoardConfig_CAN::CAN_driver_var_info),
75 #if MAX_NUMBER_OF_CAN_DRIVERS > 2 78 AP_SUBGROUPINFO(_var_info_can_protocol[2],
"D3_", 6, AP_BoardConfig_CAN, AP_BoardConfig_CAN::CAN_driver_var_info),
84 int8_t AP_BoardConfig_CAN::_st_driver_number[MAX_NUMBER_OF_CAN_INTERFACES];
85 int8_t AP_BoardConfig_CAN::_st_can_debug[MAX_NUMBER_OF_CAN_INTERFACES];
89 for (uint8_t i = 0; i < MAX_NUMBER_OF_CAN_INTERFACES; i++)
91 _st_driver_number[i] = (int8_t) _var_info_can[i]._driver_number;
92 _st_can_debug[i] = (int8_t) _var_info_can[i]._can_debug;
98 void AP_BoardConfig_CAN::setup_canbus(
void)
102 for (uint8_t i = 0; i < MAX_NUMBER_OF_CAN_INTERFACES; i++) {
103 uint8_t drv_num = _var_info_can[i]._driver_number;
105 if (drv_num != 0 && drv_num <= MAX_NUMBER_OF_CAN_DRIVERS) {
106 if (hal.
can_mgr[drv_num - 1] ==
nullptr) {
108 #if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN 110 #elif CONFIG_HAL_BOARD == HAL_BOARD_LINUX 112 #elif CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS 113 const_cast <
AP_HAL::HAL&> (
hal).can_mgr[drv_num - 1] =
new ChibiOS::CANManager;
118 if (hal.
can_mgr[drv_num - 1] !=
nullptr) {
119 initret &= hal.
can_mgr[drv_num - 1]->begin(_var_info_can[i]._can_bitrate, i);
121 printf(
"Failed to initialize can interface %d\n\r", i + 1);
126 bool any_uavcan_present =
false;
129 for (uint8_t i = 0; i < MAX_NUMBER_OF_CAN_DRIVERS; i++) {
130 if (hal.
can_mgr[i] !=
nullptr) {
131 hal.
can_mgr[i]->initialized(
true);
132 printf(
"can_mgr %d initialized well\n\r", i + 1);
134 if (_var_info_can_protocol[i]._protocol == UAVCAN_PROTOCOL_ENABLE) {
135 _var_info_can_protocol[i]._uavcan =
new AP_UAVCAN;
137 if (_var_info_can_protocol[i]._uavcan !=
nullptr)
141 hal.
can_mgr[i]->set_UAVCAN(_var_info_can_protocol[i]._uavcan);
142 _var_info_can_protocol[i]._uavcan->set_parent_can_mgr(hal.
can_mgr[i]);
144 if (_var_info_can_protocol[i]._uavcan->try_init() ==
true) {
145 any_uavcan_present =
true;
147 printf(
"Failed to initialize uavcan interface %d\n\r", i + 1);
157 if (any_uavcan_present) {
int printf(const char *fmt,...)
static void load_object_from_eeprom(const void *object_pointer, const struct GroupInfo *group_info)
AP_HAL::CANManager ** can_mgr
virtual void delay(uint16_t ms)=0
virtual void create_uavcan_thread()
static const struct AP_Param::GroupInfo var_info[]
Common definitions and utility routines for the ArduPilot libraries.
void init()
Generic board initialization function.
void panic(const char *errormsg,...) FMT_PRINTF(1
#define AP_SUBGROUPINFO(element, name, idx, thisclazz, elclazz)
AP_HAL::Scheduler * scheduler