37 #ifndef MAVROSFLIGHT_MAVLINK_SERIAL_H 38 #define MAVROSFLIGHT_MAVLINK_SERIAL_H 42 #include <boost/asio.hpp> 43 #include <boost/function.hpp> 79 virtual void do_async_read(
const boost::asio::mutable_buffers_1 &buffer, boost::function<
void(
const boost::system::error_code&,
size_t)> handler);
85 virtual void do_async_write(
const boost::asio::const_buffers_1 &buffer, boost::function<
void(
const boost::system::error_code&,
size_t)> handler);
99 #endif // MAVROSFLIGHT_MAVLINK_SERIAL_H virtual void do_async_read(const boost::asio::mutable_buffers_1 &buffer, boost::function< void(const boost::system::error_code &, size_t)> handler)
Initiate an asynchronous read operation.
boost::asio::serial_port serial_port_
boost serial port object
MavlinkSerial(std::string port, int baud_rate)
Instantiates the class and begins communication on the specified serial port.
virtual void do_async_write(const boost::asio::const_buffers_1 &buffer, boost::function< void(const boost::system::error_code &, size_t)> handler)
Initialize an asynchronous write operation.
~MavlinkSerial()
Stops communication and closes the serial port before the object is destroyed.