24 #include <boost/system/system_error.hpp> 36 #include <unordered_map> 37 #include <mavconn/mavlink_dialect.h> 42 using lock_guard = std::lock_guard<std::recursive_mutex>;
49 incomplete = mavlink::MAVLINK_FRAMING_INCOMPLETE,
50 ok = mavlink::MAVLINK_FRAMING_OK,
51 bad_crc = mavlink::MAVLINK_FRAMING_BAD_CRC,
71 std::runtime_error(make_message(module, msg))
76 std::ostringstream ss;
77 ss <<
"DeviceError:" << module <<
":" << msg_to_string(msg);
86 return ::strerror(errnum);
102 using ReceivedCb = std::function<void (const mavlink::mavlink_message_t *message, const Framing framing)>;
104 using Ptr = std::shared_ptr<MAVConnInterface>;
105 using ConstPtr = std::shared_ptr<MAVConnInterface const>;
106 using WeakPtr = std::weak_ptr<MAVConnInterface>;
119 MAVConnInterface(uint8_t system_id = 1, uint8_t component_id = MAV_COMP_ID_UDP_BRIDGE);
124 virtual void close() = 0;
136 virtual void send_message(
const mavlink::mavlink_message_t *message) = 0;
148 send_message(message, this->comp_id);
162 virtual void send_message(
const mavlink::Message &message,
const uint8_t src_compid) = 0;
168 virtual void send_bytes(
const uint8_t *bytes,
size_t length) = 0;
173 void send_message_ignore_drop(
const mavlink::mavlink_message_t *message);
181 send_message_ignore_drop(message, this->comp_id);
190 void send_message_ignore_drop(
const mavlink::Message &message,
const uint8_t src_compid);
197 virtual mavlink::mavlink_status_t get_status();
198 virtual IOStat get_iostat();
199 virtual bool is_open() = 0;
217 void set_protocol_version(
Protocol pver);
237 static Ptr open_url(std::string
url,
238 uint8_t system_id = 1, uint8_t component_id = MAV_COMP_ID_UDP_BRIDGE);
240 static std::vector<std::string> get_known_dialects();
249 static constexpr
size_t MAX_TXQ_SIZE = 1000;
252 static std::unordered_map<mavlink::msgid_t, const mavlink::mavlink_msg_entry_t*>
message_entries;
258 return &m_parse_status;
268 void parse_buffer(
const char *pfx, uint8_t *buf,
const size_t bufsize,
size_t bytes_received);
270 void iostat_tx_add(
size_t bytes);
271 void iostat_rx_add(
size_t bytes);
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);
300 static void init_msg_entry();
mavlink::mavlink_status_t m_mavlink_status
float rx_speed
current receive speed [B/s]
std::chrono::steady_clock steady_clock
std::shared_ptr< MAVConnInterface const > ConstPtr
ClosedCb port_closed_cb
Port closed notification callback.
std::lock_guard< std::recursive_mutex > lock_guard
static std::once_flag init_flag
init_msg_entry() once flag
std::function< void(const mavlink::mavlink_message_t *message, const Framing framing)> ReceivedCb
static std::string msg_to_string(const char *description)
#define MAVLINK_MAX_PACKET_LEN
mavlink::mavlink_message_t * get_buffer_p()
Common exception for communication error.
const mavlink_msg_entry_t * mavlink_get_msg_entry(uint32_t msgid)
DeviceError(const char *module, T msg)
static constexpr auto MAV_COMP_ID_UDP_BRIDGE
Same as mavlink::common::MAV_COMPONENT::COMP_ID_UDP_BRIDGE.
ReceivedCb message_received_cb
Message receive callback.
void send_message_ignore_drop(const mavlink::Message &message)
Send message and ignore possible drop due to Tx queue limit.
size_t last_tx_total_bytes
std::chrono::time_point< steady_clock > last_iostat
static std::string msg_to_string(int errnum)
Generic mavlink interface.
float tx_speed
current transfer speed [B/s]
uint8_t comp_id
Connection Component Id.
static std::string make_message(const char *module, T msg)
uint8_t get_component_id()
mavlink::mavlink_status_t * get_status_p()
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. ...
std::function< void(void)> ClosedCb
size_t conn_id
Channel number used for logging.
std::weak_ptr< MAVConnInterface > WeakPtr
mavlink::mavlink_message_t m_buffer
size_t rx_total_bytes
total bytes received
size_t tx_total_bytes
total bytes transferred
virtual void send_message(const mavlink::Message &message)
Send message (child of mavlink::Message)
static std::atomic< size_t > conn_id_counter
monotonic counter (increment only)
mavlink::mavlink_status_t m_parse_status
void set_system_id(uint8_t sysid)
Protocol
MAVLink protocol version.
static std::string msg_to_string(boost::system::system_error &err)
uint8_t sys_id
Connection System Id.
std::recursive_mutex iostat_mutex
std::atomic< size_t > tx_total_bytes
void set_component_id(uint8_t compid)
Framing
Rx packer framing status. (same as mavlink::mavlink_framing_t)
std::shared_ptr< MAVConnInterface > Ptr