interface.cpp
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 #include <set>
19 #include <cassert>
20 
22 #include <mavconn/interface.h>
23 #include <mavconn/msgbuffer.h>
24 #include <mavconn/serial.h>
25 #include <mavconn/udp.h>
26 #include <mavconn/tcp.h>
27 
28 namespace mavconn {
29 #define PFX "mavconn: "
30 
31 using mavlink::mavlink_message_t;
32 using mavlink::mavlink_status_t;
33 
34 // static members
35 std::once_flag MAVConnInterface::init_flag;
36 std::unordered_map<mavlink::msgid_t, const mavlink::mavlink_msg_entry_t*> MAVConnInterface::message_entries {};
37 std::atomic<size_t> MAVConnInterface::conn_id_counter {0};
38 
39 
40 MAVConnInterface::MAVConnInterface(uint8_t system_id, uint8_t component_id) :
41  sys_id(system_id),
42  comp_id(component_id),
43  m_parse_status {},
44  m_buffer {},
46  tx_total_bytes(0),
47  rx_total_bytes(0),
50  last_iostat(steady_clock::now())
51 {
52  conn_id = conn_id_counter.fetch_add(1);
53  std::call_once(init_flag, init_msg_entry);
54 }
55 
57 {
58  return m_mavlink_status;
59 }
60 
62 {
63  std::lock_guard<std::recursive_mutex> lock(iostat_mutex);
64  IOStat stat;
65 
68 
69  auto d_tx = stat.tx_total_bytes - last_tx_total_bytes;
70  auto d_rx = stat.rx_total_bytes - last_rx_total_bytes;
73 
74  auto now = steady_clock::now();
75  auto dt = now - last_iostat;
76  last_iostat = now;
77 
78  float dt_s = std::chrono::duration_cast<std::chrono::seconds>(dt).count();
79 
80  stat.tx_speed = d_tx / dt_s;
81  stat.rx_speed = d_rx / dt_s;
82 
83  return stat;
84 }
85 
87 {
88  tx_total_bytes += bytes;
89 }
90 
92 {
93  rx_total_bytes += bytes;
94 }
95 
96 void MAVConnInterface::parse_buffer(const char *pfx, uint8_t *buf, const size_t bufsize, size_t bytes_received)
97 {
98  mavlink::mavlink_message_t message;
99 
100  assert(bufsize >= bytes_received);
101 
102  iostat_rx_add(bytes_received);
103  for (; bytes_received > 0; bytes_received--) {
104  auto c = *buf++;
105 
106  auto msg_received = static_cast<Framing>(mavlink::mavlink_frame_char_buffer(&m_buffer, &m_parse_status, c, &message, &m_mavlink_status));
107 
108  if (msg_received != Framing::incomplete) {
109  log_recv(pfx, message, msg_received);
110 
112  message_received_cb(&message, msg_received);
113  }
114  }
115 }
116 
117 void MAVConnInterface::log_recv(const char *pfx, mavlink_message_t &msg, Framing framing)
118 {
119  const char *framing_str = (framing == Framing::ok) ? "OK" :
120  (framing == Framing::bad_crc) ? "!CRC" :
121  (framing == Framing::bad_signature) ? "!SIG" : "ERR";
122 
123  const char *proto_version_str = (msg.magic == MAVLINK_STX) ? "v2.0" : "v1.0";
124 
125  CONSOLE_BRIDGE_logDebug("%s%zu: recv: %s %4s Message-Id: %u [%u bytes] IDs: %u.%u Seq: %u",
126  pfx, conn_id,
127  proto_version_str,
128  framing_str,
129  msg.msgid, msg.len, msg.sysid, msg.compid, msg.seq);
130 }
131 
132 void MAVConnInterface::log_send(const char *pfx, const mavlink_message_t *msg)
133 {
134  const char *proto_version_str = (msg->magic == MAVLINK_STX) ? "v2.0" : "v1.0";
135 
136  CONSOLE_BRIDGE_logDebug("%s%zu: send: %s Message-Id: %u [%u bytes] IDs: %u.%u Seq: %u",
137  pfx, conn_id,
138  proto_version_str,
139  msg->msgid, msg->len, msg->sysid, msg->compid, msg->seq);
140 }
141 
142 void MAVConnInterface::log_send_obj(const char *pfx, const mavlink::Message &msg)
143 {
144  CONSOLE_BRIDGE_logDebug("%s%zu: send: %s", pfx, conn_id, msg.to_yaml().c_str());
145 }
146 
147 void MAVConnInterface::send_message_ignore_drop(const mavlink::mavlink_message_t *msg)
148 {
149  try {
150  send_message(msg);
151  }
152  catch (std::length_error &e) {
153  CONSOLE_BRIDGE_logError(PFX "%zu: DROPPED Message-Id %u [%u bytes] IDs: %u.%u Seq: %u: %s",
154  conn_id,
155  msg->msgid, msg->len, msg->sysid, msg->compid, msg->seq,
156  e.what());
157  }
158 }
159 
160 void MAVConnInterface::send_message_ignore_drop(const mavlink::Message &msg, uint8_t source_compid)
161 {
162  try {
163  send_message(msg, source_compid);
164  }
165  catch (std::length_error &e) {
166  CONSOLE_BRIDGE_logError(PFX "%zu: DROPPED Message %s: %s",
167  conn_id,
168  msg.get_name().c_str(),
169  e.what());
170  }
171 }
172 
174 {
175  if (pver == Protocol::V10)
177  else
179 }
180 
182 {
184  return Protocol::V10;
185  else
186  return Protocol::V20;
187 }
188 
192 static void url_parse_host(std::string host,
193  std::string &host_out, int &port_out,
194  const std::string def_host, const int def_port)
195 {
196  std::string port;
197 
198  auto sep_it = std::find(host.begin(), host.end(), ':');
199  if (sep_it == host.end()) {
200  // host
201  if (!host.empty()) {
202  host_out = host;
203  port_out = def_port;
204  }
205  else {
206  host_out = def_host;
207  port_out = def_port;
208  }
209  return;
210  }
211 
212  if (sep_it == host.begin()) {
213  // :port
214  host_out = def_host;
215  }
216  else {
217  // host:port
218  host_out.assign(host.begin(), sep_it);
219  }
220 
221  port.assign(sep_it + 1, host.end());
222  port_out = std::stoi(port);
223 }
224 
228 static void url_parse_query(std::string query, uint8_t &sysid, uint8_t &compid)
229 {
230  const std::string ids_end("ids=");
231  std::string sys, comp;
232 
233  if (query.empty())
234  return;
235 
236  auto ids_it = std::search(query.begin(), query.end(),
237  ids_end.begin(), ids_end.end());
238  if (ids_it == query.end()) {
239  CONSOLE_BRIDGE_logWarn(PFX "URL: unknown query arguments");
240  return;
241  }
242 
243  std::advance(ids_it, ids_end.length());
244  auto comma_it = std::find(ids_it, query.end(), ',');
245  if (comma_it == query.end()) {
246  CONSOLE_BRIDGE_logError(PFX "URL: no comma in ids= query");
247  return;
248  }
249 
250  sys.assign(ids_it, comma_it);
251  comp.assign(comma_it + 1, query.end());
252 
253  sysid = std::stoi(sys);
254  compid = std::stoi(comp);
255 
256  CONSOLE_BRIDGE_logDebug(PFX "URL: found system/component id = [%u, %u]", sysid, compid);
257 }
258 
260  std::string path, std::string query,
261  uint8_t system_id, uint8_t component_id, bool hwflow)
262 {
263  std::string file_path;
264  int baudrate;
265 
266  // /dev/ttyACM0:57600
268  url_parse_query(query, system_id, component_id);
269 
270  return std::make_shared<MAVConnSerial>(system_id, component_id,
271  file_path, baudrate, hwflow);
272 }
273 
275  std::string hosts, std::string query,
276  uint8_t system_id, uint8_t component_id, bool is_udpb, bool permanent_broadcast)
277 {
278  std::string bind_pair, remote_pair;
279  std::string bind_host, remote_host;
280  int bind_port, remote_port;
281 
282  auto sep_it = std::find(hosts.begin(), hosts.end(), '@');
283  if (sep_it == hosts.end()) {
284  CONSOLE_BRIDGE_logError(PFX "UDP URL should contain @!");
285  throw DeviceError("url", "UDP separator not found");
286  }
287 
288  bind_pair.assign(hosts.begin(), sep_it);
289  remote_pair.assign(sep_it + 1, hosts.end());
290 
291  // udp://0.0.0.0:14555@:14550
292  url_parse_host(bind_pair, bind_host, bind_port, "0.0.0.0", MAVConnUDP::DEFAULT_BIND_PORT);
293  url_parse_host(remote_pair, remote_host, remote_port, MAVConnUDP::DEFAULT_REMOTE_HOST, MAVConnUDP::DEFAULT_REMOTE_PORT);
294  url_parse_query(query, system_id, component_id);
295 
296  if (is_udpb)
298 
299  return std::make_shared<MAVConnUDP>(system_id, component_id,
300  bind_host, bind_port,
301  remote_host, remote_port);
302 }
303 
305  std::string host, std::string query,
306  uint8_t system_id, uint8_t component_id)
307 {
308  std::string server_host;
309  int server_port;
310 
311  // tcp://localhost:5760
312  url_parse_host(host, server_host, server_port, "localhost", 5760);
313  url_parse_query(query, system_id, component_id);
314 
315  return std::make_shared<MAVConnTCPClient>(system_id, component_id,
316  server_host, server_port);
317 }
318 
320  std::string host, std::string query,
321  uint8_t system_id, uint8_t component_id)
322 {
323  std::string bind_host;
324  int bind_port;
325 
326  // tcp-l://0.0.0.0:5760
327  url_parse_host(host, bind_host, bind_port, "0.0.0.0", 5760);
328  url_parse_query(query, system_id, component_id);
329 
330  return std::make_shared<MAVConnTCPServer>(system_id, component_id,
331  bind_host, bind_port);
332 }
333 
335  uint8_t system_id, uint8_t component_id)
336 {
337  /* Based on code found here:
338  * http://stackoverflow.com/questions/2616011/easy-way-to-parse-a-url-in-c-cross-platform
339  */
340 
341  const std::string proto_end("://");
342  std::string proto;
343  std::string host;
344  std::string path;
345  std::string query;
346 
347  auto proto_it = std::search(
348  url.begin(), url.end(),
349  proto_end.begin(), proto_end.end());
350  if (proto_it == url.end()) {
351  // looks like file path
352  CONSOLE_BRIDGE_logDebug(PFX "URL: %s: looks like file path", url.c_str());
353  return url_parse_serial(url, "", system_id, component_id, false);
354  }
355 
356  // copy protocol
357  proto.reserve(std::distance(url.begin(), proto_it));
358  std::transform(url.begin(), proto_it,
359  std::back_inserter(proto),
360  std::ref(tolower));
361 
362  // copy host
363  std::advance(proto_it, proto_end.length());
364  auto path_it = std::find(proto_it, url.end(), '/');
365  std::transform(proto_it, path_it,
366  std::back_inserter(host),
367  std::ref(tolower));
368 
369  // copy path, and query if exists
370  auto query_it = std::find(path_it, url.end(), '?');
371  path.assign(path_it, query_it);
372  if (query_it != url.end())
373  ++query_it;
374  query.assign(query_it, url.end());
375 
376  CONSOLE_BRIDGE_logDebug(PFX "URL: %s: proto: %s, host: %s, path: %s, query: %s",
377  url.c_str(), proto.c_str(), host.c_str(),
378  path.c_str(), query.c_str());
379 
380  if (proto == "udp")
381  return url_parse_udp(host, query, system_id, component_id, false, false);
382  else if (proto == "udp-b")
383  return url_parse_udp(host, query, system_id, component_id, true, false);
384  else if (proto == "udp-pb")
385  return url_parse_udp(host, query, system_id, component_id, true, true);
386  else if (proto == "tcp")
387  return url_parse_tcp_client(host, query, system_id, component_id);
388  else if (proto == "tcp-l")
389  return url_parse_tcp_server(host, query, system_id, component_id);
390  else if (proto == "serial")
391  return url_parse_serial(path, query, system_id, component_id, false);
392  else if (proto == "serial-hwfc")
393  return url_parse_serial(path, query, system_id, component_id, true);
394  else
395  throw DeviceError("url", "Unknown URL type");
396 }
397 } // namespace mavconn
virtual void send_message(const mavlink::mavlink_message_t *message)=0
Send message (mavlink_message_t)
mavlink::mavlink_status_t m_mavlink_status
Definition: interface.h:282
virtual mavlink::mavlink_status_t get_status()
Definition: interface.cpp:56
float rx_speed
current receive speed [B/s]
Definition: interface.h:112
void log_send(const char *pfx, const mavlink::mavlink_message_t *msg)
Definition: interface.cpp:132
void parse_buffer(const char *pfx, uint8_t *buf, const size_t bufsize, size_t bytes_received)
Definition: interface.cpp:96
static void init_msg_entry()
static std::once_flag init_flag
init_msg_entry() once flag
Definition: interface.h:293
#define CONSOLE_BRIDGE_logWarn(fmt,...)
void send_message_ignore_drop(const mavlink::mavlink_message_t *message)
Send message and ignore possible drop due to Tx queue limit.
Definition: interface.cpp:147
Common exception for communication error.
Definition: interface.h:64
static MAVConnInterface::Ptr url_parse_tcp_client(std::string host, std::string query, uint8_t system_id, uint8_t component_id)
Definition: interface.cpp:304
static constexpr auto DEFAULT_BIND_PORT
Definition: udp.h:35
#define CONSOLE_BRIDGE_logDebug(fmt,...)
void log_send_obj(const char *pfx, const mavlink::Message &msg)
Definition: interface.cpp:142
ReceivedCb message_received_cb
Message receive callback.
Definition: interface.h:193
std::chrono::time_point< steady_clock > last_iostat
Definition: interface.h:287
float tx_speed
current transfer speed [B/s]
Definition: interface.h:111
static MAVConnInterface::Ptr url_parse_serial(std::string path, std::string query, uint8_t system_id, uint8_t component_id, bool hwflow)
Definition: interface.cpp:259
MAVConn class interface.
static void url_parse_host(std::string host, std::string &host_out, int &port_out, const std::string def_host, const int def_port)
Definition: interface.cpp:192
void iostat_tx_add(size_t bytes)
Definition: interface.cpp:86
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
size_t conn_id
Channel number used for logging.
Definition: interface.h:255
#define CONSOLE_BRIDGE_logError(fmt,...)
static constexpr auto BROADCAST_REMOTE_HOST
Markers for broadcast modes. Not valid domain names.
Definition: udp.h:39
MAVConn message buffer class (internal)
MAVConn Serial link class.
static constexpr auto DEFAULT_DEVICE
Definition: serial.h:32
static constexpr auto DEFAULT_REMOTE_PORT
Definition: udp.h:37
static MAVConnInterface::Ptr url_parse_udp(std::string hosts, std::string query, uint8_t system_id, uint8_t component_id, bool is_udpb, bool permanent_broadcast)
Definition: interface.cpp:274
virtual IOStat get_iostat()
Definition: interface.cpp:61
MAVConnInterface(const MAVConnInterface &)=delete
mavlink::mavlink_message_t m_buffer
Definition: interface.h:281
std::atomic< size_t > rx_total_bytes
Definition: interface.h:284
size_t rx_total_bytes
total bytes received
Definition: interface.h:110
size_t tx_total_bytes
total bytes transferred
Definition: interface.h:109
MAVConn console-bridge compatibility header.
static constexpr auto PERMANENT_BROADCAST_REMOTE_HOST
Definition: udp.h:40
Protocol get_protocol_version()
Definition: interface.cpp:181
static constexpr auto DEFAULT_BAUDRATE
Definition: serial.h:33
static Ptr open_url(std::string url, uint8_t system_id=1, uint8_t component_id=MAV_COMP_ID_UDP_BRIDGE)
Construct connection from URL.
Definition: interface.cpp:334
static std::atomic< size_t > conn_id_counter
monotonic counter (increment only)
Definition: interface.h:290
void set_protocol_version(Protocol pver)
Definition: interface.cpp:173
mavlink::mavlink_status_t m_parse_status
Definition: interface.h:280
#define PFX
Definition: interface.cpp:29
void iostat_rx_add(size_t bytes)
Definition: interface.cpp:91
Protocol
MAVLink protocol version.
Definition: interface.h:56
static void url_parse_query(std::string query, uint8_t &sysid, uint8_t &compid)
Definition: interface.cpp:228
static constexpr auto DEFAULT_REMOTE_HOST
Definition: udp.h:36
std::recursive_mutex iostat_mutex
Definition: interface.h:285
static MAVConnInterface::Ptr url_parse_tcp_server(std::string host, std::string query, uint8_t system_id, uint8_t component_id)
Definition: interface.cpp:319
void log_recv(const char *pfx, mavlink::mavlink_message_t &msg, Framing framing)
Definition: interface.cpp:117
std::atomic< size_t > tx_total_bytes
Definition: interface.h:284
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