Template Class AsyncWorker

Inheritance Relationships

Base Type

Class Documentation

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

Handles Asynchronous I/O reading and writing.

Public Functions

explicit AsyncWorker(std::shared_ptr<StreamT> stream, std::shared_ptr<asio::io_service> io_service, std::size_t buffer_size, int debug, const rclcpp::Logger &logger)

Construct an Asynchronous I/O worker.

Parameters:
  • stream – the stream for th I/O service

  • io_service – the I/O service

  • buffer_size – the size of the input and output buffers

~AsyncWorker() override
AsyncWorker(AsyncWorker &&c) = delete
AsyncWorker &operator=(AsyncWorker &&c) = delete
AsyncWorker(const AsyncWorker &c) = delete
AsyncWorker &operator=(const AsyncWorker &c) = delete
inline virtual void setCallback(const WorkerCallback &callback) override

Set the callback function which handles input messages.

Parameters:

callback – the read callback which handles received messages

inline virtual void setRawDataCallback(const WorkerRawCallback &callback) override

Set the callback function which handles raw data.

Parameters:

callback – the write callback which handles raw data

virtual bool send(const unsigned char *data, const unsigned int size) override

Send the data bytes via the I/O stream.

Parameters:
  • data – the buffer of data bytes to send

  • size – the size of the buffer

virtual void wait(const std::chrono::milliseconds &timeout) override

Wait for incoming messages.

Parameters:

timeout – the maximum time to wait

inline virtual bool isOpen() const override

Whether or not the I/O stream is open.