7 #if CONFIG_HAL_BOARD != HAL_BOARD_CHIBIOS //we don't have ioctls in ChibiOS 11 #define UAVCAN_PROTOCOL_ENABLE 1 13 class AP_BoardConfig_CAN {
15 AP_BoardConfig_CAN() {
20 AP_BoardConfig_CAN(
const AP_BoardConfig_CAN &other) =
delete;
21 AP_BoardConfig_CAN &operator=(
const AP_BoardConfig_CAN&) =
delete;
27 class CAN_if_var_info {
28 friend class AP_BoardConfig_CAN;
39 AP_Int8 _driver_number;
41 AP_Int32 _can_bitrate;
44 class CAN_driver_var_info {
45 friend class AP_BoardConfig_CAN;
48 CAN_driver_var_info() :
62 static int8_t get_can_num_ifaces(
void)
66 for (uint8_t i = 0; i < MAX_NUMBER_OF_CAN_INTERFACES; i++) {
67 if (_st_driver_number[i]) {
75 static int8_t get_can_debug(uint8_t i)
77 if (i < MAX_NUMBER_OF_CAN_INTERFACES) {
78 return _st_can_debug[i];
84 static int8_t get_can_debug(
void)
87 for (uint8_t i = 0; i < MAX_NUMBER_OF_CAN_INTERFACES; i++) {
88 uint8_t dbg = get_can_debug(i);
89 ret = (dbg > ret) ? dbg : ret;
94 CAN_if_var_info _var_info_can[MAX_NUMBER_OF_CAN_INTERFACES];
95 CAN_driver_var_info _var_info_can_protocol[MAX_NUMBER_OF_CAN_DRIVERS];
97 static int8_t _st_driver_number[MAX_NUMBER_OF_CAN_INTERFACES];
98 static int8_t _st_can_debug[MAX_NUMBER_OF_CAN_INTERFACES];
100 void setup_canbus(
void);
A system for managing and storing variables that are of general interest to the system.
Common definitions and utility routines for the ArduPilot libraries.
void init()
Generic board initialization function.
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)