Classes | Public Member Functions | Protected Member Functions | Protected Attributes | Static Protected Attributes | Private Types | Private Member Functions | Private Attributes | List of all members
async_comm::Comm Class Referenceabstract

Abstract base class for an asynchronous communication port. More...

#include <comm.h>

Inheritance diagram for async_comm::Comm:
Inheritance graph
[legend]

Classes

struct  ReadBuffer
 
struct  WriteBuffer
 

Public Member Functions

void close ()
 Closes the port. More...
 
 Comm (MessageHandler &message_handler=default_message_handler_)
 Set up asynchronous communication base class. More...
 
bool init ()
 Initializes and opens the port. More...
 
void register_listener (CommListener &listener)
 Register a listener for when bytes are received on 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_
 
MessageHandlermessage_handler_
 

Static Protected Attributes

static DefaultMessageHandler default_message_handler_
 
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_
 
std::vector< std::reference_wrapper< CommListener > > listeners_
 
bool new_data_
 
uint8_t read_buffer_ [READ_BUFFER_SIZE]
 
std::list< ReadBufferread_queue_
 
std::function< void(const uint8_t *, size_t)> receive_callback_ = nullptr
 
bool shutdown_requested_
 
bool write_in_progress_
 
std::recursive_mutex write_mutex_
 
std::list< WriteBufferwrite_queue_
 

Detailed Description

Abstract base class for an asynchronous communication port.

Definition at line 81 of file comm.h.

Member Typedef Documentation

typedef std::lock_guard<std::recursive_mutex> async_comm::Comm::mutex_lock
private

Definition at line 192 of file comm.h.

Constructor & Destructor Documentation

async_comm::Comm::Comm ( MessageHandler message_handler = default_message_handler_)

Set up asynchronous communication base class.

Parameters
message_handlerCustom message handler, or omit for default handler

Definition at line 48 of file comm.cpp.

async_comm::Comm::~Comm ( )
virtual

Definition at line 57 of file comm.cpp.

Member Function Documentation

void async_comm::Comm::async_read ( )
private

Definition at line 120 of file comm.cpp.

void async_comm::Comm::async_read_end ( const boost::system::error_code &  error,
size_t  bytes_transferred 
)
private

Definition at line 131 of file comm.cpp.

void async_comm::Comm::async_write ( bool  check_write_state)
private

Definition at line 150 of file comm.cpp.

void async_comm::Comm::async_write_end ( const boost::system::error_code &  error,
size_t  bytes_transferred 
)
private

Definition at line 168 of file comm.cpp.

void async_comm::Comm::close ( )

Closes the port.

Definition at line 74 of file comm.cpp.

virtual void async_comm::Comm::do_async_read ( const boost::asio::mutable_buffers_1 &  buffer,
boost::function< void(const boost::system::error_code &, size_t)>  handler 
)
protectedpure virtual
virtual void async_comm::Comm::do_async_write ( const boost::asio::const_buffers_1 &  buffer,
boost::function< void(const boost::system::error_code &, size_t)>  handler 
)
protectedpure virtual
virtual void async_comm::Comm::do_close ( )
protectedpure virtual
virtual bool async_comm::Comm::do_init ( )
protectedpure virtual
bool async_comm::Comm::init ( )

Initializes and opens the port.

Returns
True if the port was succesfully initialized

Definition at line 61 of file comm.cpp.

virtual bool async_comm::Comm::is_open ( )
protectedpure virtual
void async_comm::Comm::process_callbacks ( )
private

Definition at line 197 of file comm.cpp.

void async_comm::Comm::register_listener ( CommListener listener)

Register a listener for when bytes are received on the port.

The listener must inherit from CommListener and implement the receive_callback function. This is another mechanism for receiving data from the Comm interface without needing to create function pointers. Multiple listeners can be added and all will get the callback

Parameters
listenerReference to listener

Definition at line 115 of file comm.cpp.

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.

Warning
The data buffer passed to the callback function will be invalid after the callback function exits. If you want to store the data for later processing, you must copy the data to a new buffer rather than storing the pointer to the buffer.
Parameters
funFunction to call when bytes are received

Definition at line 110 of file comm.cpp.

void async_comm::Comm::send_byte ( uint8_t  data)
inline

Send a single byte over the port.

Parameters
dataByte to send

Definition at line 113 of file comm.h.

void async_comm::Comm::send_bytes ( const uint8_t *  src,
size_t  len 
)

Send bytes from a buffer over the port.

Parameters
srcAddress of the buffer
lenNumber of bytes to send

Definition at line 97 of file comm.cpp.

Member Data Documentation

std::mutex async_comm::Comm::callback_mutex_
private

Definition at line 207 of file comm.h.

std::thread async_comm::Comm::callback_thread_
private

Definition at line 203 of file comm.h.

std::condition_variable async_comm::Comm::condition_variable_
private

Definition at line 208 of file comm.h.

DefaultMessageHandler async_comm::Comm::default_message_handler_
staticprotected

Definition at line 146 of file comm.h.

boost::asio::io_service async_comm::Comm::io_service_
protected

Definition at line 157 of file comm.h.

std::thread async_comm::Comm::io_thread_
private

Definition at line 202 of file comm.h.

std::vector<std::reference_wrapper<CommListener> > async_comm::Comm::listeners_
private

Definition at line 217 of file comm.h.

MessageHandler& async_comm::Comm::message_handler_
protected

Definition at line 156 of file comm.h.

bool async_comm::Comm::new_data_
private

Definition at line 209 of file comm.h.

uint8_t async_comm::Comm::read_buffer_[READ_BUFFER_SIZE]
private

Definition at line 205 of file comm.h.

constexpr size_t async_comm::Comm::READ_BUFFER_SIZE = 1024
staticprotected

Definition at line 143 of file comm.h.

std::list<ReadBuffer> async_comm::Comm::read_queue_
private

Definition at line 206 of file comm.h.

std::function<void(const uint8_t *, size_t)> async_comm::Comm::receive_callback_ = nullptr
private

Definition at line 216 of file comm.h.

bool async_comm::Comm::shutdown_requested_
private

Definition at line 210 of file comm.h.

constexpr size_t async_comm::Comm::WRITE_BUFFER_SIZE = 1024
staticprotected

Definition at line 144 of file comm.h.

bool async_comm::Comm::write_in_progress_
private

Definition at line 214 of file comm.h.

std::recursive_mutex async_comm::Comm::write_mutex_
private

Definition at line 213 of file comm.h.

std::list<WriteBuffer> async_comm::Comm::write_queue_
private

Definition at line 212 of file comm.h.


The documentation for this class was generated from the following files:


async_comm
Author(s):
autogenerated on Fri May 14 2021 02:35:38