29 #define PFX "mavconn: "
31 using mavlink::mavlink_message_t;
32 using mavlink::mavlink_status_t;
42 comp_id(component_id),
48 last_tx_total_bytes(0),
49 last_rx_total_bytes(0),
50 last_iostat(steady_clock::now())
52 conn_id = conn_id_counter.fetch_add(1);
53 std::call_once(init_flag, init_msg_entry);
63 std::lock_guard<std::recursive_mutex> lock(
iostat_mutex);
74 auto now = steady_clock::now();
78 float dt_s = std::chrono::duration_cast<std::chrono::seconds>(dt).count();
98 mavlink::mavlink_message_t message;
100 assert(bufsize >= bytes_received);
103 for (; bytes_received > 0; bytes_received--) {
109 log_recv(pfx, message, msg_received);
119 const char *framing_str = (framing ==
Framing::ok) ?
"OK" :
123 const char *proto_version_str = (msg.magic == MAVLINK_STX) ?
"v2.0" :
"v1.0";
129 msg.msgid, msg.len, msg.sysid, msg.compid, msg.seq);
134 const char *proto_version_str = (msg->magic == MAVLINK_STX) ?
"v2.0" :
"v1.0";
139 msg->msgid, msg->len, msg->sysid, msg->compid, msg->seq);
152 catch (std::length_error &e) {
155 msg->msgid, msg->len, msg->sysid, msg->compid, msg->seq,
165 catch (std::length_error &e) {
168 msg.get_name().c_str(),
198 std::string &host_out,
int &port_out,
199 const std::string def_host,
const int def_port)
203 auto sep_it = std::find(host.begin(), host.end(),
':');
204 if (sep_it == host.end()) {
217 if (sep_it == host.begin()) {
223 host_out.assign(host.begin(), sep_it);
226 port.assign(sep_it + 1, host.end());
227 port_out = std::stoi(port);
235 const std::string ids_end(
"ids=");
236 std::string sys, comp;
241 auto ids_it = std::search(query.begin(), query.end(),
242 ids_end.begin(), ids_end.end());
243 if (ids_it == query.end()) {
248 std::advance(ids_it, ids_end.length());
249 auto comma_it = std::find(ids_it, query.end(),
',');
250 if (comma_it == query.end()) {
255 sys.assign(ids_it, comma_it);
256 comp.assign(comma_it + 1, query.end());
258 sysid = std::stoi(sys);
259 compid = std::stoi(comp);
265 std::string path, std::string query,
266 uint8_t system_id, uint8_t component_id,
bool hwflow)
268 std::string file_path;
275 return std::make_shared<MAVConnSerial>(system_id, component_id,
276 file_path, baudrate, hwflow);
280 std::string hosts, std::string query,
281 uint8_t system_id, uint8_t component_id,
bool is_udpb,
bool permanent_broadcast)
283 std::string bind_pair, remote_pair;
284 std::string bind_host, remote_host;
285 int bind_port, remote_port;
287 auto sep_it = std::find(hosts.begin(), hosts.end(),
'@');
288 if (sep_it == hosts.end()) {
290 throw DeviceError(
"url",
"UDP separator not found");
293 bind_pair.assign(hosts.begin(), sep_it);
294 remote_pair.assign(sep_it + 1, hosts.end());
304 return std::make_shared<MAVConnUDP>(system_id, component_id,
305 bind_host, bind_port,
306 remote_host, remote_port);
310 std::string host, std::string query,
311 uint8_t system_id, uint8_t component_id)
313 std::string server_host;
317 url_parse_host(host, server_host, server_port,
"localhost", 5760);
320 return std::make_shared<MAVConnTCPClient>(system_id, component_id,
321 server_host, server_port);
325 std::string host, std::string query,
326 uint8_t system_id, uint8_t component_id)
328 std::string bind_host;
335 return std::make_shared<MAVConnTCPServer>(system_id, component_id,
336 bind_host, bind_port);
342 uint8_t component_id)
348 const std::string proto_end(
"://");
354 auto proto_it = std::search(
355 url.begin(), url.end(),
356 proto_end.begin(), proto_end.end());
357 if (proto_it == url.end()) {
364 proto.reserve(std::distance(url.begin(), proto_it));
365 std::transform(url.begin(), proto_it,
366 std::back_inserter(proto),
370 std::advance(proto_it, proto_end.length());
371 auto path_it = std::find(proto_it, url.end(),
'/');
372 std::transform(proto_it, path_it,
373 std::back_inserter(host),
377 auto query_it = std::find(path_it, url.end(),
'?');
378 path.assign(path_it, query_it);
379 if (query_it != url.end())
381 query.assign(query_it, url.end());
384 url.c_str(), proto.c_str(), host.c_str(),
385 path.c_str(), query.c_str());
390 interface_ptr =
url_parse_udp(host, query, system_id, component_id,
false,
false);
391 else if (proto ==
"udp-b")
392 interface_ptr =
url_parse_udp(host, query, system_id, component_id,
true,
false);
393 else if (proto ==
"udp-pb")
394 interface_ptr =
url_parse_udp(host, query, system_id, component_id,
true,
true);
395 else if (proto ==
"tcp")
397 else if (proto ==
"tcp-l")
399 else if (proto ==
"serial")
400 interface_ptr =
url_parse_serial(path, query, system_id, component_id,
false);
401 else if (proto ==
"serial-hwfc")
402 interface_ptr =
url_parse_serial(path, query, system_id, component_id,
true);
406 return interface_ptr;
412 uint8_t component_id,
414 const ClosedCb &cb_handle_closed_port)
419 if (!cb_handle_message)
421 CONSOLE_BRIDGE_logWarn(
PFX "You did not provide message handling callback to open_url(), it is unsafe to set it later.");
423 interface_ptr->connect(cb_handle_message, cb_handle_closed_port);
426 return interface_ptr;