tcp.h
Go to the documentation of this file.
00001 
00009 /*
00010  * libmavconn
00011  * Copyright 2014,2015 Vladimir Ermakov, All rights reserved.
00012  *
00013  * This file is part of the mavros package and subject to the license terms
00014  * in the top-level LICENSE file of the mavros repository.
00015  * https://github.com/mavlink/mavros/tree/master/LICENSE.md
00016  */
00017 
00018 #pragma once
00019 
00020 #include <list>
00021 #include <atomic>
00022 #include <boost/asio.hpp>
00023 #include <mavconn/interface.h>
00024 #include <mavconn/msgbuffer.h>
00025 
00026 namespace mavconn {
00027 
00033 class MAVConnTCPClient : public MAVConnInterface {
00034 public:
00040         MAVConnTCPClient(uint8_t system_id = 1, uint8_t component_id = MAV_COMP_ID_UDP_BRIDGE,
00041                         std::string server_host = "localhost", unsigned short server_port = 5760);
00045         explicit MAVConnTCPClient(uint8_t system_id, uint8_t component_id,
00046                         boost::asio::io_service &server_io);
00047         ~MAVConnTCPClient();
00048 
00049         void close();
00050 
00051         using MAVConnInterface::send_message;
00052         void send_message(const mavlink_message_t *message, uint8_t sysid, uint8_t compid);
00053         void send_bytes(const uint8_t *bytes, size_t length);
00054 
00055         inline bool is_open() { return socket.is_open(); };
00056 
00057 private:
00058         friend class MAVConnTCPServer;
00059         boost::asio::io_service io_service;
00060         std::unique_ptr<boost::asio::io_service::work> io_work;
00061         std::thread io_thread;
00062 
00063         boost::asio::ip::tcp::socket socket;
00064         boost::asio::ip::tcp::endpoint server_ep;
00065 
00066         std::atomic<bool> tx_in_progress;
00067         std::list<MsgBuffer*> tx_q;
00068         uint8_t rx_buf[MsgBuffer::MAX_SIZE];
00069         std::recursive_mutex mutex;
00070 
00074         void client_connected(int server_channel);
00075 
00076         void do_recv();
00077         void async_receive_end(boost::system::error_code, size_t bytes_transferred);
00078         void do_send(bool check_tx_state);
00079         void async_send_end(boost::system::error_code, size_t bytes_transferred);
00080 };
00081 
00087 class MAVConnTCPServer : public MAVConnInterface {
00088 public:
00093         MAVConnTCPServer(uint8_t system_id = 1, uint8_t component_id = MAV_COMP_ID_UDP_BRIDGE,
00094                         std::string bind_host = "localhost", unsigned short bind_port = 5760);
00095         ~MAVConnTCPServer();
00096 
00097         void close();
00098 
00099         using MAVConnInterface::send_message;
00100         void send_message(const mavlink_message_t *message, uint8_t sysid, uint8_t compid);
00101         void send_bytes(const uint8_t *bytes, size_t length);
00102 
00103         mavlink_status_t get_status();
00104         IOStat get_iostat();
00105         inline bool is_open() { return acceptor.is_open(); };
00106 
00107 private:
00108         boost::asio::io_service io_service;
00109         std::unique_ptr<boost::asio::io_service::work> io_work;
00110         std::thread io_thread;
00111 
00112         boost::asio::ip::tcp::acceptor acceptor;
00113         boost::asio::ip::tcp::endpoint bind_ep;
00114 
00115         boost::shared_ptr<MAVConnTCPClient> acceptor_client;
00116         std::list<boost::shared_ptr<MAVConnTCPClient> > client_list;
00117         std::recursive_mutex mutex;
00118 
00119         void do_accept();
00120         void async_accept_end(boost::system::error_code);
00121 
00122         // client slots
00123         void client_closed(boost::weak_ptr<MAVConnTCPClient> weak_instp);
00124         void recv_message(const mavlink_message_t *message, uint8_t sysid, uint8_t compid);
00125 };
00126 
00127 }; // namespace mavconn
00128 


libmavconn
Author(s): Vladimir Ermakov
autogenerated on Thu Feb 9 2017 04:00:13