40 using boost::asio::ip::udp;
45 using boost::asio::serial_port_base;
50 bind_host_(bind_host),
51 bind_port_(bind_port),
52 remote_host_(remote_host),
53 remote_port_(remote_port)
82 socket_.set_option(udp::socket::reuse_address(
true));
86 catch (boost::system::system_error e)
97 void MavlinkUDP::do_async_read(
const boost::asio::mutable_buffers_1 &buffer, boost::function<
void(
const boost::system::error_code&,
size_t)> handler)
102 void MavlinkUDP::do_async_write(
const boost::asio::const_buffers_1 &buffer, boost::function<
void(
const boost::system::error_code&,
size_t)> handler)
boost::asio::io_service io_service_
boost io service provider
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.
virtual void do_async_read(const boost::asio::mutable_buffers_1 &buffer, boost::function< void(const boost::system::error_code &, size_t)> handler)
boost::asio::ip::udp::endpoint bind_endpoint_
Describes an exception encountered while using the boost serial libraries.
#define MAVLINK_MAX_PACKET_LEN
Maximum packet length.
~MavlinkUDP()
Stops communication and closes the serial port before the object is destroyed.
#define MAVLINK_SERIAL_READ_BUF_SIZE
boost::asio::ip::udp::endpoint remote_endpoint_
virtual void do_async_write(const boost::asio::const_buffers_1 &buffer, boost::function< void(const boost::system::error_code &, size_t)> handler)
boost::asio::ip::udp::socket socket_