29 #define PFX "mavconn: " 31 using mavlink::mavlink_message_t;
32 using mavlink::mavlink_status_t;
42 comp_id(component_id),
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) {
193 std::string &host_out,
int &port_out,
194 const std::string def_host,
const int def_port)
198 auto sep_it = std::find(host.begin(), host.end(),
':');
199 if (sep_it == host.end()) {
212 if (sep_it == host.begin()) {
218 host_out.assign(host.begin(), sep_it);
221 port.assign(sep_it + 1, host.end());
222 port_out = std::stoi(port);
230 const std::string ids_end(
"ids=");
231 std::string sys, comp;
236 auto ids_it = std::search(query.begin(), query.end(),
237 ids_end.begin(), ids_end.end());
238 if (ids_it == query.end()) {
243 std::advance(ids_it, ids_end.length());
244 auto comma_it = std::find(ids_it, query.end(),
',');
245 if (comma_it == query.end()) {
250 sys.assign(ids_it, comma_it);
251 comp.assign(comma_it + 1, query.end());
253 sysid = std::stoi(sys);
254 compid = std::stoi(comp);
260 std::string path, std::string query,
261 uint8_t system_id, uint8_t component_id,
bool hwflow)
263 std::string file_path;
270 return std::make_shared<MAVConnSerial>(system_id, component_id,
271 file_path, baudrate, hwflow);
275 std::string hosts, std::string query,
276 uint8_t system_id, uint8_t component_id,
bool is_udpb,
bool permanent_broadcast)
278 std::string bind_pair, remote_pair;
279 std::string bind_host, remote_host;
280 int bind_port, remote_port;
282 auto sep_it = std::find(hosts.begin(), hosts.end(),
'@');
283 if (sep_it == hosts.end()) {
285 throw DeviceError(
"url",
"UDP separator not found");
288 bind_pair.assign(hosts.begin(), sep_it);
289 remote_pair.assign(sep_it + 1, hosts.end());
299 return std::make_shared<MAVConnUDP>(system_id, component_id,
300 bind_host, bind_port,
301 remote_host, remote_port);
305 std::string host, std::string query,
306 uint8_t system_id, uint8_t component_id)
308 std::string server_host;
312 url_parse_host(host, server_host, server_port,
"localhost", 5760);
315 return std::make_shared<MAVConnTCPClient>(system_id, component_id,
316 server_host, server_port);
320 std::string host, std::string query,
321 uint8_t system_id, uint8_t component_id)
323 std::string bind_host;
330 return std::make_shared<MAVConnTCPServer>(system_id, component_id,
331 bind_host, bind_port);
335 uint8_t system_id, uint8_t component_id)
341 const std::string proto_end(
"://");
347 auto proto_it = std::search(
348 url.begin(), url.end(),
349 proto_end.begin(), proto_end.end());
350 if (proto_it == url.end()) {
357 proto.reserve(std::distance(url.begin(), proto_it));
358 std::transform(url.begin(), proto_it,
359 std::back_inserter(proto),
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),
370 auto query_it = std::find(path_it, url.end(),
'?');
371 path.assign(path_it, query_it);
372 if (query_it != url.end())
374 query.assign(query_it, url.end());
377 url.c_str(), proto.c_str(), host.c_str(),
378 path.c_str(), query.c_str());
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")
388 else if (proto ==
"tcp-l")
390 else if (proto ==
"serial")
392 else if (proto ==
"serial-hwfc")
virtual void send_message(const mavlink::mavlink_message_t *message)=0
Send message (mavlink_message_t)
mavlink::mavlink_status_t m_mavlink_status
virtual mavlink::mavlink_status_t get_status()
float rx_speed
current receive speed [B/s]
void log_send(const char *pfx, const mavlink::mavlink_message_t *msg)
void parse_buffer(const char *pfx, uint8_t *buf, const size_t bufsize, size_t bytes_received)
static void init_msg_entry()
static std::once_flag init_flag
init_msg_entry() once flag
#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.
Common exception for communication error.
static MAVConnInterface::Ptr url_parse_tcp_client(std::string host, std::string query, uint8_t system_id, uint8_t component_id)
static constexpr auto DEFAULT_BIND_PORT
#define CONSOLE_BRIDGE_logDebug(fmt,...)
void log_send_obj(const char *pfx, const mavlink::Message &msg)
ReceivedCb message_received_cb
Message receive callback.
size_t last_tx_total_bytes
std::chrono::time_point< steady_clock > last_iostat
float tx_speed
current transfer speed [B/s]
static MAVConnInterface::Ptr url_parse_serial(std::string path, std::string query, uint8_t system_id, uint8_t component_id, bool hwflow)
static void url_parse_host(std::string host, std::string &host_out, int &port_out, const std::string def_host, const int def_port)
void iostat_tx_add(size_t bytes)
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. ...
virtual std::string to_yaml(void) const =0
size_t conn_id
Channel number used for logging.
#define CONSOLE_BRIDGE_logError(fmt,...)
static constexpr auto BROADCAST_REMOTE_HOST
Markers for broadcast modes. Not valid domain names.
MAVConn message buffer class (internal)
MAVConn Serial link class.
static constexpr auto DEFAULT_DEVICE
static constexpr auto DEFAULT_REMOTE_PORT
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)
#define MAVLINK_STATUS_FLAG_OUT_MAVLINK1
size_t last_rx_total_bytes
virtual IOStat get_iostat()
MAVConnInterface(const MAVConnInterface &)=delete
mavlink::mavlink_message_t m_buffer
std::atomic< size_t > rx_total_bytes
size_t rx_total_bytes
total bytes received
size_t tx_total_bytes
total bytes transferred
MAVConn console-bridge compatibility header.
static constexpr auto PERMANENT_BROADCAST_REMOTE_HOST
Protocol get_protocol_version()
struct __mavlink_status mavlink_status_t
static constexpr auto DEFAULT_BAUDRATE
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.
static std::atomic< size_t > conn_id_counter
monotonic counter (increment only)
void set_protocol_version(Protocol pver)
mavlink::mavlink_status_t m_parse_status
void iostat_rx_add(size_t bytes)
Protocol
MAVLink protocol version.
static void url_parse_query(std::string query, uint8_t &sysid, uint8_t &compid)
static constexpr auto DEFAULT_REMOTE_HOST
virtual std::string get_name(void) const =0
std::recursive_mutex iostat_mutex
static MAVConnInterface::Ptr url_parse_tcp_server(std::string host, std::string query, uint8_t system_id, uint8_t component_id)
void log_recv(const char *pfx, mavlink::mavlink_message_t &msg, Framing framing)
std::atomic< size_t > tx_total_bytes
Framing
Rx packer framing status. (same as mavlink::mavlink_framing_t)
std::shared_ptr< MAVConnInterface > Ptr