MAVConn connection handling library. More...
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... | |
Namespaces | |
namespace | mavconn |
Defines | |
#define | _DIALECT(name) _DIALECT_CONCAT(name) |
#define | _DIALECT_ardupilotmega 1 |
#define | _DIALECT_ASLUAV 11 |
#define | _DIALECT_autoquad 2 |
#define | _DIALECT_common 3 |
#define | _DIALECT_CONCAT(name) _DIALECT_ ## name |
#define | _DIALECT_matrixpilot 4 |
#define | _DIALECT_minimal 5 |
#define | _DIALECT_paparazzi 12 |
#define | _DIALECT_pixhawk 6 /* removed */ |
#define | _DIALECT_sensesoar 10 /* removed */ |
#define | _DIALECT_slugs 7 |
#define | _DIALECT_test 8 |
#define | _DIALECT_ualberta 9 |
#define | MAVLINK_DIALECT common |
#define | MAVLINK_GET_CHANNEL_BUFFER |
#define | MAVLINK_GET_CHANNEL_STATUS |
#define | PFX "mavconn: " |
#define | PFXd "mavconn: serial%d: " |
#define | PFXd "mavconn: tcp%d: " |
#define | PFXd "mavconn: udp%d: " |
Typedefs | |
typedef boost::shared_ptr < MAVConnInterface const > | mavconn::MAVConnInterface::ConstPtr |
typedef std::lock_guard < std::recursive_mutex > | mavconn::lock_guard |
typedef sig2::signal< void(const mavlink_message_t *message, uint8_t system_id, uint8_t component_id) | mavconn::MAVConnInterface::MessageSig ) |
typedef boost::shared_ptr < MAVConnInterface > | mavconn::MAVConnInterface::Ptr |
typedef boost::weak_ptr < MAVConnInterface > | mavconn::MAVConnInterface::WeakPtr |
Functions | |
void | mavconn::MAVConnTCPServer::async_accept_end (boost::system::error_code) |
void | mavconn::MAVConnSerial::async_read_end (boost::system::error_code, size_t bytes_transferred) |
void | mavconn::MAVConnUDP::async_receive_end (boost::system::error_code, size_t bytes_transferred) |
void | mavconn::MAVConnTCPClient::async_receive_end (boost::system::error_code, size_t bytes_transferred) |
void | mavconn::MAVConnTCPClient::async_send_end (boost::system::error_code, size_t bytes_transferred) |
void | mavconn::MAVConnUDP::async_sendto_end (boost::system::error_code, size_t bytes_transferred) |
void | mavconn::MAVConnSerial::async_write_end (boost::system::error_code, size_t bytes_transferred) |
static int | mavconn::MAVConnInterface::channes_available () |
void | mavconn::MAVConnTCPServer::client_closed (boost::weak_ptr< MAVConnTCPClient > weak_instp) |
void | mavconn::MAVConnTCPClient::client_connected (int server_channel) |
void | mavconn::MAVConnSerial::close () |
Close connection. | |
void | mavconn::MAVConnUDP::close () |
Close connection. | |
void | mavconn::MAVConnTCPClient::close () |
Close connection. | |
void | mavconn::MAVConnTCPServer::close () |
Close connection. | |
virtual void | mavconn::MAVConnInterface::close ()=0 |
Close connection. | |
static void | mavconn::MAVConnInterface::delete_channel (int chan) |
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 () |
int | mavconn::MAVConnInterface::get_channel () |
uint8_t | mavconn::MAVConnInterface::get_component_id () |
IOStat | mavconn::MAVConnTCPServer::get_iostat () |
virtual IOStat | mavconn::MAVConnInterface::get_iostat () |
mavlink_status_t | mavconn::MAVConnTCPServer::get_status () |
virtual mavlink_status_t | mavconn::MAVConnInterface::get_status () |
uint8_t | mavconn::MAVConnInterface::get_system_id () |
void | mavconn::MAVConnInterface::iostat_rx_add (size_t bytes) |
void | mavconn::MAVConnInterface::iostat_tx_add (size_t bytes) |
bool | mavconn::MAVConnSerial::is_open () |
bool | mavconn::MAVConnUDP::is_open () |
bool | mavconn::MAVConnTCPClient::is_open () |
bool | mavconn::MAVConnTCPServer::is_open () |
virtual bool | mavconn::MAVConnInterface::is_open ()=0 |
template<typename T > | |
static std::string | mavconn::DeviceError::make_message (const char *module, T msg) |
mavconn::MAVConnInterface::MAVConnInterface (const MAVConnInterface &) | |
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="/dev/ttyACM0", unsigned baudrate=57600) | |
mavconn::MAVConnTCPClient::MAVConnTCPClient (uint8_t system_id=1, uint8_t component_id=MAV_COMP_ID_UDP_BRIDGE, std::string server_host="localhost", unsigned short server_port=5760) | |
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="localhost", unsigned short bind_port=5760) | |
mavconn::MAVConnUDP::MAVConnUDP (uint8_t system_id=1, uint8_t component_id=MAV_COMP_ID_UDP_BRIDGE, std::string bind_host="localhost", unsigned short bind_port=14555, std::string remote_host="", unsigned short remote_port=14550) | |
mavlink_message_t * | mavlink_get_channel_buffer (uint8_t chan) |
mavlink_status_t * | mavlink_get_channel_status (uint8_t chan) |
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_message_t *msg) | |
Buffer constructor from mavlink_message_t. | |
mavconn::MsgBuffer::MsgBuffer (const uint8_t *bytes, ssize_t nbytes) | |
Buffer constructor for send_bytes() | |
ssize_t | mavconn::MsgBuffer::nbytes () |
static int | mavconn::MAVConnInterface::new_channel () |
MsgBuffer * | mavconn::MAVConnInterface::new_msgbuffer (const mavlink_message_t *message, uint8_t sysid, uint8_t compid) |
static Ptr | mavconn::MAVConnInterface::open_url (std::string url, uint8_t system_id=1, uint8_t component_id=MAV_COMP_ID_UDP_BRIDGE) |
Construct connection from URL. | |
void | mavconn::MAVConnTCPServer::recv_message (const mavlink_message_t *message, uint8_t sysid, uint8_t compid) |
static bool | mavconn::resolve_address_tcp (io_service &io, int chan, std::string host, unsigned short port, tcp::endpoint &ep) |
static bool | mavconn::resolve_address_udp (io_service &io, int chan, std::string host, unsigned short port, udp::endpoint &ep) |
void | mavconn::MAVConnSerial::send_bytes (const uint8_t *bytes, size_t length) |
Send raw bytes (for some quirks) | |
void | mavconn::MAVConnUDP::send_bytes (const uint8_t *bytes, size_t length) |
Send raw bytes (for some quirks) | |
void | mavconn::MAVConnTCPClient::send_bytes (const uint8_t *bytes, size_t length) |
Send raw bytes (for some quirks) | |
void | mavconn::MAVConnTCPServer::send_bytes (const uint8_t *bytes, size_t length) |
Send raw bytes (for some quirks) | |
virtual void | mavconn::MAVConnInterface::send_bytes (const uint8_t *bytes, size_t length)=0 |
Send raw bytes (for some quirks) | |
void | mavconn::MAVConnSerial::send_message (const mavlink_message_t *message, uint8_t sysid, uint8_t compid) |
Send message Can be used in message_received signal. | |
void | mavconn::MAVConnUDP::send_message (const mavlink_message_t *message, uint8_t sysid, uint8_t compid) |
Send message Can be used in message_received signal. | |
void | mavconn::MAVConnTCPClient::send_message (const mavlink_message_t *message, uint8_t sysid, uint8_t compid) |
Send message Can be used in message_received signal. | |
void | mavconn::MAVConnTCPServer::send_message (const mavlink_message_t *message, uint8_t sysid, uint8_t compid) |
Send message Can be used in message_received signal. | |
void | mavconn::MAVConnInterface::send_message (const mavlink_message_t *message) |
Send message with default link system/component id. | |
virtual void | mavconn::MAVConnInterface::send_message (const mavlink_message_t *message, uint8_t sysid, uint8_t compid)=0 |
Send message Can be used in message_received signal. | |
void | mavconn::MAVConnInterface::set_component_id (uint8_t compid) |
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) |
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) |
virtual | mavconn::MAVConnInterface::~MAVConnInterface () |
mavconn::MAVConnSerial::~MAVConnSerial () | |
mavconn::MAVConnTCPClient::~MAVConnTCPClient () | |
mavconn::MAVConnTCPServer::~MAVConnTCPServer () | |
mavconn::MAVConnUDP::~MAVConnUDP () | |
virtual | mavconn::MsgBuffer::~MsgBuffer () |
Variables | |
boost::asio::ip::tcp::acceptor | mavconn::MAVConnTCPServer::acceptor |
boost::shared_ptr < MAVConnTCPClient > | mavconn::MAVConnTCPServer::acceptor_client |
static std::set< int > | mavconn::MAVConnInterface::allocated_channels |
boost::asio::ip::udp::endpoint | mavconn::MAVConnUDP::bind_ep |
boost::asio::ip::tcp::endpoint | mavconn::MAVConnTCPServer::bind_ep |
int | mavconn::MAVConnInterface::channel |
static std::recursive_mutex | mavconn::MAVConnInterface::channel_mutex |
std::list< boost::shared_ptr < MAVConnTCPClient > > | mavconn::MAVConnTCPServer::client_list |
uint8_t | mavconn::MAVConnInterface::comp_id |
uint8_t | mavconn::MsgBuffer::data [MAX_SIZE] |
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::chrono::time_point < steady_clock > | mavconn::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 |
static mavlink_message_t | m_mavlink_buffer [MAVLINK_COMM_NUM_BUFFERS] |
static mavlink_status_t | m_mavlink_status [MAVLINK_COMM_NUM_BUFFERS] |
static constexpr ssize_t | mavconn::MsgBuffer::MAX_SIZE = MAVLINK_MAX_PACKET_LEN + 2 + 7 |
Maximum buffer size with padding for CRC bytes (263 + 2 + align padding) | |
MessageSig | mavconn::MAVConnInterface::message_received |
Message receive signal. | |
std::recursive_mutex | mavconn::MAVConnSerial::mutex |
std::recursive_mutex | mavconn::MAVConnUDP::mutex |
std::recursive_mutex | mavconn::MAVConnTCPClient::mutex |
std::recursive_mutex | mavconn::MAVConnTCPServer::mutex |
sig2::signal< void()> | mavconn::MAVConnInterface::port_closed |
ssize_t | mavconn::MsgBuffer::pos |
boost::asio::ip::udp::endpoint | mavconn::MAVConnUDP::remote_ep |
std::atomic< bool > | mavconn::MAVConnUDP::remote_exists |
uint8_t | mavconn::MAVConnSerial::rx_buf [MsgBuffer::MAX_SIZE] |
uint8_t | mavconn::MAVConnUDP::rx_buf [MsgBuffer::MAX_SIZE] |
uint8_t | mavconn::MAVConnTCPClient::rx_buf [MsgBuffer::MAX_SIZE] |
float | mavconn::MAVConnInterface::IOStat::rx_speed |
current receive speed [B/s] | |
size_t | mavconn::MAVConnInterface::IOStat::rx_total_bytes |
total bytes received | |
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::udp::socket | mavconn::MAVConnUDP::socket |
boost::asio::ip::tcp::socket | mavconn::MAVConnTCPClient::socket |
uint8_t | mavconn::MAVConnInterface::sys_id |
std::atomic< bool > | mavconn::MAVConnSerial::tx_in_progress |
std::atomic< bool > | mavconn::MAVConnUDP::tx_in_progress |
std::atomic< bool > | mavconn::MAVConnTCPClient::tx_in_progress |
std::list< MsgBuffer * > | mavconn::MAVConnSerial::tx_q |
std::list< MsgBuffer * > | mavconn::MAVConnUDP::tx_q |
std::list< MsgBuffer * > | mavconn::MAVConnTCPClient::tx_q |
float | mavconn::MAVConnInterface::IOStat::tx_speed |
current transfer speed [B/s] | |
size_t | mavconn::MAVConnInterface::IOStat::tx_total_bytes |
total bytes transferred | |
std::atomic< size_t > | mavconn::MAVConnInterface::tx_total_bytes |
Friends | |
class | mavconn::MAVConnTCPClient::MAVConnTCPServer |
MAVConn connection handling library.
This lib provide simple interface to MAVLink enabled devices such as autopilots.
#define _DIALECT | ( | name | ) | _DIALECT_CONCAT(name) |
Definition at line 41 of file mavlink_dialect.h.
#define _DIALECT_ardupilotmega 1 |
Definition at line 43 of file mavlink_dialect.h.
#define _DIALECT_ASLUAV 11 |
Definition at line 53 of file mavlink_dialect.h.
#define _DIALECT_autoquad 2 |
Definition at line 44 of file mavlink_dialect.h.
#define _DIALECT_common 3 |
Definition at line 45 of file mavlink_dialect.h.
#define _DIALECT_CONCAT | ( | name | ) | _DIALECT_ ## name |
Definition at line 42 of file mavlink_dialect.h.
#define _DIALECT_matrixpilot 4 |
Definition at line 46 of file mavlink_dialect.h.
#define _DIALECT_minimal 5 |
Definition at line 47 of file mavlink_dialect.h.
#define _DIALECT_paparazzi 12 |
Definition at line 54 of file mavlink_dialect.h.
#define _DIALECT_pixhawk 6 /* removed */ |
Definition at line 48 of file mavlink_dialect.h.
#define _DIALECT_sensesoar 10 /* removed */ |
Definition at line 52 of file mavlink_dialect.h.
#define _DIALECT_slugs 7 |
Definition at line 49 of file mavlink_dialect.h.
#define _DIALECT_test 8 |
Definition at line 50 of file mavlink_dialect.h.
#define _DIALECT_ualberta 9 |
Definition at line 51 of file mavlink_dialect.h.
#define MAVLINK_DIALECT common |
Definition at line 21 of file mavlink_dialect.h.
#define MAVLINK_GET_CHANNEL_BUFFER |
Definition at line 29 of file mavlink_dialect.h.
#define MAVLINK_GET_CHANNEL_STATUS |
Definition at line 28 of file mavlink_dialect.h.
#define PFX "mavconn: " |
Definition at line 30 of file interface.cpp.
#define PFXd "mavconn: serial%d: " |
Definition at line 31 of file serial.cpp.
typedef boost::shared_ptr<MAVConnInterface const> mavconn::MAVConnInterface::ConstPtr |
Definition at line 96 of file interface.h.
typedef std::lock_guard< std::recursive_mutex > mavconn::lock_guard |
Definition at line 29 of file serial.cpp.
typedef sig2::signal<void(const mavlink_message_t *message, uint8_t system_id, uint8_t component_id) mavconn::MAVConnInterface::MessageSig) |
Definition at line 94 of file interface.h.
typedef boost::shared_ptr<MAVConnInterface> mavconn::MAVConnInterface::Ptr |
Definition at line 95 of file interface.h.
typedef boost::weak_ptr<MAVConnInterface> mavconn::MAVConnInterface::WeakPtr |
Definition at line 97 of file interface.h.
void mavconn::MAVConnTCPServer::async_accept_end | ( | boost::system::error_code | ) | [private] |
void mavconn::MAVConnSerial::async_read_end | ( | boost::system::error_code | , |
size_t | bytes_transferred | ||
) | [private] |
Definition at line 134 of file serial.cpp.
void mavconn::MAVConnUDP::async_receive_end | ( | boost::system::error_code | , |
size_t | bytes_transferred | ||
) | [private] |
void mavconn::MAVConnTCPClient::async_receive_end | ( | boost::system::error_code | , |
size_t | bytes_transferred | ||
) | [private] |
void mavconn::MAVConnTCPClient::async_send_end | ( | boost::system::error_code | , |
size_t | bytes_transferred | ||
) | [private] |
void mavconn::MAVConnUDP::async_sendto_end | ( | boost::system::error_code | , |
size_t | bytes_transferred | ||
) | [private] |
void mavconn::MAVConnSerial::async_write_end | ( | boost::system::error_code | , |
size_t | bytes_transferred | ||
) | [private] |
Definition at line 177 of file serial.cpp.
int mavconn::MAVConnInterface::channes_available | ( | ) | [static, protected] |
Definition at line 74 of file interface.cpp.
void mavconn::MAVConnTCPServer::client_closed | ( | boost::weak_ptr< MAVConnTCPClient > | weak_instp | ) | [private] |
void mavconn::MAVConnTCPClient::client_connected | ( | int | server_channel | ) | [private] |
void mavconn::MAVConnSerial::close | ( | ) | [virtual] |
void mavconn::MAVConnUDP::close | ( | ) | [virtual] |
void mavconn::MAVConnTCPClient::close | ( | ) | [virtual] |
void mavconn::MAVConnTCPServer::close | ( | ) | [virtual] |
virtual void mavconn::MAVConnInterface::close | ( | ) | [pure virtual] |
Close connection.
Implemented in mavconn::MAVConnTCPServer, mavconn::MAVConnTCPClient, mavconn::MAVConnUDP, and mavconn::MAVConnSerial.
void mavconn::MAVConnInterface::delete_channel | ( | int | chan | ) | [static, protected] |
Definition at line 68 of file interface.cpp.
mavconn::DeviceError::DeviceError | ( | const char * | module, |
T | msg | ||
) | [inline] |
Construct error.
Definition at line 62 of file interface.h.
void mavconn::MAVConnTCPServer::do_accept | ( | ) | [private] |
void mavconn::MAVConnSerial::do_read | ( | void | ) | [private] |
Definition at line 124 of file serial.cpp.
void mavconn::MAVConnTCPClient::do_recv | ( | ) | [private] |
void mavconn::MAVConnUDP::do_recvfrom | ( | ) | [private] |
void mavconn::MAVConnTCPClient::do_send | ( | bool | check_tx_state | ) | [private] |
void mavconn::MAVConnUDP::do_sendto | ( | bool | check_tx_state | ) | [private] |
void mavconn::MAVConnSerial::do_write | ( | bool | check_tx_state | ) | [private] |
Definition at line 158 of file serial.cpp.
uint8_t* mavconn::MsgBuffer::dpos | ( | ) | [inline] |
Definition at line 68 of file msgbuffer.h.
int mavconn::MAVConnInterface::get_channel | ( | ) | [inline] |
Definition at line 152 of file interface.h.
uint8_t mavconn::MAVConnInterface::get_component_id | ( | ) | [inline] |
Definition at line 155 of file interface.h.
MAVConnInterface::IOStat mavconn::MAVConnTCPServer::get_iostat | ( | ) | [virtual] |
Reimplemented from mavconn::MAVConnInterface.
MAVConnInterface::IOStat mavconn::MAVConnInterface::get_iostat | ( | ) | [virtual] |
Reimplemented in mavconn::MAVConnTCPServer.
Definition at line 111 of file interface.cpp.
mavlink_status_t mavconn::MAVConnTCPServer::get_status | ( | ) | [virtual] |
Reimplemented from mavconn::MAVConnInterface.
mavlink_status_t mavconn::MAVConnInterface::get_status | ( | ) | [virtual] |
Reimplemented in mavconn::MAVConnTCPServer.
Definition at line 106 of file interface.cpp.
uint8_t mavconn::MAVConnInterface::get_system_id | ( | ) | [inline] |
Definition at line 153 of file interface.h.
void mavconn::MAVConnInterface::iostat_rx_add | ( | size_t | bytes | ) | [protected] |
Definition at line 141 of file interface.cpp.
void mavconn::MAVConnInterface::iostat_tx_add | ( | size_t | bytes | ) | [protected] |
Definition at line 136 of file interface.cpp.
bool mavconn::MAVConnSerial::is_open | ( | ) | [inline, virtual] |
Implements mavconn::MAVConnInterface.
bool mavconn::MAVConnUDP::is_open | ( | ) | [inline, virtual] |
Implements mavconn::MAVConnInterface.
bool mavconn::MAVConnTCPClient::is_open | ( | ) | [inline, virtual] |
Implements mavconn::MAVConnInterface.
bool mavconn::MAVConnTCPServer::is_open | ( | ) | [inline, virtual] |
Implements mavconn::MAVConnInterface.
virtual bool mavconn::MAVConnInterface::is_open | ( | ) | [pure virtual] |
Implemented in mavconn::MAVConnTCPServer, mavconn::MAVConnTCPClient, mavconn::MAVConnUDP, and mavconn::MAVConnSerial.
static std::string mavconn::DeviceError::make_message | ( | const char * | module, |
T | msg | ||
) | [inline, static] |
Definition at line 67 of file interface.h.
mavconn::MAVConnInterface::MAVConnInterface | ( | const MAVConnInterface & | ) | [private] |
mavconn::MAVConnInterface::MAVConnInterface | ( | uint8_t | system_id = 1 , |
uint8_t | component_id = MAV_COMP_ID_UDP_BRIDGE |
||
) |
[in] | system_id | sysid for send_message |
[in] | component_id | compid for send_message |
Definition at line 39 of file interface.cpp.
mavconn::MAVConnSerial::MAVConnSerial | ( | uint8_t | system_id = 1 , |
uint8_t | component_id = MAV_COMP_ID_UDP_BRIDGE , |
||
std::string | device = "/dev/ttyACM0" , |
||
unsigned | baudrate = 57600 |
||
) |
Open and run serial link.
[in] | device | TTY device path |
[in] | baudrate | serial baudrate |
Definition at line 34 of file serial.cpp.
mavconn::MAVConnTCPClient::MAVConnTCPClient | ( | uint8_t | system_id = 1 , |
uint8_t | component_id = MAV_COMP_ID_UDP_BRIDGE , |
||
std::string | server_host = "localhost" , |
||
unsigned short | server_port = 5760 |
||
) |
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
mavconn::MAVConnTCPServer::MAVConnTCPServer | ( | uint8_t | system_id = 1 , |
uint8_t | component_id = MAV_COMP_ID_UDP_BRIDGE , |
||
std::string | bind_host = "localhost" , |
||
unsigned short | bind_port = 5760 |
||
) |
mavconn::MAVConnUDP::MAVConnUDP | ( | uint8_t | system_id = 1 , |
uint8_t | component_id = MAV_COMP_ID_UDP_BRIDGE , |
||
std::string | bind_host = "localhost" , |
||
unsigned short | bind_port = 14555 , |
||
std::string | remote_host = "" , |
||
unsigned short | remote_port = 14550 |
||
) |
mavlink_message_t* mavlink_get_channel_buffer | ( | uint8_t | chan | ) |
Internal function to give access to the channel buffer for each channel
mavlink_status_t* mavlink_get_channel_status | ( | uint8_t | chan | ) |
Internal function to give access to the channel status for each channel
static std::string mavconn::DeviceError::msg_to_string | ( | const char * | description | ) | [inline, static] |
Definition at line 73 of file interface.h.
static std::string mavconn::DeviceError::msg_to_string | ( | int | errnum | ) | [inline, static] |
Definition at line 77 of file interface.h.
static std::string mavconn::DeviceError::msg_to_string | ( | boost::system::system_error & | err | ) | [inline, static] |
Definition at line 81 of file interface.h.
mavconn::MsgBuffer::MsgBuffer | ( | ) | [inline] |
Definition at line 35 of file msgbuffer.h.
mavconn::MsgBuffer::MsgBuffer | ( | const mavlink_message_t * | msg | ) | [inline, explicit] |
Buffer constructor from mavlink_message_t.
Definition at line 43 of file msgbuffer.h.
mavconn::MsgBuffer::MsgBuffer | ( | const uint8_t * | bytes, |
ssize_t | nbytes | ||
) | [inline] |
Buffer constructor for send_bytes()
[in] | nbytes | should be less than MAX_SIZE |
Definition at line 55 of file msgbuffer.h.
ssize_t mavconn::MsgBuffer::nbytes | ( | ) | [inline] |
Definition at line 72 of file msgbuffer.h.
int mavconn::MAVConnInterface::new_channel | ( | ) | [static, protected] |
Definition at line 52 of file interface.cpp.
MsgBuffer * mavconn::MAVConnInterface::new_msgbuffer | ( | const mavlink_message_t * | message, |
uint8_t | sysid, | ||
uint8_t | compid | ||
) | [protected] |
This helper function construct new MsgBuffer from message.
Definition at line 79 of file interface.cpp.
MAVConnInterface::Ptr mavconn::MAVConnInterface::open_url | ( | std::string | url, |
uint8_t | system_id = 1 , |
||
uint8_t | component_id = MAV_COMP_ID_UDP_BRIDGE |
||
) | [static] |
Construct connection from URL.
Supported URL schemas:
Please see user's documentation for details.
[in] | url | resource locator |
[in] | system_id | optional system id |
[in] | component_id | optional component id |
Definition at line 288 of file interface.cpp.
void mavconn::MAVConnTCPServer::recv_message | ( | const mavlink_message_t * | message, |
uint8_t | sysid, | ||
uint8_t | compid | ||
) | [private] |
static bool mavconn::resolve_address_tcp | ( | io_service & | io, |
int | chan, | ||
std::string | host, | ||
unsigned short | port, | ||
tcp::endpoint & | ep | ||
) | [static] |
static bool mavconn::resolve_address_udp | ( | io_service & | io, |
int | chan, | ||
std::string | host, | ||
unsigned short | port, | ||
udp::endpoint & | ep | ||
) | [static] |
void mavconn::MAVConnSerial::send_bytes | ( | const uint8_t * | bytes, |
size_t | length | ||
) | [virtual] |
Send raw bytes (for some quirks)
Implements mavconn::MAVConnInterface.
Definition at line 89 of file serial.cpp.
void mavconn::MAVConnUDP::send_bytes | ( | const uint8_t * | bytes, |
size_t | length | ||
) | [virtual] |
Send raw bytes (for some quirks)
Implements mavconn::MAVConnInterface.
void mavconn::MAVConnTCPClient::send_bytes | ( | const uint8_t * | bytes, |
size_t | length | ||
) | [virtual] |
Send raw bytes (for some quirks)
Implements mavconn::MAVConnInterface.
void mavconn::MAVConnTCPServer::send_bytes | ( | const uint8_t * | bytes, |
size_t | length | ||
) | [virtual] |
Send raw bytes (for some quirks)
Implements mavconn::MAVConnInterface.
virtual void mavconn::MAVConnInterface::send_bytes | ( | const uint8_t * | bytes, |
size_t | length | ||
) | [pure virtual] |
Send raw bytes (for some quirks)
Implemented in mavconn::MAVConnTCPServer, mavconn::MAVConnTCPClient, mavconn::MAVConnUDP, and mavconn::MAVConnSerial.
void mavconn::MAVConnSerial::send_message | ( | const mavlink_message_t * | message, |
uint8_t | sysid, | ||
uint8_t | compid | ||
) | [virtual] |
Send message Can be used in message_received signal.
[in] | *message | not changed |
[in] | sysid | message sys id |
[in] | compid | message component id |
Implements mavconn::MAVConnInterface.
Definition at line 104 of file serial.cpp.
void mavconn::MAVConnUDP::send_message | ( | const mavlink_message_t * | message, |
uint8_t | sysid, | ||
uint8_t | compid | ||
) | [virtual] |
Send message Can be used in message_received signal.
[in] | *message | not changed |
[in] | sysid | message sys id |
[in] | compid | message component id |
Implements mavconn::MAVConnInterface.
void mavconn::MAVConnTCPClient::send_message | ( | const mavlink_message_t * | message, |
uint8_t | sysid, | ||
uint8_t | compid | ||
) | [virtual] |
Send message Can be used in message_received signal.
[in] | *message | not changed |
[in] | sysid | message sys id |
[in] | compid | message component id |
Implements mavconn::MAVConnInterface.
void mavconn::MAVConnTCPServer::send_message | ( | const mavlink_message_t * | message, |
uint8_t | sysid, | ||
uint8_t | compid | ||
) | [virtual] |
Send message Can be used in message_received signal.
[in] | *message | not changed |
[in] | sysid | message sys id |
[in] | compid | message component id |
Implements mavconn::MAVConnInterface.
void mavconn::MAVConnInterface::send_message | ( | const mavlink_message_t * | message | ) | [inline] |
Send message with default link system/component id.
Definition at line 123 of file interface.h.
virtual void mavconn::MAVConnInterface::send_message | ( | const mavlink_message_t * | message, |
uint8_t | sysid, | ||
uint8_t | compid | ||
) | [pure virtual] |
Send message Can be used in message_received signal.
[in] | *message | not changed |
[in] | sysid | message sys id |
[in] | compid | message component id |
Implemented in mavconn::MAVConnTCPServer, mavconn::MAVConnTCPClient, mavconn::MAVConnUDP, and mavconn::MAVConnSerial.
void mavconn::MAVConnInterface::set_component_id | ( | uint8_t | compid | ) | [inline] |
Definition at line 156 of file interface.h.
void mavconn::MAVConnInterface::set_system_id | ( | uint8_t | sysid | ) | [inline] |
Definition at line 154 of file interface.h.
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 149 of file interface.cpp.
static void mavconn::url_parse_query | ( | std::string | query, |
uint8_t & | sysid, | ||
uint8_t & | compid | ||
) | [static] |
Parse ?ids=sid,cid
Definition at line 185 of file interface.cpp.
static MAVConnInterface::Ptr mavconn::url_parse_serial | ( | std::string | path, |
std::string | query, | ||
uint8_t | system_id, | ||
uint8_t | component_id | ||
) | [static] |
Definition at line 216 of file interface.cpp.
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 258 of file interface.cpp.
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 273 of file interface.cpp.
static MAVConnInterface::Ptr mavconn::url_parse_udp | ( | std::string | hosts, |
std::string | query, | ||
uint8_t | system_id, | ||
uint8_t | component_id | ||
) | [static] |
Definition at line 231 of file interface.cpp.
virtual mavconn::MAVConnInterface::~MAVConnInterface | ( | ) | [inline, virtual] |
Definition at line 111 of file interface.h.
Definition at line 66 of file serial.cpp.
virtual mavconn::MsgBuffer::~MsgBuffer | ( | ) | [inline, virtual] |
Definition at line 63 of file msgbuffer.h.
boost::asio::ip::tcp::acceptor mavconn::MAVConnTCPServer::acceptor [private] |
boost::shared_ptr<MAVConnTCPClient> mavconn::MAVConnTCPServer::acceptor_client [private] |
std::set< int > mavconn::MAVConnInterface::allocated_channels [static, private] |
Definition at line 201 of file interface.h.
boost::asio::ip::udp::endpoint mavconn::MAVConnUDP::bind_ep [private] |
boost::asio::ip::tcp::endpoint mavconn::MAVConnTCPServer::bind_ep [private] |
int mavconn::MAVConnInterface::channel [protected] |
Definition at line 179 of file interface.h.
std::recursive_mutex mavconn::MAVConnInterface::channel_mutex [static, private] |
Definition at line 200 of file interface.h.
std::list<boost::shared_ptr<MAVConnTCPClient> > mavconn::MAVConnTCPServer::client_list [private] |
uint8_t mavconn::MAVConnInterface::comp_id [protected] |
Definition at line 181 of file interface.h.
uint8_t mavconn::MsgBuffer::data[MAX_SIZE] |
Definition at line 31 of file msgbuffer.h.
boost::asio::io_service mavconn::MAVConnSerial::io_service [private] |
boost::asio::io_service mavconn::MAVConnUDP::io_service [private] |
boost::asio::io_service mavconn::MAVConnTCPClient::io_service [private] |
boost::asio::io_service mavconn::MAVConnTCPServer::io_service [private] |
std::thread mavconn::MAVConnSerial::io_thread [private] |
std::thread mavconn::MAVConnUDP::io_thread [private] |
std::thread mavconn::MAVConnTCPClient::io_thread [private] |
std::thread mavconn::MAVConnTCPServer::io_thread [private] |
std::unique_ptr<boost::asio::io_service::work> mavconn::MAVConnUDP::io_work [private] |
std::unique_ptr<boost::asio::io_service::work> mavconn::MAVConnTCPClient::io_work [private] |
std::unique_ptr<boost::asio::io_service::work> mavconn::MAVConnTCPServer::io_work [private] |
std::recursive_mutex mavconn::MAVConnInterface::iostat_mutex [private] |
Definition at line 204 of file interface.h.
std::chrono::time_point<steady_clock> mavconn::MAVConnInterface::last_iostat [private] |
Definition at line 206 of file interface.h.
boost::asio::ip::udp::endpoint mavconn::MAVConnUDP::last_remote_ep [private] |
size_t mavconn::MAVConnInterface::last_rx_total_bytes [private] |
Definition at line 205 of file interface.h.
size_t mavconn::MAVConnInterface::last_tx_total_bytes [private] |
Definition at line 205 of file interface.h.
ssize_t mavconn::MsgBuffer::len |
Definition at line 32 of file msgbuffer.h.
Definition at line 27 of file mavlink_helpers.cpp.
Definition at line 26 of file mavlink_helpers.cpp.
constexpr ssize_t mavconn::MsgBuffer::MAX_SIZE = MAVLINK_MAX_PACKET_LEN + 2 + 7 [static] |
Maximum buffer size with padding for CRC bytes (263 + 2 + align padding)
Definition at line 30 of file msgbuffer.h.
MessageSig mavconn::MAVConnInterface::message_received |
Message receive signal.
Definition at line 145 of file interface.h.
std::recursive_mutex mavconn::MAVConnSerial::mutex [private] |
std::recursive_mutex mavconn::MAVConnUDP::mutex [private] |
std::recursive_mutex mavconn::MAVConnTCPClient::mutex [private] |
std::recursive_mutex mavconn::MAVConnTCPServer::mutex [private] |
sig2::signal<void()> mavconn::MAVConnInterface::port_closed |
Definition at line 146 of file interface.h.
ssize_t mavconn::MsgBuffer::pos |
Definition at line 33 of file msgbuffer.h.
boost::asio::ip::udp::endpoint mavconn::MAVConnUDP::remote_ep [private] |
std::atomic<bool> mavconn::MAVConnUDP::remote_exists [private] |
uint8_t mavconn::MAVConnSerial::rx_buf[MsgBuffer::MAX_SIZE] [private] |
uint8_t mavconn::MAVConnUDP::rx_buf[MsgBuffer::MAX_SIZE] [private] |
uint8_t mavconn::MAVConnTCPClient::rx_buf[MsgBuffer::MAX_SIZE] [private] |
current receive speed [B/s]
Definition at line 103 of file interface.h.
total bytes received
Definition at line 101 of file interface.h.
std::atomic<size_t> mavconn::MAVConnInterface::rx_total_bytes [private] |
Definition at line 203 of file interface.h.
boost::asio::serial_port mavconn::MAVConnSerial::serial_dev [private] |
boost::asio::ip::tcp::endpoint mavconn::MAVConnTCPClient::server_ep [private] |
boost::asio::ip::udp::socket mavconn::MAVConnUDP::socket [private] |
boost::asio::ip::tcp::socket mavconn::MAVConnTCPClient::socket [private] |
uint8_t mavconn::MAVConnInterface::sys_id [protected] |
Definition at line 180 of file interface.h.
std::atomic<bool> mavconn::MAVConnSerial::tx_in_progress [private] |
std::atomic<bool> mavconn::MAVConnUDP::tx_in_progress [private] |
std::atomic<bool> mavconn::MAVConnTCPClient::tx_in_progress [private] |
std::list<MsgBuffer*> mavconn::MAVConnSerial::tx_q [private] |
std::list<MsgBuffer*> mavconn::MAVConnUDP::tx_q [private] |
std::list<MsgBuffer*> mavconn::MAVConnTCPClient::tx_q [private] |
current transfer speed [B/s]
Definition at line 102 of file interface.h.
total bytes transferred
Definition at line 100 of file interface.h.
std::atomic<size_t> mavconn::MAVConnInterface::tx_total_bytes [private] |
Definition at line 203 of file interface.h.