mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
mavlink shell: check if there's enough free buffer to send the mavlink message
if there is not, the process on the other end of the pipe will just block. This improves reliability over slow links.
This commit is contained in:
parent
644d237ce6
commit
cfcc75d444
@ -2225,13 +2225,15 @@ Mavlink::task_main(int argc, char *argv[])
|
||||
|
||||
/* check for shell output */
|
||||
if (_mavlink_shell && _mavlink_shell->available() > 0) {
|
||||
mavlink_serial_control_t msg;
|
||||
msg.baudrate = 0;
|
||||
msg.flags = SERIAL_CONTROL_FLAG_REPLY;
|
||||
msg.timeout = 0;
|
||||
msg.device = SERIAL_CONTROL_DEV_SHELL;
|
||||
msg.count = _mavlink_shell->read(msg.data, sizeof(msg.data));
|
||||
mavlink_msg_serial_control_send_struct(get_channel(), &msg);
|
||||
if (get_free_tx_buf() >= MAVLINK_MSG_ID_SERIAL_CONTROL_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES) {
|
||||
mavlink_serial_control_t msg;
|
||||
msg.baudrate = 0;
|
||||
msg.flags = SERIAL_CONTROL_FLAG_REPLY;
|
||||
msg.timeout = 0;
|
||||
msg.device = SERIAL_CONTROL_DEV_SHELL;
|
||||
msg.count = _mavlink_shell->read(msg.data, sizeof(msg.data));
|
||||
mavlink_msg_serial_control_send_struct(get_channel(), &msg);
|
||||
}
|
||||
}
|
||||
|
||||
/* check for ulog streaming messages */
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user