42 using boost::asio::serial_port_base;
46 write_in_progress_(false)
82 bool already_registered =
false;
87 already_registered =
true;
92 if (!already_registered)
120 boost::asio::placeholders::error,
121 boost::asio::placeholders::bytes_transferred));
134 for (
int i = 0; i < bytes_transferred; i++)
174 boost::asio::buffer(buffer->
dpos(), buffer->
nbytes()),
178 boost::asio::placeholders::error,
179 boost::asio::placeholders::bytes_transferred));
187 std::cerr << error.message() << std::endl;
200 buffer->
pos += bytes_transferred;
201 if (buffer->
nbytes() == 0)
void async_read()
Initiate an asynchronous read operation.
boost::asio::io_service io_service_
boost io service provider
void async_read_end(const boost::system::error_code &error, size_t bytes_transferred)
Handler for end of asynchronous read operation.
uint8_t read_buf_raw_[MAVLINK_SERIAL_READ_BUF_SIZE]
MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_message_t *r_message, mavlink_status_t *r_mavlink_status)
Describes an interface classes can implement to receive and handle mavlink messages.
bool write_in_progress_
flag for whether async_write is already running
void close()
Stops communication and closes the port.
mavlink_message_t msg_in_
boost::lock_guard< boost::recursive_mutex > mutex_lock
Convenience typedef for mutex lock.
boost::thread io_thread_
thread on which the io service runs
void register_mavlink_listener(MavlinkListenerInterface *const listener)
Register a listener for mavlink messages.
mavlink_status_t status_in_
uint8_t data[MAVLINK_MAX_PACKET_LEN]
void open()
Opens the port and begins communication.
void unregister_mavlink_listener(MavlinkListenerInterface *const listener)
Unregister a listener for mavlink messages.
const uint8_t * dpos() const
std::vector< MavlinkListenerInterface * > listeners_
listeners for mavlink messages
#define MAVLINK_MAX_PACKET_LEN
Maximum packet length.
virtual void do_async_read(const boost::asio::mutable_buffers_1 &buffer, boost::function< void(const boost::system::error_code &, size_t)> handler)=0
MavlinkComm()
Instantiates the class and begins communication on the specified serial port.
#define MAVLINK_SERIAL_READ_BUF_SIZE
void async_write_end(const boost::system::error_code &error, size_t bytes_transferred)
Handler for end of asynchronous write operation.
~MavlinkComm()
Stops communication and closes the serial port before the object is destroyed.
MAVLINK_HELPER uint16_t mavlink_msg_to_send_buffer(uint8_t *buffer, const mavlink_message_t *msg)
Pack a message to send it over a serial byte stream.
virtual void do_close()=0
boost::recursive_mutex mutex_
mutex for threadsafe operation
Struct for buffering the contents of a mavlink message.
void async_write(bool check_write_state)
Initialize an asynchronous write operation.
virtual void do_async_write(const boost::asio::const_buffers_1 &buffer, boost::function< void(const boost::system::error_code &, size_t)> handler)=0
void send_message(const mavlink_message_t &msg)
Send a mavlink message.
std::list< WriteBuffer * > write_queue_
queue of buffers to be written to the serial port