21 #include <boost/asio.hpp> 30 public std::enable_shared_from_this<MAVConnSerial> {
42 std::string device = DEFAULT_DEVICE,
unsigned baudrate = DEFAULT_BAUDRATE,
bool hwflow =
false);
48 void close()
override;
50 void send_message(
const mavlink::mavlink_message_t *message)
override;
52 void send_bytes(
const uint8_t *bytes,
size_t length)
override;
64 std::deque<MsgBuffer>
tx_q;
65 std::array<uint8_t, MsgBuffer::MAX_SIZE>
rx_buf;
void connect(const ReceivedCb &cb_handle_message, const ClosedCb &cb_handle_closed_port=ClosedCb()) override
Establish connection, automatically called by open_url()
std::function< void(const mavlink::mavlink_message_t *message, const Framing framing)> ReceivedCb
boost::asio::io_service io_service
static constexpr auto MAV_COMP_ID_UDP_BRIDGE
Same as mavlink::common::MAV_COMPONENT::COMP_ID_UDP_BRIDGE.
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)
std::function< void(void)> ClosedCb
MAVConn message buffer class (internal)
static constexpr auto DEFAULT_DEVICE
boost::asio::serial_port serial_dev
std::deque< MsgBuffer > tx_q
static constexpr auto DEFAULT_BAUDRATE
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)
void do_write(bool check_tx_state)
std::recursive_mutex mutex