32 mavlink_serial_control_t packet;
33 mavlink_msg_serial_control_decode(msg, &packet);
38 if (packet.flags & SERIAL_CONTROL_FLAG_REPLY) {
43 bool exclusive = (packet.flags & SERIAL_CONTROL_FLAG_EXCLUSIVE) != 0;
45 switch (packet.device) {
46 case SERIAL_CONTROL_DEV_TELEM1:
47 stream = port = hal.
uartC;
50 case SERIAL_CONTROL_DEV_TELEM2:
51 stream = port = hal.
uartD;
54 case SERIAL_CONTROL_DEV_GPS1:
55 stream = port = hal.
uartB;
58 case SERIAL_CONTROL_DEV_GPS2:
59 stream = port = hal.
uartE;
62 case SERIAL_CONTROL_DEV_SHELL:
64 if (stream ==
nullptr) {
72 if (stream ==
nullptr) {
74 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL 80 if (exclusive && port !=
nullptr) {
88 if (packet.baudrate != 0 && port !=
nullptr) {
89 port->
begin(packet.baudrate);
93 if (packet.count != 0) {
94 if ((packet.flags & SERIAL_CONTROL_FLAG_BLOCKING) == 0) {
95 stream->
write(packet.data, packet.count);
97 const uint8_t *data = &packet.data[0];
98 uint8_t
count = packet.count;
100 while (stream->
txspace() <= 0) {
103 uint16_t n = stream->
txspace();
104 if (n > packet.count) {
107 stream->
write(data, n);
114 if ((packet.flags & SERIAL_CONTROL_FLAG_RESPOND) == 0) {
119 uint8_t flags = packet.flags;
123 while (packet.timeout != 0 &&
124 stream->
available() < (int16_t)
sizeof(packet.data)) {
129 packet.flags = SERIAL_CONTROL_FLAG_REPLY;
136 if (available > (int16_t)
sizeof(packet.data)) {
137 available =
sizeof(packet.data);
139 if (available == 0 && (flags & SERIAL_CONTROL_FLAG_BLOCKING) == 0) {
143 if (packet.flags & SERIAL_CONTROL_FLAG_BLOCKING) {
156 memset(packet.data, 0,
sizeof(packet.data));
157 while (available > 0) {
158 packet.data[packet.count++] = (uint8_t)stream->
read();
163 _mav_finalize_message_chan_send(
chan,
164 MAVLINK_MSG_ID_SERIAL_CONTROL,
165 (
const char *)&packet,
166 MAVLINK_MSG_ID_SERIAL_CONTROL_MIN_LEN,
167 MAVLINK_MSG_ID_SERIAL_CONTROL_LEN,
168 MAVLINK_MSG_ID_SERIAL_CONTROL_CRC);
169 if ((flags & SERIAL_CONTROL_FLAG_MULTI) && packet.count != 0) {
170 if (flags & SERIAL_CONTROL_FLAG_BLOCKING) {
AP_HAL::UARTDriver * uartE
virtual void begin(uint32_t baud)=0
Interface definition for the various Ground Control System.
void lock_channel(mavlink_channel_t chan, bool lock)
void lock_port(uint8_t instance, bool locked)
AP_HAL::UARTDriver * uartB
virtual uint32_t txspace()=0
virtual void delay(uint16_t ms)=0
AP_HAL::UARTDriver * uartC
#define HAVE_PAYLOAD_SPACE(chan, id)
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
virtual size_t write(uint8_t)=0
AP_HAL::UARTDriver * uartD
virtual void set_flow_control(enum flow_control flow_control_setting)
void handle_serial_control(const mavlink_message_t *msg)
virtual uint32_t available()=0
virtual AP_HAL::BetterStream * get_shell_stream()
void panic(const char *errormsg,...) FMT_PRINTF(1
AP_HAL::Scheduler * scheduler