Go to the documentation of this file.00001 
00009 
00010 
00011 
00012 
00013 
00014 
00015 
00016 
00017 
00018 
00019 
00020 
00021 
00022 
00023 
00024 
00025 
00026 
00027 #pragma once
00028 
00029 #include <list>
00030 #include <atomic>
00031 #include <boost/asio.hpp>
00032 #include <mavconn/interface.h>
00033 #include <mavconn/msgbuffer.h>
00034 
00035 namespace mavconn {
00036 
00042 class MAVConnTCPClient : public MAVConnInterface {
00043 public:
00049         MAVConnTCPClient(uint8_t system_id = 1, uint8_t component_id = MAV_COMP_ID_UDP_BRIDGE,
00050                         std::string server_host = "localhost", unsigned short server_port = 5760);
00054         explicit MAVConnTCPClient(uint8_t system_id, uint8_t component_id,
00055                         boost::asio::io_service &server_io);
00056         ~MAVConnTCPClient();
00057 
00058         void close();
00059 
00060         using MAVConnInterface::send_message;
00061         void send_message(const mavlink_message_t *message, uint8_t sysid, uint8_t compid);
00062         void send_bytes(const uint8_t *bytes, size_t length);
00063 
00064         inline mavlink_status_t get_status() { return *mavlink_get_channel_status(channel); };
00065         inline bool is_open() { return socket.is_open(); };
00066 
00067 private:
00068         friend class MAVConnTCPServer;
00069         boost::asio::io_service io_service;
00070         std::unique_ptr<boost::asio::io_service::work> io_work;
00071         std::thread io_thread;
00072 
00073         boost::asio::ip::tcp::socket socket;
00074         boost::asio::ip::tcp::endpoint server_ep;
00075 
00076         std::atomic<bool> tx_in_progress;
00077         std::list<MsgBuffer*> tx_q;
00078         uint8_t rx_buf[MsgBuffer::MAX_SIZE];
00079         std::recursive_mutex mutex;
00080 
00084         void client_connected(int server_channel);
00085 
00086         void do_recv();
00087         void async_receive_end(boost::system::error_code, size_t bytes_transferred);
00088         void do_send(bool check_tx_state);
00089         void async_send_end(boost::system::error_code, size_t bytes_transferred);
00090 };
00091 
00097 class MAVConnTCPServer : public MAVConnInterface {
00098 public:
00103         MAVConnTCPServer(uint8_t system_id = 1, uint8_t component_id = MAV_COMP_ID_UDP_BRIDGE,
00104                         std::string bind_host = "localhost", unsigned short bind_port = 5760);
00105         ~MAVConnTCPServer();
00106 
00107         void close();
00108 
00109         using MAVConnInterface::send_message;
00110         void send_message(const mavlink_message_t *message, uint8_t sysid, uint8_t compid);
00111         void send_bytes(const uint8_t *bytes, size_t length);
00112 
00113         inline mavlink_status_t get_status() { return *mavlink_get_channel_status(channel); };
00114         inline bool is_open() { return acceptor.is_open(); };
00115 
00116 private:
00117         boost::asio::io_service io_service;
00118         std::unique_ptr<boost::asio::io_service::work> io_work;
00119         std::thread io_thread;
00120 
00121         boost::asio::ip::tcp::acceptor acceptor;
00122         boost::asio::ip::tcp::endpoint bind_ep;
00123 
00124         boost::shared_ptr<MAVConnTCPClient> acceptor_client;
00125         std::list<boost::shared_ptr<MAVConnTCPClient> > client_list;
00126         std::recursive_mutex mutex;
00127 
00128         void do_accept();
00129         void async_accept_end(boost::system::error_code);
00130 
00131         
00132         void client_closed(boost::weak_ptr<MAVConnTCPClient> weak_instp);
00133         void recv_message(const mavlink_message_t *message, uint8_t sysid, uint8_t compid);
00134 };
00135 
00136 }; 
00137