APM:Libraries
AP_SerialManager.cpp
Go to the documentation of this file.
1 /*
2  Please contribute your ideas! See http://dev.ardupilot.org for details
3 
4  This program is free software: you can redistribute it and/or modify
5  it under the terms of the GNU General Public License as published by
6  the Free Software Foundation, either version 3 of the License, or
7  (at your option) any later version.
8 
9  This program is distributed in the hope that it will be useful,
10  but WITHOUT ANY WARRANTY; without even the implied warranty of
11  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12  GNU General Public License for more details.
13 
14  You should have received a copy of the GNU General Public License
15  along with this program. If not, see <http://www.gnu.org/licenses/>.
16  */
17 /*
18  SerialManager allows defining the protocol and baud rates for the available
19  serial ports and provides helper functions so objects (like a gimbal) can
20  find which serial port they should use
21  */
22 
23 #include <AP_HAL/AP_HAL.h>
24 #include "AP_SerialManager.h"
25 
26 extern const AP_HAL::HAL& hal;
27 
28 #ifdef HAL_SERIAL5_PROTOCOL
29 #define SERIAL5_PROTOCOL HAL_SERIAL5_PROTOCOL
30 #define SERIAL5_BAUD HAL_SERIAL5_BAUD
31 #elif defined(CONFIG_ARCH_BOARD_PX4FMU_V4)
32 #define SERIAL5_PROTOCOL SerialProtocol_MAVLink
33 #define SERIAL5_BAUD 921600
34 #else
35 #define SERIAL5_PROTOCOL SerialProtocol_None
36 #define SERIAL5_BAUD AP_SERIALMANAGER_MAVLINK_BAUD/1000
37 #endif
38 
40  // @Param: 0_BAUD
41  // @DisplayName: Serial0 baud rate
42  // @Description: The baud rate used on the USB console. The APM2 can support all baudrates up to 115, and also can support 500. The PX4 can support rates of up to 1500. If you setup a rate you cannot support on APM2 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.
43  // @Values: 1:1200,2:2400,4:4800,9:9600,19:19200,38:38400,57:57600,111:111100,115:115200,460:460800,500:500000,921:921600,1500:1500000
44  // @User: Standard
46 
47  // @Param: 0_PROTOCOL
48  // @DisplayName: Console protocol selection
49  // @Description: Control what protocol to use on the console.
50  // @Values: 1:MAVlink1, 2:MAVLink2
51  // @User: Standard
52  // @RebootRequired: True
53  AP_GROUPINFO("0_PROTOCOL", 11, AP_SerialManager, state[0].protocol, SerialProtocol_MAVLink),
54 
55  // @Param: 1_PROTOCOL
56  // @DisplayName: Telem1 protocol selection
57  // @Description: Control what protocol to use on the Telem1 port. Note that the Frsky options require external converter hardware. See the wiki for details.
58  // @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
59  // @User: Standard
60  // @RebootRequired: True
61  AP_GROUPINFO("1_PROTOCOL", 1, AP_SerialManager, state[1].protocol, SerialProtocol_MAVLink),
62 
63  // @Param: 1_BAUD
64  // @DisplayName: Telem1 Baud Rate
65  // @Description: The baud rate used on the Telem1 port. The APM2 can support all baudrates up to 115, and also can support 500. The PX4 can support rates of up to 1500. If you setup a rate you cannot support on APM2 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.
66  // @Values: 1:1200,2:2400,4:4800,9:9600,19:19200,38:38400,57:57600,111:111100,115:115200,500:500000,921:921600,1500:1500000
67  // @User: Standard
69 
70  // @Param: 2_PROTOCOL
71  // @DisplayName: Telemetry 2 protocol selection
72  // @Description: Control what protocol to use on the Telem2 port. Note that the Frsky options require external converter hardware. See the wiki for details.
73  // @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
74  // @User: Standard
75  // @RebootRequired: True
76  AP_GROUPINFO("2_PROTOCOL", 3, AP_SerialManager, state[2].protocol, SerialProtocol_MAVLink),
77 
78  // @Param: 2_BAUD
79  // @DisplayName: Telemetry 2 Baud Rate
80  // @Description: The baud rate of the Telem2 port. The APM2 can support all baudrates up to 115, and also can support 500. The PX4 can support rates of up to 1500. If you setup a rate you cannot support on APM2 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.
81  // @Values: 1:1200,2:2400,4:4800,9:9600,19:19200,38:38400,57:57600,111:111100,115:115200,500:500000,921:921600,1500:1500000
82  // @User: Standard
84 
85  // @Param: 3_PROTOCOL
86  // @DisplayName: Serial 3 (GPS) protocol selection
87  // @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.
88  // @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
89  // @User: Standard
90  // @RebootRequired: True
91  AP_GROUPINFO("3_PROTOCOL", 5, AP_SerialManager, state[3].protocol, SerialProtocol_GPS),
92 
93  // @Param: 3_BAUD
94  // @DisplayName: Serial 3 (GPS) Baud Rate
95  // @Description: The baud rate used for the Serial 3 (GPS). The APM2 can support all baudrates up to 115, and also can support 500. The PX4 can support rates of up to 1500. If you setup a rate you cannot support on APM2 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.
96  // @Values: 1:1200,2:2400,4:4800,9:9600,19:19200,38:38400,57:57600,111:111100,115:115200,500:500000,921:921600,1500:1500000
97  // @User: Standard
98  AP_GROUPINFO("3_BAUD", 6, AP_SerialManager, state[3].baud, AP_SERIALMANAGER_GPS_BAUD/1000),
99 
100  // @Param: 4_PROTOCOL
101  // @DisplayName: Serial4 protocol selection
102  // @Description: Control what protocol Serial4 port 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
104  // @User: Standard
105  // @RebootRequired: True
106  AP_GROUPINFO("4_PROTOCOL", 7, AP_SerialManager, state[4].protocol, SerialProtocol_GPS),
107 
108  // @Param: 4_BAUD
109  // @DisplayName: Serial 4 Baud Rate
110  // @Description: The baud rate used for Serial4. The APM2 can support all baudrates up to 115, and also can support 500. The PX4 can support rates of up to 1500. If you setup a rate you cannot support on APM2 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.
111  // @Values: 1:1200,2:2400,4:4800,9:9600,19:19200,38:38400,57:57600,111:111100,115:115200,500:500000,921:921600,1500:1500000
112  // @User: Standard
113  AP_GROUPINFO("4_BAUD", 8, AP_SerialManager, state[4].baud, AP_SERIALMANAGER_GPS_BAUD/1000),
114 
115  // @Param: 5_PROTOCOL
116  // @DisplayName: Serial5 protocol selection
117  // @Description: Control what protocol Serial5 port should be used for. Note that the Frsky options require external converter hardware. See the wiki for details.
118  // @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
119  // @User: Standard
120  // @RebootRequired: True
121  AP_GROUPINFO("5_PROTOCOL", 9, AP_SerialManager, state[5].protocol, SERIAL5_PROTOCOL),
122 
123  // @Param: 5_BAUD
124  // @DisplayName: Serial 5 Baud Rate
125  // @Description: The baud rate used for Serial5. The APM2 can support all baudrates up to 115, and also can support 500. The PX4 can support rates of up to 1500. If you setup a rate you cannot support on APM2 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.
126  // @Values: 1:1200,2:2400,4:4800,9:9600,19:19200,38:38400,57:57600,111:111100,115:115200,500:500000,921:921600,1500:1500000
127  // @User: Standard
128  AP_GROUPINFO("5_BAUD", 10, AP_SerialManager, state[5].baud, SERIAL5_BAUD),
129 
130  // index 11 used by 0_PROTOCOL
131 
133 };
134 
135 // singleton instance
137 
138 // Constructor
140 {
141  _instance = this;
142  // setup parameter defaults
144 }
145 
146 // init_console - initialise console at default baud rate
148 {
149  // initialise console immediately at default size and baud
150  state[0].uart = hal.uartA; // serial0, uartA, always console
151  state[0].uart->begin(AP_SERIALMANAGER_CONSOLE_BAUD,
154 }
155 
156 extern bool g_nsh_should_exit;
157 
158 // init - // init - initialise serial ports
160 {
161  // initialise pointers to serial ports
162  state[1].uart = hal.uartC; // serial1, uartC, normally telem1
163  state[2].uart = hal.uartD; // serial2, uartD, normally telem2
164  state[3].uart = hal.uartB; // serial3, uartB, normally 1st GPS
165  state[4].uart = hal.uartE; // serial4, uartE, normally 2nd GPS
166  state[5].uart = hal.uartF; // serial5
167 
168  if (state[0].uart == nullptr) {
169  init_console();
170  }
171 
172  // initialise serial ports
173  for (uint8_t i=1; i<SERIALMANAGER_NUM_PORTS; i++) {
174 
175 #ifdef CONFIG_ARCH_BOARD_PX4FMU_V2
176  if (i == 5 && state[i].protocol != SerialProtocol_None) {
177  // tell nsh to exit to free up this uart
178  g_nsh_should_exit = true;
179  }
180 #endif
181 
182  if (state[i].uart != nullptr) {
183  switch (state[i].protocol) {
184  case SerialProtocol_None:
185  break;
189  state[i].uart->begin(map_baudrate(state[i].baud),
192  break;
194  // Note baudrate is hardcoded to 9600
195  state[i].baud = AP_SERIALMANAGER_FRSKY_D_BAUD/1000; // update baud param in case user looks at it
196  // begin is handled by AP_Frsky_telem library
197  break;
200  // Note baudrate is hardcoded to 57600
201  state[i].baud = AP_SERIALMANAGER_FRSKY_SPORT_BAUD/1000; // update baud param in case user looks at it
202  // begin is handled by AP_Frsky_telem library
203  break;
204  case SerialProtocol_GPS:
205  case SerialProtocol_GPS2:
206  state[i].uart->begin(map_baudrate(state[i].baud),
209  break;
211  // Note baudrate is hardcoded to 115200
212  state[i].baud = AP_SERIALMANAGER_ALEXMOS_BAUD / 1000; // update baud param in case user looks at it
213  state[i].uart->begin(AP_SERIALMANAGER_ALEXMOS_BAUD,
216  break;
218  // Note baudrate is hardcoded to 115200
219  state[i].baud = AP_SERIALMANAGER_SToRM32_BAUD / 1000; // update baud param in case user looks at it
220  state[i].uart->begin(map_baudrate(state[i].baud),
223  break;
225  state[i].protocol.set_and_save(SerialProtocol_Rangefinder);
226  break;
227  case SerialProtocol_Volz:
228  // Note baudrate is hardcoded to 115200
229  state[i].baud = AP_SERIALMANAGER_VOLZ_BAUD; // update baud param in case user looks at it
230  state[i].uart->begin(map_baudrate(state[i].baud),
233  state[i].uart->set_unbuffered_writes(true);
234  state[i].uart->set_flow_control(AP_HAL::UARTDriver::FLOW_CONTROL_DISABLE);
235  break;
237  state[i].baud = AP_SERIALMANAGER_SBUS1_BAUD / 1000; // update baud param in case user looks at it
238  state[i].uart->begin(map_baudrate(state[i].baud),
241  state[i].uart->configure_parity(2); // enable even parity
242  state[i].uart->set_stop_bits(2);
243  state[i].uart->set_unbuffered_writes(true);
244  state[i].uart->set_flow_control(AP_HAL::UARTDriver::FLOW_CONTROL_DISABLE);
245  break;
246 
248  // ESC telemetry protocol from BLHeli32 ESCs. Note that baudrate is hardcoded to 115200
249  state[i].baud = 115200;
250  state[i].uart->begin(map_baudrate(state[i].baud), 30, 30);
251  state[i].uart->set_flow_control(AP_HAL::UARTDriver::FLOW_CONTROL_DISABLE);
252  break;
253  }
254  }
255  }
256 }
257 
258 // find_serial - searches available serial ports for the first instance that allows the given protocol
259 // instance should be zero if searching for the first instance, 1 for the second, etc
260 // returns uart on success, nullptr if a serial port cannot be found
262 {
263  uint8_t found_instance = 0;
264 
265  // search for matching protocol
266  for(uint8_t i=0; i<SERIALMANAGER_NUM_PORTS; i++) {
267  if (protocol_match(protocol, (enum SerialProtocol)state[i].protocol.get())) {
268  if (found_instance == instance) {
269  return state[i].uart;
270  }
271  found_instance++;
272  }
273  }
274 
275  // if we got this far we did not find the uart
276  return nullptr;
277 }
278 
279 // find_baudrate - searches available serial ports for the first instance that allows the given protocol
280 // instance should be zero if searching for the first instance, 1 for the second, etc
281 // returns baudrate on success, 0 if a serial port cannot be found
282 uint32_t AP_SerialManager::find_baudrate(enum SerialProtocol protocol, uint8_t instance) const
283 {
284  uint8_t found_instance = 0;
285 
286  // search for matching protocol
287  for(uint8_t i=0; i<SERIALMANAGER_NUM_PORTS; i++) {
288  if (protocol_match(protocol, (enum SerialProtocol)state[i].protocol.get())) {
289  if (found_instance == instance) {
290  return map_baudrate(state[i].baud);
291  }
292  found_instance++;
293  }
294  }
295 
296  // if we got this far we did not find the uart
297  return 0;
298 }
299 
300 // get_mavlink_channel - provides the mavlink channel associated with a given protocol
301 // instance should be zero if searching for the first instance, 1 for the second, etc
302 // returns true if a channel is found, false if not
303 bool AP_SerialManager::get_mavlink_channel(enum SerialProtocol protocol, uint8_t instance, mavlink_channel_t &mav_chan) const
304 {
305  // check for MAVLink
306  if (protocol_match(protocol, SerialProtocol_MAVLink)) {
307  if (instance < MAVLINK_COMM_NUM_BUFFERS) {
308  mav_chan = (mavlink_channel_t)(MAVLINK_COMM_0 + instance);
309  return true;
310  }
311  }
312  // report failure
313  return false;
314 }
315 
316 
317 // get_mavlink_protocol - provides the specific MAVLink protocol for a
318 // given channel, or SerialProtocol_None if not found
320 {
321  uint8_t instance = 0;
322  uint8_t chan_idx = (uint8_t)(mav_chan - MAVLINK_COMM_0);
323  for (uint8_t i=0; i<SERIALMANAGER_NUM_PORTS; i++) {
326  if (instance == chan_idx) {
327  return (SerialProtocol)state[i].protocol.get();
328  }
329  instance++;
330  }
331  }
332  return SerialProtocol_None;
333 }
334 
335 // set_blocking_writes_all - sets block_writes on or off for all serial channels
337 {
338  // set block_writes for all initialised serial ports
339  for (uint8_t i=0; i<SERIALMANAGER_NUM_PORTS; i++) {
340  if (state[i].uart != nullptr) {
341  state[i].uart->set_blocking_writes(blocking);
342  }
343  }
344 }
345 
346 // set_console_baud - sets the console's baud rate to the rate specified by the protocol
348 {
349  uint8_t found_instance = 0;
350 
351  // find baud rate of this protocol
352  for (uint8_t i=0; i<SERIALMANAGER_NUM_PORTS; i++) {
353  if (protocol_match(protocol, (enum SerialProtocol)state[i].protocol.get())) {
354  if (instance == found_instance) {
355  // set console's baud rate
356  state[0].uart->begin(map_baudrate(state[i].baud));
357  return;
358  }
359  found_instance++;
360  }
361  }
362 }
363 
364 /*
365  * map from a 16 bit EEPROM baud rate to a real baud rate.
366  * For PX4 we can do 1.5MBit, although 921600 is more reliable.
367  */
368 uint32_t AP_SerialManager::map_baudrate(int32_t rate) const
369 {
370  if (rate <= 0) {
371  rate = 57;
372  }
373  switch (rate) {
374  case 1: return 1200;
375  case 2: return 2400;
376  case 4: return 4800;
377  case 9: return 9600;
378  case 19: return 19200;
379  case 38: return 38400;
380  case 57: return 57600;
381  case 100: return 100000;
382  case 111: return 111100;
383  case 115: return 115200;
384  case 230: return 230400;
385  case 460: return 460800;
386  case 500: return 500000;
387  case 921: return 921600;
388  case 1500: return 1500000;
389  }
390 
391  if (rate > 2000) {
392  // assume it is a direct baudrate. This allows for users to
393  // set an exact baudrate as long as it is over 2000 baud
394  return (uint32_t)rate;
395  }
396 
397  // otherwise allow any other kbaud rate
398  return rate*1000;
399 }
400 
401 // protocol_match - returns true if the protocols match
402 bool AP_SerialManager::protocol_match(enum SerialProtocol protocol1, enum SerialProtocol protocol2) const
403 {
404  // check for obvious match
405  if (protocol1 == protocol2) {
406  return true;
407  }
408 
409  // mavlink match
410  if (((protocol1 == SerialProtocol_MAVLink) || (protocol1 == SerialProtocol_MAVLink2)) &&
411  ((protocol2 == SerialProtocol_MAVLink) || (protocol2 == SerialProtocol_MAVLink2))) {
412  return true;
413  }
414 
415  // gps match
416  if (((protocol1 == SerialProtocol_GPS) || (protocol1 == SerialProtocol_GPS2)) &&
417  ((protocol2 == SerialProtocol_GPS) || (protocol2 == SerialProtocol_GPS2))) {
418  return true;
419  }
420 
421  return false;
422 }
423 
424 
425 namespace AP {
426 
428 {
430 }
431 
432 }
#define AP_SERIALMANAGER_SToRM32_BAUD
bool get_mavlink_channel(enum SerialProtocol protocol, uint8_t instance, mavlink_channel_t &mav_chan) const
AP_HAL::UARTDriver * uartE
Definition: HAL.h:104
#define AP_SERIALMANAGER_VOLZ_BUFSIZE_TX
#define AP_SERIALMANAGER_GPS_BAUD
#define AP_SERIALMANAGER_CONSOLE_BUFSIZE_RX
#define AP_SERIALMANAGER_ALEXMOS_BUFSIZE_TX
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
#define AP_SERIALMANAGER_VOLZ_BUFSIZE_RX
SerialProtocol get_mavlink_protocol(mavlink_channel_t mav_chan) const
#define AP_GROUPINFO(name, idx, clazz, element, def)
Definition: AP_Param.h:102
AP_HAL::UARTDriver * uartB
Definition: HAL.h:101
#define SERIAL5_BAUD
#define AP_SERIALMANAGER_FRSKY_D_BAUD
#define AP_SERIALMANAGER_FRSKY_SPORT_BAUD
#define AP_SERIALMANAGER_ALEXMOS_BAUD
uint32_t find_baudrate(enum SerialProtocol protocol, uint8_t instance) const
#define AP_SERIALMANAGER_CONSOLE_BAUD
bool protocol_match(enum SerialProtocol protocol1, enum SerialProtocol protocol2) const
#define AP_SERIALMANAGER_VOLZ_BAUD
#define SERIALMANAGER_NUM_PORTS
AP_HAL::UARTDriver * uartC
Definition: HAL.h:102
#define AP_SERIALMANAGER_SBUS1_BAUD
AP_HAL::UARTDriver * uart
#define AP_SERIALMANAGER_SBUS1_BUFSIZE_TX
Definition: AP_AHRS.cpp:486
AP_SerialManager & serialmanager()
#define AP_SERIALMANAGER_GPS_BUFSIZE_TX
AP_HAL::UARTDriver * uartF
Definition: HAL.h:105
bool g_nsh_should_exit
#define AP_SERIALMANAGER_MAVLINK_BUFSIZE_TX
AP_HAL::UARTDriver * uartD
Definition: HAL.h:103
#define AP_SERIALMANAGER_SToRM32_BUFSIZE_TX
static AP_SerialManager * _instance
static int state
Definition: Util.cpp:20
void set_console_baud(enum SerialProtocol protocol, uint8_t instance) const
#define AP_SERIALMANAGER_SToRM32_BUFSIZE_RX
static AP_SerialManager * get_instance(void)
#define AP_SERIALMANAGER_SBUS1_BUFSIZE_RX
#define SERIAL5_PROTOCOL
#define AP_SERIALMANAGER_MAVLINK_BAUD
AP_HAL::UARTDriver * uartA
Definition: HAL.h:100
#define AP_SERIALMANAGER_CONSOLE_BUFSIZE_TX
#define AP_SERIALMANAGER_ALEXMOS_BUFSIZE_RX
uint32_t map_baudrate(int32_t rate) const
#define AP_SERIALMANAGER_GPS_BUFSIZE_RX
void set_blocking_writes_all(bool blocking)
static const struct AP_Param::GroupInfo var_info[]
#define AP_SERIALMANAGER_MAVLINK_BUFSIZE_RX
#define AP_GROUPEND
Definition: AP_Param.h:121
AP_HAL::UARTDriver * find_serial(enum SerialProtocol protocol, uint8_t instance) const
struct AP_SerialManager::@182 state[SERIALMANAGER_NUM_PORTS]
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)
Definition: AP_Param.cpp:1214