Serial interface. More...
#include <serial.h>
Public Member Functions | |
void | close () |
Close connection. | |
bool | is_open () |
MAVConnSerial (uint8_t system_id=1, uint8_t component_id=MAV_COMP_ID_UDP_BRIDGE, std::string device="/dev/ttyACM0", unsigned baudrate=57600) | |
void | send_bytes (const uint8_t *bytes, size_t length) |
Send raw bytes (for some quirks) | |
void | send_message (const mavlink_message_t *message, uint8_t sysid, uint8_t compid) |
Send message Can be used in message_received signal. | |
~MAVConnSerial () | |
Private Member Functions | |
void | async_read_end (boost::system::error_code, size_t bytes_transferred) |
void | async_write_end (boost::system::error_code, size_t bytes_transferred) |
void | do_read () |
void | do_write (bool check_tx_state) |
Private Attributes | |
boost::asio::io_service | io_service |
std::thread | io_thread |
std::recursive_mutex | mutex |
uint8_t | rx_buf [MsgBuffer::MAX_SIZE] |
boost::asio::serial_port | serial_dev |
std::atomic< bool > | tx_in_progress |
std::list< MsgBuffer * > | tx_q |