comm.h
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD-3 License)
3  *
4  * Copyright (c) 2018 Daniel Koch.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions are met:
9  *
10  * * Redistributions of source code must retain the above copyright notice, this
11  * list of conditions and the following disclaimer.
12  *
13  * * Redistributions in binary form must reproduce the above copyright notice,
14  * this list of conditions and the following disclaimer in the documentation
15  * and/or other materials provided with the distribution.
16  *
17  * * Neither the name of the copyright holder nor the names of its
18  * contributors may be used to endorse or promote products derived from
19  * this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
22  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
23  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
24  * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
25  * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
26  * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
27  * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
28  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
29  * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
30  * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
31  */
32 
38 #ifndef ASYNC_COMM_COMM_H
39 #define ASYNC_COMM_COMM_H
40 
41 #include <condition_variable>
42 #include <cstddef>
43 #include <cstdint>
44 #include <functional>
45 #include <list>
46 #include <mutex>
47 #include <thread>
48 
49 #include <boost/asio.hpp>
50 #include <boost/function.hpp>
51 
52 namespace async_comm
53 {
54 
59 class Comm
60 {
61 public:
62  Comm();
63  virtual ~Comm();
64 
69  bool init();
70 
74  void close();
75 
81  void send_bytes(const uint8_t * src, size_t len);
82 
87  inline void send_byte(uint8_t data) { send_bytes(&data, 1); }
88 
102  void register_receive_callback(std::function<void(const uint8_t*, size_t)> fun);
103 
104 protected:
105 
106  static constexpr size_t READ_BUFFER_SIZE = 1024;
107  static constexpr size_t WRITE_BUFFER_SIZE = 1024;
108 
109  virtual bool is_open() = 0;
110  virtual bool do_init() = 0;
111  virtual void do_close() = 0;
112  virtual void do_async_read(const boost::asio::mutable_buffers_1 &buffer,
113  boost::function<void(const boost::system::error_code&, size_t)> handler) = 0;
114  virtual void do_async_write(const boost::asio::const_buffers_1 &buffer,
115  boost::function<void(const boost::system::error_code&, size_t)> handler) = 0;
116 
117  boost::asio::io_service io_service_;
118 
119 private:
120 
121  struct ReadBuffer
122  {
124  size_t len;
125 
126  ReadBuffer(const uint8_t * buf, size_t len) : len(len)
127  {
128  assert(len <= READ_BUFFER_SIZE); // only checks in debug mode
129  memcpy(data, buf, len);
130  }
131  };
132 
133  struct WriteBuffer
134  {
136  size_t len;
137  size_t pos;
138 
139  WriteBuffer() : len(0), pos(0) {}
140 
141  WriteBuffer(const uint8_t * buf, size_t len) : len(len), pos(0)
142  {
143  assert(len <= WRITE_BUFFER_SIZE); // only checks in debug mode
144  memcpy(data, buf, len);
145  }
146 
147  const uint8_t * dpos() const { return data + pos; }
148 
149  size_t nbytes() const { return len - pos; }
150  };
151 
152  typedef std::lock_guard<std::recursive_mutex> mutex_lock;
153 
154  void async_read();
155  void async_read_end(const boost::system::error_code& error, size_t bytes_transferred);
156 
157  void async_write(bool check_write_state);
158  void async_write_end(const boost::system::error_code& error, size_t bytes_transferred);
159 
160  void process_callbacks();
161 
162  std::thread io_thread_;
163  std::thread callback_thread_;
164 
166  std::list<ReadBuffer> read_queue_;
169  bool new_data_;
171 
172  std::list<WriteBuffer> write_queue_;
173  std::recursive_mutex write_mutex_;
175 
176  std::function<void(const uint8_t*, size_t)> receive_callback_;
177 };
178 
179 } // namespace async_comm
180 
181 #endif // ASYNC_COMM_COMM_H
std::thread callback_thread_
Definition: comm.h:163
virtual void do_async_read(const boost::asio::mutable_buffers_1 &buffer, boost::function< void(const boost::system::error_code &, size_t)> handler)=0
static constexpr size_t WRITE_BUFFER_SIZE
Definition: comm.h:107
boost::asio::io_service io_service_
Definition: comm.h:117
bool write_in_progress_
Definition: comm.h:174
WriteBuffer(const uint8_t *buf, size_t len)
Definition: comm.h:141
uint8_t read_buffer_[READ_BUFFER_SIZE]
Definition: comm.h:165
Abstract base class for an asynchronous communication port.
Definition: comm.h:59
void async_read_end(const boost::system::error_code &error, size_t bytes_transferred)
Definition: comm.cpp:123
void send_bytes(const uint8_t *src, size_t len)
Send bytes from a buffer over the port.
Definition: comm.cpp:94
bool init()
Initializes and opens the port.
Definition: comm.cpp:58
std::lock_guard< std::recursive_mutex > mutex_lock
Definition: comm.h:152
virtual bool is_open()=0
size_t nbytes() const
Definition: comm.h:149
void send_byte(uint8_t data)
Send a single byte over the port.
Definition: comm.h:87
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.
Definition: comm.cpp:107
std::thread io_thread_
Definition: comm.h:162
std::list< WriteBuffer > write_queue_
Definition: comm.h:172
std::recursive_mutex write_mutex_
Definition: comm.h:173
void async_write(bool check_write_state)
Definition: comm.cpp:142
void close()
Closes the port.
Definition: comm.cpp:71
const uint8_t * dpos() const
Definition: comm.h:147
static constexpr size_t READ_BUFFER_SIZE
Definition: comm.h:106
void async_write_end(const boost::system::error_code &error, size_t bytes_transferred)
Definition: comm.cpp:160
std::condition_variable condition_variable_
Definition: comm.h:168
void async_read()
Definition: comm.cpp:112
ReadBuffer(const uint8_t *buf, size_t len)
Definition: comm.h:126
std::list< ReadBuffer > read_queue_
Definition: comm.h:166
std::mutex mutex
mutex for synchronization between the main thread and callback thread
virtual bool do_init()=0
bool new_data_
Definition: comm.h:169
std::function< void(const uint8_t *, size_t)> receive_callback_
Definition: comm.h:176
virtual ~Comm()
Definition: comm.cpp:54
virtual void do_async_write(const boost::asio::const_buffers_1 &buffer, boost::function< void(const boost::system::error_code &, size_t)> handler)=0
bool shutdown_requested_
Definition: comm.h:170
uint8_t data[READ_BUFFER_SIZE]
Definition: comm.h:123
void process_callbacks()
Definition: comm.cpp:189
std::mutex callback_mutex_
Definition: comm.h:167
std::condition_variable condition_variable
condition variable used to suspend main thread until all messages have been received back ...
virtual void do_close()=0


async_comm
Author(s):
autogenerated on Thu May 16 2019 03:03:47