Namespaces | Classes | Macros | Typedefs | Enumerations | Functions | Variables | Friends
Mavconn

MAVConn connection handling library. More...

Collaboration diagram for Mavconn:

Namespaces

 mavconn
 

Classes

class  mavconn::DeviceError
 Common exception for communication error. More...
 
struct  mavconn::MAVConnInterface::IOStat
 
class  mavconn::MAVConnInterface
 Generic mavlink interface. More...
 
class  mavconn::MAVConnSerial
 Serial interface. More...
 
class  mavconn::MAVConnTCPClient
 TCP client interface. More...
 
class  mavconn::MAVConnTCPServer
 TCP server interface. More...
 
class  mavconn::MAVConnUDP
 UDP interface. More...
 
struct  mavconn::MsgBuffer
 Message buffer for internal use in libmavconn. More...
 

Macros

#define CONSOLE_BRIDGE_logDebug(fmt, ...)   console_bridge::log(__FILE__, __LINE__, console_bridge::CONSOLE_BRIDGE_LOG_DEBUG, fmt, ##__VA_ARGS__)
 
#define CONSOLE_BRIDGE_logError(fmt, ...)   console_bridge::log(__FILE__, __LINE__, console_bridge::CONSOLE_BRIDGE_LOG_ERROR, fmt, ##__VA_ARGS__)
 
#define CONSOLE_BRIDGE_logInform(fmt, ...)   console_bridge::log(__FILE__, __LINE__, console_bridge::CONSOLE_BRIDGE_LOG_INFO, fmt, ##__VA_ARGS__)
 
#define CONSOLE_BRIDGE_logWarn(fmt, ...)   console_bridge::log(__FILE__, __LINE__, console_bridge::CONSOLE_BRIDGE_LOG_WARN, fmt, ##__VA_ARGS__)
 
#define GET_IO_SERVICE(s)   ((s).get_io_service())
 
#define PFX   "mavconn: "
 
#define PFX   "mavconn: udp"
 
#define PFX   "mavconn: serial"
 
#define PFX   "mavconn: tcp"
 
#define PFXd   PFX "%zu: "
 
#define PFXd   PFX "%zu: "
 
#define PFXd   PFX "%zu: "
 

Typedefs

using mavconn::MAVConnInterface::ClosedCb = std::function< void(void)>
 
using mavconn::MAVConnInterface::ConstPtr = std::shared_ptr< MAVConnInterface const >
 
using mavconn::lock_guard = std::lock_guard< std::recursive_mutex >
 
using mavconn::MAVConnInterface::Ptr = std::shared_ptr< MAVConnInterface >
 
using mavconn::MAVConnInterface::ReceivedCb = std::function< void(const mavlink::mavlink_message_t *message, const Framing framing)>
 
using mavconn::steady_clock = std::chrono::steady_clock
 
using mavconn::MAVConnInterface::WeakPtr = std::weak_ptr< MAVConnInterface >
 

Enumerations

enum  mavconn::Framing : uint8_t { mavconn::Framing::incomplete = mavlink::MAVLINK_FRAMING_INCOMPLETE, mavconn::Framing::ok = mavlink::MAVLINK_FRAMING_OK, mavconn::Framing::bad_crc = mavlink::MAVLINK_FRAMING_BAD_CRC, mavconn::Framing::bad_signature = mavlink::MAVLINK_FRAMING_BAD_SIGNATURE }
 Rx packer framing status. (same as mavlink::mavlink_framing_t) More...
 
enum  mavconn::Protocol : uint8_t { mavconn::Protocol::V10 = 1, mavconn::Protocol::V20 = 2 }
 MAVLink protocol version. More...
 

Functions

void mavconn::MAVConnTCPServer::client_closed (std::weak_ptr< MAVConnTCPClient > weak_instp)
 
void mavconn::MAVConnTCPClient::client_connected (size_t server_channel)
 
void mavconn::MAVConnSerial::close () override
 Close connection. More...
 
void mavconn::MAVConnUDP::close () override
 Close connection. More...
 
void mavconn::MAVConnTCPClient::close () override
 Close connection. More...
 
void mavconn::MAVConnTCPServer::close () override
 Close connection. More...
 
virtual void mavconn::MAVConnInterface::close ()=0
 Close connection. More...
 
void mavconn::MAVConnSerial::connect (const ReceivedCb &cb_handle_message, const ClosedCb &cb_handle_closed_port=ClosedCb()) override
 Establish connection, automatically called by open_url() More...
 
void mavconn::MAVConnUDP::connect (const ReceivedCb &cb_handle_message, const ClosedCb &cb_handle_closed_port=ClosedCb()) override
 Establish connection, automatically called by open_url() More...
 
void mavconn::MAVConnTCPClient::connect (const ReceivedCb &cb_handle_message, const ClosedCb &cb_handle_closed_port=ClosedCb()) override
 Establish connection, automatically called by open_url() More...
 
void mavconn::MAVConnTCPServer::connect (const ReceivedCb &cb_handle_message, const ClosedCb &cb_handle_closed_port=ClosedCb()) override
 Establish connection, automatically called by open_url() More...
 
virtual void mavconn::MAVConnInterface::connect (const ReceivedCb &cb_handle_message, const ClosedCb &cb_handle_closed_port=ClosedCb())=0
 Establish connection, automatically called by open_url() More...
 
template<typename T >
 mavconn::DeviceError::DeviceError (const char *module, T msg)
 
void mavconn::MAVConnTCPServer::do_accept ()
 
void mavconn::MAVConnSerial::do_read ()
 
void mavconn::MAVConnTCPClient::do_recv ()
 
void mavconn::MAVConnUDP::do_recvfrom ()
 
void mavconn::MAVConnTCPClient::do_send (bool check_tx_state)
 
void mavconn::MAVConnUDP::do_sendto (bool check_tx_state)
 
void mavconn::MAVConnSerial::do_write (bool check_tx_state)
 
uint8_t * mavconn::MsgBuffer::dpos ()
 
mavlink::mavlink_message_tmavconn::MAVConnInterface::get_buffer_p ()
 
uint8_t mavconn::MAVConnInterface::get_component_id ()
 
IOStat mavconn::MAVConnTCPServer::get_iostat () override
 
virtual IOStat mavconn::MAVConnInterface::get_iostat ()
 
static std::vector< std::string > mavconn::MAVConnInterface::get_known_dialects ()
 
Protocol mavconn::MAVConnInterface::get_protocol_version ()
 
std::string mavconn::MAVConnUDP::get_remote_endpoint () const
 
mavlink::mavlink_status_t mavconn::MAVConnTCPServer::get_status () override
 
virtual mavlink::mavlink_status_t mavconn::MAVConnInterface::get_status ()
 
mavlink::mavlink_status_tmavconn::MAVConnInterface::get_status_p ()
 
uint8_t mavconn::MAVConnInterface::get_system_id ()
 
static void mavconn::MAVConnInterface::init_msg_entry ()
 
void mavconn::MAVConnInterface::iostat_rx_add (size_t bytes)
 
void mavconn::MAVConnInterface::iostat_tx_add (size_t bytes)
 
bool mavconn::MAVConnSerial::is_open () override
 
bool mavconn::MAVConnUDP::is_open () override
 
bool mavconn::MAVConnTCPClient::is_open () override
 
bool mavconn::MAVConnTCPServer::is_open () override
 
virtual bool mavconn::MAVConnInterface::is_open ()=0
 
void mavconn::MAVConnInterface::log_recv (const char *pfx, mavlink::mavlink_message_t &msg, Framing framing)
 
void mavconn::MAVConnInterface::log_send (const char *pfx, const mavlink::mavlink_message_t *msg)
 
void mavconn::MAVConnInterface::log_send_obj (const char *pfx, const mavlink::Message &msg)
 
template<typename T >
static std::string mavconn::DeviceError::make_message (const char *module, T msg)
 
 mavconn::MAVConnInterface::MAVConnInterface (const MAVConnInterface &)=delete
 
 mavconn::MAVConnInterface::MAVConnInterface (uint8_t system_id=1, uint8_t component_id=MAV_COMP_ID_UDP_BRIDGE)
 
 mavconn::MAVConnSerial::MAVConnSerial (uint8_t system_id=1, uint8_t component_id=MAV_COMP_ID_UDP_BRIDGE, std::string device=DEFAULT_DEVICE, unsigned baudrate=DEFAULT_BAUDRATE, bool hwflow=false)
 
 mavconn::MAVConnTCPClient::MAVConnTCPClient (uint8_t system_id=1, uint8_t component_id=MAV_COMP_ID_UDP_BRIDGE, std::string server_host=DEFAULT_SERVER_HOST, unsigned short server_port=DEFAULT_SERVER_PORT)
 
 mavconn::MAVConnTCPClient::MAVConnTCPClient (uint8_t system_id, uint8_t component_id, boost::asio::io_service &server_io)
 
 mavconn::MAVConnTCPServer::MAVConnTCPServer (uint8_t system_id=1, uint8_t component_id=MAV_COMP_ID_UDP_BRIDGE, std::string bind_host=DEFAULT_BIND_HOST, unsigned short bind_port=DEFAULT_BIND_PORT)
 
 mavconn::MAVConnUDP::MAVConnUDP (uint8_t system_id=1, uint8_t component_id=MAV_COMP_ID_UDP_BRIDGE, std::string bind_host=DEFAULT_BIND_HOST, unsigned short bind_port=DEFAULT_BIND_PORT, std::string remote_host=DEFAULT_REMOTE_HOST, unsigned short remote_port=DEFAULT_REMOTE_PORT)
 
static std::string mavconn::DeviceError::msg_to_string (const char *description)
 
static std::string mavconn::DeviceError::msg_to_string (int errnum)
 
static std::string mavconn::DeviceError::msg_to_string (boost::system::system_error &err)
 
 mavconn::MsgBuffer::MsgBuffer ()
 
 mavconn::MsgBuffer::MsgBuffer (const mavlink::mavlink_message_t *msg)
 Buffer constructor from mavlink_message_t. More...
 
 mavconn::MsgBuffer::MsgBuffer (const mavlink::Message &obj, mavlink::mavlink_status_t *status, uint8_t sysid, uint8_t compid)
 Buffer constructor for mavlink::Message derived object. More...
 
 mavconn::MsgBuffer::MsgBuffer (const uint8_t *bytes, ssize_t nbytes)
 Buffer constructor for send_bytes() More...
 
ssize_t mavconn::MsgBuffer::nbytes ()
 
static Ptr mavconn::MAVConnInterface::open_url (std::string url, uint8_t system_id=1, uint8_t component_id=MAV_COMP_ID_UDP_BRIDGE, const ReceivedCb &cb_handle_message=ReceivedCb(), const ClosedCb &cb_handle_closed_port=ClosedCb())
 Construct connection from URL. More...
 
static Ptr mavconn::MAVConnInterface::open_url_no_connect (std::string url, uint8_t system_id=1, uint8_t component_id=MAV_COMP_ID_UDP_BRIDGE)
 version of open_url() which do not perform connect() More...
 
void mavconn::MAVConnInterface::parse_buffer (const char *pfx, uint8_t *buf, const size_t bufsize, size_t bytes_received)
 
static bool mavconn::resolve_address_tcp (io_service &io, size_t chan, std::string host, unsigned short port, tcp::endpoint &ep)
 
static bool mavconn::resolve_address_udp (io_service &io, size_t chan, std::string host, unsigned short port, udp::endpoint &ep)
 
void mavconn::MAVConnSerial::send_bytes (const uint8_t *bytes, size_t length) override
 Send raw bytes (for some quirks) More...
 
void mavconn::MAVConnUDP::send_bytes (const uint8_t *bytes, size_t length) override
 Send raw bytes (for some quirks) More...
 
void mavconn::MAVConnTCPClient::send_bytes (const uint8_t *bytes, size_t length) override
 Send raw bytes (for some quirks) More...
 
void mavconn::MAVConnTCPServer::send_bytes (const uint8_t *bytes, size_t length) override
 Send raw bytes (for some quirks) More...
 
virtual void mavconn::MAVConnInterface::send_bytes (const uint8_t *bytes, size_t length)=0
 Send raw bytes (for some quirks) More...
 
void mavconn::MAVConnSerial::send_message (const mavlink::mavlink_message_t *message) override
 Send message (mavlink_message_t) More...
 
void mavconn::MAVConnSerial::send_message (const mavlink::Message &message, const uint8_t source_compid) override
 Send message (child of mavlink::Message) More...
 
void mavconn::MAVConnUDP::send_message (const mavlink::mavlink_message_t *message) override
 Send message (mavlink_message_t) More...
 
void mavconn::MAVConnUDP::send_message (const mavlink::Message &message, const uint8_t source_compid) override
 Send message (child of mavlink::Message) More...
 
void mavconn::MAVConnTCPClient::send_message (const mavlink::mavlink_message_t *message) override
 Send message (mavlink_message_t) More...
 
void mavconn::MAVConnTCPClient::send_message (const mavlink::Message &message, const uint8_t source_compid) override
 Send message (child of mavlink::Message) More...
 
void mavconn::MAVConnTCPServer::send_message (const mavlink::mavlink_message_t *message) override
 Send message (mavlink_message_t) More...
 
void mavconn::MAVConnTCPServer::send_message (const mavlink::Message &message, const uint8_t source_compid) override
 Send message (child of mavlink::Message) More...
 
virtual void mavconn::MAVConnInterface::send_message (const mavlink::mavlink_message_t *message)=0
 Send message (mavlink_message_t) More...
 
virtual void mavconn::MAVConnInterface::send_message (const mavlink::Message &message)
 Send message (child of mavlink::Message) More...
 
virtual void mavconn::MAVConnInterface::send_message (const mavlink::Message &message, const uint8_t src_compid)=0
 Send message (child of mavlink::Message) More...
 
void mavconn::MAVConnInterface::send_message_ignore_drop (const mavlink::mavlink_message_t *message)
 Send message and ignore possible drop due to Tx queue limit. More...
 
void mavconn::MAVConnInterface::send_message_ignore_drop (const mavlink::Message &message)
 Send message and ignore possible drop due to Tx queue limit. More...
 
void mavconn::MAVConnInterface::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 mavconn::MAVConnInterface::set_component_id (uint8_t compid)
 
void mavconn::MAVConnInterface::set_protocol_version (Protocol pver)
 
void mavconn::MAVConnInterface::set_system_id (uint8_t sysid)
 
static void mavconn::url_parse_host (std::string host, std::string &host_out, int &port_out, const std::string def_host, const int def_port)
 
static void mavconn::url_parse_query (std::string query, uint8_t &sysid, uint8_t &compid)
 
static MAVConnInterface::Ptr mavconn::url_parse_serial (std::string path, std::string query, uint8_t system_id, uint8_t component_id, bool hwflow)
 
static MAVConnInterface::Ptr mavconn::url_parse_tcp_client (std::string host, std::string query, uint8_t system_id, uint8_t component_id)
 
static MAVConnInterface::Ptr mavconn::url_parse_tcp_server (std::string host, std::string query, uint8_t system_id, uint8_t component_id)
 
static MAVConnInterface::Ptr mavconn::url_parse_udp (std::string hosts, std::string query, uint8_t system_id, uint8_t component_id, bool is_udpb, bool permanent_broadcast)
 
virtual mavconn::MAVConnSerial::~MAVConnSerial ()
 
virtual mavconn::MAVConnTCPClient::~MAVConnTCPClient ()
 
virtual mavconn::MAVConnTCPServer::~MAVConnTCPServer ()
 
virtual mavconn::MAVConnUDP::~MAVConnUDP ()
 
virtual mavconn::MsgBuffer::~MsgBuffer ()
 

Variables

boost::asio::ip::tcp::acceptor mavconn::MAVConnTCPServer::acceptor
 
boost::asio::ip::udp::endpoint mavconn::MAVConnUDP::bind_ep
 
boost::asio::ip::tcp::endpoint mavconn::MAVConnTCPServer::bind_ep
 
static constexpr auto mavconn::MAVConnUDP::BROADCAST_REMOTE_HOST = "***i want broadcast***"
 Markers for broadcast modes. Not valid domain names. More...
 
std::list< std::shared_ptr< MAVConnTCPClient > > mavconn::MAVConnTCPServer::client_list
 
uint8_t mavconn::MAVConnInterface::comp_id
 Connection Component Id. More...
 
size_t mavconn::MAVConnInterface::conn_id
 Channel number used for logging. More...
 
static std::atomic< size_t > mavconn::MAVConnInterface::conn_id_counter {0}
 monotonic counter (increment only) More...
 
uint8_t mavconn::MsgBuffer::data [MAX_SIZE]
 
static constexpr auto mavconn::MAVConnSerial::DEFAULT_BAUDRATE = 57600
 
static constexpr auto mavconn::MAVConnUDP::DEFAULT_BIND_HOST = "localhost"
 
static constexpr auto mavconn::MAVConnTCPServer::DEFAULT_BIND_HOST = "localhost"
 
static constexpr auto mavconn::MAVConnUDP::DEFAULT_BIND_PORT = 14555
 
static constexpr auto mavconn::MAVConnTCPServer::DEFAULT_BIND_PORT = 5760
 
static constexpr auto mavconn::MAVConnSerial::DEFAULT_DEVICE = "/dev/ttyACM0"
 
static constexpr auto mavconn::MAVConnUDP::DEFAULT_REMOTE_HOST = ""
 
static constexpr auto mavconn::MAVConnUDP::DEFAULT_REMOTE_PORT = 14550
 
static constexpr auto mavconn::MAVConnTCPClient::DEFAULT_SERVER_HOST = "localhost"
 
static constexpr auto mavconn::MAVConnTCPClient::DEFAULT_SERVER_PORT = 5760
 
static std::once_flag mavconn::MAVConnInterface::init_flag
 init_msg_entry() once flag More...
 
boost::asio::io_service mavconn::MAVConnSerial::io_service
 
boost::asio::io_service mavconn::MAVConnUDP::io_service
 
boost::asio::io_service mavconn::MAVConnTCPClient::io_service
 
boost::asio::io_service mavconn::MAVConnTCPServer::io_service
 
std::thread mavconn::MAVConnSerial::io_thread
 
std::thread mavconn::MAVConnUDP::io_thread
 
std::thread mavconn::MAVConnTCPClient::io_thread
 
std::thread mavconn::MAVConnTCPServer::io_thread
 
std::unique_ptr< boost::asio::io_service::work > mavconn::MAVConnUDP::io_work
 
std::unique_ptr< boost::asio::io_service::work > mavconn::MAVConnTCPClient::io_work
 
std::unique_ptr< boost::asio::io_service::work > mavconn::MAVConnTCPServer::io_work
 
std::recursive_mutex mavconn::MAVConnInterface::iostat_mutex
 
std::atomic< bool > mavconn::MAVConnTCPClient::is_destroying
 
std::atomic< bool > mavconn::MAVConnTCPServer::is_destroying
 
std::chrono::time_point< steady_clockmavconn::MAVConnInterface::last_iostat
 
boost::asio::ip::udp::endpoint mavconn::MAVConnUDP::last_remote_ep
 
size_t mavconn::MAVConnInterface::last_rx_total_bytes
 
size_t mavconn::MAVConnInterface::last_tx_total_bytes
 
ssize_t mavconn::MsgBuffer::len
 
mavlink::mavlink_message_t mavconn::MAVConnInterface::m_buffer
 
mavlink::mavlink_status_t mavconn::MAVConnInterface::m_mavlink_status
 
mavlink::mavlink_status_t mavconn::MAVConnInterface::m_parse_status
 
static constexpr auto mavconn::MAV_COMP_ID_UDP_BRIDGE = 240
 Same as mavlink::common::MAV_COMPONENT::COMP_ID_UDP_BRIDGE. More...
 
static constexpr size_t mavconn::MAVConnInterface::MAX_PACKET_SIZE = MAVLINK_MAX_PACKET_LEN + 16
 Maximum mavlink packet size + some extra bytes for padding. More...
 
static constexpr ssize_t mavconn::MsgBuffer::MAX_SIZE = MAVLINK_MAX_PACKET_LEN + 16
 Maximum buffer size with padding for CRC bytes (280 + padding) More...
 
static constexpr size_t mavconn::MAVConnInterface::MAX_TXQ_SIZE = 1000
 Maximum count of transmission buffers. More...
 
static std::unordered_map< mavlink::msgid_t, const mavlink::mavlink_msg_entry_t * > mavconn::MAVConnInterface::message_entries {}
 This map merge all dialect mavlink_msg_entry_t structs. Needed for packet parser. More...
 
ReceivedCb mavconn::MAVConnInterface::message_received_cb
 Message receive callback. More...
 
std::recursive_mutex mavconn::MAVConnSerial::mutex
 
std::recursive_mutex mavconn::MAVConnTCPClient::mutex
 
std::recursive_mutex mavconn::MAVConnUDP::mutex
 
std::recursive_mutex mavconn::MAVConnTCPServer::mutex
 
bool mavconn::MAVConnUDP::permanent_broadcast
 
static constexpr auto mavconn::MAVConnUDP::PERMANENT_BROADCAST_REMOTE_HOST = "***permanent broadcast***"
 
ClosedCb mavconn::MAVConnInterface::port_closed_cb
 Port closed notification callback. More...
 
ssize_t mavconn::MsgBuffer::pos
 
boost::asio::ip::udp::endpoint mavconn::MAVConnUDP::recv_ep
 
boost::asio::ip::udp::endpoint mavconn::MAVConnUDP::remote_ep
 
std::atomic< bool > mavconn::MAVConnUDP::remote_exists
 
std::array< uint8_t, MsgBuffer::MAX_SIZEmavconn::MAVConnSerial::rx_buf
 
std::array< uint8_t, MsgBuffer::MAX_SIZEmavconn::MAVConnTCPClient::rx_buf
 
std::array< uint8_t, MsgBuffer::MAX_SIZEmavconn::MAVConnUDP::rx_buf
 
float mavconn::MAVConnInterface::IOStat::rx_speed
 current receive speed [B/s] More...
 
size_t mavconn::MAVConnInterface::IOStat::rx_total_bytes
 total bytes received More...
 
std::atomic< size_t > mavconn::MAVConnInterface::rx_total_bytes
 
boost::asio::serial_port mavconn::MAVConnSerial::serial_dev
 
boost::asio::ip::tcp::endpoint mavconn::MAVConnTCPClient::server_ep
 
boost::asio::ip::tcp::socket mavconn::MAVConnTCPClient::socket
 
boost::asio::ip::udp::socket mavconn::MAVConnUDP::socket
 
uint8_t mavconn::MAVConnInterface::sys_id
 Connection System Id. More...
 
std::atomic< bool > mavconn::MAVConnSerial::tx_in_progress
 
std::atomic< bool > mavconn::MAVConnTCPClient::tx_in_progress
 
std::atomic< bool > mavconn::MAVConnUDP::tx_in_progress
 
std::deque< MsgBuffermavconn::MAVConnSerial::tx_q
 
std::deque< MsgBuffermavconn::MAVConnTCPClient::tx_q
 
std::deque< MsgBuffermavconn::MAVConnUDP::tx_q
 
float mavconn::MAVConnInterface::IOStat::tx_speed
 current transfer speed [B/s] More...
 
size_t mavconn::MAVConnInterface::IOStat::tx_total_bytes
 total bytes transferred More...
 
std::atomic< size_t > mavconn::MAVConnInterface::tx_total_bytes
 

Friends

class mavconn::MAVConnTCPClient::MAVConnTCPServer
 
const mavlink::mavlink_msg_entry_tmavconn::MAVConnInterface::mavlink::mavlink_get_msg_entry (uint32_t msgid)
 

Detailed Description

MAVConn connection handling library.

This lib provide simple interface to MAVLink enabled devices such as autopilots.

Macro Definition Documentation

◆ CONSOLE_BRIDGE_logDebug

#define CONSOLE_BRIDGE_logDebug (   fmt,
  ... 
)    console_bridge::log(__FILE__, __LINE__, console_bridge::CONSOLE_BRIDGE_LOG_DEBUG, fmt, ##__VA_ARGS__)

Definition at line 39 of file console_bridge_compat.h.

◆ CONSOLE_BRIDGE_logError

#define CONSOLE_BRIDGE_logError (   fmt,
  ... 
)    console_bridge::log(__FILE__, __LINE__, console_bridge::CONSOLE_BRIDGE_LOG_ERROR, fmt, ##__VA_ARGS__)

Definition at line 54 of file console_bridge_compat.h.

◆ CONSOLE_BRIDGE_logInform

#define CONSOLE_BRIDGE_logInform (   fmt,
  ... 
)    console_bridge::log(__FILE__, __LINE__, console_bridge::CONSOLE_BRIDGE_LOG_INFO, fmt, ##__VA_ARGS__)

Definition at line 44 of file console_bridge_compat.h.

◆ CONSOLE_BRIDGE_logWarn

#define CONSOLE_BRIDGE_logWarn (   fmt,
  ... 
)    console_bridge::log(__FILE__, __LINE__, console_bridge::CONSOLE_BRIDGE_LOG_WARN, fmt, ##__VA_ARGS__)

Definition at line 49 of file console_bridge_compat.h.

◆ GET_IO_SERVICE

#define GET_IO_SERVICE (   s)    ((s).get_io_service())

Definition at line 28 of file tcp.cpp.

◆ PFX [1/4]

#define PFX   "mavconn: "

Definition at line 29 of file interface.cpp.

◆ PFX [2/4]

#define PFX   "mavconn: udp"

Definition at line 34 of file udp.cpp.

◆ PFX [3/4]

#define PFX   "mavconn: serial"

Definition at line 36 of file serial.cpp.

◆ PFX [4/4]

#define PFX   "mavconn: tcp"

Definition at line 41 of file tcp.cpp.

◆ PFXd [1/3]

#define PFXd   PFX "%zu: "

Definition at line 35 of file udp.cpp.

◆ PFXd [2/3]

#define PFXd   PFX "%zu: "

Definition at line 37 of file serial.cpp.

◆ PFXd [3/3]

#define PFXd   PFX "%zu: "

Definition at line 42 of file tcp.cpp.

Typedef Documentation

◆ ClosedCb

using mavconn::MAVConnInterface::ClosedCb = std::function<void (void)>

Definition at line 103 of file interface.h.

◆ ConstPtr

using mavconn::MAVConnInterface::ConstPtr = std::shared_ptr<MAVConnInterface const>

Definition at line 105 of file interface.h.

◆ lock_guard

using mavconn::lock_guard = typedef std::lock_guard<std::recursive_mutex>

Definition at line 42 of file interface.h.

◆ Ptr

Definition at line 104 of file interface.h.

◆ ReceivedCb

using mavconn::MAVConnInterface::ReceivedCb = std::function<void (const mavlink::mavlink_message_t *message, const Framing framing)>

Definition at line 102 of file interface.h.

◆ steady_clock

using mavconn::steady_clock = typedef std::chrono::steady_clock

Definition at line 41 of file interface.h.

◆ WeakPtr

Definition at line 106 of file interface.h.

Enumeration Type Documentation

◆ Framing

enum mavconn::Framing : uint8_t
strong

Rx packer framing status. (same as mavlink::mavlink_framing_t)

Enumerator
incomplete 
ok 
bad_crc 
bad_signature 

Definition at line 48 of file interface.h.

◆ Protocol

enum mavconn::Protocol : uint8_t
strong

MAVLink protocol version.

Enumerator
V10 

MAVLink v1.0.

V20 

MAVLink v2.0.

Definition at line 56 of file interface.h.

Function Documentation

◆ client_closed()

void mavconn::MAVConnTCPServer::client_closed ( std::weak_ptr< MAVConnTCPClient weak_instp)
private

Definition at line 464 of file tcp.cpp.

◆ client_connected()

void mavconn::MAVConnTCPClient::client_connected ( size_t  server_channel)
private

This special function called by TCP server when connection accepted.

Definition at line 114 of file tcp.cpp.

◆ close() [1/5]

void mavconn::MAVConnSerial::close ( )
overridevirtual

Close connection.

Implements mavconn::MAVConnInterface.

Definition at line 133 of file serial.cpp.

◆ close() [2/5]

void mavconn::MAVConnUDP::close ( )
overridevirtual

Close connection.

Implements mavconn::MAVConnInterface.

Definition at line 146 of file udp.cpp.

◆ close() [3/5]

void mavconn::MAVConnTCPClient::close ( )
overridevirtual

Close connection.

Implements mavconn::MAVConnInterface.

Definition at line 146 of file tcp.cpp.

◆ close() [4/5]

void mavconn::MAVConnTCPServer::close ( )
overridevirtual

Close connection.

Implements mavconn::MAVConnInterface.

Definition at line 343 of file tcp.cpp.

◆ close() [5/5]

virtual void mavconn::MAVConnInterface::close ( )
pure virtual

◆ connect() [1/5]

void mavconn::MAVConnSerial::connect ( const ReceivedCb cb_handle_message,
const ClosedCb cb_handle_closed_port = ClosedCb() 
)
overridevirtual

Establish connection, automatically called by open_url()

Implements mavconn::MAVConnInterface.

Definition at line 116 of file serial.cpp.

◆ connect() [2/5]

void mavconn::MAVConnUDP::connect ( const ReceivedCb cb_handle_message,
const ClosedCb cb_handle_closed_port = ClosedCb() 
)
overridevirtual

Establish connection, automatically called by open_url()

Implements mavconn::MAVConnInterface.

Definition at line 129 of file udp.cpp.

◆ connect() [3/5]

void mavconn::MAVConnTCPClient::connect ( const ReceivedCb cb_handle_message,
const ClosedCb cb_handle_closed_port = ClosedCb() 
)
overridevirtual

Establish connection, automatically called by open_url()

Implements mavconn::MAVConnInterface.

Definition at line 129 of file tcp.cpp.

◆ connect() [4/5]

void mavconn::MAVConnTCPServer::connect ( const ReceivedCb cb_handle_message,
const ClosedCb cb_handle_closed_port = ClosedCb() 
)
overridevirtual

Establish connection, automatically called by open_url()

Implements mavconn::MAVConnInterface.

Definition at line 326 of file tcp.cpp.

◆ connect() [5/5]

virtual void mavconn::MAVConnInterface::connect ( const ReceivedCb cb_handle_message,
const ClosedCb cb_handle_closed_port = ClosedCb() 
)
pure virtual

Establish connection, automatically called by open_url()

Implemented in mavconn::MAVConnTCPServer, mavconn::MAVConnTCPClient, mavconn::MAVConnUDP, and mavconn::MAVConnSerial.

◆ DeviceError()

template<typename T >
mavconn::DeviceError::DeviceError ( const char *  module,
msg 
)
inline

Construct error.

Definition at line 70 of file interface.h.

◆ do_accept()

void mavconn::MAVConnTCPServer::do_accept ( )
private

Definition at line 433 of file tcp.cpp.

◆ do_read()

void mavconn::MAVConnSerial::do_read ( void  )
private

Definition at line 213 of file serial.cpp.

◆ do_recv()

void mavconn::MAVConnTCPClient::do_recv ( )
private

Definition at line 231 of file tcp.cpp.

◆ do_recvfrom()

void mavconn::MAVConnUDP::do_recvfrom ( )
private

Definition at line 242 of file udp.cpp.

◆ do_send()

void mavconn::MAVConnTCPClient::do_send ( bool  check_tx_state)
private

Definition at line 251 of file tcp.cpp.

◆ do_sendto()

void mavconn::MAVConnUDP::do_sendto ( bool  check_tx_state)
private

Definition at line 266 of file udp.cpp.

◆ do_write()

void mavconn::MAVConnSerial::do_write ( bool  check_tx_state)
private

Definition at line 230 of file serial.cpp.

◆ dpos()

uint8_t* mavconn::MsgBuffer::dpos ( )
inline

Definition at line 86 of file msgbuffer.h.

◆ get_buffer_p()

mavlink::mavlink_message_t* mavconn::MAVConnInterface::get_buffer_p ( )
inlineprotected

Definition at line 280 of file interface.h.

◆ get_component_id()

uint8_t mavconn::MAVConnInterface::get_component_id ( )
inline

Definition at line 214 of file interface.h.

◆ get_iostat() [1/2]

MAVConnInterface::IOStat mavconn::MAVConnTCPServer::get_iostat ( )
overridevirtual

Reimplemented from mavconn::MAVConnInterface.

Definition at line 386 of file tcp.cpp.

◆ get_iostat() [2/2]

MAVConnInterface::IOStat mavconn::MAVConnInterface::get_iostat ( )
virtual

Reimplemented in mavconn::MAVConnTCPServer.

Definition at line 61 of file interface.cpp.

◆ get_known_dialects()

static std::vector<std::string> mavconn::MAVConnInterface::get_known_dialects ( )
static

◆ get_protocol_version()

Protocol mavconn::MAVConnInterface::get_protocol_version ( )

Definition at line 186 of file interface.cpp.

◆ get_remote_endpoint()

std::string mavconn::MAVConnUDP::get_remote_endpoint ( ) const

Definition at line 314 of file udp.cpp.

◆ get_status() [1/2]

mavlink_status_t mavconn::MAVConnTCPServer::get_status ( )
overridevirtual

Reimplemented from mavconn::MAVConnInterface.

Definition at line 362 of file tcp.cpp.

◆ get_status() [2/2]

mavlink_status_t mavconn::MAVConnInterface::get_status ( )
virtual

Reimplemented in mavconn::MAVConnTCPServer.

Definition at line 56 of file interface.cpp.

◆ get_status_p()

mavlink::mavlink_status_t* mavconn::MAVConnInterface::get_status_p ( )
inlineprotected

Definition at line 276 of file interface.h.

◆ get_system_id()

uint8_t mavconn::MAVConnInterface::get_system_id ( )
inline

Definition at line 208 of file interface.h.

◆ init_msg_entry()

static void mavconn::MAVConnInterface::init_msg_entry ( )
staticprivate

Initialize message_entries map

autogenerated. placed in mavlink_helpers.cpp

◆ iostat_rx_add()

void mavconn::MAVConnInterface::iostat_rx_add ( size_t  bytes)
protected

Definition at line 91 of file interface.cpp.

◆ iostat_tx_add()

void mavconn::MAVConnInterface::iostat_tx_add ( size_t  bytes)
protected

Definition at line 86 of file interface.cpp.

◆ is_open() [1/5]

bool mavconn::MAVConnSerial::is_open ( )
inlineoverridevirtual

Implements mavconn::MAVConnInterface.

Definition at line 54 of file serial.h.

◆ is_open() [2/5]

bool mavconn::MAVConnUDP::is_open ( )
inlineoverridevirtual

Implements mavconn::MAVConnInterface.

Definition at line 62 of file udp.h.

◆ is_open() [3/5]

bool mavconn::MAVConnTCPClient::is_open ( )
inlineoverridevirtual

Implements mavconn::MAVConnInterface.

Definition at line 63 of file tcp.h.

◆ is_open() [4/5]

bool mavconn::MAVConnTCPServer::is_open ( )
inlineoverridevirtual

Implements mavconn::MAVConnInterface.

Definition at line 122 of file tcp.h.

◆ is_open() [5/5]

virtual bool mavconn::MAVConnInterface::is_open ( )
pure virtual

◆ log_recv()

void mavconn::MAVConnInterface::log_recv ( const char *  pfx,
mavlink::mavlink_message_t msg,
Framing  framing 
)
protected

Definition at line 117 of file interface.cpp.

◆ log_send()

void mavconn::MAVConnInterface::log_send ( const char *  pfx,
const mavlink::mavlink_message_t msg 
)
protected

Definition at line 132 of file interface.cpp.

◆ log_send_obj()

void mavconn::MAVConnInterface::log_send_obj ( const char *  pfx,
const mavlink::Message msg 
)
protected

Definition at line 142 of file interface.cpp.

◆ make_message()

template<typename T >
static std::string mavconn::DeviceError::make_message ( const char *  module,
msg 
)
inlinestatic

Definition at line 75 of file interface.h.

◆ MAVConnInterface() [1/2]

mavconn::MAVConnInterface::MAVConnInterface ( const MAVConnInterface )
privatedelete

◆ MAVConnInterface() [2/2]

mavconn::MAVConnInterface::MAVConnInterface ( uint8_t  system_id = 1,
uint8_t  component_id = MAV_COMP_ID_UDP_BRIDGE 
)
Parameters
[in]system_idsysid for send_message
[in]component_idcompid for send_message

Definition at line 40 of file interface.cpp.

◆ MAVConnSerial()

mavconn::MAVConnSerial::MAVConnSerial ( uint8_t  system_id = 1,
uint8_t  component_id = MAV_COMP_ID_UDP_BRIDGE,
std::string  device = DEFAULT_DEVICE,
unsigned  baudrate = DEFAULT_BAUDRATE,
bool  hwflow = false 
)

Open and run serial link.

Parameters
[in]deviceTTY device path
[in]baudrateserial baudrate

Definition at line 40 of file serial.cpp.

◆ MAVConnTCPClient() [1/2]

mavconn::MAVConnTCPClient::MAVConnTCPClient ( uint8_t  system_id = 1,
uint8_t  component_id = MAV_COMP_ID_UDP_BRIDGE,
std::string  server_host = DEFAULT_SERVER_HOST,
unsigned short  server_port = DEFAULT_SERVER_PORT 
)

Create generic TCP client (connect to the server)

Parameters

Definition at line 77 of file tcp.cpp.

◆ MAVConnTCPClient() [2/2]

mavconn::MAVConnTCPClient::MAVConnTCPClient ( uint8_t  system_id,
uint8_t  component_id,
boost::asio::io_service &  server_io 
)
explicit

Special client variation for use in MAVConnTCPServer

Definition at line 102 of file tcp.cpp.

◆ MAVConnTCPServer()

mavconn::MAVConnTCPServer::MAVConnTCPServer ( uint8_t  system_id = 1,
uint8_t  component_id = MAV_COMP_ID_UDP_BRIDGE,
std::string  bind_host = DEFAULT_BIND_HOST,
unsigned short  bind_port = DEFAULT_BIND_PORT 
)
Parameters

Definition at line 297 of file tcp.cpp.

◆ MAVConnUDP()

mavconn::MAVConnUDP::MAVConnUDP ( uint8_t  system_id = 1,
uint8_t  component_id = MAV_COMP_ID_UDP_BRIDGE,
std::string  bind_host = DEFAULT_BIND_HOST,
unsigned short  bind_port = DEFAULT_BIND_PORT,
std::string  remote_host = DEFAULT_REMOTE_HOST,
unsigned short  remote_port = DEFAULT_REMOTE_PORT 
)
Parameters

Definition at line 68 of file udp.cpp.

◆ msg_to_string() [1/3]

static std::string mavconn::DeviceError::msg_to_string ( const char *  description)
inlinestatic

Definition at line 81 of file interface.h.

◆ msg_to_string() [2/3]

static std::string mavconn::DeviceError::msg_to_string ( int  errnum)
inlinestatic

Definition at line 85 of file interface.h.

◆ msg_to_string() [3/3]

static std::string mavconn::DeviceError::msg_to_string ( boost::system::system_error &  err)
inlinestatic

Definition at line 89 of file interface.h.

◆ MsgBuffer() [1/4]

mavconn::MsgBuffer::MsgBuffer ( )
inline

Definition at line 34 of file msgbuffer.h.

◆ MsgBuffer() [2/4]

mavconn::MsgBuffer::MsgBuffer ( const mavlink::mavlink_message_t msg)
inlineexplicit

Buffer constructor from mavlink_message_t.

Definition at line 42 of file msgbuffer.h.

◆ MsgBuffer() [3/4]

mavconn::MsgBuffer::MsgBuffer ( const mavlink::Message obj,
mavlink::mavlink_status_t status,
uint8_t  sysid,
uint8_t  compid 
)
inline

Buffer constructor for mavlink::Message derived object.

Definition at line 53 of file msgbuffer.h.

◆ MsgBuffer() [4/4]

mavconn::MsgBuffer::MsgBuffer ( const uint8_t *  bytes,
ssize_t  nbytes 
)
inline

Buffer constructor for send_bytes()

Parameters
[in]nbytesshould be less than MAX_SIZE

Definition at line 73 of file msgbuffer.h.

◆ nbytes()

ssize_t mavconn::MsgBuffer::nbytes ( )
inline

Definition at line 90 of file msgbuffer.h.

◆ open_url()

MAVConnInterface::Ptr mavconn::MAVConnInterface::open_url ( std::string  url,
uint8_t  system_id = 1,
uint8_t  component_id = MAV_COMP_ID_UDP_BRIDGE,
const ReceivedCb cb_handle_message = ReceivedCb(),
const ClosedCb cb_handle_closed_port = ClosedCb() 
)
static

Construct connection from URL.

Supported URL schemas:

  • serial://
  • udp://
  • tcp://
  • tcp-l://

Please see user's documentation for details.

Parameters
[in]urlresource locator
[in]system_idoptional system id
[in]component_idoptional component id
Returns
Ptr to constructed interface class, or throw DeviceError if error occured.

Definition at line 409 of file interface.cpp.

◆ open_url_no_connect()

MAVConnInterface::Ptr mavconn::MAVConnInterface::open_url_no_connect ( std::string  url,
uint8_t  system_id = 1,
uint8_t  component_id = MAV_COMP_ID_UDP_BRIDGE 
)
static

version of open_url() which do not perform connect()

Definition at line 339 of file interface.cpp.

◆ parse_buffer()

void mavconn::MAVConnInterface::parse_buffer ( const char *  pfx,
uint8_t *  buf,
const size_t  bufsize,
size_t  bytes_received 
)
protected

Parse buffer and emit massage_received.

Definition at line 96 of file interface.cpp.

◆ resolve_address_tcp()

static bool mavconn::resolve_address_tcp ( io_service &  io,
size_t  chan,
std::string  host,
unsigned short  port,
tcp::endpoint &  ep 
)
static

Definition at line 45 of file tcp.cpp.

◆ resolve_address_udp()

static bool mavconn::resolve_address_udp ( io_service &  io,
size_t  chan,
std::string  host,
unsigned short  port,
udp::endpoint &  ep 
)
static

Definition at line 38 of file udp.cpp.

◆ send_bytes() [1/5]

void mavconn::MAVConnSerial::send_bytes ( const uint8_t *  bytes,
size_t  length 
)
overridevirtual

Send raw bytes (for some quirks)

Exceptions
std::length_errorOn exceeding Tx queue limit (MAX_TXQ_SIZE)

Implements mavconn::MAVConnInterface.

Definition at line 153 of file serial.cpp.

◆ send_bytes() [2/5]

void mavconn::MAVConnUDP::send_bytes ( const uint8_t *  bytes,
size_t  length 
)
overridevirtual

Send raw bytes (for some quirks)

Exceptions
std::length_errorOn exceeding Tx queue limit (MAX_TXQ_SIZE)

Implements mavconn::MAVConnInterface.

Definition at line 167 of file udp.cpp.

◆ send_bytes() [3/5]

void mavconn::MAVConnTCPClient::send_bytes ( const uint8_t *  bytes,
size_t  length 
)
overridevirtual

Send raw bytes (for some quirks)

Exceptions
std::length_errorOn exceeding Tx queue limit (MAX_TXQ_SIZE)

Implements mavconn::MAVConnInterface.

Definition at line 171 of file tcp.cpp.

◆ send_bytes() [4/5]

void mavconn::MAVConnTCPServer::send_bytes ( const uint8_t *  bytes,
size_t  length 
)
overridevirtual

Send raw bytes (for some quirks)

Exceptions
std::length_errorOn exceeding Tx queue limit (MAX_TXQ_SIZE)

Implements mavconn::MAVConnInterface.

Definition at line 409 of file tcp.cpp.

◆ send_bytes() [5/5]

virtual void mavconn::MAVConnInterface::send_bytes ( const uint8_t *  bytes,
size_t  length 
)
pure virtual

Send raw bytes (for some quirks)

Exceptions
std::length_errorOn exceeding Tx queue limit (MAX_TXQ_SIZE)

Implemented in mavconn::MAVConnTCPServer, mavconn::MAVConnTCPClient, mavconn::MAVConnUDP, and mavconn::MAVConnSerial.

◆ send_message() [1/11]

void mavconn::MAVConnSerial::send_message ( const mavlink::mavlink_message_t message)
overridevirtual

Send message (mavlink_message_t)

Can be used to forward messages from other connection channel.

Note
Does not do finalization!
Exceptions
std::length_errorOn exceeding Tx queue limit (MAX_TXQ_SIZE)
Parameters
[in]*messagenot changed

Implements mavconn::MAVConnInterface.

◆ send_message() [2/11]

void mavconn::MAVConnSerial::send_message ( const mavlink::Message message,
const uint8_t  src_compid 
)
overridevirtual

Send message (child of mavlink::Message)

Does serialization inside. System ID = from this object. Component ID passed by argument.

Exceptions
std::length_errorOn exceeding Tx queue limit (MAX_TXQ_SIZE)
Parameters
[in]&messagenot changed
[in]src_compidsets the component ID of the message source

Implements mavconn::MAVConnInterface.

Definition at line 193 of file serial.cpp.

◆ send_message() [3/11]

void mavconn::MAVConnUDP::send_message ( const mavlink::mavlink_message_t message)
overridevirtual

Send message (mavlink_message_t)

Can be used to forward messages from other connection channel.

Note
Does not do finalization!
Exceptions
std::length_errorOn exceeding Tx queue limit (MAX_TXQ_SIZE)
Parameters
[in]*messagenot changed

Implements mavconn::MAVConnInterface.

◆ send_message() [4/11]

void mavconn::MAVConnUDP::send_message ( const mavlink::Message message,
const uint8_t  src_compid 
)
overridevirtual

Send message (child of mavlink::Message)

Does serialization inside. System ID = from this object. Component ID passed by argument.

Exceptions
std::length_errorOn exceeding Tx queue limit (MAX_TXQ_SIZE)
Parameters
[in]&messagenot changed
[in]src_compidsets the component ID of the message source

Implements mavconn::MAVConnInterface.

Definition at line 217 of file udp.cpp.

◆ send_message() [5/11]

void mavconn::MAVConnTCPClient::send_message ( const mavlink::mavlink_message_t message)
overridevirtual

Send message (mavlink_message_t)

Can be used to forward messages from other connection channel.

Note
Does not do finalization!
Exceptions
std::length_errorOn exceeding Tx queue limit (MAX_TXQ_SIZE)
Parameters
[in]*messagenot changed

Implements mavconn::MAVConnInterface.

◆ send_message() [6/11]

void mavconn::MAVConnTCPClient::send_message ( const mavlink::Message message,
const uint8_t  src_compid 
)
overridevirtual

Send message (child of mavlink::Message)

Does serialization inside. System ID = from this object. Component ID passed by argument.

Exceptions
std::length_errorOn exceeding Tx queue limit (MAX_TXQ_SIZE)
Parameters
[in]&messagenot changed
[in]src_compidsets the component ID of the message source

Implements mavconn::MAVConnInterface.

Definition at line 211 of file tcp.cpp.

◆ send_message() [7/11]

void mavconn::MAVConnTCPServer::send_message ( const mavlink::mavlink_message_t message)
overridevirtual

Send message (mavlink_message_t)

Can be used to forward messages from other connection channel.

Note
Does not do finalization!
Exceptions
std::length_errorOn exceeding Tx queue limit (MAX_TXQ_SIZE)
Parameters
[in]*messagenot changed

Implements mavconn::MAVConnInterface.

◆ send_message() [8/11]

void mavconn::MAVConnTCPServer::send_message ( const mavlink::Message message,
const uint8_t  src_compid 
)
overridevirtual

Send message (child of mavlink::Message)

Does serialization inside. System ID = from this object. Component ID passed by argument.

Exceptions
std::length_errorOn exceeding Tx queue limit (MAX_TXQ_SIZE)
Parameters
[in]&messagenot changed
[in]src_compidsets the component ID of the message source

Implements mavconn::MAVConnInterface.

Definition at line 425 of file tcp.cpp.

◆ send_message() [9/11]

virtual void mavconn::MAVConnInterface::send_message ( const mavlink::mavlink_message_t message)
pure virtual

Send message (mavlink_message_t)

Can be used to forward messages from other connection channel.

Note
Does not do finalization!
Exceptions
std::length_errorOn exceeding Tx queue limit (MAX_TXQ_SIZE)
Parameters
[in]*messagenot changed

Implemented in mavconn::MAVConnTCPServer, mavconn::MAVConnTCPClient, mavconn::MAVConnUDP, and mavconn::MAVConnSerial.

◆ send_message() [10/11]

virtual void mavconn::MAVConnInterface::send_message ( const mavlink::Message message)
inlinevirtual

Send message (child of mavlink::Message)

Does serialization inside. System and Component ID = from this object.

Exceptions
std::length_errorOn exceeding Tx queue limit (MAX_TXQ_SIZE)
Parameters
[in]&messagenot changed

Definition at line 154 of file interface.h.

◆ send_message() [11/11]

virtual void mavconn::MAVConnInterface::send_message ( const mavlink::Message message,
const uint8_t  src_compid 
)
pure virtual

Send message (child of mavlink::Message)

Does serialization inside. System ID = from this object. Component ID passed by argument.

Exceptions
std::length_errorOn exceeding Tx queue limit (MAX_TXQ_SIZE)
Parameters
[in]&messagenot changed
[in]src_compidsets the component ID of the message source

Implemented in mavconn::MAVConnTCPServer, mavconn::MAVConnTCPClient, mavconn::MAVConnUDP, and mavconn::MAVConnSerial.

◆ send_message_ignore_drop() [1/3]

void mavconn::MAVConnInterface::send_message_ignore_drop ( const mavlink::mavlink_message_t message)

Send message and ignore possible drop due to Tx queue limit.

Definition at line 147 of file interface.cpp.

◆ send_message_ignore_drop() [2/3]

void mavconn::MAVConnInterface::send_message_ignore_drop ( const mavlink::Message message)
inline

Send message and ignore possible drop due to Tx queue limit.

System and Component ID = from this object.

Definition at line 187 of file interface.h.

◆ send_message_ignore_drop() [3/3]

void mavconn::MAVConnInterface::send_message_ignore_drop ( const mavlink::Message message,
const uint8_t  src_compid 
)

Send message and ignore possible drop due to Tx queue limit.

System ID = from this object. Component ID passed by argument.

Definition at line 160 of file interface.cpp.

◆ set_component_id()

void mavconn::MAVConnInterface::set_component_id ( uint8_t  compid)
inline

Definition at line 217 of file interface.h.

◆ set_protocol_version()

void mavconn::MAVConnInterface::set_protocol_version ( Protocol  pver)

Set protocol used for encoding mavlink::Mavlink messages.

Definition at line 173 of file interface.cpp.

◆ set_system_id()

void mavconn::MAVConnInterface::set_system_id ( uint8_t  sysid)
inline

Definition at line 211 of file interface.h.

◆ url_parse_host()

static void mavconn::url_parse_host ( std::string  host,
std::string &  host_out,
int port_out,
const std::string  def_host,
const int  def_port 
)
static

Parse host:port pairs

Definition at line 197 of file interface.cpp.

◆ url_parse_query()

static void mavconn::url_parse_query ( std::string  query,
uint8_t &  sysid,
uint8_t &  compid 
)
static

Parse ?ids=sid,cid

Definition at line 233 of file interface.cpp.

◆ url_parse_serial()

static MAVConnInterface::Ptr mavconn::url_parse_serial ( std::string  path,
std::string  query,
uint8_t  system_id,
uint8_t  component_id,
bool  hwflow 
)
static

Definition at line 264 of file interface.cpp.

◆ url_parse_tcp_client()

static MAVConnInterface::Ptr mavconn::url_parse_tcp_client ( std::string  host,
std::string  query,
uint8_t  system_id,
uint8_t  component_id 
)
static

Definition at line 309 of file interface.cpp.

◆ url_parse_tcp_server()

static MAVConnInterface::Ptr mavconn::url_parse_tcp_server ( std::string  host,
std::string  query,
uint8_t  system_id,
uint8_t  component_id 
)
static

Definition at line 324 of file interface.cpp.

◆ url_parse_udp()

static MAVConnInterface::Ptr mavconn::url_parse_udp ( std::string  hosts,
std::string  query,
uint8_t  system_id,
uint8_t  component_id,
bool  is_udpb,
bool  permanent_broadcast 
)
static

Definition at line 279 of file interface.cpp.

◆ ~MAVConnSerial()

mavconn::MAVConnSerial::~MAVConnSerial ( )
virtual

Definition at line 111 of file serial.cpp.

◆ ~MAVConnTCPClient()

mavconn::MAVConnTCPClient::~MAVConnTCPClient ( )
virtual

Definition at line 123 of file tcp.cpp.

◆ ~MAVConnTCPServer()

mavconn::MAVConnTCPServer::~MAVConnTCPServer ( )
virtual

Definition at line 320 of file tcp.cpp.

◆ ~MAVConnUDP()

mavconn::MAVConnUDP::~MAVConnUDP ( )
virtual

Definition at line 124 of file udp.cpp.

◆ ~MsgBuffer()

virtual mavconn::MsgBuffer::~MsgBuffer ( )
inlinevirtual

Definition at line 81 of file msgbuffer.h.

Variable Documentation

◆ acceptor

boost::asio::ip::tcp::acceptor mavconn::MAVConnTCPServer::acceptor
private

Definition at line 131 of file tcp.h.

◆ bind_ep [1/2]

boost::asio::ip::udp::endpoint mavconn::MAVConnUDP::bind_ep
private

Definition at line 79 of file udp.h.

◆ bind_ep [2/2]

boost::asio::ip::tcp::endpoint mavconn::MAVConnTCPServer::bind_ep
private

Definition at line 132 of file tcp.h.

◆ BROADCAST_REMOTE_HOST

constexpr auto mavconn::MAVConnUDP::BROADCAST_REMOTE_HOST = "***i want broadcast***"
static

Markers for broadcast modes. Not valid domain names.

Definition at line 39 of file udp.h.

◆ client_list

std::list<std::shared_ptr<MAVConnTCPClient> > mavconn::MAVConnTCPServer::client_list
private

Definition at line 136 of file tcp.h.

◆ comp_id

uint8_t mavconn::MAVConnInterface::comp_id
protected

Connection Component Id.

Definition at line 263 of file interface.h.

◆ conn_id

size_t mavconn::MAVConnInterface::conn_id
protected

Channel number used for logging.

Definition at line 274 of file interface.h.

◆ conn_id_counter

std::atomic< size_t > mavconn::MAVConnInterface::conn_id_counter {0}
staticprivate

monotonic counter (increment only)

Definition at line 309 of file interface.h.

◆ data

uint8_t mavconn::MsgBuffer::data[MAX_SIZE]

Definition at line 30 of file msgbuffer.h.

◆ DEFAULT_BAUDRATE

constexpr auto mavconn::MAVConnSerial::DEFAULT_BAUDRATE = 57600
static

Definition at line 33 of file serial.h.

◆ DEFAULT_BIND_HOST [1/2]

constexpr auto mavconn::MAVConnUDP::DEFAULT_BIND_HOST = "localhost"
static

Definition at line 34 of file udp.h.

◆ DEFAULT_BIND_HOST [2/2]

constexpr auto mavconn::MAVConnTCPServer::DEFAULT_BIND_HOST = "localhost"
static

Definition at line 100 of file tcp.h.

◆ DEFAULT_BIND_PORT [1/2]

constexpr auto mavconn::MAVConnUDP::DEFAULT_BIND_PORT = 14555
static

Definition at line 35 of file udp.h.

◆ DEFAULT_BIND_PORT [2/2]

constexpr auto mavconn::MAVConnTCPServer::DEFAULT_BIND_PORT = 5760
static

Definition at line 101 of file tcp.h.

◆ DEFAULT_DEVICE

constexpr auto mavconn::MAVConnSerial::DEFAULT_DEVICE = "/dev/ttyACM0"
static

Definition at line 32 of file serial.h.

◆ DEFAULT_REMOTE_HOST

constexpr auto mavconn::MAVConnUDP::DEFAULT_REMOTE_HOST = ""
static

Definition at line 36 of file udp.h.

◆ DEFAULT_REMOTE_PORT

constexpr auto mavconn::MAVConnUDP::DEFAULT_REMOTE_PORT = 14550
static

Definition at line 37 of file udp.h.

◆ DEFAULT_SERVER_HOST

constexpr auto mavconn::MAVConnTCPClient::DEFAULT_SERVER_HOST = "localhost"
static

Definition at line 37 of file tcp.h.

◆ DEFAULT_SERVER_PORT

constexpr auto mavconn::MAVConnTCPClient::DEFAULT_SERVER_PORT = 5760
static

Definition at line 38 of file tcp.h.

◆ init_flag

std::once_flag mavconn::MAVConnInterface::init_flag
staticprivate

init_msg_entry() once flag

Definition at line 312 of file interface.h.

◆ io_service [1/4]

boost::asio::io_service mavconn::MAVConnSerial::io_service
private

Definition at line 59 of file serial.h.

◆ io_service [2/4]

boost::asio::io_service mavconn::MAVConnUDP::io_service
private

Definition at line 69 of file udp.h.

◆ io_service [3/4]

boost::asio::io_service mavconn::MAVConnTCPClient::io_service
private

Definition at line 69 of file tcp.h.

◆ io_service [4/4]

boost::asio::io_service mavconn::MAVConnTCPServer::io_service
private

Definition at line 127 of file tcp.h.

◆ io_thread [1/4]

std::thread mavconn::MAVConnSerial::io_thread
private

Definition at line 60 of file serial.h.

◆ io_thread [2/4]

std::thread mavconn::MAVConnUDP::io_thread
private

Definition at line 71 of file udp.h.

◆ io_thread [3/4]

std::thread mavconn::MAVConnTCPClient::io_thread
private

Definition at line 71 of file tcp.h.

◆ io_thread [4/4]

std::thread mavconn::MAVConnTCPServer::io_thread
private

Definition at line 129 of file tcp.h.

◆ io_work [1/3]

std::unique_ptr<boost::asio::io_service::work> mavconn::MAVConnUDP::io_work
private

Definition at line 70 of file udp.h.

◆ io_work [2/3]

std::unique_ptr<boost::asio::io_service::work> mavconn::MAVConnTCPClient::io_work
private

Definition at line 70 of file tcp.h.

◆ io_work [3/3]

std::unique_ptr<boost::asio::io_service::work> mavconn::MAVConnTCPServer::io_work
private

Definition at line 128 of file tcp.h.

◆ iostat_mutex

std::recursive_mutex mavconn::MAVConnInterface::iostat_mutex
private

Definition at line 304 of file interface.h.

◆ is_destroying [1/2]

std::atomic<bool> mavconn::MAVConnTCPClient::is_destroying
private

Definition at line 76 of file tcp.h.

◆ is_destroying [2/2]

std::atomic<bool> mavconn::MAVConnTCPServer::is_destroying
private

Definition at line 134 of file tcp.h.

◆ last_iostat

std::chrono::time_point<steady_clock> mavconn::MAVConnInterface::last_iostat
private

Definition at line 306 of file interface.h.

◆ last_remote_ep

boost::asio::ip::udp::endpoint mavconn::MAVConnUDP::last_remote_ep
private

Definition at line 78 of file udp.h.

◆ last_rx_total_bytes

size_t mavconn::MAVConnInterface::last_rx_total_bytes
private

Definition at line 305 of file interface.h.

◆ last_tx_total_bytes

size_t mavconn::MAVConnInterface::last_tx_total_bytes
private

Definition at line 305 of file interface.h.

◆ len

ssize_t mavconn::MsgBuffer::len

Definition at line 31 of file msgbuffer.h.

◆ m_buffer

mavlink::mavlink_message_t mavconn::MAVConnInterface::m_buffer
private

Definition at line 300 of file interface.h.

◆ m_mavlink_status

mavlink::mavlink_status_t mavconn::MAVConnInterface::m_mavlink_status
private

Definition at line 301 of file interface.h.

◆ m_parse_status

mavlink::mavlink_status_t mavconn::MAVConnInterface::m_parse_status
private

Definition at line 299 of file interface.h.

◆ MAV_COMP_ID_UDP_BRIDGE

constexpr auto mavconn::MAV_COMP_ID_UDP_BRIDGE = 240
static

Same as mavlink::common::MAV_COMPONENT::COMP_ID_UDP_BRIDGE.

Definition at line 45 of file interface.h.

◆ MAX_PACKET_SIZE

constexpr size_t mavconn::MAVConnInterface::MAX_PACKET_SIZE = MAVLINK_MAX_PACKET_LEN + 16
staticprotected

Maximum mavlink packet size + some extra bytes for padding.

Definition at line 266 of file interface.h.

◆ MAX_SIZE

constexpr ssize_t mavconn::MsgBuffer::MAX_SIZE = MAVLINK_MAX_PACKET_LEN + 16
static

Maximum buffer size with padding for CRC bytes (280 + padding)

Definition at line 29 of file msgbuffer.h.

◆ MAX_TXQ_SIZE

constexpr size_t mavconn::MAVConnInterface::MAX_TXQ_SIZE = 1000
staticprotected

Maximum count of transmission buffers.

Definition at line 268 of file interface.h.

◆ message_entries

std::unordered_map< mavlink::msgid_t, const mavlink::mavlink_msg_entry_t * > mavconn::MAVConnInterface::message_entries {}
staticprotected

This map merge all dialect mavlink_msg_entry_t structs. Needed for packet parser.

Definition at line 271 of file interface.h.

◆ message_received_cb

ReceivedCb mavconn::MAVConnInterface::message_received_cb

Message receive callback.

Definition at line 200 of file interface.h.

◆ mutex [1/4]

std::recursive_mutex mavconn::MAVConnSerial::mutex
private

Definition at line 66 of file serial.h.

◆ mutex [2/4]

std::recursive_mutex mavconn::MAVConnTCPClient::mutex
private

Definition at line 81 of file tcp.h.

◆ mutex [3/4]

std::recursive_mutex mavconn::MAVConnUDP::mutex
private

Definition at line 84 of file udp.h.

◆ mutex [4/4]

std::recursive_mutex mavconn::MAVConnTCPServer::mutex
private

Definition at line 137 of file tcp.h.

◆ permanent_broadcast

bool mavconn::MAVConnUDP::permanent_broadcast
private

Definition at line 72 of file udp.h.

◆ PERMANENT_BROADCAST_REMOTE_HOST

constexpr auto mavconn::MAVConnUDP::PERMANENT_BROADCAST_REMOTE_HOST = "***permanent broadcast***"
static

Definition at line 40 of file udp.h.

◆ port_closed_cb

ClosedCb mavconn::MAVConnInterface::port_closed_cb

Port closed notification callback.

Definition at line 202 of file interface.h.

◆ pos

ssize_t mavconn::MsgBuffer::pos

Definition at line 32 of file msgbuffer.h.

◆ recv_ep

boost::asio::ip::udp::endpoint mavconn::MAVConnUDP::recv_ep
private

Definition at line 77 of file udp.h.

◆ remote_ep

boost::asio::ip::udp::endpoint mavconn::MAVConnUDP::remote_ep
private

Definition at line 76 of file udp.h.

◆ remote_exists

std::atomic<bool> mavconn::MAVConnUDP::remote_exists
private

Definition at line 74 of file udp.h.

◆ rx_buf [1/3]

std::array<uint8_t, MsgBuffer::MAX_SIZE> mavconn::MAVConnSerial::rx_buf
private

Definition at line 65 of file serial.h.

◆ rx_buf [2/3]

std::array<uint8_t, MsgBuffer::MAX_SIZE> mavconn::MAVConnTCPClient::rx_buf
private

Definition at line 80 of file tcp.h.

◆ rx_buf [3/3]

std::array<uint8_t, MsgBuffer::MAX_SIZE> mavconn::MAVConnUDP::rx_buf
private

Definition at line 83 of file udp.h.

◆ rx_speed

float mavconn::MAVConnInterface::IOStat::rx_speed

current receive speed [B/s]

Definition at line 112 of file interface.h.

◆ rx_total_bytes [1/2]

size_t mavconn::MAVConnInterface::IOStat::rx_total_bytes

total bytes received

Definition at line 110 of file interface.h.

◆ rx_total_bytes [2/2]

std::atomic<size_t> mavconn::MAVConnInterface::rx_total_bytes
private

Definition at line 303 of file interface.h.

◆ serial_dev

boost::asio::serial_port mavconn::MAVConnSerial::serial_dev
private

Definition at line 61 of file serial.h.

◆ server_ep

boost::asio::ip::tcp::endpoint mavconn::MAVConnTCPClient::server_ep
private

Definition at line 74 of file tcp.h.

◆ socket [1/2]

boost::asio::ip::tcp::socket mavconn::MAVConnTCPClient::socket
private

Definition at line 73 of file tcp.h.

◆ socket [2/2]

boost::asio::ip::udp::socket mavconn::MAVConnUDP::socket
private

Definition at line 75 of file udp.h.

◆ sys_id

uint8_t mavconn::MAVConnInterface::sys_id
protected

Connection System Id.

Definition at line 262 of file interface.h.

◆ tx_in_progress [1/3]

std::atomic<bool> mavconn::MAVConnSerial::tx_in_progress
private

Definition at line 63 of file serial.h.

◆ tx_in_progress [2/3]

std::atomic<bool> mavconn::MAVConnTCPClient::tx_in_progress
private

Definition at line 78 of file tcp.h.

◆ tx_in_progress [3/3]

std::atomic<bool> mavconn::MAVConnUDP::tx_in_progress
private

Definition at line 81 of file udp.h.

◆ tx_q [1/3]

std::deque<MsgBuffer> mavconn::MAVConnSerial::tx_q
private

Definition at line 64 of file serial.h.

◆ tx_q [2/3]

std::deque<MsgBuffer> mavconn::MAVConnTCPClient::tx_q
private

Definition at line 79 of file tcp.h.

◆ tx_q [3/3]

std::deque<MsgBuffer> mavconn::MAVConnUDP::tx_q
private

Definition at line 82 of file udp.h.

◆ tx_speed

float mavconn::MAVConnInterface::IOStat::tx_speed

current transfer speed [B/s]

Definition at line 111 of file interface.h.

◆ tx_total_bytes [1/2]

size_t mavconn::MAVConnInterface::IOStat::tx_total_bytes

total bytes transferred

Definition at line 109 of file interface.h.

◆ tx_total_bytes [2/2]

std::atomic<size_t> mavconn::MAVConnInterface::tx_total_bytes
private

Definition at line 303 of file interface.h.

Friends

◆ MAVConnTCPServer

friend class MAVConnTCPServer
friend

Definition at line 68 of file tcp.h.

◆ mavlink::mavlink_get_msg_entry



libmavconn
Author(s): Vladimir Ermakov
autogenerated on Tue Jun 13 2023 02:17:45