37 #ifndef MAVROSFLIGHT_MAVLINK_COMM_H 38 #define MAVROSFLIGHT_MAVLINK_COMM_H 40 #include <boost/asio.hpp> 41 #include <boost/thread.hpp> 42 #include <boost/function.hpp> 50 #define BUFFER_SIZE 2048 55 virtual void handle_bytes(
const uint8_t* bytes, uint8_t len) = 0;
68 Serial(std::__cxx11::string port,
int baud_rate);
90 void write(
const uint8_t *buffer, uint8_t len);
120 memcpy(data, buf, len);
123 const uint8_t *
dpos()
const {
return data + pos; }
125 size_t nbytes()
const {
return len - pos; }
140 typedef boost::lock_guard<boost::recursive_mutex>
mutex_lock;
156 void async_read_end(
const boost::system::error_code& error,
size_t bytes_transferred);
162 void async_write(
bool check_write_state);
169 void async_write_end(
const boost::system::error_code& error,
size_t bytes_transferred);
197 init(description.c_str());
209 virtual const char*
what()
const throw()
211 return what_.c_str();
217 void init(
const char *
const description)
219 std::ostringstream ss;
220 ss <<
"Serial Error: " << description;
boost::asio::serial_port serial_port_
boost serial port object
SerialException(const SerialException &other)
boost::asio::io_service io_service_
boost io service provider
WriteBuffer(const uint8_t *buf, uint16_t len)
bool init(test_data_t &t)
bool write_in_progress_
flag for whether async_write is already running
SerialException(const boost::system::system_error &err)
Struct for buffering the contents of a mavlink message.
virtual const char * what() const
SerialException(const char *const description)
virtual void handle_bytes(const uint8_t *bytes, uint8_t len)=0
boost::recursive_mutex mutex_
mutex for threadsafe operation
void init(const char *const description)
boost::lock_guard< boost::recursive_mutex > mutex_lock
Convenience typedef for mutex lock.
USBInterfaceDescriptor data
NMI_API sint8 close(SOCKET sock)
std::list< WriteBuffer * > write_queue_
queue of buffers to be written to the serial port
SerialException(const std::string &description)
const uint8_t * dpos() const
SerialListener * listener_
Pointer to byte listener.
boost::thread io_thread_
thread on which the io service runs