Class MAVConnInterface
Defined in File interface.hpp
Nested Relationships
Nested Types
Inheritance Relationships
Derived Types
public mavconn::MAVConnSerial
(Class MAVConnSerial)public mavconn::MAVConnTCPClient
(Class MAVConnTCPClient)public mavconn::MAVConnTCPServer
(Class MAVConnTCPServer)public mavconn::MAVConnUDP
(Class MAVConnUDP)
Class Documentation
-
class MAVConnInterface
Generic mavlink interface.
Subclassed by mavconn::MAVConnSerial, mavconn::MAVConnTCPClient, mavconn::MAVConnTCPServer, mavconn::MAVConnUDP
Public Types
-
using ReceivedCb = std::function<void(const mavlink::mavlink_message_t *message, const Framing framing)>
-
using ClosedCb = std::function<void(void)>
-
using Ptr = std::shared_ptr<MAVConnInterface>
-
using ConstPtr = std::shared_ptr<MAVConnInterface const>
-
using WeakPtr = std::weak_ptr<MAVConnInterface>
Public Functions
-
explicit MAVConnInterface(uint8_t system_id = 1, uint8_t component_id = MAV_COMP_ID_UDP_BRIDGE)
- Parameters:
system_id – [in] sysid for send_message
component_id – [in] compid for send_message
-
virtual void connect(const ReceivedCb &cb_handle_message, const ClosedCb &cb_handle_closed_port = ClosedCb()) = 0
Establish connection, automatically called by open_url()
-
virtual void close() = 0
Close connection.
-
virtual void send_message(const mavlink::mavlink_message_t *message) = 0
Send message (mavlink_message_t)
Can be used to forward messages from other connection channel.
Note
Does not do finalization!
- Throws:
std::length_error – On exceeding Tx queue limit (MAX_TXQ_SIZE)
- Parameters:
*message – [in] not changed
-
inline virtual void send_message(const mavlink::Message &message)
Send message (child of mavlink::Message)
Does serialization inside. System and Component ID = from this object.
- Throws:
std::length_error – On exceeding Tx queue limit (MAX_TXQ_SIZE)
- Parameters:
&message – [in] not changed
-
virtual void send_message(const mavlink::Message &message, const uint8_t src_compid) = 0
Send message (child of mavlink::Message)
Does serialization inside. System ID = from this object. Component ID passed by argument.
- Throws:
std::length_error – On exceeding Tx queue limit (MAX_TXQ_SIZE)
- Parameters:
&message – [in] not changed
src_compid – [in] sets the component ID of the message source
-
virtual void send_bytes(const uint8_t *bytes, size_t length) = 0
Send raw bytes (for some quirks)
- Throws:
std::length_error – On exceeding Tx queue limit (MAX_TXQ_SIZE)
-
void send_message_ignore_drop(const mavlink::mavlink_message_t *message)
Send message and ignore possible drop due to Tx queue limit.
-
inline void send_message_ignore_drop(const mavlink::Message &message)
Send message and ignore possible drop due to Tx queue limit.
System and Component ID = from this object.
-
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.
System ID = from this object. Component ID passed by argument.
-
virtual mavlink::mavlink_status_t get_status()
-
virtual bool is_open() = 0
-
inline uint8_t get_system_id()
-
inline void set_system_id(uint8_t sysid)
-
inline uint8_t get_component_id()
-
inline void set_component_id(uint8_t compid)
Public Members
-
ReceivedCb message_received_cb
Message receive callback.
Public Static Functions
-
static Ptr 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.
Supported URL schemas:
serial://
udp://
tcp://
tcp-l://
Please see user’s documentation for details.
- Parameters:
url – [in] resource locator
system_id – [in] optional system id
component_id – [in] optional component id
- Returns:
Ptr to constructed interface class, or throw DeviceError if error occured.
-
static Ptr 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()
-
static std::vector<std::string> get_known_dialects()
Protected Functions
-
inline mavlink::mavlink_status_t *get_status_p()
-
inline mavlink::mavlink_message_t *get_buffer_p()
-
void parse_buffer(const char *pfx, uint8_t *buf, const size_t bufsize, size_t bytes_received)
Parse buffer and emit massage_received.
-
void iostat_tx_add(size_t bytes)
-
void iostat_rx_add(size_t bytes)
-
void log_send(const char *pfx, const mavlink::mavlink_message_t *msg)
-
void log_send_obj(const char *pfx, const mavlink::Message &msg)
Protected Attributes
-
uint8_t sys_id
Connection System Id.
-
uint8_t comp_id
Connection Component Id.
-
size_t conn_id
Channel number used for logging.
Protected Static Attributes
-
static constexpr size_t MAX_PACKET_SIZE = MAVLINK_MAX_PACKET_LEN + 16
Maximum mavlink packet size + some extra bytes for padding.
-
static constexpr size_t MAX_TXQ_SIZE = 1000
Maximum count of transmission buffers.
-
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.
-
struct IOStat
-
using ReceivedCb = std::function<void(const mavlink::mavlink_message_t *message, const Framing framing)>