29 #define SERIALMANAGER_NUM_PORTS 6 32 #ifdef HAL_SERIAL0_BAUD_DEFAULT 33 # define AP_SERIALMANAGER_CONSOLE_BAUD HAL_SERIAL0_BAUD_DEFAULT 35 # define AP_SERIALMANAGER_CONSOLE_BAUD 115200 37 # define AP_SERIALMANAGER_CONSOLE_BUFSIZE_RX 128 38 # define AP_SERIALMANAGER_CONSOLE_BUFSIZE_TX 512 41 #define AP_SERIALMANAGER_MAVLINK_BAUD 57600 42 #define AP_SERIALMANAGER_MAVLINK_BUFSIZE_RX 128 43 #define AP_SERIALMANAGER_MAVLINK_BUFSIZE_TX 256 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 53 #define AP_SERIALMANAGER_GPS_BAUD 38400 54 #define AP_SERIALMANAGER_GPS_BUFSIZE_RX 256 55 #define AP_SERIALMANAGER_GPS_BUFSIZE_TX 16 58 #define AP_SERIALMANAGER_ALEXMOS_BAUD 115200 59 #define AP_SERIALMANAGER_ALEXMOS_BUFSIZE_RX 128 60 #define AP_SERIALMANAGER_ALEXMOS_BUFSIZE_TX 128 62 #define AP_SERIALMANAGER_SToRM32_BAUD 115200 63 #define AP_SERIALMANAGER_SToRM32_BUFSIZE_RX 128 64 #define AP_SERIALMANAGER_SToRM32_BUFSIZE_TX 128 66 #define AP_SERIALMANAGER_VOLZ_BAUD 115 67 #define AP_SERIALMANAGER_VOLZ_BUFSIZE_RX 128 68 #define AP_SERIALMANAGER_VOLZ_BUFSIZE_TX 128 71 #define AP_SERIALMANAGER_SBUS1_BAUD 100000 72 #define AP_SERIALMANAGER_SBUS1_BUFSIZE_RX 16 73 #define AP_SERIALMANAGER_SBUS1_BUFSIZE_TX 32
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
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]