24 #if defined(__linux__) 25 #include <linux/serial.h> 30 using boost::system::error_code;
31 using boost::asio::io_service;
32 using boost::asio::buffer;
33 using mavlink::mavlink_message_t;
36 #define PFX "mavconn: serial" 37 #define PFXd PFX "%zu: " 41 std::string device,
unsigned baudrate,
bool hwflow) :
44 serial_dev(io_service),
45 tx_in_progress(false),
49 using SPB = boost::asio::serial_port_base;
57 serial_dev.set_option(SPB::baud_rate(baudrate));
59 serial_dev.set_option(SPB::parity(SPB::parity::none));
60 serial_dev.set_option(SPB::stop_bits(SPB::stop_bits::one));
62 #if BOOST_ASIO_VERSION >= 101200 || !defined(__linux__) 64 serial_dev.set_option(SPB::flow_control( (hwflow) ? SPB::flow_control::hardware : SPB::flow_control::none));
65 #elif BOOST_ASIO_VERSION < 101200 && defined(__linux__) 77 tio.c_iflag &= ~(IXOFF | IXON);
78 tio.c_cflag |= CRTSCTS;
80 tio.c_iflag &= ~(IXOFF | IXON);
81 tio.c_cflag &= ~CRTSCTS;
88 tcsetattr(fd, TCSANOW, &tio);
92 #if defined(__linux__) 97 struct serial_struct ser_info;
98 ioctl(fd, TIOCGSERIAL, &ser_info);
100 ser_info.flags |= ASYNC_LOW_LATENCY;
102 ioctl(fd, TIOCSSERIAL, &ser_info);
106 catch (boost::system::system_error &err) {
158 throw std::length_error(
"MAVConnSerial::send_bytes: TX queue overflow");
160 tx_q.emplace_back(bytes, length);
167 assert(message !=
nullptr);
180 throw std::length_error(
"MAVConnSerial::send_message: TX queue overflow");
182 tx_q.emplace_back(message);
200 throw std::length_error(
"MAVConnSerial::send_message: TX queue overflow");
209 auto sthis = shared_from_this();
212 [sthis] (error_code error,
size_t bytes_transferred) {
219 sthis->parse_buffer(
PFX, sthis->rx_buf.data(), sthis->rx_buf.size(), bytes_transferred);
234 auto sthis = shared_from_this();
235 auto &buf_ref =
tx_q.front();
237 buffer(buf_ref.dpos(), buf_ref.nbytes()),
238 [sthis, &buf_ref] (error_code error,
size_t bytes_transferred) {
239 assert(bytes_transferred <= buf_ref.len);
247 sthis->iostat_tx_add(bytes_transferred);
250 if (sthis->tx_q.empty()) {
251 sthis->tx_in_progress =
false;
255 buf_ref.pos += bytes_transferred;
256 if (buf_ref.nbytes() == 0) {
257 sthis->tx_q.pop_front();
260 if (!sthis->tx_q.empty())
261 sthis->do_write(
false);
263 sthis->tx_in_progress =
false;
void log_send(const char *pfx, const mavlink::mavlink_message_t *msg)
ClosedCb port_closed_cb
Port closed notification callback.
std::lock_guard< std::recursive_mutex > lock_guard
#define CONSOLE_BRIDGE_logInform(fmt,...)
static constexpr size_t MAX_TXQ_SIZE
Maximum count of transmission buffers.
boost::asio::io_service io_service
Common exception for communication error.
bool set_this_thread_name(const std::string &name, Args &&...args)
Set name to current thread, printf-like.
void log_send_obj(const char *pfx, const mavlink::Message &msg)
std::array< uint8_t, MsgBuffer::MAX_SIZE > rx_buf
void close() override
Close connection.
Generic mavlink interface.
void send_bytes(const uint8_t *bytes, size_t length) override
Send raw bytes (for some quirks)
mavlink::mavlink_status_t * get_status_p()
size_t conn_id
Channel number used for logging.
#define CONSOLE_BRIDGE_logError(fmt,...)
MAVConn Serial link class.
boost::asio::serial_port serial_dev
MAVConn console-bridge compatibility header.
std::deque< MsgBuffer > tx_q
struct __mavlink_message mavlink_message_t
std::atomic< bool > tx_in_progress
MAVConnSerial(uint8_t system_id=1, uint8_t component_id=MAV_COMP_ID_UDP_BRIDGE, std::string device=DEFAULT_DEVICE, unsigned baudrate=DEFAULT_BAUDRATE, bool hwflow=false)
void send_message(const mavlink::mavlink_message_t *message) override
Send message (mavlink_message_t)
uint8_t sys_id
Connection System Id.
void do_write(bool check_tx_state)
std::recursive_mutex mutex