Generic mavlink interface. More...
#include <interface.h>
Classes | |
struct | IOStat |
Public Types | |
typedef boost::shared_ptr < MAVConnInterface const > | ConstPtr |
typedef sig2::signal< void(const mavlink_message_t *message, uint8_t system_id, uint8_t component_id) | MessageSig ) |
typedef boost::shared_ptr < MAVConnInterface > | Ptr |
typedef boost::weak_ptr < MAVConnInterface > | WeakPtr |
Public Member Functions | |
virtual void | close ()=0 |
Close connection. | |
int | get_channel () |
uint8_t | get_component_id () |
virtual IOStat | get_iostat () |
virtual 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) | |
void | send_message (const mavlink_message_t *message) |
Send message with default link system/component id. | |
virtual void | send_message (const mavlink_message_t *message, uint8_t sysid, uint8_t compid)=0 |
Send message Can be used in message_received signal. | |
void | set_component_id (uint8_t compid) |
void | set_system_id (uint8_t sysid) |
virtual | ~MAVConnInterface () |
Static Public Member Functions | |
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. | |
Public Attributes | |
MessageSig | message_received |
Message receive signal. | |
sig2::signal< void()> | port_closed |
Protected Member Functions | |
void | iostat_rx_add (size_t bytes) |
void | iostat_tx_add (size_t bytes) |
MsgBuffer * | new_msgbuffer (const mavlink_message_t *message, uint8_t sysid, uint8_t compid) |
Static Protected Member Functions | |
static int | channes_available () |
static void | delete_channel (int chan) |
static int | new_channel () |
Protected Attributes | |
int | channel |
uint8_t | comp_id |
uint8_t | sys_id |
Private Member Functions | |
MAVConnInterface (const MAVConnInterface &) | |
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 |
std::atomic< size_t > | rx_total_bytes |
std::atomic< size_t > | tx_total_bytes |
Static Private Attributes | |
static std::set< int > | allocated_channels |
static std::recursive_mutex | channel_mutex |
Generic mavlink interface.
Definition at line 89 of file interface.h.