APM:Libraries
AP_SerialManager.h
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 #pragma once
23 
24 #include <AP_Math/AP_Math.h>
25 #include <AP_Common/AP_Common.h>
26 #include <AP_HAL/AP_HAL.h>
28 
29 #define SERIALMANAGER_NUM_PORTS 6
30 
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 
40 // mavlink default baud rates and buffer sizes
41 #define AP_SERIALMANAGER_MAVLINK_BAUD 57600
42 #define AP_SERIALMANAGER_MAVLINK_BUFSIZE_RX 128
43 #define AP_SERIALMANAGER_MAVLINK_BUFSIZE_TX 256
44 
45 // FrSky default baud rates, use default buffer sizes
46 #define AP_SERIALMANAGER_FRSKY_D_BAUD 9600
47 #define AP_SERIALMANAGER_FRSKY_SPORT_BAUD 57600
48 #define AP_SERIALMANAGER_FRSKY_BUFSIZE_RX 0
49 #define AP_SERIALMANAGER_FRSKY_BUFSIZE_TX 0
50 
51 // GPS default baud rates and buffer sizes
52 // we need a 256 byte buffer for some GPS types (eg. UBLOX)
53 #define AP_SERIALMANAGER_GPS_BAUD 38400
54 #define AP_SERIALMANAGER_GPS_BUFSIZE_RX 256
55 #define AP_SERIALMANAGER_GPS_BUFSIZE_TX 16
56 
57 // AlexMos Gimbal protocol default baud rates and buffer sizes
58 #define AP_SERIALMANAGER_ALEXMOS_BAUD 115200
59 #define AP_SERIALMANAGER_ALEXMOS_BUFSIZE_RX 128
60 #define AP_SERIALMANAGER_ALEXMOS_BUFSIZE_TX 128
61 
62 #define AP_SERIALMANAGER_SToRM32_BAUD 115200
63 #define AP_SERIALMANAGER_SToRM32_BUFSIZE_RX 128
64 #define AP_SERIALMANAGER_SToRM32_BUFSIZE_TX 128
65 
66 #define AP_SERIALMANAGER_VOLZ_BAUD 115
67 #define AP_SERIALMANAGER_VOLZ_BUFSIZE_RX 128
68 #define AP_SERIALMANAGER_VOLZ_BUFSIZE_TX 128
69 
70 // SBUS servo outputs
71 #define AP_SERIALMANAGER_SBUS1_BAUD 100000
72 #define AP_SERIALMANAGER_SBUS1_BUFSIZE_RX 16
73 #define AP_SERIALMANAGER_SBUS1_BUFSIZE_TX 32
74 
76 public:
78 
79  /* Do not allow copies */
80  AP_SerialManager(const AP_SerialManager &other) = delete;
82 
85  SerialProtocol_Console = 0, // unused
87  SerialProtocol_MAVLink2 = 2, // do not use - use MAVLink and provide instance of 1
88  SerialProtocol_FrSky_D = 3, // FrSky D protocol (D-receivers)
89  SerialProtocol_FrSky_SPort = 4, // FrSky SPort protocol (X-receivers)
91  SerialProtocol_GPS2 = 6, // do not use - use GPS and provide instance of 1
95  SerialProtocol_FrSky_SPort_Passthrough = 10, // FrSky SPort Passthrough (OpenTX) protocol (X-receivers)
96  SerialProtocol_Lidar360 = 11, // Lightware SF40C, TeraRanger Tower or RPLidarA2
97  SerialProtocol_Aerotenna_uLanding = 12, // Ulanding support - deprecated, users should use Rangefinder
99  SerialProtocol_Volz = 14, // Volz servo protocol
103  };
104 
105  // get singleton instance
107  return _instance;
108  }
109 
110  // init_console - initialise console at default baud rate
111  void init_console();
112 
113  // init - initialise serial ports
114  void init();
115 
116  // find_serial - searches available serial ports that allows the given protocol
117  // instance should be zero if searching for the first instance, 1 for the second, etc
118  // returns uart on success, nullptr if a serial port cannot be found
119  AP_HAL::UARTDriver *find_serial(enum SerialProtocol protocol, uint8_t instance) const;
120 
121  // find_baudrate - searches available serial ports for the first instance that allows the given protocol
122  // instance should be zero if searching for the first instance, 1 for the second, etc
123  // returns the baudrate of that protocol on success, 0 if a serial port cannot be found
124  uint32_t find_baudrate(enum SerialProtocol protocol, uint8_t instance) const;
125 
126  // get_mavlink_channel - provides the mavlink channel associated with a given protocol (and instance)
127  // instance should be zero if searching for the first instance, 1 for the second, etc
128  // returns true if a channel is found, false if not
129  bool get_mavlink_channel(enum SerialProtocol protocol, uint8_t instance, mavlink_channel_t &mav_chan) const;
130 
131  // get_mavlink_protocol - provides the specific MAVLink protocol for a
132  // given channel, or SerialProtocol_None if not found
133  SerialProtocol get_mavlink_protocol(mavlink_channel_t mav_chan) const;
134 
135  // set_blocking_writes_all - sets block_writes on or off for all serial channels
136  void set_blocking_writes_all(bool blocking);
137 
138  // set_console_baud - sets the console's baud rate to the rate specified by the protocol
139  void set_console_baud(enum SerialProtocol protocol, uint8_t instance) const;
140 
141  // parameter var table
142  static const struct AP_Param::GroupInfo var_info[];
143 
144 private:
146 
147  // array of uart info
148  struct {
149  AP_Int8 protocol;
150  AP_Int32 baud;
153 
154  uint32_t map_baudrate(int32_t rate) const;
155 
156  // protocol_match - returns true if the protocols match
157  bool protocol_match(enum SerialProtocol protocol1, enum SerialProtocol protocol2) const;
158 };
159 
160 namespace AP {
162 };
bool get_mavlink_channel(enum SerialProtocol protocol, uint8_t instance, mavlink_channel_t &mav_chan) const
SerialProtocol get_mavlink_protocol(mavlink_channel_t mav_chan) const
uint32_t find_baudrate(enum SerialProtocol protocol, uint8_t instance) const
AP_SerialManager & operator=(const AP_SerialManager &)=delete
bool protocol_match(enum SerialProtocol protocol1, enum SerialProtocol protocol2) const
#define SERIALMANAGER_NUM_PORTS
AP_HAL::UARTDriver * uart
Definition: AP_AHRS.cpp:486
AP_SerialManager & serialmanager()
static AP_SerialManager * _instance
void set_console_baud(enum SerialProtocol protocol, uint8_t instance) const
static AP_SerialManager * get_instance(void)
Common definitions and utility routines for the ArduPilot libraries.
uint32_t map_baudrate(int32_t rate) const
void set_blocking_writes_all(bool blocking)
static const struct AP_Param::GroupInfo var_info[]
AP_HAL::UARTDriver * find_serial(enum SerialProtocol protocol, uint8_t instance) const
struct AP_SerialManager::@182 state[SERIALMANAGER_NUM_PORTS]