Abstract base class for an asynchronous communication port. More...
#include <comm.h>

Classes | |
| struct | ReadBuffer |
| struct | WriteBuffer |
Public Member Functions | |
| void | close () |
| Closes the port. More... | |
| Comm () | |
| bool | init () |
| Initializes and opens the port. More... | |
| void | register_receive_callback (std::function< void(const uint8_t *, size_t)> fun) |
| Register a callback function for when bytes are received on the port. More... | |
| void | send_byte (uint8_t data) |
| Send a single byte over the port. More... | |
| void | send_bytes (const uint8_t *src, size_t len) |
| Send bytes from a buffer over the port. More... | |
| virtual | ~Comm () |
Protected Member Functions | |
| virtual void | do_async_read (const boost::asio::mutable_buffers_1 &buffer, boost::function< void(const boost::system::error_code &, size_t)> handler)=0 |
| virtual void | do_async_write (const boost::asio::const_buffers_1 &buffer, boost::function< void(const boost::system::error_code &, size_t)> handler)=0 |
| virtual void | do_close ()=0 |
| virtual bool | do_init ()=0 |
| virtual bool | is_open ()=0 |
Protected Attributes | |
| boost::asio::io_service | io_service_ |
Static Protected Attributes | |
| static constexpr size_t | READ_BUFFER_SIZE = 1024 |
| static constexpr size_t | WRITE_BUFFER_SIZE = 1024 |
Private Types | |
| typedef std::lock_guard< std::recursive_mutex > | mutex_lock |
Private Member Functions | |
| void | async_read () |
| void | async_read_end (const boost::system::error_code &error, size_t bytes_transferred) |
| void | async_write (bool check_write_state) |
| void | async_write_end (const boost::system::error_code &error, size_t bytes_transferred) |
| void | process_callbacks () |
Private Attributes | |
| std::mutex | callback_mutex_ |
| std::thread | callback_thread_ |
| std::condition_variable | condition_variable_ |
| std::thread | io_thread_ |
| bool | new_data_ |
| uint8_t | read_buffer_ [READ_BUFFER_SIZE] |
| std::list< ReadBuffer > | read_queue_ |
| std::function< void(const uint8_t *, size_t)> | receive_callback_ |
| bool | shutdown_requested_ |
| bool | write_in_progress_ |
| std::recursive_mutex | write_mutex_ |
| std::list< WriteBuffer > | write_queue_ |
|
private |
|
private |
|
private |
|
private |
|
protectedpure virtual |
Implemented in async_comm::Serial, async_comm::UDP, and async_comm::TCPClient.
|
protectedpure virtual |
Implemented in async_comm::Serial, async_comm::UDP, and async_comm::TCPClient.
|
protectedpure virtual |
Implemented in async_comm::Serial, async_comm::UDP, and async_comm::TCPClient.
|
protectedpure virtual |
Implemented in async_comm::Serial, async_comm::UDP, and async_comm::TCPClient.
| bool async_comm::Comm::init | ( | ) |
|
protectedpure virtual |
Implemented in async_comm::Serial, async_comm::UDP, and async_comm::TCPClient.
| void async_comm::Comm::register_receive_callback | ( | std::function< void(const uint8_t *, size_t)> | fun | ) |
Register a callback function for when bytes are received on the port.
The callback function needs to accept two parameters. The first is of type const uint8_t*, and is a constant pointer to the data buffer. The second is of type size_t, and specifies the number of bytes available in the buffer.
| fun | Function to call when bytes are received |
|
inline |
| void async_comm::Comm::send_bytes | ( | const uint8_t * | src, |
| size_t | len | ||
| ) |
|
private |
|
private |
|
protected |
|
private |
|
staticprotected |
|
private |
|
private |
|
staticprotected |
|
private |