APM:Libraries
AP_BoardConfig_CAN.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include <AP_HAL/AP_HAL.h>
4 #include "AP_BoardConfig.h"
5 #include <AP_Common/AP_Common.h>
6 #include <AP_Param/AP_Param.h>
7 #if CONFIG_HAL_BOARD != HAL_BOARD_CHIBIOS //we don't have ioctls in ChibiOS
8 #include <sys/ioctl.h>
9 #endif
10 #if HAL_WITH_UAVCAN
11 #define UAVCAN_PROTOCOL_ENABLE 1
12 
13 class AP_BoardConfig_CAN {
14 public:
15  AP_BoardConfig_CAN() {
16  AP_Param::setup_object_defaults(this, var_info);
17  };
18 
19  /* Do not allow copies */
20  AP_BoardConfig_CAN(const AP_BoardConfig_CAN &other) = delete;
21  AP_BoardConfig_CAN &operator=(const AP_BoardConfig_CAN&) = delete;
22 
23  void init(void);
24 
25  static const struct AP_Param::GroupInfo var_info[];
26 
27  class CAN_if_var_info {
28  friend class AP_BoardConfig_CAN;
29 
30  public:
31  CAN_if_var_info()
32  {
33  AP_Param::setup_object_defaults(this, var_info);
34  }
35 
36  static const struct AP_Param::GroupInfo var_info[];
37 
38  private:
39  AP_Int8 _driver_number;
40  AP_Int8 _can_debug;
41  AP_Int32 _can_bitrate;
42  };
43 
44  class CAN_driver_var_info {
45  friend class AP_BoardConfig_CAN;
46 
47  public:
48  CAN_driver_var_info() :
49  _uavcan(nullptr)
50  {
51  AP_Param::setup_object_defaults(this, var_info);
52  }
53  static const struct AP_Param::GroupInfo var_info[];
54 
55  private:
56  AP_Int8 _protocol;
57 
58  AP_UAVCAN* _uavcan;
59  };
60 
61  // returns number of enabled CAN interfaces
62  static int8_t get_can_num_ifaces(void)
63  {
64  uint8_t ret = 0;
65 
66  for (uint8_t i = 0; i < MAX_NUMBER_OF_CAN_INTERFACES; i++) {
67  if (_st_driver_number[i]) {
68  ret++;
69  }
70  }
71 
72  return ret;
73  }
74 
75  static int8_t get_can_debug(uint8_t i)
76  {
77  if (i < MAX_NUMBER_OF_CAN_INTERFACES) {
78  return _st_can_debug[i];
79  }
80  return 0;
81  }
82 
83  // return maximum level of debug
84  static int8_t get_can_debug(void)
85  {
86  uint8_t ret = 0;
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;
90  }
91  return ret;
92  }
93 
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];
96 
97  static int8_t _st_driver_number[MAX_NUMBER_OF_CAN_INTERFACES];
98  static int8_t _st_can_debug[MAX_NUMBER_OF_CAN_INTERFACES];
99 
100  void setup_canbus(void);
101 
102 };
103 #endif
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.
Definition: system.cpp:136
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)
Definition: AP_Param.cpp:1214