Program Listing for File tcp.hpp
↰ Return to documentation for file (include/mavconn/tcp.hpp
)
//
// libmavconn
// Copyright 2014,2015,2016,2021 Vladimir Ermakov, All rights reserved.
//
// This file is part of the mavros package and subject to the license terms
// in the top-level LICENSE file of the mavros repository.
// https://github.com/mavlink/mavros/tree/master/LICENSE.md
//
#pragma once
#ifndef MAVCONN__TCP_HPP_
#define MAVCONN__TCP_HPP_
#include <atomic>
#include <cstring>
#include <deque>
#include <list>
#include <memory>
#include <string>
#include <asio.hpp>
#include <mavconn/interface.hpp>
#include <mavconn/msgbuffer.hpp>
namespace mavconn
{
class MAVConnTCPClient : public MAVConnInterface,
public std::enable_shared_from_this<MAVConnTCPClient>
{
public:
static constexpr auto DEFAULT_SERVER_HOST = "localhost";
static constexpr auto DEFAULT_SERVER_PORT = 5760;
MAVConnTCPClient(
uint8_t system_id = 1, uint8_t component_id = MAV_COMP_ID_UDP_BRIDGE,
std::string server_host = DEFAULT_SERVER_HOST,
uint16_t server_port = DEFAULT_SERVER_PORT);
explicit MAVConnTCPClient(
uint8_t system_id, uint8_t component_id,
asio::io_service & server_io);
virtual ~MAVConnTCPClient();
void connect(
const ReceivedCb & cb_handle_message,
const ClosedCb & cb_handle_closed_port = ClosedCb()) override;
void close() override;
void send_message(const mavlink::mavlink_message_t * message) override;
void send_message(const mavlink::Message & message, const uint8_t source_compid) override;
void send_bytes(const uint8_t * bytes, size_t length) override;
inline bool is_open() override
{
return socket.is_open();
}
private:
friend class MAVConnTCPServer;
asio::io_service io_service;
std::unique_ptr<asio::io_service::work> io_work;
std::thread io_thread;
std::atomic<bool> is_running;
asio::ip::tcp::socket socket;
asio::ip::tcp::endpoint server_ep;
std::atomic<bool> is_destroying;
std::atomic<bool> tx_in_progress;
std::deque<MsgBuffer> tx_q;
std::array<uint8_t, MsgBuffer::MAX_SIZE> rx_buf;
std::recursive_mutex mutex;
void client_connected(size_t server_channel);
void do_recv();
void do_send(bool check_tx_state);
void stop();
};
class MAVConnTCPServer : public MAVConnInterface,
public std::enable_shared_from_this<MAVConnTCPServer>
{
public:
static constexpr auto DEFAULT_BIND_HOST = "localhost";
static constexpr auto DEFAULT_BIND_PORT = 5760;
MAVConnTCPServer(
uint8_t system_id = 1, uint8_t component_id = MAV_COMP_ID_UDP_BRIDGE,
std::string bind_host = DEFAULT_BIND_HOST, uint16_t bind_port = DEFAULT_BIND_PORT);
virtual ~MAVConnTCPServer();
void connect(
const ReceivedCb & cb_handle_message,
const ClosedCb & cb_handle_closed_port = ClosedCb()) override;
void close() override;
void send_message(const mavlink::mavlink_message_t * message) override;
void send_message(const mavlink::Message & message, const uint8_t source_compid) override;
void send_bytes(const uint8_t * bytes, size_t length) override;
mavlink::mavlink_status_t get_status() override;
IOStat get_iostat() override;
inline bool is_open() override
{
return acceptor.is_open();
}
private:
asio::io_service io_service;
std::unique_ptr<asio::io_service::work> io_work;
std::thread io_thread;
asio::ip::tcp::acceptor acceptor;
asio::ip::tcp::endpoint bind_ep;
std::atomic<bool> is_destroying;
std::list<std::shared_ptr<MAVConnTCPClient>> client_list;
std::recursive_mutex mutex;
void do_accept();
// client slots
void client_closed(std::weak_ptr<MAVConnTCPClient> weak_instp);
};
} // namespace mavconn
#endif // MAVCONN__TCP_HPP_