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 35 #define SERIAL5_PROTOCOL SerialProtocol_None 36 #define SERIAL5_BAUD AP_SERIALMANAGER_MAVLINK_BAUD/1000 175 #ifdef CONFIG_ARCH_BOARD_PX4FMU_V2 233 state[i].uart->set_unbuffered_writes(
true);
241 state[i].uart->configure_parity(2);
242 state[i].uart->set_stop_bits(2);
243 state[i].uart->set_unbuffered_writes(
true);
249 state[i].baud = 115200;
263 uint8_t found_instance = 0;
268 if (found_instance == instance) {
269 return state[i].uart;
284 uint8_t found_instance = 0;
289 if (found_instance == instance) {
308 mav_chan = (mavlink_channel_t)(MAVLINK_COMM_0 + instance);
321 uint8_t instance = 0;
322 uint8_t chan_idx = (uint8_t)(mav_chan - MAVLINK_COMM_0);
326 if (instance == chan_idx) {
341 state[i].uart->set_blocking_writes(blocking);
349 uint8_t found_instance = 0;
354 if (instance == found_instance) {
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;
394 return (uint32_t)rate;
405 if (protocol1 == protocol2) {
#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
#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 -*-
#define AP_SERIALMANAGER_VOLZ_BUFSIZE_RX
SerialProtocol get_mavlink_protocol(mavlink_channel_t mav_chan) const
#define AP_GROUPINFO(name, idx, clazz, element, def)
AP_HAL::UARTDriver * uartB
#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
#define AP_SERIALMANAGER_SBUS1_BAUD
AP_HAL::UARTDriver * uart
#define AP_SERIALMANAGER_SBUS1_BUFSIZE_TX
AP_SerialManager & serialmanager()
#define AP_SERIALMANAGER_GPS_BUFSIZE_TX
AP_HAL::UARTDriver * uartF
#define AP_SERIALMANAGER_MAVLINK_BUFSIZE_TX
AP_HAL::UARTDriver * uartD
#define AP_SERIALMANAGER_SToRM32_BUFSIZE_TX
static AP_SerialManager * _instance
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 AP_SERIALMANAGER_MAVLINK_BAUD
AP_HAL::UARTDriver * uartA
#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 MAVLINK_COMM_NUM_BUFFERS
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)