tcp.h
Go to the documentation of this file.
1 
9 /*
10  * libmavconn
11  * Copyright 2014,2015,2016 Vladimir Ermakov, All rights reserved.
12  *
13  * This file is part of the mavros package and subject to the license terms
14  * in the top-level LICENSE file of the mavros repository.
15  * https://github.com/mavlink/mavros/tree/master/LICENSE.md
16  */
17 
18 #pragma once
19 
20 #include <list>
21 #include <atomic>
22 #include <cstring>
23 #include <boost/asio.hpp>
24 #include <mavconn/interface.h>
25 #include <mavconn/msgbuffer.h>
26 
27 
28 namespace mavconn {
35  public std::enable_shared_from_this<MAVConnTCPClient> {
36 public:
37  static constexpr auto DEFAULT_SERVER_HOST = "localhost";
38  static constexpr auto DEFAULT_SERVER_PORT = 5760;
39 
45  MAVConnTCPClient(uint8_t system_id = 1, uint8_t component_id = MAV_COMP_ID_UDP_BRIDGE,
46  std::string server_host = DEFAULT_SERVER_HOST, unsigned short server_port = DEFAULT_SERVER_PORT);
50  explicit MAVConnTCPClient(uint8_t system_id, uint8_t component_id,
51  boost::asio::io_service &server_io);
52  virtual ~MAVConnTCPClient();
53 
54  void connect(
55  const ReceivedCb &cb_handle_message,
56  const ClosedCb &cb_handle_closed_port = ClosedCb()) override;
57  void close() override;
58 
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;
62 
63  inline bool is_open() override {
64  return socket.is_open();
65  }
66 
67 private:
68  friend class MAVConnTCPServer;
69  boost::asio::io_service io_service;
70  std::unique_ptr<boost::asio::io_service::work> io_work;
71  std::thread io_thread;
72 
73  boost::asio::ip::tcp::socket socket;
74  boost::asio::ip::tcp::endpoint server_ep;
75 
76  std::atomic<bool> is_destroying;
77 
78  std::atomic<bool> tx_in_progress;
79  std::deque<MsgBuffer> tx_q;
80  std::array<uint8_t, MsgBuffer::MAX_SIZE> rx_buf;
81  std::recursive_mutex mutex;
82 
86  void client_connected(size_t server_channel);
87 
88  void do_recv();
89  void do_send(bool check_tx_state);
90 };
91 
98  public std::enable_shared_from_this<MAVConnTCPServer> {
99 public:
100  static constexpr auto DEFAULT_BIND_HOST = "localhost";
101  static constexpr auto DEFAULT_BIND_PORT = 5760;
102 
107  MAVConnTCPServer(uint8_t system_id = 1, uint8_t component_id = MAV_COMP_ID_UDP_BRIDGE,
108  std::string bind_host = DEFAULT_BIND_HOST, unsigned short bind_port = DEFAULT_BIND_PORT);
109  virtual ~MAVConnTCPServer();
110 
111  void connect(
112  const ReceivedCb &cb_handle_message,
113  const ClosedCb &cb_handle_closed_port = ClosedCb()) override;
114  void close() override;
115 
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;
119 
120  mavlink::mavlink_status_t get_status() override;
121  IOStat get_iostat() override;
122  inline bool is_open() override {
123  return acceptor.is_open();
124  }
125 
126 private:
127  boost::asio::io_service io_service;
128  std::unique_ptr<boost::asio::io_service::work> io_work;
129  std::thread io_thread;
130 
131  boost::asio::ip::tcp::acceptor acceptor;
132  boost::asio::ip::tcp::endpoint bind_ep;
133 
134  std::atomic<bool> is_destroying;
135 
136  std::list<std::shared_ptr<MAVConnTCPClient> > client_list;
137  std::recursive_mutex mutex;
138 
139  void do_accept();
140 
141  // client slots
142  void client_closed(std::weak_ptr<MAVConnTCPClient> weak_instp);
143 };
144 } // namespace mavconn
virtual mavlink::mavlink_status_t get_status()
Definition: interface.cpp:56
virtual ~MAVConnTCPClient()
Definition: tcp.cpp:123
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)
Definition: tcp.cpp:77
static constexpr auto DEFAULT_SERVER_HOST
Definition: tcp.h:37
boost::asio::ip::tcp::acceptor acceptor
Definition: tcp.h:131
std::function< void(const mavlink::mavlink_message_t *message, const Framing framing)> ReceivedCb
Definition: interface.h:102
void connect(const ReceivedCb &cb_handle_message, const ClosedCb &cb_handle_closed_port=ClosedCb()) override
Establish connection, automatically called by open_url()
Definition: tcp.cpp:129
static constexpr auto DEFAULT_SERVER_PORT
Definition: tcp.h:38
boost::asio::io_service io_service
Definition: tcp.h:127
TCP server interface.
Definition: tcp.h:97
void close() override
Close connection.
Definition: tcp.cpp:146
std::atomic< bool > tx_in_progress
Definition: tcp.h:78
std::unique_ptr< boost::asio::io_service::work > io_work
Definition: tcp.h:128
static constexpr auto MAV_COMP_ID_UDP_BRIDGE
Same as mavlink::common::MAV_COMPONENT::COMP_ID_UDP_BRIDGE.
Definition: interface.h:45
std::recursive_mutex mutex
Definition: tcp.h:137
boost::asio::ip::tcp::endpoint bind_ep
Definition: tcp.h:132
std::recursive_mutex mutex
Definition: tcp.h:81
Generic mavlink interface.
Definition: interface.h:97
TCP client interface.
Definition: tcp.h:34
void send_message(const mavlink::mavlink_message_t *message) override
Send message (mavlink_message_t)
MAVConn class interface.
void client_connected(size_t server_channel)
Definition: tcp.cpp:114
friend class MAVConnTCPServer
Definition: tcp.h:68
std::function< void(void)> ClosedCb
Definition: interface.h:103
MAVConn message buffer class (internal)
bool is_open() override
Definition: tcp.h:63
virtual IOStat get_iostat()
Definition: interface.cpp:61
std::array< uint8_t, MsgBuffer::MAX_SIZE > rx_buf
Definition: tcp.h:80
std::atomic< bool > is_destroying
Definition: tcp.h:134
void send_bytes(const uint8_t *bytes, size_t length) override
Send raw bytes (for some quirks)
Definition: tcp.cpp:171
std::atomic< bool > is_destroying
Definition: tcp.h:76
bool is_open() override
Definition: tcp.h:122
boost::asio::ip::tcp::socket socket
Definition: tcp.h:73
std::list< std::shared_ptr< MAVConnTCPClient > > client_list
Definition: tcp.h:136
std::unique_ptr< boost::asio::io_service::work > io_work
Definition: tcp.h:70
boost::asio::ip::tcp::endpoint server_ep
Definition: tcp.h:74
std::thread io_thread
Definition: tcp.h:71
std::deque< MsgBuffer > tx_q
Definition: tcp.h:79
boost::asio::io_service io_service
Definition: tcp.h:69
std::thread io_thread
Definition: tcp.h:129
void do_send(bool check_tx_state)
Definition: tcp.cpp:251


libmavconn
Author(s): Vladimir Ermakov
autogenerated on Tue Jun 13 2023 02:17:45