AP_BoardConfig_CAN.h 4.0 KB

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