Go to the documentation of this file.
23 #include <boost/asio.hpp>
35 public std::enable_shared_from_this<MAVConnTCPClient> {
51 boost::asio::io_service &server_io);
57 void close()
override;
59 void send_message(
const mavlink::mavlink_message_t *message)
override;
60 void send_message(
const mavlink::Message &message,
const uint8_t source_compid)
override;
61 void send_bytes(
const uint8_t *bytes,
size_t length)
override;
70 std::unique_ptr<boost::asio::io_service::work>
io_work;
79 std::deque<MsgBuffer>
tx_q;
80 std::array<uint8_t, MsgBuffer::MAX_SIZE>
rx_buf;
89 void do_send(
bool check_tx_state);
98 public std::enable_shared_from_this<MAVConnTCPServer> {
114 void close()
override;
116 void send_message(
const mavlink::mavlink_message_t *message)
override;
117 void send_message(
const mavlink::Message &message,
const uint8_t source_compid)
override;
118 void send_bytes(
const uint8_t *bytes,
size_t length)
override;
120 mavlink::mavlink_status_t
get_status()
override;
128 std::unique_ptr<boost::asio::io_service::work>
io_work;
142 void client_closed(std::weak_ptr<MAVConnTCPClient> weak_instp);
std::list< std::shared_ptr< MAVConnTCPClient > > client_list
mavlink::mavlink_status_t get_status() override
void client_closed(std::weak_ptr< MAVConnTCPClient > weak_instp)
boost::asio::ip::tcp::socket socket
void client_connected(size_t server_channel)
std::array< uint8_t, MsgBuffer::MAX_SIZE > rx_buf
boost::asio::ip::tcp::acceptor acceptor
MAVConnTCPServer(uint8_t system_id=1, uint8_t component_id=MAV_COMP_ID_UDP_BRIDGE, std::string bind_host=DEFAULT_BIND_HOST, unsigned short bind_port=DEFAULT_BIND_PORT)
void send_message(const mavlink::mavlink_message_t *message) override
Send message (mavlink_message_t)
std::atomic< bool > is_destroying
static constexpr auto DEFAULT_BIND_HOST
void connect(const ReceivedCb &cb_handle_message, const ClosedCb &cb_handle_closed_port=ClosedCb()) override
Establish connection, automatically called by open_url()
std::deque< MsgBuffer > tx_q
IOStat get_iostat() override
static constexpr auto DEFAULT_SERVER_HOST
void send_bytes(const uint8_t *bytes, size_t length) override
Send raw bytes (for some quirks)
Generic mavlink interface.
static constexpr auto DEFAULT_BIND_PORT
static constexpr auto DEFAULT_SERVER_PORT
std::unique_ptr< boost::asio::io_service::work > io_work
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::atomic< bool > is_destroying
MAVConnTCPClient(uint8_t system_id=1, uint8_t component_id=MAV_COMP_ID_UDP_BRIDGE, std::string server_host=DEFAULT_SERVER_HOST, unsigned short server_port=DEFAULT_SERVER_PORT)
void do_send(bool check_tx_state)
boost::asio::ip::tcp::endpoint bind_ep
virtual ~MAVConnTCPClient()
boost::asio::io_service io_service
void close() override
Close connection.
std::recursive_mutex mutex
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)
std::atomic< bool > tx_in_progress
void connect(const ReceivedCb &cb_handle_message, const ClosedCb &cb_handle_closed_port=ClosedCb()) override
Establish connection, automatically called by open_url()
void send_message(const mavlink::mavlink_message_t *message) override
Send message (mavlink_message_t)
virtual ~MAVConnTCPServer()
std::recursive_mutex mutex
boost::asio::ip::tcp::endpoint server_ep
void close() override
Close connection.
std::function< void(const mavlink::mavlink_message_t *message, const Framing framing)> ReceivedCb
std::unique_ptr< boost::asio::io_service::work > io_work
libmavconn
Author(s): Vladimir Ermakov
autogenerated on Tue May 6 2025 02:34:01