Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
ublox_gps::AsyncWorker< StreamT > Class Template Reference

Handles Asynchronous I/O reading and writing. More...

#include <async_worker.h>

Inheritance diagram for ublox_gps::AsyncWorker< StreamT >:
Inheritance graph
[legend]

Public Types

typedef boost::mutex Mutex
 
typedef boost::mutex::scoped_lock ScopedLock
 
- Public Types inherited from ublox_gps::Worker
typedef boost::function< void(unsigned char *, std::size_t &)> Callback
 

Public Member Functions

 AsyncWorker (boost::shared_ptr< StreamT > stream, boost::shared_ptr< boost::asio::io_service > io_service, std::size_t buffer_size=8192)
 Construct an Asynchronous I/O worker. More...
 
bool isOpen () const
 Whether or not the I/O stream is open. More...
 
bool send (const unsigned char *data, const unsigned int size)
 Send the data bytes via the I/O stream. More...
 
void setCallback (const Callback &callback)
 Set the callback function which handles input messages. More...
 
void setRawDataCallback (const Callback &callback)
 Set the callback function which handles raw data. More...
 
void wait (const boost::posix_time::time_duration &timeout)
 Wait for incoming messages. More...
 
virtual ~AsyncWorker ()
 
- Public Member Functions inherited from ublox_gps::Worker
virtual ~Worker ()
 

Protected Member Functions

void doClose ()
 Close the I/O stream. More...
 
void doRead ()
 Read the input stream. More...
 
void doRead ()
 
void doWrite ()
 Send all the data in the output buffer. More...
 
void doWrite ()
 
void readEnd (const boost::system::error_code &, std::size_t)
 Process messages read from the input stream. More...
 

Protected Attributes

boost::shared_ptr< boost::thread > background_thread_
 
std::vector< unsigned char > in_
 The input buffer. More...
 
std::size_t in_buffer_size_
 
boost::shared_ptr< boost::asio::io_service > io_service_
 The I/O service. More...
 
std::vector< unsigned char > out_
 The output buffer. More...
 
Callback read_callback_
 Callback function to handle received messages. More...
 
boost::condition read_condition_
 
Mutex read_mutex_
 Lock for the input buffer. More...
 
bool stopping_
 Whether or not the I/O service is closed. More...
 
boost::shared_ptr< StreamT > stream_
 The I/O stream. More...
 
Callback write_callback_
 Callback function to handle raw data. More...
 
boost::condition write_condition_
 
Mutex write_mutex_
 Lock for the output buffer. More...
 

Detailed Description

template<typename StreamT>
class ublox_gps::AsyncWorker< StreamT >

Handles Asynchronous I/O reading and writing.

Definition at line 51 of file async_worker.h.

Member Typedef Documentation

◆ Mutex

template<typename StreamT >
typedef boost::mutex ublox_gps::AsyncWorker< StreamT >::Mutex

Definition at line 53 of file async_worker.h.

◆ ScopedLock

template<typename StreamT >
typedef boost::mutex::scoped_lock ublox_gps::AsyncWorker< StreamT >::ScopedLock

Definition at line 54 of file async_worker.h.

Constructor & Destructor Documentation

◆ AsyncWorker()

template<typename StreamT >
ublox_gps::AsyncWorker< StreamT >::AsyncWorker ( boost::shared_ptr< StreamT >  stream,
boost::shared_ptr< boost::asio::io_service >  io_service,
std::size_t  buffer_size = 8192 
)

Construct an Asynchronous I/O worker.

Parameters
streamthe stream for th I/O service
io_servicethe I/O service
buffer_sizethe size of the input and output buffers

Definition at line 138 of file async_worker.h.

◆ ~AsyncWorker()

template<typename StreamT >
ublox_gps::AsyncWorker< StreamT >::~AsyncWorker
virtual

Definition at line 155 of file async_worker.h.

Member Function Documentation

◆ doClose()

template<typename StreamT >
void ublox_gps::AsyncWorker< StreamT >::doClose
protected

Close the I/O stream.

Definition at line 294 of file async_worker.h.

◆ doRead() [1/2]

template<typename StreamT >
void ublox_gps::AsyncWorker< StreamT >::doRead
protected

Read the input stream.

Definition at line 226 of file async_worker.h.

◆ doRead() [2/2]

void ublox_gps::AsyncWorker< boost::asio::ip::udp::socket >::doRead ( )
inlineprotected

Definition at line 236 of file async_worker.h.

◆ doWrite() [1/2]

template<typename StreamT >
void ublox_gps::AsyncWorker< StreamT >::doWrite
protected

Send all the data in the output buffer.

Definition at line 181 of file async_worker.h.

◆ doWrite() [2/2]

void ublox_gps::AsyncWorker< boost::asio::ip::udp::socket >::doWrite ( )
inlineprotected

Definition at line 203 of file async_worker.h.

◆ isOpen()

template<typename StreamT >
bool ublox_gps::AsyncWorker< StreamT >::isOpen ( ) const
inlinevirtual

Whether or not the I/O stream is open.

Implements ublox_gps::Worker.

Definition at line 91 of file async_worker.h.

◆ readEnd()

template<typename StreamT >
void ublox_gps::AsyncWorker< StreamT >::readEnd ( const boost::system::error_code &  error,
std::size_t  bytes_transfered 
)
protected

Process messages read from the input stream.

Parameters
error_codean error code for read failures
thenumber of bytes received

Definition at line 247 of file async_worker.h.

◆ send()

template<typename StreamT >
bool ublox_gps::AsyncWorker< StreamT >::send ( const unsigned char *  data,
const unsigned int  size 
)
virtual

Send the data bytes via the I/O stream.

Parameters
datathe buffer of data bytes to send
sizethe size of the buffer

Implements ublox_gps::Worker.

Definition at line 162 of file async_worker.h.

◆ setCallback()

template<typename StreamT >
void ublox_gps::AsyncWorker< StreamT >::setCallback ( const Callback callback)
inlinevirtual

Set the callback function which handles input messages.

Parameters
callbackthe read callback which handles received messages

Implements ublox_gps::Worker.

Definition at line 71 of file async_worker.h.

◆ setRawDataCallback()

template<typename StreamT >
void ublox_gps::AsyncWorker< StreamT >::setRawDataCallback ( const Callback callback)
inlinevirtual

Set the callback function which handles raw data.

Parameters
callbackthe write callback which handles raw data

Implements ublox_gps::Worker.

Definition at line 77 of file async_worker.h.

◆ wait()

template<typename StreamT >
void ublox_gps::AsyncWorker< StreamT >::wait ( const boost::posix_time::time_duration &  timeout)
virtual

Wait for incoming messages.

Parameters
timeoutthe maximum time to wait

Implements ublox_gps::Worker.

Definition at line 305 of file async_worker.h.

Member Data Documentation

◆ background_thread_

template<typename StreamT >
boost::shared_ptr<boost::thread> ublox_gps::AsyncWorker< StreamT >::background_thread_
protected

thread for the I/O service

Definition at line 129 of file async_worker.h.

◆ in_

template<typename StreamT >
std::vector<unsigned char> ublox_gps::AsyncWorker< StreamT >::in_
protected

The input buffer.

Definition at line 121 of file async_worker.h.

◆ in_buffer_size_

template<typename StreamT >
std::size_t ublox_gps::AsyncWorker< StreamT >::in_buffer_size_
protected

number of bytes currently in the input buffer

Definition at line 122 of file async_worker.h.

◆ io_service_

template<typename StreamT >
boost::shared_ptr<boost::asio::io_service> ublox_gps::AsyncWorker< StreamT >::io_service_
protected

The I/O service.

Definition at line 117 of file async_worker.h.

◆ out_

template<typename StreamT >
std::vector<unsigned char> ublox_gps::AsyncWorker< StreamT >::out_
protected

The output buffer.

Definition at line 127 of file async_worker.h.

◆ read_callback_

template<typename StreamT >
Callback ublox_gps::AsyncWorker< StreamT >::read_callback_
protected

Callback function to handle received messages.

Definition at line 131 of file async_worker.h.

◆ read_condition_

template<typename StreamT >
boost::condition ublox_gps::AsyncWorker< StreamT >::read_condition_
protected

Definition at line 120 of file async_worker.h.

◆ read_mutex_

template<typename StreamT >
Mutex ublox_gps::AsyncWorker< StreamT >::read_mutex_
protected

Lock for the input buffer.

Definition at line 119 of file async_worker.h.

◆ stopping_

template<typename StreamT >
bool ublox_gps::AsyncWorker< StreamT >::stopping_
protected

Whether or not the I/O service is closed.

Definition at line 134 of file async_worker.h.

◆ stream_

template<typename StreamT >
boost::shared_ptr<StreamT> ublox_gps::AsyncWorker< StreamT >::stream_
protected

The I/O stream.

Definition at line 116 of file async_worker.h.

◆ write_callback_

template<typename StreamT >
Callback ublox_gps::AsyncWorker< StreamT >::write_callback_
protected

Callback function to handle raw data.

Definition at line 132 of file async_worker.h.

◆ write_condition_

template<typename StreamT >
boost::condition ublox_gps::AsyncWorker< StreamT >::write_condition_
protected

Definition at line 126 of file async_worker.h.

◆ write_mutex_

template<typename StreamT >
Mutex ublox_gps::AsyncWorker< StreamT >::write_mutex_
protected

Lock for the output buffer.

Definition at line 125 of file async_worker.h.


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


ublox_gps
Author(s): Johannes Meyer
autogenerated on Wed Dec 7 2022 03:47:53