123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203 |
- #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
- #define SERIALMANAGER_NUM_PORTS 8
-
- #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
- #define AP_SERIALMANAGER_MAVLINK_BAUD 57600
- #define AP_SERIALMANAGER_MAVLINK_BUFSIZE_RX 128
- #define AP_SERIALMANAGER_MAVLINK_BUFSIZE_TX 256
- #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
- #define AP_SERIALMANAGER_GPS_BAUD 38400
- #define AP_SERIALMANAGER_GPS_BUFSIZE_RX 256
- #define AP_SERIALMANAGER_GPS_BUFSIZE_TX 16
- #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
- #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();
-
- AP_SerialManager(const AP_SerialManager &other) = delete;
- AP_SerialManager &operator=(const AP_SerialManager&) = delete;
- enum SerialProtocol {
- SerialProtocol_None = -1,
- SerialProtocol_Console = 0,
- SerialProtocol_MAVLink = 1,
- SerialProtocol_MAVLink2 = 2,
- SerialProtocol_FrSky_D = 3,
- SerialProtocol_FrSky_SPort = 4,
- SerialProtocol_GPS = 5,
- SerialProtocol_GPS2 = 6,
- SerialProtocol_AlexMos = 7,
- SerialProtocol_SToRM32 = 8,
- SerialProtocol_Rangefinder = 9,
- SerialProtocol_FrSky_SPort_Passthrough = 10,
- SerialProtocol_Lidar360 = 11,
- SerialProtocol_Aerotenna_uLanding = 12,
- SerialProtocol_Beacon = 13,
- SerialProtocol_Volz = 14,
- 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,
- };
-
- static AP_SerialManager *get_singleton(void) {
- return _singleton;
- }
-
-
- void init_console();
-
- void init();
-
-
-
- AP_HAL::UARTDriver *find_serial(enum SerialProtocol protocol, uint8_t instance) const;
-
-
-
- uint32_t find_baudrate(enum SerialProtocol protocol, uint8_t instance) const;
-
-
-
- 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;
-
-
- void set_blocking_writes_all(bool blocking);
-
- bool get_passthru(AP_HAL::UARTDriver *&port1, AP_HAL::UARTDriver *&port2, uint8_t &timeout_s) const;
-
- void disable_passthru(void);
-
- AP_HAL::UARTDriver *get_serial_by_id(uint8_t id);
-
- static const struct AP_Param::GroupInfo var_info[];
- private:
- static AP_SerialManager *_singleton;
-
-
- struct UARTState {
- AP_Int8 protocol;
- AP_Int32 baud;
- AP_HAL::UARTDriver* uart;
- AP_Int16 options;
- } state[SERIALMANAGER_NUM_PORTS];
-
- AP_Int8 passthru_port1;
- AP_Int8 passthru_port2;
- AP_Int8 passthru_timeout;
-
-
- const UARTState *find_protocol_instance(enum SerialProtocol protocol,
- uint8_t instance) const;
- uint32_t map_baudrate(int32_t rate) const;
-
- bool protocol_match(enum SerialProtocol protocol1, enum SerialProtocol protocol2) const;
-
- void set_options(uint8_t i);
- };
- namespace AP {
- AP_SerialManager &serialmanager();
- };
|