#include <mavlink_udp.h>
|
virtual void | do_async_read (const boost::asio::mutable_buffers_1 &buffer, boost::function< void(const boost::system::error_code &, size_t)> handler) |
|
virtual void | do_async_write (const boost::asio::const_buffers_1 &buffer, boost::function< void(const boost::system::error_code &, size_t)> handler) |
|
virtual void | do_close () |
|
virtual void | do_open () |
|
virtual bool | is_open () |
|
Definition at line 49 of file mavlink_udp.h.
mavrosflight::MavlinkUDP::MavlinkUDP |
( |
std::string |
bind_host, |
|
|
uint16_t |
bind_port, |
|
|
std::string |
remote_host, |
|
|
uint16_t |
remote_port |
|
) |
| |
Instantiates the class and begins communication on the specified serial port.
- Parameters
-
bind_host | Host where this node is running |
bind_port | Port number for this node |
remote_host | Host where the other node is running |
remote_port | Port number for the other node |
Definition at line 46 of file mavlink_udp.cpp.
mavrosflight::MavlinkUDP::~MavlinkUDP |
( |
| ) |
|
Stops communication and closes the serial port before the object is destroyed.
Definition at line 56 of file mavlink_udp.cpp.
void mavrosflight::MavlinkUDP::do_async_read |
( |
const boost::asio::mutable_buffers_1 & |
buffer, |
|
|
boost::function< void(const boost::system::error_code &, size_t)> |
handler |
|
) |
| |
|
privatevirtual |
void mavrosflight::MavlinkUDP::do_async_write |
( |
const boost::asio::const_buffers_1 & |
buffer, |
|
|
boost::function< void(const boost::system::error_code &, size_t)> |
handler |
|
) |
| |
|
privatevirtual |
void mavrosflight::MavlinkUDP::do_close |
( |
| ) |
|
|
privatevirtual |
void mavrosflight::MavlinkUDP::do_open |
( |
| ) |
|
|
privatevirtual |
bool mavrosflight::MavlinkUDP::is_open |
( |
| ) |
|
|
privatevirtual |
boost::asio::ip::udp::endpoint mavrosflight::MavlinkUDP::bind_endpoint_ |
|
private |
std::string mavrosflight::MavlinkUDP::bind_host_ |
|
private |
uint16_t mavrosflight::MavlinkUDP::bind_port_ |
|
private |
boost::asio::ip::udp::endpoint mavrosflight::MavlinkUDP::remote_endpoint_ |
|
private |
std::string mavrosflight::MavlinkUDP::remote_host_ |
|
private |
uint16_t mavrosflight::MavlinkUDP::remote_port_ |
|
private |
boost::asio::ip::udp::socket mavrosflight::MavlinkUDP::socket_ |
|
private |
The documentation for this class was generated from the following files: