37 #ifndef MAVROSFLIGHT_MAVLINK_UDP_H 38 #define MAVROSFLIGHT_MAVLINK_UDP_H 42 #include <boost/asio.hpp> 43 #include <boost/function.hpp> 61 MavlinkUDP(std::string bind_host, uint16_t
bind_port, std::string remote_host, uint16_t remote_port);
77 virtual void do_async_read(
const boost::asio::mutable_buffers_1 &buffer, boost::function<
void(
const boost::system::error_code&,
size_t)> handler);
78 virtual void do_async_write(
const boost::asio::const_buffers_1 &buffer, boost::function<
void(
const boost::system::error_code&,
size_t)> handler);
97 #endif // MAVROSFLIGHT_MAVLINK_UDP_H 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_
~MavlinkUDP()
Stops communication and closes the serial port before the object is destroyed.
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_