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);
53 
54  void close() override;
55 
56  void send_message(const mavlink::mavlink_message_t *message) override;
57  void send_message(const mavlink::Message &message, const uint8_t source_compid) override;
58  void send_bytes(const uint8_t *bytes, size_t length) override;
59 
60  inline bool is_open() override {
61  return socket.is_open();
62  }
63 
64 private:
65  friend class MAVConnTCPServer;
66  boost::asio::io_service io_service;
67  std::unique_ptr<boost::asio::io_service::work> io_work;
68  std::thread io_thread;
69 
70  boost::asio::ip::tcp::socket socket;
71  boost::asio::ip::tcp::endpoint server_ep;
72 
73  std::atomic<bool> is_destroying;
74 
75  std::atomic<bool> tx_in_progress;
76  std::deque<MsgBuffer> tx_q;
77  std::array<uint8_t, MsgBuffer::MAX_SIZE> rx_buf;
78  std::recursive_mutex mutex;
79 
83  void client_connected(size_t server_channel);
84 
85  void do_recv();
86  void do_send(bool check_tx_state);
87 };
88 
95  public std::enable_shared_from_this<MAVConnTCPServer> {
96 public:
97  static constexpr auto DEFAULT_BIND_HOST = "localhost";
98  static constexpr auto DEFAULT_BIND_PORT = 5760;
99 
104  MAVConnTCPServer(uint8_t system_id = 1, uint8_t component_id = MAV_COMP_ID_UDP_BRIDGE,
105  std::string bind_host = DEFAULT_BIND_HOST, unsigned short bind_port = DEFAULT_BIND_PORT);
106  ~MAVConnTCPServer();
107 
108  void close() override;
109 
110  void send_message(const mavlink::mavlink_message_t *message) override;
111  void send_message(const mavlink::Message &message, const uint8_t source_compid) override;
112  void send_bytes(const uint8_t *bytes, size_t length) override;
113 
114  mavlink::mavlink_status_t get_status() override;
115  IOStat get_iostat() override;
116  inline bool is_open() override {
117  return acceptor.is_open();
118  }
119 
120 private:
121  boost::asio::io_service io_service;
122  std::unique_ptr<boost::asio::io_service::work> io_work;
123  std::thread io_thread;
124 
125  boost::asio::ip::tcp::acceptor acceptor;
126  boost::asio::ip::tcp::endpoint bind_ep;
127 
128  std::atomic<bool> is_destroying;
129 
130  std::list<std::shared_ptr<MAVConnTCPClient> > client_list;
131  std::recursive_mutex mutex;
132 
133  void do_accept();
134 
135  // client slots
136  void client_closed(std::weak_ptr<MAVConnTCPClient> weak_instp);
137  void recv_message(const mavlink::mavlink_message_t *message, const Framing framing);
138 };
139 } // namespace mavconn
virtual mavlink::mavlink_status_t get_status()
Definition: interface.cpp:55
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:70
static constexpr auto DEFAULT_SERVER_HOST
Definition: tcp.h:37
boost::asio::ip::tcp::acceptor acceptor
Definition: tcp.h:125
static constexpr auto DEFAULT_SERVER_PORT
Definition: tcp.h:38
boost::asio::io_service io_service
Definition: tcp.h:121
TCP server interface.
Definition: tcp.h:94
void close() override
Close connection.
Definition: tcp.cpp:132
std::atomic< bool > tx_in_progress
Definition: tcp.h:75
std::unique_ptr< boost::asio::io_service::work > io_work
Definition: tcp.h:122
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:131
boost::asio::ip::tcp::endpoint bind_ep
Definition: tcp.h:126
std::recursive_mutex mutex
Definition: tcp.h:78
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:117
friend class MAVConnTCPServer
Definition: tcp.h:65
MAVConn message buffer class (internal)
bool is_open() override
Definition: tcp.h:60
virtual IOStat get_iostat()
Definition: interface.cpp:60
std::array< uint8_t, MsgBuffer::MAX_SIZE > rx_buf
Definition: tcp.h:77
std::atomic< bool > is_destroying
Definition: tcp.h:128
void send_bytes(const uint8_t *bytes, size_t length) override
Send raw bytes (for some quirks)
Definition: tcp.cpp:154
std::atomic< bool > is_destroying
Definition: tcp.h:73
bool is_open() override
Definition: tcp.h:116
boost::asio::ip::tcp::socket socket
Definition: tcp.h:70
std::list< std::shared_ptr< MAVConnTCPClient > > client_list
Definition: tcp.h:130
std::unique_ptr< boost::asio::io_service::work > io_work
Definition: tcp.h:67
boost::asio::ip::tcp::endpoint server_ep
Definition: tcp.h:71
std::thread io_thread
Definition: tcp.h:68
std::deque< MsgBuffer > tx_q
Definition: tcp.h:76
boost::asio::io_service io_service
Definition: tcp.h:66
std::thread io_thread
Definition: tcp.h:123
Framing
Rx packer framing status. (same as mavlink::mavlink_framing_t)
Definition: interface.h:48
void do_send(bool check_tx_state)
Definition: tcp.cpp:234


libmavconn
Author(s): Vladimir Ermakov
autogenerated on Mon Jul 8 2019 03:20:07