Generic mavlink interface. More...
#include <interface.h>
Classes | |
struct | IOStat |
Public Types | |
using | ClosedCb = std::function< void(void)> |
using | ConstPtr = std::shared_ptr< MAVConnInterface const > |
using | Ptr = std::shared_ptr< MAVConnInterface > |
using | ReceivedCb = std::function< void(const mavlink::mavlink_message_t *message, const Framing framing)> |
using | WeakPtr = std::weak_ptr< MAVConnInterface > |
Public Member Functions | |
virtual void | close ()=0 |
Close connection. More... | |
uint8_t | get_component_id () |
virtual IOStat | get_iostat () |
Protocol | get_protocol_version () |
virtual mavlink::mavlink_status_t | get_status () |
uint8_t | get_system_id () |
virtual bool | is_open ()=0 |
MAVConnInterface (uint8_t system_id=1, uint8_t component_id=MAV_COMP_ID_UDP_BRIDGE) | |
virtual void | send_bytes (const uint8_t *bytes, size_t length)=0 |
Send raw bytes (for some quirks) More... | |
virtual void | send_message (const mavlink::mavlink_message_t *message)=0 |
Send message (mavlink_message_t) More... | |
virtual void | send_message (const mavlink::Message &message) |
Send message (child of mavlink::Message) More... | |
virtual void | send_message (const mavlink::Message &message, const uint8_t src_compid)=0 |
Send message (child of mavlink::Message) More... | |
void | send_message_ignore_drop (const mavlink::mavlink_message_t *message) |
Send message and ignore possible drop due to Tx queue limit. More... | |
void | send_message_ignore_drop (const mavlink::Message &message) |
Send message and ignore possible drop due to Tx queue limit. More... | |
void | send_message_ignore_drop (const mavlink::Message &message, const uint8_t src_compid) |
Send message and ignore possible drop due to Tx queue limit. More... | |
void | set_component_id (uint8_t compid) |
void | set_protocol_version (Protocol pver) |
void | set_system_id (uint8_t sysid) |
Static Public Member Functions | |
static std::vector< std::string > | get_known_dialects () |
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. More... | |
Public Attributes | |
ReceivedCb | message_received_cb |
Message receive callback. More... | |
ClosedCb | port_closed_cb |
Port closed notification callback. More... | |
Protected Member Functions | |
mavlink::mavlink_message_t * | get_buffer_p () |
mavlink::mavlink_status_t * | get_status_p () |
void | iostat_rx_add (size_t bytes) |
void | iostat_tx_add (size_t bytes) |
void | log_recv (const char *pfx, mavlink::mavlink_message_t &msg, Framing framing) |
void | log_send (const char *pfx, const mavlink::mavlink_message_t *msg) |
void | log_send_obj (const char *pfx, const mavlink::Message &msg) |
void | parse_buffer (const char *pfx, uint8_t *buf, const size_t bufsize, size_t bytes_received) |
Protected Attributes | |
uint8_t | comp_id |
Connection Component Id. More... | |
size_t | conn_id |
Channel number used for logging. More... | |
uint8_t | sys_id |
Connection System Id. More... | |
Static Protected Attributes | |
static constexpr size_t | MAX_PACKET_SIZE = MAVLINK_MAX_PACKET_LEN + 16 |
Maximum mavlink packet size + some extra bytes for padding. More... | |
static constexpr size_t | MAX_TXQ_SIZE = 1000 |
Maximum count of transmission buffers. More... | |
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. More... | |
Private Member Functions | |
MAVConnInterface (const MAVConnInterface &)=delete | |
Static Private Member Functions | |
static void | init_msg_entry () |
Private Attributes | |
std::recursive_mutex | iostat_mutex |
std::chrono::time_point< steady_clock > | last_iostat |
size_t | last_rx_total_bytes |
size_t | last_tx_total_bytes |
mavlink::mavlink_message_t | m_buffer |
mavlink::mavlink_status_t | m_status |
std::atomic< size_t > | rx_total_bytes |
std::atomic< size_t > | tx_total_bytes |
Static Private Attributes | |
static std::atomic< size_t > | conn_id_counter {0} |
monotonic counter (increment only) More... | |
static std::once_flag | init_flag |
init_msg_entry() once flag More... | |
Friends | |
const mavlink::mavlink_msg_entry_t * | mavlink::mavlink_get_msg_entry (uint32_t msgid) |
Generic mavlink interface.
Definition at line 97 of file interface.h.