interface.h
Go to the documentation of this file.
1 
13 /*
14  * libmavconn
15  * Copyright 2013,2014,2015,2016 Vladimir Ermakov, All rights reserved.
16  *
17  * This file is part of the mavros package and subject to the license terms
18  * in the top-level LICENSE file of the mavros repository.
19  * https://github.com/mavlink/mavros/tree/master/LICENSE.md
20  */
21 
22 #pragma once
23 
24 #include <boost/system/system_error.hpp>
25 
26 #include <deque>
27 #include <mutex>
28 #include <vector>
29 #include <atomic>
30 #include <chrono>
31 #include <thread>
32 #include <memory>
33 #include <sstream>
34 #include <cassert>
35 #include <stdexcept>
36 #include <unordered_map>
37 #include <mavconn/mavlink_dialect.h>
38 
39 
40 namespace mavconn {
42 using lock_guard = std::lock_guard<std::recursive_mutex>;
43 
45 static constexpr auto MAV_COMP_ID_UDP_BRIDGE = 240;
46 
48 enum class Framing : uint8_t {
49  incomplete = mavlink::MAVLINK_FRAMING_INCOMPLETE,
50  ok = mavlink::MAVLINK_FRAMING_OK,
51  bad_crc = mavlink::MAVLINK_FRAMING_BAD_CRC,
52  bad_signature = mavlink::MAVLINK_FRAMING_BAD_SIGNATURE,
53 };
54 
56 enum class Protocol : uint8_t {
57  V10 = 1,
58  V20 = 2
59 };
60 
64 class DeviceError : public std::runtime_error {
65 public:
69  template <typename T>
70  DeviceError(const char *module, T msg) :
71  std::runtime_error(make_message(module, msg))
72  { }
73 
74  template <typename T>
75  static std::string make_message(const char *module, T msg) {
76  std::ostringstream ss;
77  ss << "DeviceError:" << module << ":" << msg_to_string(msg);
78  return ss.str();
79  }
80 
81  static std::string msg_to_string(const char *description) {
82  return description;
83  }
84 
85  static std::string msg_to_string(int errnum) {
86  return ::strerror(errnum);
87  }
88 
89  static std::string msg_to_string(boost::system::system_error &err) {
90  return err.what();
91  }
92 };
93 
98 private:
99  MAVConnInterface(const MAVConnInterface&) = delete;
100 
101 public:
102  using ReceivedCb = std::function<void (const mavlink::mavlink_message_t *message, const Framing framing)>;
103  using ClosedCb = std::function<void (void)>;
104  using Ptr = std::shared_ptr<MAVConnInterface>;
105  using ConstPtr = std::shared_ptr<MAVConnInterface const>;
106  using WeakPtr = std::weak_ptr<MAVConnInterface>;
107 
108  struct IOStat {
109  size_t tx_total_bytes;
110  size_t rx_total_bytes;
111  float tx_speed;
112  float rx_speed;
113  };
114 
119  MAVConnInterface(uint8_t system_id = 1, uint8_t component_id = MAV_COMP_ID_UDP_BRIDGE);
120 
124  virtual void close() = 0;
125 
136  virtual void send_message(const mavlink::mavlink_message_t *message) = 0;
137 
147  virtual void send_message(const mavlink::Message &message) {
148  send_message(message, this->comp_id);
149  }
150 
162  virtual void send_message(const mavlink::Message &message, const uint8_t src_compid) = 0;
163 
168  virtual void send_bytes(const uint8_t *bytes, size_t length) = 0;
169 
173  void send_message_ignore_drop(const mavlink::mavlink_message_t *message);
174 
181  send_message_ignore_drop(message, this->comp_id);
182  }
183 
190  void send_message_ignore_drop(const mavlink::Message &message, const uint8_t src_compid);
191 
196 
197  virtual mavlink::mavlink_status_t get_status();
198  virtual IOStat get_iostat();
199  virtual bool is_open() = 0;
200 
201  inline uint8_t get_system_id() {
202  return sys_id;
203  }
204  inline void set_system_id(uint8_t sysid) {
205  sys_id = sysid;
206  }
207  inline uint8_t get_component_id() {
208  return comp_id;
209  }
210  inline void set_component_id(uint8_t compid) {
211  comp_id = compid;
212  }
213 
217  void set_protocol_version(Protocol pver);
218  Protocol get_protocol_version();
219 
237  static Ptr open_url(std::string url,
238  uint8_t system_id = 1, uint8_t component_id = MAV_COMP_ID_UDP_BRIDGE);
239 
240  static std::vector<std::string> get_known_dialects();
241 
242 protected:
243  uint8_t sys_id;
244  uint8_t comp_id;
245 
247  static constexpr size_t MAX_PACKET_SIZE = MAVLINK_MAX_PACKET_LEN + 16;
249  static constexpr size_t MAX_TXQ_SIZE = 1000;
250 
252  static std::unordered_map<mavlink::msgid_t, const mavlink::mavlink_msg_entry_t*> message_entries;
253 
255  size_t conn_id;
256 
257  inline mavlink::mavlink_status_t *get_status_p() {
258  return &m_parse_status;
259  }
260 
261  inline mavlink::mavlink_message_t *get_buffer_p() {
262  return &m_buffer;
263  }
264 
268  void parse_buffer(const char *pfx, uint8_t *buf, const size_t bufsize, size_t bytes_received);
269 
270  void iostat_tx_add(size_t bytes);
271  void iostat_rx_add(size_t bytes);
272 
273  void log_recv(const char *pfx, mavlink::mavlink_message_t &msg, Framing framing);
274  void log_send(const char *pfx, const mavlink::mavlink_message_t *msg);
275  void log_send_obj(const char *pfx, const mavlink::Message &msg);
276 
277 private:
278  friend const mavlink::mavlink_msg_entry_t* mavlink::mavlink_get_msg_entry(uint32_t msgid);
279 
280  mavlink::mavlink_status_t m_parse_status;
281  mavlink::mavlink_message_t m_buffer;
282  mavlink::mavlink_status_t m_mavlink_status;
283 
284  std::atomic<size_t> tx_total_bytes, rx_total_bytes;
285  std::recursive_mutex iostat_mutex;
286  size_t last_tx_total_bytes, last_rx_total_bytes;
287  std::chrono::time_point<steady_clock> last_iostat;
288 
290  static std::atomic<size_t> conn_id_counter;
291 
293  static std::once_flag init_flag;
294 
300  static void init_msg_entry();
301 };
302 } // namespace mavconn
mavlink::mavlink_status_t m_mavlink_status
Definition: interface.h:282
float rx_speed
current receive speed [B/s]
Definition: interface.h:112
std::chrono::steady_clock steady_clock
Definition: interface.h:41
std::shared_ptr< MAVConnInterface const > ConstPtr
Definition: interface.h:105
ClosedCb port_closed_cb
Port closed notification callback.
Definition: interface.h:195
std::lock_guard< std::recursive_mutex > lock_guard
Definition: interface.h:42
static std::once_flag init_flag
init_msg_entry() once flag
Definition: interface.h:293
std::function< void(const mavlink::mavlink_message_t *message, const Framing framing)> ReceivedCb
Definition: interface.h:102
static std::string msg_to_string(const char *description)
Definition: interface.h:81
mavlink::mavlink_message_t * get_buffer_p()
Definition: interface.h:261
Common exception for communication error.
Definition: interface.h:64
DeviceError(const char *module, T msg)
Definition: interface.h:70
static constexpr auto MAV_COMP_ID_UDP_BRIDGE
Same as mavlink::common::MAV_COMPONENT::COMP_ID_UDP_BRIDGE.
Definition: interface.h:45
ReceivedCb message_received_cb
Message receive callback.
Definition: interface.h:193
void send_message_ignore_drop(const mavlink::Message &message)
Send message and ignore possible drop due to Tx queue limit.
Definition: interface.h:180
std::chrono::time_point< steady_clock > last_iostat
Definition: interface.h:287
static std::string msg_to_string(int errnum)
Definition: interface.h:85
Generic mavlink interface.
Definition: interface.h:97
float tx_speed
current transfer speed [B/s]
Definition: interface.h:111
uint8_t comp_id
Connection Component Id.
Definition: interface.h:244
static std::string make_message(const char *module, T msg)
Definition: interface.h:75
mavlink::mavlink_status_t * get_status_p()
Definition: interface.h:257
static std::unordered_map< mavlink::msgid_t, const mavlink::mavlink_msg_entry_t * > message_entries
This map merge all dialect mavlink_msg_entry_t structs. Needed for packet parser. ...
Definition: interface.h:252
std::function< void(void)> ClosedCb
Definition: interface.h:103
size_t conn_id
Channel number used for logging.
Definition: interface.h:255
std::weak_ptr< MAVConnInterface > WeakPtr
Definition: interface.h:106
mavlink::mavlink_message_t m_buffer
Definition: interface.h:281
size_t rx_total_bytes
total bytes received
Definition: interface.h:110
size_t tx_total_bytes
total bytes transferred
Definition: interface.h:109
virtual void send_message(const mavlink::Message &message)
Send message (child of mavlink::Message)
Definition: interface.h:147
static std::atomic< size_t > conn_id_counter
monotonic counter (increment only)
Definition: interface.h:290
mavlink::mavlink_status_t m_parse_status
Definition: interface.h:280
void set_system_id(uint8_t sysid)
Definition: interface.h:204
Protocol
MAVLink protocol version.
Definition: interface.h:56
static std::string msg_to_string(boost::system::system_error &err)
Definition: interface.h:89
uint8_t sys_id
Connection System Id.
Definition: interface.h:243
std::recursive_mutex iostat_mutex
Definition: interface.h:285
std::atomic< size_t > tx_total_bytes
Definition: interface.h:284
void set_component_id(uint8_t compid)
Definition: interface.h:210
Framing
Rx packer framing status. (same as mavlink::mavlink_framing_t)
Definition: interface.h:48
std::shared_ptr< MAVConnInterface > Ptr
Definition: interface.h:104


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