AP_SerialManager.h 8.1 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203
  1. /*
  2. Please contribute your ideas! See http://dev.ardupilot.org for details
  3. This program is free software: you can redistribute it and/or modify
  4. it under the terms of the GNU General Public License as published by
  5. the Free Software Foundation, either version 3 of the License, or
  6. (at your option) any later version.
  7. This program is distributed in the hope that it will be useful,
  8. but WITHOUT ANY WARRANTY; without even the implied warranty of
  9. MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  10. GNU General Public License for more details.
  11. You should have received a copy of the GNU General Public License
  12. along with this program. If not, see <http://www.gnu.org/licenses/>.
  13. */
  14. /*
  15. SerialManager allows defining the protocol and baud rates for the available
  16. serial ports and provides helper functions so objects (like a gimbal) can
  17. find which serial port they should use
  18. */
  19. #pragma once
  20. #include <AP_HAL/AP_HAL.h>
  21. #include <GCS_MAVLink/GCS_MAVLink.h>
  22. #include <AP_Param/AP_Param.h>
  23. #define BAUD_115200 115200
  24. #define AP_SERIALMANAGER_USART2_BUFSIZE_RX 128
  25. #define AP_SERIALMANAGER_USART2_BUFSIZE_TX 8
  26. #define BAUD_19200 19200
  27. #define AP_SERIALMANAGER_USART1_BUFSIZE_RX 16
  28. #define AP_SERIALMANAGER_USART1_BUFSIZE_TX 16
  29. // we have hal.uartA to hal.uartH
  30. #define SERIALMANAGER_NUM_PORTS 8
  31. // console default baud rates and buffer sizes
  32. #ifdef HAL_SERIAL0_BAUD_DEFAULT
  33. # define AP_SERIALMANAGER_CONSOLE_BAUD HAL_SERIAL0_BAUD_DEFAULT
  34. #else
  35. # define AP_SERIALMANAGER_CONSOLE_BAUD 115200
  36. #endif
  37. # define AP_SERIALMANAGER_CONSOLE_BUFSIZE_RX 128
  38. # define AP_SERIALMANAGER_CONSOLE_BUFSIZE_TX 512
  39. // mavlink default baud rates and buffer sizes
  40. #define AP_SERIALMANAGER_MAVLINK_BAUD 57600
  41. #define AP_SERIALMANAGER_MAVLINK_BUFSIZE_RX 128
  42. #define AP_SERIALMANAGER_MAVLINK_BUFSIZE_TX 256
  43. // FrSky default baud rates, use default buffer sizes
  44. #define AP_SERIALMANAGER_FRSKY_D_BAUD 9600
  45. #define AP_SERIALMANAGER_FRSKY_SPORT_BAUD 57600
  46. #define AP_SERIALMANAGER_FRSKY_BUFSIZE_RX 0
  47. #define AP_SERIALMANAGER_FRSKY_BUFSIZE_TX 0
  48. // GPS default baud rates and buffer sizes
  49. // we need a 256 byte buffer for some GPS types (eg. UBLOX)
  50. #define AP_SERIALMANAGER_GPS_BAUD 38400
  51. #define AP_SERIALMANAGER_GPS_BUFSIZE_RX 256
  52. #define AP_SERIALMANAGER_GPS_BUFSIZE_TX 16
  53. // AlexMos Gimbal protocol default baud rates and buffer sizes
  54. #define AP_SERIALMANAGER_ALEXMOS_BAUD 115200
  55. #define AP_SERIALMANAGER_ALEXMOS_BUFSIZE_RX 128
  56. #define AP_SERIALMANAGER_ALEXMOS_BUFSIZE_TX 128
  57. #define AP_SERIALMANAGER_SToRM32_BAUD 115200
  58. #define AP_SERIALMANAGER_SToRM32_BUFSIZE_RX 128
  59. #define AP_SERIALMANAGER_SToRM32_BUFSIZE_TX 128
  60. #define AP_SERIALMANAGER_VOLZ_BAUD 115
  61. #define AP_SERIALMANAGER_VOLZ_BUFSIZE_RX 128
  62. #define AP_SERIALMANAGER_VOLZ_BUFSIZE_TX 128
  63. #define AP_SERIALMANAGER_ROBOTIS_BUFSIZE_RX 128
  64. #define AP_SERIALMANAGER_ROBOTIS_BUFSIZE_TX 128
  65. // SBUS servo outputs
  66. #define AP_SERIALMANAGER_SBUS1_BAUD 100000
  67. #define AP_SERIALMANAGER_SBUS1_BUFSIZE_RX 16
  68. #define AP_SERIALMANAGER_SBUS1_BUFSIZE_TX 32
  69. #define AP_SERIALMANAGER_SLCAN_BAUD 115200
  70. #define AP_SERIALMANAGER_SLCAN_BUFSIZE_RX 128
  71. #define AP_SERIALMANAGER_SLCAN_BUFSIZE_TX 128
  72. class AP_SerialManager {
  73. public:
  74. AP_SerialManager();
  75. /* Do not allow copies */
  76. AP_SerialManager(const AP_SerialManager &other) = delete;
  77. AP_SerialManager &operator=(const AP_SerialManager&) = delete;
  78. enum SerialProtocol {
  79. SerialProtocol_None = -1,
  80. SerialProtocol_Console = 0, // unused
  81. SerialProtocol_MAVLink = 1,
  82. SerialProtocol_MAVLink2 = 2, // do not use - use MAVLink and provide instance of 1
  83. SerialProtocol_FrSky_D = 3, // FrSky D protocol (D-receivers)
  84. SerialProtocol_FrSky_SPort = 4, // FrSky SPort protocol (X-receivers)
  85. SerialProtocol_GPS = 5,
  86. SerialProtocol_GPS2 = 6, // do not use - use GPS and provide instance of 1
  87. SerialProtocol_AlexMos = 7,
  88. SerialProtocol_SToRM32 = 8,
  89. SerialProtocol_Rangefinder = 9,
  90. SerialProtocol_FrSky_SPort_Passthrough = 10, // FrSky SPort Passthrough (OpenTX) protocol (X-receivers)
  91. SerialProtocol_Lidar360 = 11, // Lightware SF40C, TeraRanger Tower or RPLidarA2
  92. SerialProtocol_Aerotenna_uLanding = 12, // Ulanding support - deprecated, users should use Rangefinder
  93. SerialProtocol_Beacon = 13,
  94. SerialProtocol_Volz = 14, // Volz servo protocol
  95. SerialProtocol_Sbus1 = 15,
  96. SerialProtocol_ESCTelemetry = 16,
  97. SerialProtocol_Devo_Telem = 17,
  98. SerialProtocol_OpticalFlow = 18,
  99. SerialProtocol_Robotis = 19,
  100. SerialProtocol_NMEAOutput = 20,
  101. SerialProtocol_WindVane = 21,
  102. SerialProtocol_SLCAN = 22,
  103. SerialProtocol_RCIN = 23,
  104. SerialProtocol_usart2 = 24,//自定义串口协议
  105. SerialProtocol_usart1 = 25,//自定义串口协议
  106. };
  107. // get singleton instance
  108. static AP_SerialManager *get_singleton(void) {
  109. return _singleton;
  110. }
  111. // init_console - initialise console at default baud rate
  112. void init_console();
  113. // init - initialise serial ports
  114. void init();
  115. // find_serial - searches available serial ports that allows the given protocol
  116. // instance should be zero if searching for the first instance, 1 for the second, etc
  117. // returns uart on success, nullptr if a serial port cannot be found
  118. AP_HAL::UARTDriver *find_serial(enum SerialProtocol protocol, uint8_t instance) const;
  119. // find_baudrate - searches available serial ports for the first instance that allows the given protocol
  120. // instance should be zero if searching for the first instance, 1 for the second, etc
  121. // returns the baudrate of that protocol on success, 0 if a serial port cannot be found
  122. uint32_t find_baudrate(enum SerialProtocol protocol, uint8_t instance) const;
  123. // get_mavlink_channel - provides the mavlink channel associated with a given protocol (and instance)
  124. // instance should be zero if searching for the first instance, 1 for the second, etc
  125. // returns true if a channel is found, false if not
  126. bool get_mavlink_channel(enum SerialProtocol protocol, uint8_t instance, mavlink_channel_t &mav_chan) const;
  127. // get_mavlink_protocol - provides the specific MAVLink protocol for a
  128. // given channel, or SerialProtocol_None if not found
  129. SerialProtocol get_mavlink_protocol(mavlink_channel_t mav_chan) const;
  130. // set_blocking_writes_all - sets block_writes on or off for all serial channels
  131. void set_blocking_writes_all(bool blocking);
  132. // get the passthru ports if enabled
  133. bool get_passthru(AP_HAL::UARTDriver *&port1, AP_HAL::UARTDriver *&port2, uint8_t &timeout_s) const;
  134. // disable passthru by settings SERIAL_PASS2 to -1
  135. void disable_passthru(void);
  136. // get Serial Port
  137. AP_HAL::UARTDriver *get_serial_by_id(uint8_t id);
  138. // parameter var table
  139. static const struct AP_Param::GroupInfo var_info[];
  140. private:
  141. static AP_SerialManager *_singleton;
  142. // array of uart info
  143. struct UARTState {
  144. AP_Int8 protocol;
  145. AP_Int32 baud;
  146. AP_HAL::UARTDriver* uart;
  147. AP_Int16 options;
  148. } state[SERIALMANAGER_NUM_PORTS];
  149. // pass-through serial support
  150. AP_Int8 passthru_port1;
  151. AP_Int8 passthru_port2;
  152. AP_Int8 passthru_timeout;
  153. // search through managed serial connections looking for the
  154. // instance-nth UART which is running protocol protocol
  155. const UARTState *find_protocol_instance(enum SerialProtocol protocol,
  156. uint8_t instance) const;
  157. uint32_t map_baudrate(int32_t rate) const;
  158. // protocol_match - returns true if the protocols match
  159. bool protocol_match(enum SerialProtocol protocol1, enum SerialProtocol protocol2) const;
  160. // setup any special options
  161. void set_options(uint8_t i);
  162. };
  163. namespace AP {
  164. AP_SerialManager &serialmanager();
  165. };