AP_BoardConfig_CAN.h 4.0 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161
  1. #pragma once
  2. #include <AP_HAL/AP_HAL.h>
  3. #if HAL_WITH_UAVCAN
  4. #include <AP_Param/AP_Param.h>
  5. #ifndef AP_CAN_DEBUG
  6. #define AP_CAN_DEBUG 0
  7. #endif
  8. class AP_BoardConfig_CAN {
  9. public:
  10. AP_BoardConfig_CAN();
  11. /* Do not allow copies */
  12. AP_BoardConfig_CAN(const AP_BoardConfig_CAN &other) = delete;
  13. AP_BoardConfig_CAN &operator=(const AP_BoardConfig_CAN&) = delete;
  14. static AP_BoardConfig_CAN* get_singleton() {
  15. return _singleton;
  16. }
  17. enum Protocol_Type : uint8_t {
  18. Protocol_Type_None = 0,
  19. Protocol_Type_UAVCAN = 1,
  20. Protocol_Type_KDECAN = 2,
  21. Protocol_Type_ToshibaCAN = 3
  22. };
  23. void init(void);
  24. // returns number of active CAN drivers
  25. uint8_t get_num_drivers(void) const { return _num_drivers; }
  26. // return debug level for interface i
  27. uint8_t get_debug_level(uint8_t i) const {
  28. #if AP_CAN_DEBUG
  29. if (i < MAX_NUMBER_OF_CAN_INTERFACES) {
  30. return _interfaces[i]._driver_number_cache ? _interfaces[i]._debug_level : 0;
  31. }
  32. #endif
  33. return 0;
  34. }
  35. // return maximum level of debug of all interfaces
  36. uint8_t get_debug_level(void) const {
  37. uint8_t ret = 0;
  38. #if AP_CAN_DEBUG
  39. for (uint8_t i = 0; i < MAX_NUMBER_OF_CAN_INTERFACES; i++) {
  40. uint8_t dbg = get_debug_level(i);
  41. ret = (dbg > ret) ? dbg : ret;
  42. }
  43. #endif
  44. return ret;
  45. }
  46. // return maximum level of debug for driver index i
  47. uint8_t get_debug_level_driver(uint8_t i) const {
  48. uint8_t ret = 0;
  49. #if AP_CAN_DEBUG
  50. for (uint8_t j = 0; j < MAX_NUMBER_OF_CAN_INTERFACES; j++) {
  51. if (_interfaces[j]._driver_number_cache == i) {
  52. uint8_t dbg = get_debug_level(j);
  53. ret = (dbg > ret) ? dbg : ret;
  54. }
  55. }
  56. #endif
  57. return ret;
  58. }
  59. // return driver for index i
  60. AP_HAL::CANProtocol* get_driver(uint8_t i) const {
  61. if (i < MAX_NUMBER_OF_CAN_DRIVERS) {
  62. return _drivers[i]._driver;
  63. }
  64. return nullptr;
  65. }
  66. // return protocol type index i
  67. Protocol_Type get_protocol_type(uint8_t i) const {
  68. if (i < MAX_NUMBER_OF_CAN_DRIVERS) {
  69. return _drivers[i]._protocol_type_cache;
  70. }
  71. return Protocol_Type_None;
  72. }
  73. static const struct AP_Param::GroupInfo var_info[];
  74. #if AP_UAVCAN_SLCAN_ENABLED
  75. AP_HAL::UARTDriver *get_slcan_serial();
  76. uint8_t get_slcan_timeout() { return _slcan._timeout; }
  77. void reset_slcan_serial() { _slcan._ser_port.set_and_save_ifchanged(-1); }
  78. #endif
  79. private:
  80. class Interface {
  81. friend class AP_BoardConfig_CAN;
  82. public:
  83. Interface() {
  84. AP_Param::setup_object_defaults(this, var_info);
  85. }
  86. static const struct AP_Param::GroupInfo var_info[];
  87. private:
  88. AP_Int8 _driver_number;
  89. uint8_t _driver_number_cache;
  90. AP_Int32 _bitrate;
  91. #if AP_CAN_DEBUG
  92. AP_Int8 _debug_level;
  93. #endif
  94. };
  95. class Driver {
  96. friend class AP_BoardConfig_CAN;
  97. public:
  98. Driver() {
  99. AP_Param::setup_object_defaults(this, var_info);
  100. }
  101. static const struct AP_Param::GroupInfo var_info[];
  102. private:
  103. AP_Int8 _protocol_type;
  104. Protocol_Type _protocol_type_cache;
  105. AP_HAL::CANProtocol* _driver;
  106. AP_HAL::CANProtocol* _uavcan;
  107. AP_HAL::CANProtocol* _kdecan;
  108. AP_HAL::CANProtocol* _tcan;
  109. };
  110. #if AP_UAVCAN_SLCAN_ENABLED
  111. class SLCAN_Interface {
  112. friend class AP_BoardConfig_CAN;
  113. public:
  114. SLCAN_Interface() {
  115. AP_Param::setup_object_defaults(this, var_info);
  116. }
  117. static const struct AP_Param::GroupInfo var_info[];
  118. private:
  119. AP_Int8 _can_port;
  120. AP_Int8 _ser_port;
  121. AP_Int16 _timeout;
  122. };
  123. SLCAN_Interface _slcan;
  124. #endif
  125. Interface _interfaces[MAX_NUMBER_OF_CAN_INTERFACES];
  126. Driver _drivers[MAX_NUMBER_OF_CAN_DRIVERS];
  127. uint8_t _num_drivers;
  128. static AP_BoardConfig_CAN *_singleton;
  129. };
  130. namespace AP {
  131. AP_BoardConfig_CAN& can();
  132. }
  133. #endif