udp.h
Go to the documentation of this file.
1 
9 /*
10  * libmavconn
11  * Copyright 2013,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 <atomic>
21 #include <boost/asio.hpp>
22 #include <mavconn/interface.h>
23 #include <mavconn/msgbuffer.h>
24 
25 namespace mavconn {
32  public std::enable_shared_from_this<MAVConnUDP> {
33 public:
34  static constexpr auto DEFAULT_BIND_HOST = "localhost";
35  static constexpr auto DEFAULT_BIND_PORT = 14555;
36  static constexpr auto DEFAULT_REMOTE_HOST = "";
37  static constexpr auto DEFAULT_REMOTE_PORT = 14550;
39  static constexpr auto BROADCAST_REMOTE_HOST = "***i want broadcast***";
40  static constexpr auto PERMANENT_BROADCAST_REMOTE_HOST = "***permanent broadcast***";
41 
48  MAVConnUDP(uint8_t system_id = 1, uint8_t component_id = MAV_COMP_ID_UDP_BRIDGE,
49  std::string bind_host = DEFAULT_BIND_HOST, unsigned short bind_port = DEFAULT_BIND_PORT,
50  std::string remote_host = DEFAULT_REMOTE_HOST, unsigned short remote_port = DEFAULT_REMOTE_PORT);
51  virtual ~MAVConnUDP();
52 
53  void close() override;
54 
55  void send_message(const mavlink::mavlink_message_t *message) override;
56  void send_message(const mavlink::Message &message, const uint8_t source_compid) override;
57  void send_bytes(const uint8_t *bytes, size_t length) override;
58 
59  inline bool is_open() override {
60  return socket.is_open();
61  }
62 
63  std::string get_remote_endpoint() const;
64 
65 private:
66  boost::asio::io_service io_service;
67  std::unique_ptr<boost::asio::io_service::work> io_work;
68  std::thread io_thread;
70 
71  std::atomic<bool> remote_exists;
72  boost::asio::ip::udp::socket socket;
73  boost::asio::ip::udp::endpoint remote_ep;
74  boost::asio::ip::udp::endpoint recv_ep;
75  boost::asio::ip::udp::endpoint last_remote_ep;
76  boost::asio::ip::udp::endpoint bind_ep;
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 
83  void do_recvfrom();
84  void do_sendto(bool check_tx_state);
85 };
86 } // namespace mavconn
std::string get_remote_endpoint() const
Definition: udp.cpp:308
boost::asio::ip::udp::endpoint bind_ep
Definition: udp.h:76
static constexpr auto DEFAULT_BIND_HOST
Definition: udp.h:34
MAVConnUDP(uint8_t system_id=1, uint8_t component_id=MAV_COMP_ID_UDP_BRIDGE, std::string bind_host=DEFAULT_BIND_HOST, unsigned short bind_port=DEFAULT_BIND_PORT, std::string remote_host=DEFAULT_REMOTE_HOST, unsigned short remote_port=DEFAULT_REMOTE_PORT)
Definition: udp.cpp:68
void send_bytes(const uint8_t *bytes, size_t length) override
Send raw bytes (for some quirks)
Definition: udp.cpp:161
static constexpr auto DEFAULT_BIND_PORT
Definition: udp.h:35
static constexpr auto MAV_COMP_ID_UDP_BRIDGE
Same as mavlink::common::MAV_COMPONENT::COMP_ID_UDP_BRIDGE.
Definition: interface.h:45
bool permanent_broadcast
Definition: udp.h:69
boost::asio::ip::udp::endpoint remote_ep
Definition: udp.h:73
Generic mavlink interface.
Definition: interface.h:97
MAVConn class interface.
std::deque< MsgBuffer > tx_q
Definition: udp.h:79
std::array< uint8_t, MsgBuffer::MAX_SIZE > rx_buf
Definition: udp.h:80
static constexpr auto BROADCAST_REMOTE_HOST
Markers for broadcast modes. Not valid domain names.
Definition: udp.h:39
MAVConn message buffer class (internal)
static constexpr auto DEFAULT_REMOTE_PORT
Definition: udp.h:37
void close() override
Close connection.
Definition: udp.cpp:140
boost::asio::ip::udp::endpoint last_remote_ep
Definition: udp.h:75
bool is_open() override
Definition: udp.h:59
static constexpr auto PERMANENT_BROADCAST_REMOTE_HOST
Definition: udp.h:40
UDP interface.
Definition: udp.h:31
boost::asio::ip::udp::socket socket
Definition: udp.h:72
std::atomic< bool > remote_exists
Definition: udp.h:71
std::atomic< bool > tx_in_progress
Definition: udp.h:78
void do_sendto(bool check_tx_state)
Definition: udp.cpp:260
std::thread io_thread
Definition: udp.h:68
std::unique_ptr< boost::asio::io_service::work > io_work
Definition: udp.h:67
boost::asio::io_service io_service
Definition: udp.h:66
virtual ~MAVConnUDP()
Definition: udp.cpp:135
void send_message(const mavlink::mavlink_message_t *message) override
Send message (mavlink_message_t)
boost::asio::ip::udp::endpoint recv_ep
Definition: udp.h:74
static constexpr auto DEFAULT_REMOTE_HOST
Definition: udp.h:36
std::recursive_mutex mutex
Definition: udp.h:81
void do_recvfrom()
Definition: udp.cpp:236


libmavconn
Author(s): Vladimir Ermakov
autogenerated on Tue Jun 1 2021 02:36:21