123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203 |
- /*
- Please contribute your ideas! See http://dev.ardupilot.org for details
- This program is free software: you can redistribute it and/or modify
- it under the terms of the GNU General Public License as published by
- the Free Software Foundation, either version 3 of the License, or
- (at your option) any later version.
- This program is distributed in the hope that it will be useful,
- but WITHOUT ANY WARRANTY; without even the implied warranty of
- MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
- GNU General Public License for more details.
- You should have received a copy of the GNU General Public License
- along with this program. If not, see <http://www.gnu.org/licenses/>.
- */
- /*
- SerialManager allows defining the protocol and baud rates for the available
- serial ports and provides helper functions so objects (like a gimbal) can
- find which serial port they should use
- */
- #pragma once
- #include <AP_HAL/AP_HAL.h>
- #include <GCS_MAVLink/GCS_MAVLink.h>
- #include <AP_Param/AP_Param.h>
- #define BAUD_115200 115200
- #define AP_SERIALMANAGER_USART2_BUFSIZE_RX 128
- #define AP_SERIALMANAGER_USART2_BUFSIZE_TX 8
- #define BAUD_19200 19200
- #define AP_SERIALMANAGER_USART1_BUFSIZE_RX 16
- #define AP_SERIALMANAGER_USART1_BUFSIZE_TX 16
- // we have hal.uartA to hal.uartH
- #define SERIALMANAGER_NUM_PORTS 8
- // console default baud rates and buffer sizes
- #ifdef HAL_SERIAL0_BAUD_DEFAULT
- # define AP_SERIALMANAGER_CONSOLE_BAUD HAL_SERIAL0_BAUD_DEFAULT
- #else
- # define AP_SERIALMANAGER_CONSOLE_BAUD 115200
- #endif
- # define AP_SERIALMANAGER_CONSOLE_BUFSIZE_RX 128
- # define AP_SERIALMANAGER_CONSOLE_BUFSIZE_TX 512
- // mavlink default baud rates and buffer sizes
- #define AP_SERIALMANAGER_MAVLINK_BAUD 57600
- #define AP_SERIALMANAGER_MAVLINK_BUFSIZE_RX 128
- #define AP_SERIALMANAGER_MAVLINK_BUFSIZE_TX 256
- // FrSky default baud rates, use default buffer sizes
- #define AP_SERIALMANAGER_FRSKY_D_BAUD 9600
- #define AP_SERIALMANAGER_FRSKY_SPORT_BAUD 57600
- #define AP_SERIALMANAGER_FRSKY_BUFSIZE_RX 0
- #define AP_SERIALMANAGER_FRSKY_BUFSIZE_TX 0
- // GPS default baud rates and buffer sizes
- // we need a 256 byte buffer for some GPS types (eg. UBLOX)
- #define AP_SERIALMANAGER_GPS_BAUD 38400
- #define AP_SERIALMANAGER_GPS_BUFSIZE_RX 256
- #define AP_SERIALMANAGER_GPS_BUFSIZE_TX 16
- // AlexMos Gimbal protocol default baud rates and buffer sizes
- #define AP_SERIALMANAGER_ALEXMOS_BAUD 115200
- #define AP_SERIALMANAGER_ALEXMOS_BUFSIZE_RX 128
- #define AP_SERIALMANAGER_ALEXMOS_BUFSIZE_TX 128
- #define AP_SERIALMANAGER_SToRM32_BAUD 115200
- #define AP_SERIALMANAGER_SToRM32_BUFSIZE_RX 128
- #define AP_SERIALMANAGER_SToRM32_BUFSIZE_TX 128
- #define AP_SERIALMANAGER_VOLZ_BAUD 115
- #define AP_SERIALMANAGER_VOLZ_BUFSIZE_RX 128
- #define AP_SERIALMANAGER_VOLZ_BUFSIZE_TX 128
- #define AP_SERIALMANAGER_ROBOTIS_BUFSIZE_RX 128
- #define AP_SERIALMANAGER_ROBOTIS_BUFSIZE_TX 128
- // SBUS servo outputs
- #define AP_SERIALMANAGER_SBUS1_BAUD 100000
- #define AP_SERIALMANAGER_SBUS1_BUFSIZE_RX 16
- #define AP_SERIALMANAGER_SBUS1_BUFSIZE_TX 32
- #define AP_SERIALMANAGER_SLCAN_BAUD 115200
- #define AP_SERIALMANAGER_SLCAN_BUFSIZE_RX 128
- #define AP_SERIALMANAGER_SLCAN_BUFSIZE_TX 128
- class AP_SerialManager {
- public:
- AP_SerialManager();
- /* Do not allow copies */
- AP_SerialManager(const AP_SerialManager &other) = delete;
- AP_SerialManager &operator=(const AP_SerialManager&) = delete;
- enum SerialProtocol {
- SerialProtocol_None = -1,
- SerialProtocol_Console = 0, // unused
- SerialProtocol_MAVLink = 1,
- SerialProtocol_MAVLink2 = 2, // do not use - use MAVLink and provide instance of 1
- SerialProtocol_FrSky_D = 3, // FrSky D protocol (D-receivers)
- SerialProtocol_FrSky_SPort = 4, // FrSky SPort protocol (X-receivers)
- SerialProtocol_GPS = 5,
- SerialProtocol_GPS2 = 6, // do not use - use GPS and provide instance of 1
- SerialProtocol_AlexMos = 7,
- SerialProtocol_SToRM32 = 8,
- SerialProtocol_Rangefinder = 9,
- SerialProtocol_FrSky_SPort_Passthrough = 10, // FrSky SPort Passthrough (OpenTX) protocol (X-receivers)
- SerialProtocol_Lidar360 = 11, // Lightware SF40C, TeraRanger Tower or RPLidarA2
- SerialProtocol_Aerotenna_uLanding = 12, // Ulanding support - deprecated, users should use Rangefinder
- SerialProtocol_Beacon = 13,
- SerialProtocol_Volz = 14, // Volz servo protocol
- SerialProtocol_Sbus1 = 15,
- SerialProtocol_ESCTelemetry = 16,
- SerialProtocol_Devo_Telem = 17,
- SerialProtocol_OpticalFlow = 18,
- SerialProtocol_Robotis = 19,
- SerialProtocol_NMEAOutput = 20,
- SerialProtocol_WindVane = 21,
- SerialProtocol_SLCAN = 22,
- SerialProtocol_RCIN = 23,
- SerialProtocol_usart2 = 24,//自定义串口协议
- SerialProtocol_usart1 = 25,//自定义串口协议
- };
- // get singleton instance
- static AP_SerialManager *get_singleton(void) {
- return _singleton;
- }
-
- // init_console - initialise console at default baud rate
- void init_console();
- // init - initialise serial ports
- void init();
- // find_serial - searches available serial ports that allows the given protocol
- // instance should be zero if searching for the first instance, 1 for the second, etc
- // returns uart on success, nullptr if a serial port cannot be found
- AP_HAL::UARTDriver *find_serial(enum SerialProtocol protocol, uint8_t instance) const;
- // find_baudrate - searches available serial ports for the first instance that allows the given protocol
- // instance should be zero if searching for the first instance, 1 for the second, etc
- // returns the baudrate of that protocol on success, 0 if a serial port cannot be found
- uint32_t find_baudrate(enum SerialProtocol protocol, uint8_t instance) const;
- // get_mavlink_channel - provides the mavlink channel associated with a given protocol (and instance)
- // instance should be zero if searching for the first instance, 1 for the second, etc
- // returns true if a channel is found, false if not
- bool get_mavlink_channel(enum SerialProtocol protocol, uint8_t instance, mavlink_channel_t &mav_chan) const;
- // get_mavlink_protocol - provides the specific MAVLink protocol for a
- // given channel, or SerialProtocol_None if not found
- SerialProtocol get_mavlink_protocol(mavlink_channel_t mav_chan) const;
-
- // set_blocking_writes_all - sets block_writes on or off for all serial channels
- void set_blocking_writes_all(bool blocking);
- // get the passthru ports if enabled
- bool get_passthru(AP_HAL::UARTDriver *&port1, AP_HAL::UARTDriver *&port2, uint8_t &timeout_s) const;
- // disable passthru by settings SERIAL_PASS2 to -1
- void disable_passthru(void);
- // get Serial Port
- AP_HAL::UARTDriver *get_serial_by_id(uint8_t id);
- // parameter var table
- static const struct AP_Param::GroupInfo var_info[];
- private:
- static AP_SerialManager *_singleton;
-
- // array of uart info
- struct UARTState {
- AP_Int8 protocol;
- AP_Int32 baud;
- AP_HAL::UARTDriver* uart;
- AP_Int16 options;
- } state[SERIALMANAGER_NUM_PORTS];
- // pass-through serial support
- AP_Int8 passthru_port1;
- AP_Int8 passthru_port2;
- AP_Int8 passthru_timeout;
- // search through managed serial connections looking for the
- // instance-nth UART which is running protocol protocol
- const UARTState *find_protocol_instance(enum SerialProtocol protocol,
- uint8_t instance) const;
- uint32_t map_baudrate(int32_t rate) const;
- // protocol_match - returns true if the protocols match
- bool protocol_match(enum SerialProtocol protocol1, enum SerialProtocol protocol2) const;
- // setup any special options
- void set_options(uint8_t i);
- };
- namespace AP {
- AP_SerialManager &serialmanager();
- };
|