AP_SerialManager.cpp 31 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633
  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. #include <AP_HAL/AP_HAL.h>
  20. #include <AP_Math/AP_Math.h>
  21. #include <AP_RCProtocol/AP_RCProtocol.h>
  22. #include "AP_SerialManager.h"
  23. extern const AP_HAL::HAL& hal;
  24. #ifdef HAL_SERIAL2_PROTOCOL
  25. #define SERIAL2_PROTOCOL HAL_SERIAL2_PROTOCOL
  26. #else
  27. #define SERIAL2_PROTOCOL SerialProtocol_MAVLink
  28. #endif
  29. #ifndef HAL_SERIAL3_PROTOCOL
  30. #define SERIAL3_PROTOCOL SerialProtocol_GPS
  31. #else
  32. #define SERIAL3_PROTOCOL HAL_SERIAL3_PROTOCOL
  33. #endif
  34. #ifndef HAL_SERIAL4_PROTOCOL
  35. #define SERIAL4_PROTOCOL SerialProtocol_GPS
  36. #else
  37. #define SERIAL4_PROTOCOL HAL_SERIAL4_PROTOCOL
  38. #endif
  39. #ifdef HAL_SERIAL5_PROTOCOL
  40. #define SERIAL5_PROTOCOL HAL_SERIAL5_PROTOCOL
  41. #define SERIAL5_BAUD HAL_SERIAL5_BAUD
  42. #else
  43. #define SERIAL5_PROTOCOL SerialProtocol_None
  44. #define SERIAL5_BAUD AP_SERIALMANAGER_MAVLINK_BAUD/1000
  45. #endif
  46. #ifndef HAL_SERIAL6_PROTOCOL
  47. #define SERIAL6_PROTOCOL SerialProtocol_None
  48. #define SERIAL6_BAUD AP_SERIALMANAGER_MAVLINK_BAUD/1000
  49. #else
  50. #define SERIAL6_PROTOCOL HAL_SERIAL6_PROTOCOL
  51. #define SERIAL6_BAUD HAL_SERIAL6_BAUD
  52. #endif
  53. #ifndef HAL_SERIAL7_PROTOCOL
  54. #define SERIAL7_PROTOCOL SerialProtocol_None
  55. #define SERIAL7_BAUD AP_SERIALMANAGER_MAVLINK_BAUD/1000
  56. #else
  57. #define SERIAL7_PROTOCOL HAL_SERIAL7_PROTOCOL
  58. #define SERIAL7_BAUD HAL_SERIAL7_BAUD
  59. #endif
  60. const AP_Param::GroupInfo AP_SerialManager::var_info[] = {
  61. // @Param: 0_BAUD
  62. // @DisplayName: Serial0 baud rate
  63. // @Description: The baud rate used on the USB console. Most stm32-based boards can support rates of up to 1500. If you setup a rate you cannot support and then can't connect to your board you should load a firmware from a different vehicle type. That will reset all your parameters to defaults.
  64. // @Values: 1:1200,2:2400,4:4800,9:9600,19:19200,38:38400,57:57600,111:111100,115:115200,256:256000,460:460800,500:500000,921:921600,1500:1500000
  65. // @User: Standard
  66. AP_GROUPINFO("0_BAUD", 0, AP_SerialManager, state[0].baud, AP_SERIALMANAGER_CONSOLE_BAUD/1000),
  67. // @Param: 0_PROTOCOL
  68. // @DisplayName: Console protocol selection
  69. // @Description: Control what protocol to use on the console.
  70. // @Values: 1:MAVlink1, 2:MAVLink2
  71. // @User: Standard
  72. // @RebootRequired: True
  73. AP_GROUPINFO("0_PROTOCOL", 11, AP_SerialManager, state[0].protocol, SerialProtocol_MAVLink2),
  74. // @Param: 1_PROTOCOL
  75. // @DisplayName: Telem1 protocol selection
  76. // @Description: Control what protocol to use on the Telem1 port. Note that the Frsky options require external converter hardware. See the wiki for details.
  77. // @Values: -1:None, 1:MAVLink1, 2:MAVLink2, 3:Frsky D, 4:Frsky SPort, 5:GPS, 7:Alexmos Gimbal Serial, 8:SToRM32 Gimbal Serial, 9:Rangefinder, 10:FrSky SPort Passthrough (OpenTX), 11:Lidar360, 13:Beacon, 14:Volz servo out, 15:SBus servo out, 16:ESC Telemetry, 17:Devo Telemetry, 18:OpticalFlow, 19:RobotisServo, 20:NMEA Output, 21:WindVane, 22:SLCAN, 23:RCIN
  78. // @User: Standard
  79. // @RebootRequired: True
  80. AP_GROUPINFO("1_PROTOCOL", 1, AP_SerialManager, state[1].protocol, SerialProtocol_MAVLink),
  81. // @Param: 1_BAUD
  82. // @DisplayName: Telem1 Baud Rate
  83. // @Description: The baud rate used on the Telem1 port. Most stm32-based boards can support rates of up to 1500. If you setup a rate you cannot support and then can't connect to your board you should load a firmware from a different vehicle type. That will reset all your parameters to defaults.
  84. // @Values: 1:1200,2:2400,4:4800,9:9600,19:19200,38:38400,57:57600,111:111100,115:115200,256:256000,500:500000,921:921600,1500:1500000
  85. // @User: Standard
  86. AP_GROUPINFO("1_BAUD", 2, AP_SerialManager, state[1].baud, AP_SERIALMANAGER_MAVLINK_BAUD/1000),
  87. // @Param: 2_PROTOCOL
  88. // @DisplayName: Telemetry 2 protocol selection
  89. // @Description: Control what protocol to use on the Telem2 port. Note that the Frsky options require external converter hardware. See the wiki for details.
  90. // @Values: -1:None, 1:MAVLink1, 2:MAVLink2, 3:Frsky D, 4:Frsky SPort, 5:GPS, 7:Alexmos Gimbal Serial, 8:SToRM32 Gimbal Serial, 9:Rangefinder, 10:FrSky SPort Passthrough (OpenTX), 11:Lidar360, 13:Beacon, 14:Volz servo out, 15:SBus servo out, 16:ESC Telemetry, 17:Devo Telemetry, 18:OpticalFlow, 19:RobotisServo, 20:NMEA Output, 21:WindVane, 22:SLCAN, 23:RCIN
  91. // @User: Standard
  92. // @RebootRequired: True
  93. AP_GROUPINFO("2_PROTOCOL", 3, AP_SerialManager, state[2].protocol, 24),
  94. // @Param: 2_BAUD
  95. // @DisplayName: Telemetry 2 Baud Rate
  96. // @Description: The baud rate of the Telem2 port. Most stm32-based boards can support rates of up to 1500. If you setup a rate you cannot support and then can't connect to your board you should load a firmware from a different vehicle type. That will reset all your parameters to defaults.
  97. // @Values: 1:1200,2:2400,4:4800,9:9600,19:19200,38:38400,57:57600,111:111100,115:115200,256:256000,500:500000,921:921600,1500:1500000
  98. // @User: Standard
  99. AP_GROUPINFO("2_BAUD", 4, AP_SerialManager, state[2].baud, BAUD_115200/1000),
  100. // @Param: 3_PROTOCOL
  101. // @DisplayName: Serial 3 (GPS) protocol selection
  102. // @Description: Control what protocol Serial 3 (GPS) should be used for. Note that the Frsky options require external converter hardware. See the wiki for details.
  103. // @Values: -1:None, 1:MAVLink1, 2:MAVLink2, 3:Frsky D, 4:Frsky SPort, 5:GPS, 7:Alexmos Gimbal Serial, 8:SToRM32 Gimbal Serial, 9:Rangefinder, 10:FrSky SPort Passthrough (OpenTX), 11:Lidar360, 13:Beacon, 14:Volz servo out, 15:SBus servo out, 16:ESC Telemetry, 17:Devo Telemetry, 18:OpticalFlow, 19:RobotisServo, 20:NMEA Output, 21:WindVane, 22:SLCAN, 23:RCIN
  104. // @User: Standard
  105. // @RebootRequired: True
  106. AP_GROUPINFO("3_PROTOCOL", 5, AP_SerialManager, state[3].protocol, SERIAL3_PROTOCOL),
  107. // @Param: 3_BAUD
  108. // @DisplayName: Serial 3 (GPS) Baud Rate
  109. // @Description: The baud rate used for the Serial 3 (GPS). Most stm32-based boards can support rates of up to 1500. If you setup a rate you cannot support and then can't connect to your board you should load a firmware from a different vehicle type. That will reset all your parameters to defaults.
  110. // @Values: 1:1200,2:2400,4:4800,9:9600,19:19200,38:38400,57:57600,111:111100,115:115200,256:256000,500:500000,921:921600,1500:1500000
  111. // @User: Standard
  112. AP_GROUPINFO("3_BAUD", 6, AP_SerialManager, state[3].baud, AP_SERIALMANAGER_GPS_BAUD/1000),
  113. // @Param: 4_PROTOCOL
  114. // @DisplayName: Serial4 protocol selection
  115. // @Description: Control what protocol Serial4 port should be used for. Note that the Frsky options require external converter hardware. See the wiki for details.
  116. // @Values: -1:None, 1:MAVLink1, 2:MAVLink2, 3:Frsky D, 4:Frsky SPort, 5:GPS, 7:Alexmos Gimbal Serial, 8:SToRM32 Gimbal Serial, 9:Rangefinder, 10:FrSky SPort Passthrough (OpenTX), 11:Lidar360, 13:Beacon, 14:Volz servo out, 15:SBus servo out, 16:ESC Telemetry, 17:Devo Telemetry, 18:OpticalFlow, 19:RobotisServo, 20:NMEA Output, 21:WindVane, 22:SLCAN, 23:RCIN
  117. // @User: Standard
  118. // @RebootRequired: True
  119. AP_GROUPINFO("4_PROTOCOL", 7, AP_SerialManager, state[4].protocol, 25),
  120. // @Param: 4_BAUD
  121. // @DisplayName: Serial 4 Baud Rate
  122. // @Description: The baud rate used for Serial4. Most stm32-based boards can support rates of up to 1500. If you setup a rate you cannot support and then can't connect to your board you should load a firmware from a different vehicle type. That will reset all your parameters to defaults.
  123. // @Values: 1:1200,2:2400,4:4800,9:9600,19:19200,38:38400,57:57600,111:111100,115:115200,256:256000,500:500000,921:921600,1500:1500000
  124. // @User: Standard
  125. AP_GROUPINFO("4_BAUD", 8, AP_SerialManager, state[4].baud, BAUD_115200/1000),
  126. // @Param: 5_PROTOCOL
  127. // @DisplayName: Serial5 protocol selection
  128. // @Description: Control what protocol Serial5 port should be used for. Note that the Frsky options require external converter hardware. See the wiki for details.
  129. // @Values: -1:None, 1:MAVLink1, 2:MAVLink2, 3:Frsky D, 4:Frsky SPort, 5:GPS, 7:Alexmos Gimbal Serial, 8:SToRM32 Gimbal Serial, 9:Rangefinder, 10:FrSky SPort Passthrough (OpenTX), 11:Lidar360, 13:Beacon, 14:Volz servo out, 15:SBus servo out, 16:ESC Telemetry, 17:Devo Telemetry, 18:OpticalFlow, 19:RobotisServo, 20:NMEA Output, 21:WindVane, 22:SLCAN, 23:RCIN
  130. // @User: Standard
  131. // @RebootRequired: True
  132. AP_GROUPINFO("5_PROTOCOL", 9, AP_SerialManager, state[5].protocol, SERIAL5_PROTOCOL),
  133. // @Param: 5_BAUD
  134. // @DisplayName: Serial 5 Baud Rate
  135. // @Description: The baud rate used for Serial5. Most stm32-based boards can support rates of up to 1500. If you setup a rate you cannot support and then can't connect to your board you should load a firmware from a different vehicle type. That will reset all your parameters to defaults.
  136. // @Values: 1:1200,2:2400,4:4800,9:9600,19:19200,38:38400,57:57600,111:111100,115:115200,256:256000,500:500000,921:921600,1500:1500000
  137. // @User: Standard
  138. AP_GROUPINFO("5_BAUD", 10, AP_SerialManager, state[5].baud, SERIAL5_BAUD),
  139. // index 11 used by 0_PROTOCOL
  140. // @Param: 6_PROTOCOL
  141. // @DisplayName: Serial6 protocol selection
  142. // @Description: Control what protocol Serial6 port should be used for. Note that the Frsky options require external converter hardware. See the wiki for details.
  143. // @Values: -1:None, 1:MAVLink1, 2:MAVLink2, 3:Frsky D, 4:Frsky SPort, 5:GPS, 7:Alexmos Gimbal Serial, 8:SToRM32 Gimbal Serial, 9:Rangefinder, 10:FrSky SPort Passthrough (OpenTX), 11:Lidar360, 13:Beacon, 14:Volz servo out, 15:SBus servo out, 16:ESC Telemetry, 17:Devo Telemetry, 18:OpticalFlow, 19:RobotisServo, 20:NMEA Output, 21:WindVane, 22:SLCAN, 23:RCIN
  144. // @User: Standard
  145. // @RebootRequired: True
  146. AP_GROUPINFO("6_PROTOCOL", 12, AP_SerialManager, state[6].protocol, SERIAL6_PROTOCOL),
  147. // @Param: 6_BAUD
  148. // @DisplayName: Serial 6 Baud Rate
  149. // @Description: The baud rate used for Serial6. Most stm32-based boards can support rates of up to 1500. If you setup a rate you cannot support and then can't connect to your board you should load a firmware from a different vehicle type. That will reset all your parameters to defaults.
  150. // @Values: 1:1200,2:2400,4:4800,9:9600,19:19200,38:38400,57:57600,111:111100,115:115200,256:256000,500:500000,921:921600,1500:1500000
  151. // @User: Standard
  152. AP_GROUPINFO("6_BAUD", 13, AP_SerialManager, state[6].baud, SERIAL6_BAUD),
  153. // @Param: 1_OPTIONS
  154. // @DisplayName: Telem1 options
  155. // @Description: Control over UART options. The InvertRX option controls invert of the receive pin. The InvertTX option controls invert of the transmit pin. The HalfDuplex option controls half-duplex (onewire) mode, where both transmit and receive is done on the transmit wire. The Swap option allows the RX and TX pins to be swapped on STM32F7 based boards.
  156. // @Bitmask: 0:InvertRX, 1:InvertTX, 2:HalfDuplex, 4:Swap
  157. // @User: Advanced
  158. // @RebootRequired: True
  159. AP_GROUPINFO("1_OPTIONS", 14, AP_SerialManager, state[1].options, 0),
  160. // @Param: 2_OPTIONS
  161. // @DisplayName: Telem2 options
  162. // @Description: Control over UART options. The InvertRX option controls invert of the receive pin. The InvertTX option controls invert of the transmit pin. The HalfDuplex option controls half-duplex (onewire) mode, where both transmit and receive is done on the transmit wire.
  163. // @Bitmask: 0:InvertRX, 1:InvertTX, 2:HalfDuplex, 4:Swap
  164. // @User: Advanced
  165. // @RebootRequired: True
  166. AP_GROUPINFO("2_OPTIONS", 15, AP_SerialManager, state[2].options, 0),
  167. // @Param: 3_OPTIONS
  168. // @DisplayName: Serial3 options
  169. // @Description: Control over UART options. The InvertRX option controls invert of the receive pin. The InvertTX option controls invert of the transmit pin. The HalfDuplex option controls half-duplex (onewire) mode, where both transmit and receive is done on the transmit wire.
  170. // @Bitmask: 0:InvertRX, 1:InvertTX, 2:HalfDuplex, 4:Swap
  171. // @User: Advanced
  172. // @RebootRequired: True
  173. AP_GROUPINFO("3_OPTIONS", 16, AP_SerialManager, state[3].options, 0),
  174. // @Param: 4_OPTIONS
  175. // @DisplayName: Serial4 options
  176. // @Description: Control over UART options. The InvertRX option controls invert of the receive pin. The InvertTX option controls invert of the transmit pin. The HalfDuplex option controls half-duplex (onewire) mode, where both transmit and receive is done on the transmit wire.
  177. // @Bitmask: 0:InvertRX, 1:InvertTX, 2:HalfDuplex, 4:Swap
  178. // @User: Advanced
  179. // @RebootRequired: True
  180. AP_GROUPINFO("4_OPTIONS", 17, AP_SerialManager, state[4].options, 0),
  181. // @Param: 5_OPTIONS
  182. // @DisplayName: Serial5 options
  183. // @Description: Control over UART options. The InvertRX option controls invert of the receive pin. The InvertTX option controls invert of the transmit pin. The HalfDuplex option controls half-duplex (onewire) mode, where both transmit and receive is done on the transmit wire.
  184. // @Bitmask: 0:InvertRX, 1:InvertTX, 2:HalfDuplex, 4:Swap
  185. // @User: Advanced
  186. // @RebootRequired: True
  187. AP_GROUPINFO("5_OPTIONS", 18, AP_SerialManager, state[5].options, 0),
  188. // @Param: 6_OPTIONS
  189. // @DisplayName: Serial6 options
  190. // @Description: Control over UART options. The InvertRX option controls invert of the receive pin. The InvertTX option controls invert of the transmit pin. The HalfDuplex option controls half-duplex (onewire) mode, where both transmit and receive is done on the transmit wire.
  191. // @Bitmask: 0:InvertRX, 1:InvertTX, 2:HalfDuplex, 4:Swap
  192. // @User: Advanced
  193. // @RebootRequired: True
  194. AP_GROUPINFO("6_OPTIONS", 19, AP_SerialManager, state[6].options, 0),
  195. // @Param: _PASS1
  196. // @DisplayName: Serial passthru first port
  197. // @Description: This sets one side of pass-through between two serial ports. Once both sides are set then all data received on either port will be passed to the other port
  198. // @Values: -1:Disabled,0:Serial0,1:Serial1,2:Serial2,3:Serial3,4:Serial4,5:Serial5,6:Serial6
  199. // @User: Advanced
  200. AP_GROUPINFO("_PASS1", 20, AP_SerialManager, passthru_port1, 0),
  201. // @Param: _PASS2
  202. // @DisplayName: Serial passthru second port
  203. // @Description: This sets one side of pass-through between two serial ports. Once both sides are set then all data received on either port will be passed to the other port
  204. // @Values: -1:Disabled,0:Serial0,1:Serial1,2:Serial2,3:Serial3,4:Serial4,5:Serial5,6:Serial6
  205. // @User: Advanced
  206. AP_GROUPINFO("_PASS2", 21, AP_SerialManager, passthru_port2, -1),
  207. // @Param: _PASSTIMO
  208. // @DisplayName: Serial passthru timeout
  209. // @Description: This sets a timeout for serial pass-through in seconds. When the pass-through is enabled by setting the SERIAL_PASS1 and SERIAL_PASS2 parameters then it remains in effect until no data comes from the first port for SERIAL_PASSTIMO seconds. This allows the port to revent to its normal usage (such as MAVLink connection to a GCS) when it is no longer needed. A value of 0 means no timeout.
  210. // @Range: 0 120
  211. // @Units: s
  212. // @User: Advanced
  213. AP_GROUPINFO("_PASSTIMO", 22, AP_SerialManager, passthru_timeout, 15),
  214. // @Param: 7_PROTOCOL
  215. // @DisplayName: Serial7 protocol selection
  216. // @Description: Control what protocol Serial7 port should be used for. Note that the Frsky options require external converter hardware. See the wiki for details.
  217. // @Values: -1:None, 1:MAVLink1, 2:MAVLink2, 3:Frsky D, 4:Frsky SPort, 5:GPS, 7:Alexmos Gimbal Serial, 8:SToRM32 Gimbal Serial, 9:Rangefinder, 10:FrSky SPort Passthrough (OpenTX), 11:Lidar360, 13:Beacon, 14:Volz servo out, 15:SBus servo out, 16:ESC Telemetry, 17:Devo Telemetry, 18:OpticalFlow, 19:RobotisServo, 20:NMEA Output, 21:WindVane, 22:SLCAN, 23:RCIN
  218. // @User: Standard
  219. // @RebootRequired: True
  220. AP_GROUPINFO("7_PROTOCOL", 23, AP_SerialManager, state[7].protocol, SERIAL7_PROTOCOL),
  221. // @Param: 7_BAUD
  222. // @DisplayName: Serial 7 Baud Rate
  223. // @Description: The baud rate used for Serial7. Most stm32-based boards can support rates of up to 1500. If you setup a rate you cannot support and then can't connect to your board you should load a firmware from a different vehicle type. That will reset all your parameters to defaults.
  224. // @Values: 1:1200,2:2400,4:4800,9:9600,19:19200,38:38400,57:57600,111:111100,115:115200,256:256000,500:500000,921:921600,1500:1500000
  225. // @User: Standard
  226. AP_GROUPINFO("7_BAUD", 24, AP_SerialManager, state[7].baud, SERIAL7_BAUD),
  227. // @Param: 7_OPTIONS
  228. // @DisplayName: Serial7 options
  229. // @Description: Control over UART options. The InvertRX option controls invert of the receive pin. The InvertTX option controls invert of the transmit pin. The HalfDuplex option controls half-duplex (onewire) mode, where both transmit and receive is done on the transmit wire.
  230. // @Bitmask: 0:InvertRX, 1:InvertTX, 2:HalfDuplex, 4:Swap
  231. // @User: Advanced
  232. // @RebootRequired: True
  233. AP_GROUPINFO("7_OPTIONS", 25, AP_SerialManager, state[7].options, 0),
  234. AP_GROUPEND
  235. };
  236. // singleton instance
  237. AP_SerialManager *AP_SerialManager::_singleton;
  238. // Constructor
  239. AP_SerialManager::AP_SerialManager()
  240. {
  241. _singleton = this;
  242. // setup parameter defaults
  243. AP_Param::setup_object_defaults(this, var_info);
  244. }
  245. // init_console - initialise console at default baud rate
  246. void AP_SerialManager::init_console()
  247. {
  248. // initialise console immediately at default size and baud
  249. state[0].uart = hal.uartA; // serial0, uartA, always console
  250. state[0].uart->begin(AP_SERIALMANAGER_CONSOLE_BAUD,
  251. AP_SERIALMANAGER_CONSOLE_BUFSIZE_RX,
  252. AP_SERIALMANAGER_CONSOLE_BUFSIZE_TX);
  253. }
  254. extern bool g_nsh_should_exit;
  255. // init - // init - initialise serial ports
  256. void AP_SerialManager::init()
  257. {
  258. // always reset passthru port2 on boot
  259. passthru_port2.set_and_save_ifchanged(-1);
  260. // initialise pointers to serial ports
  261. state[1].uart = hal.uartC; // serial1, uartC, normally telem1
  262. state[2].uart = hal.uartD; // serial2, uartD, normally telem2
  263. state[3].uart = hal.uartB; // serial3, uartB, normally 1st GPS
  264. state[4].uart = hal.uartE; // serial4, uartE, normally 2nd GPS
  265. state[5].uart = hal.uartF; // serial5
  266. state[6].uart = hal.uartG; // serial6
  267. state[7].uart = hal.uartH; // serial7
  268. if (state[0].uart == nullptr) {
  269. init_console();
  270. }
  271. // initialise serial ports
  272. for (uint8_t i=1; i<SERIALMANAGER_NUM_PORTS; i++) {
  273. if (state[i].uart != nullptr) {
  274. // see if special options have been requested
  275. if (state[i].protocol != SerialProtocol_None && state[i].options) {
  276. set_options(i);
  277. }
  278. switch (state[i].protocol) {
  279. case SerialProtocol_None:
  280. break;
  281. case SerialProtocol_Console:
  282. case SerialProtocol_MAVLink:
  283. case SerialProtocol_MAVLink2:
  284. state[i].uart->begin(map_baudrate(state[i].baud),
  285. AP_SERIALMANAGER_MAVLINK_BUFSIZE_RX,
  286. AP_SERIALMANAGER_MAVLINK_BUFSIZE_TX);
  287. break;
  288. case SerialProtocol_FrSky_D:
  289. // Note baudrate is hardcoded to 9600
  290. state[i].baud = AP_SERIALMANAGER_FRSKY_D_BAUD/1000; // update baud param in case user looks at it
  291. // begin is handled by AP_Frsky_telem library
  292. break;
  293. case SerialProtocol_FrSky_SPort:
  294. case SerialProtocol_FrSky_SPort_Passthrough:
  295. // Note baudrate is hardcoded to 57600
  296. state[i].baud = AP_SERIALMANAGER_FRSKY_SPORT_BAUD/1000; // update baud param in case user looks at it
  297. // begin is handled by AP_Frsky_telem library
  298. break;
  299. case SerialProtocol_GPS:
  300. case SerialProtocol_GPS2:
  301. state[i].uart->begin(map_baudrate(state[i].baud),
  302. AP_SERIALMANAGER_GPS_BUFSIZE_RX,
  303. AP_SERIALMANAGER_GPS_BUFSIZE_TX);
  304. break;
  305. case SerialProtocol_AlexMos:
  306. // Note baudrate is hardcoded to 115200
  307. state[i].baud = AP_SERIALMANAGER_ALEXMOS_BAUD / 1000; // update baud param in case user looks at it
  308. state[i].uart->begin(AP_SERIALMANAGER_ALEXMOS_BAUD,
  309. AP_SERIALMANAGER_ALEXMOS_BUFSIZE_RX,
  310. AP_SERIALMANAGER_ALEXMOS_BUFSIZE_TX);
  311. break;
  312. case SerialProtocol_SToRM32:
  313. // Note baudrate is hardcoded to 115200
  314. state[i].baud = AP_SERIALMANAGER_SToRM32_BAUD / 1000; // update baud param in case user looks at it
  315. state[i].uart->begin(map_baudrate(state[i].baud),
  316. AP_SERIALMANAGER_SToRM32_BUFSIZE_RX,
  317. AP_SERIALMANAGER_SToRM32_BUFSIZE_TX);
  318. break;
  319. case SerialProtocol_Aerotenna_uLanding:
  320. state[i].protocol.set_and_save(SerialProtocol_Rangefinder);
  321. break;
  322. case SerialProtocol_Volz:
  323. // Note baudrate is hardcoded to 115200
  324. state[i].baud = AP_SERIALMANAGER_VOLZ_BAUD; // update baud param in case user looks at it
  325. state[i].uart->begin(map_baudrate(state[i].baud),
  326. AP_SERIALMANAGER_VOLZ_BUFSIZE_RX,
  327. AP_SERIALMANAGER_VOLZ_BUFSIZE_TX);
  328. state[i].uart->set_unbuffered_writes(true);
  329. state[i].uart->set_flow_control(AP_HAL::UARTDriver::FLOW_CONTROL_DISABLE);
  330. break;
  331. case SerialProtocol_Sbus1:
  332. state[i].baud = AP_SERIALMANAGER_SBUS1_BAUD / 1000; // update baud param in case user looks at it
  333. state[i].uart->begin(map_baudrate(state[i].baud),
  334. AP_SERIALMANAGER_SBUS1_BUFSIZE_RX,
  335. AP_SERIALMANAGER_SBUS1_BUFSIZE_TX);
  336. state[i].uart->configure_parity(2); // enable even parity
  337. state[i].uart->set_stop_bits(2);
  338. state[i].uart->set_unbuffered_writes(true);
  339. state[i].uart->set_flow_control(AP_HAL::UARTDriver::FLOW_CONTROL_DISABLE);
  340. break;
  341. case SerialProtocol_ESCTelemetry:
  342. // ESC telemetry protocol from BLHeli32 ESCs. Note that baudrate is hardcoded to 115200
  343. state[i].baud = 115200;
  344. state[i].uart->begin(map_baudrate(state[i].baud), 30, 30);
  345. state[i].uart->set_flow_control(AP_HAL::UARTDriver::FLOW_CONTROL_DISABLE);
  346. break;
  347. case SerialProtocol_Robotis:
  348. state[i].uart->begin(map_baudrate(state[i].baud),
  349. AP_SERIALMANAGER_ROBOTIS_BUFSIZE_RX,
  350. AP_SERIALMANAGER_ROBOTIS_BUFSIZE_TX);
  351. state[i].uart->set_unbuffered_writes(true);
  352. state[i].uart->set_flow_control(AP_HAL::UARTDriver::FLOW_CONTROL_DISABLE);
  353. break;
  354. case SerialProtocol_SLCAN:
  355. state[i].uart->begin(map_baudrate(state[i].baud),
  356. AP_SERIALMANAGER_SLCAN_BUFSIZE_RX,
  357. AP_SERIALMANAGER_SLCAN_BUFSIZE_TX);
  358. break;
  359. #ifndef HAL_BUILD_AP_PERIPH
  360. case SerialProtocol_RCIN:
  361. AP::RC().add_uart(state[i].uart);
  362. break;
  363. #endif
  364. case SerialProtocol_usart2:
  365. state[i].uart->begin(map_baudrate(state[i].baud),
  366. AP_SERIALMANAGER_USART2_BUFSIZE_RX,
  367. AP_SERIALMANAGER_USART2_BUFSIZE_TX);
  368. break;
  369. case SerialProtocol_usart1:
  370. state[i].uart->begin(map_baudrate(state[i].baud),
  371. AP_SERIALMANAGER_USART1_BUFSIZE_RX,
  372. AP_SERIALMANAGER_USART1_BUFSIZE_TX);
  373. default:
  374. state[i].uart->begin(map_baudrate(state[i].baud));
  375. }
  376. }
  377. }
  378. }
  379. const AP_SerialManager::UARTState *AP_SerialManager::find_protocol_instance(enum SerialProtocol protocol, uint8_t instance) const
  380. {
  381. uint8_t found_instance = 0;
  382. // search for matching protocol
  383. for(uint8_t i=0; i<SERIALMANAGER_NUM_PORTS; i++) {
  384. if (protocol_match(protocol, (enum SerialProtocol)state[i].protocol.get())) {
  385. if (found_instance == instance) {
  386. return &state[i];
  387. }
  388. found_instance++;
  389. }
  390. }
  391. // if we got this far we did not find the uart
  392. return nullptr;
  393. }
  394. // find_serial - searches available serial ports for the first instance that allows the given protocol
  395. // instance should be zero if searching for the first instance, 1 for the second, etc
  396. // returns uart on success, nullptr if a serial port cannot be found
  397. AP_HAL::UARTDriver *AP_SerialManager::find_serial(enum SerialProtocol protocol, uint8_t instance) const
  398. {
  399. const struct UARTState *_state = find_protocol_instance(protocol, instance);
  400. if (_state == nullptr) {
  401. return nullptr;
  402. }
  403. return _state->uart;
  404. }
  405. // find_baudrate - searches available serial ports for the first instance that allows the given protocol
  406. // instance should be zero if searching for the first instance, 1 for the second, etc
  407. // returns baudrate on success, 0 if a serial port cannot be found
  408. uint32_t AP_SerialManager::find_baudrate(enum SerialProtocol protocol, uint8_t instance) const
  409. {
  410. const struct UARTState *_state = find_protocol_instance(protocol, instance);
  411. if (_state == nullptr) {
  412. return 0;
  413. }
  414. return map_baudrate(_state->baud);
  415. }
  416. // get_mavlink_channel - provides the mavlink channel associated with a given protocol
  417. // instance should be zero if searching for the first instance, 1 for the second, etc
  418. // returns true if a channel is found, false if not
  419. bool AP_SerialManager::get_mavlink_channel(enum SerialProtocol protocol, uint8_t instance, mavlink_channel_t &mav_chan) const
  420. {
  421. // check for MAVLink
  422. if (protocol_match(protocol, SerialProtocol_MAVLink)) {
  423. if (instance < MAVLINK_COMM_NUM_BUFFERS) {
  424. mav_chan = (mavlink_channel_t)(MAVLINK_COMM_0 + instance);
  425. return true;
  426. }
  427. }
  428. // report failure
  429. return false;
  430. }
  431. // get_mavlink_protocol - provides the specific MAVLink protocol for a
  432. // given channel, or SerialProtocol_None if not found
  433. AP_SerialManager::SerialProtocol AP_SerialManager::get_mavlink_protocol(mavlink_channel_t mav_chan) const
  434. {
  435. uint8_t instance = 0;
  436. uint8_t chan_idx = (uint8_t)(mav_chan - MAVLINK_COMM_0);
  437. for (uint8_t i=0; i<SERIALMANAGER_NUM_PORTS; i++) {
  438. if (state[i].protocol == SerialProtocol_MAVLink ||
  439. state[i].protocol == SerialProtocol_MAVLink2) {
  440. if (instance == chan_idx) {
  441. return (SerialProtocol)state[i].protocol.get();
  442. }
  443. instance++;
  444. }
  445. }
  446. return SerialProtocol_None;
  447. }
  448. // get_serial_by_id - gets serial by serial id
  449. AP_HAL::UARTDriver *AP_SerialManager::get_serial_by_id(uint8_t id)
  450. {
  451. if (id < SERIALMANAGER_NUM_PORTS) {
  452. return state[id].uart;
  453. }
  454. return nullptr;
  455. }
  456. // set_blocking_writes_all - sets block_writes on or off for all serial channels
  457. void AP_SerialManager::set_blocking_writes_all(bool blocking)
  458. {
  459. // set block_writes for all initialised serial ports
  460. for (uint8_t i=0; i<SERIALMANAGER_NUM_PORTS; i++) {
  461. if (state[i].uart != nullptr) {
  462. state[i].uart->set_blocking_writes(blocking);
  463. }
  464. }
  465. }
  466. /*
  467. * map from a 16 bit EEPROM baud rate to a real baud rate. For
  468. * stm32-based boards we can do 1.5MBit, although 921600 is more
  469. * reliable.
  470. */
  471. uint32_t AP_SerialManager::map_baudrate(int32_t rate) const
  472. {
  473. if (rate <= 0) {
  474. rate = 57;
  475. }
  476. switch (rate) {
  477. case 1: return 1200;
  478. case 2: return 2400;
  479. case 4: return 4800;
  480. case 9: return 9600;
  481. case 19: return 19200;
  482. case 38: return 38400;
  483. case 57: return 57600;
  484. case 100: return 100000;
  485. case 111: return 111100;
  486. case 115: return 115200;
  487. case 230: return 230400;
  488. case 256: return 256000;
  489. case 460: return 460800;
  490. case 500: return 500000;
  491. case 921: return 921600;
  492. case 1500: return 1500000;
  493. }
  494. if (rate > 2000) {
  495. // assume it is a direct baudrate. This allows for users to
  496. // set an exact baudrate as long as it is over 2000 baud
  497. return (uint32_t)rate;
  498. }
  499. // otherwise allow any other kbaud rate
  500. return rate*1000;
  501. }
  502. // protocol_match - returns true if the protocols match
  503. bool AP_SerialManager::protocol_match(enum SerialProtocol protocol1, enum SerialProtocol protocol2) const
  504. {
  505. // check for obvious match
  506. if (protocol1 == protocol2) {
  507. return true;
  508. }
  509. // mavlink match
  510. if (((protocol1 == SerialProtocol_MAVLink) || (protocol1 == SerialProtocol_MAVLink2)) &&
  511. ((protocol2 == SerialProtocol_MAVLink) || (protocol2 == SerialProtocol_MAVLink2))) {
  512. return true;
  513. }
  514. // gps match
  515. if (((protocol1 == SerialProtocol_GPS) || (protocol1 == SerialProtocol_GPS2)) &&
  516. ((protocol2 == SerialProtocol_GPS) || (protocol2 == SerialProtocol_GPS2))) {
  517. return true;
  518. }
  519. return false;
  520. }
  521. // setup any special options
  522. void AP_SerialManager::set_options(uint8_t i)
  523. {
  524. struct UARTState &opt = state[i];
  525. // pass through to HAL
  526. if (!opt.uart->set_options(opt.options)) {
  527. hal.console->printf("Unable to setup options for Serial%u\n", i);
  528. }
  529. }
  530. // get the passthru ports if enabled
  531. bool AP_SerialManager::get_passthru(AP_HAL::UARTDriver *&port1, AP_HAL::UARTDriver *&port2, uint8_t &timeout_s) const
  532. {
  533. if (passthru_port2 < 0 ||
  534. passthru_port2 >= SERIALMANAGER_NUM_PORTS ||
  535. passthru_port1 < 0 ||
  536. passthru_port1 >= SERIALMANAGER_NUM_PORTS) {
  537. return false;
  538. }
  539. port1 = state[passthru_port1].uart;
  540. port2 = state[passthru_port2].uart;
  541. timeout_s = MAX(passthru_timeout, 0);
  542. return true;
  543. }
  544. // disable passthru by settings SERIAL_PASS2 to -1
  545. void AP_SerialManager::disable_passthru(void)
  546. {
  547. passthru_port2.set_and_notify(-1);
  548. }
  549. namespace AP {
  550. AP_SerialManager &serialmanager()
  551. {
  552. return *AP_SerialManager::get_singleton();
  553. }
  554. }