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 connect(
54  const ReceivedCb &cb_handle_message,
55  const ClosedCb &cb_handle_closed_port = ClosedCb()) override;
56  void close() override;
57 
58  void send_message(const mavlink::mavlink_message_t *message) override;
59  void send_message(const mavlink::Message &message, const uint8_t source_compid) override;
60  void send_bytes(const uint8_t *bytes, size_t length) override;
61 
62  inline bool is_open() override {
63  return socket.is_open();
64  }
65 
66  std::string get_remote_endpoint() const;
67 
68 private:
69  boost::asio::io_service io_service;
70  std::unique_ptr<boost::asio::io_service::work> io_work;
71  std::thread io_thread;
73 
74  std::atomic<bool> remote_exists;
75  boost::asio::ip::udp::socket socket;
76  boost::asio::ip::udp::endpoint remote_ep;
77  boost::asio::ip::udp::endpoint recv_ep;
78  boost::asio::ip::udp::endpoint last_remote_ep;
79  boost::asio::ip::udp::endpoint bind_ep;
80 
81  std::atomic<bool> tx_in_progress;
82  std::deque<MsgBuffer> tx_q;
83  std::array<uint8_t, MsgBuffer::MAX_SIZE> rx_buf;
84  std::recursive_mutex mutex;
85 
86  void do_recvfrom();
87  void do_sendto(bool check_tx_state);
88 };
89 } // namespace mavconn
std::function< void(const mavlink::mavlink_message_t *message, const Framing framing)> ReceivedCb
Definition: interface.h:102
boost::asio::ip::udp::endpoint bind_ep
Definition: udp.h:79
static constexpr auto DEFAULT_BIND_HOST
Definition: udp.h:34
void connect(const ReceivedCb &cb_handle_message, const ClosedCb &cb_handle_closed_port=ClosedCb()) override
Establish connection, automatically called by open_url()
Definition: udp.cpp:129
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:167
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:72
boost::asio::ip::udp::endpoint remote_ep
Definition: udp.h:76
std::string get_remote_endpoint() const
Definition: udp.cpp:314
Generic mavlink interface.
Definition: interface.h:97
MAVConn class interface.
std::deque< MsgBuffer > tx_q
Definition: udp.h:82
std::array< uint8_t, MsgBuffer::MAX_SIZE > rx_buf
Definition: udp.h:83
std::function< void(void)> ClosedCb
Definition: interface.h:103
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:146
boost::asio::ip::udp::endpoint last_remote_ep
Definition: udp.h:78
bool is_open() override
Definition: udp.h:62
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:75
std::atomic< bool > remote_exists
Definition: udp.h:74
std::atomic< bool > tx_in_progress
Definition: udp.h:81
void do_sendto(bool check_tx_state)
Definition: udp.cpp:266
std::thread io_thread
Definition: udp.h:71
std::unique_ptr< boost::asio::io_service::work > io_work
Definition: udp.h:70
boost::asio::io_service io_service
Definition: udp.h:69
virtual ~MAVConnUDP()
Definition: udp.cpp:124
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:77
static constexpr auto DEFAULT_REMOTE_HOST
Definition: udp.h:36
std::recursive_mutex mutex
Definition: udp.h:84
void do_recvfrom()
Definition: udp.cpp:242


libmavconn
Author(s): Vladimir Ermakov
autogenerated on Tue Jun 13 2023 02:17:45