AsyncSerial.cpp
Go to the documentation of this file.
1 /*
2  * File: AsyncSerial.cpp
3  * Author: Terraneo Federico
4  * Distributed under the Boost Software License, Version 1.0.
5  * Created on September 7, 2009, 10:46 AM
6  *
7  * v1.02: Fixed a bug in BufferedAsyncSerial: Using the default constructor
8  * the callback was not set up and reading didn't work.
9  *
10  * v1.01: Fixed a bug that did not allow to reopen a closed serial port.
11  *
12  * v1.00: First release.
13  *
14  * IMPORTANT:
15  * On Mac OS X boost asio's serial ports have bugs, and the usual implementation
16  * of this class does not work. So a workaround class was written temporarily,
17  * until asio (hopefully) will fix Mac compatibility for serial ports.
18  *
19  * Please note that unlike said in the documentation on OS X until asio will
20  * be fixed serial port *writes* are *not* asynchronous, but at least
21  * asynchronous *read* works.
22  * In addition the serial port open ignores the following options: parity,
23  * character size, flow, stop bits, and defaults to 8N1 format.
24  * I know it is bad but at least it's better than nothing.
25  *
26  */
27 
28 #include <string>
29 #include <algorithm>
30 #include <iostream>
31 #include <boost/bind.hpp>
32 #include <sys/ioctl.h>
33 #include <linux/serial.h>
34 
36 
37 using namespace std;
38 using namespace boost;
39 
40 //
41 // Class AsyncSerial
42 //
43 
44 #ifndef __APPLE__
45 
46 class AsyncSerialImpl : private boost::noncopyable
47 {
48 public:
49  AsyncSerialImpl() : io(), port(io), backgroundThread(), open(false), error(false)
50  {
51  }
52 
53  boost::asio::io_service io;
54  boost::asio::serial_port port;
55  boost::thread backgroundThread;
56  bool open;
57  bool error;
58  mutable boost::mutex errorMutex;
59 
61  std::vector<char> writeQueue;
63  size_t writeBufferSize;
64  boost::mutex writeQueueMutex;
65  char readBuffer[AsyncSerial::readBufferSize];
66  char readBuffer1[AsyncSerial::readBufferSize];
67  char readBuffer2[AsyncSerial::readBufferSize];
69  boost::function<void(const char*, size_t)> callback;
70 };
71 
73 {
74 }
75 
76 AsyncSerial::AsyncSerial(const std::string& devname, unsigned int baud_rate, asio::serial_port_base::parity opt_parity,
77  asio::serial_port_base::character_size opt_csize,
78  asio::serial_port_base::flow_control opt_flow, asio::serial_port_base::stop_bits opt_stop)
79  : pimpl(new AsyncSerialImpl)
80 {
81  open(devname, baud_rate, opt_parity, opt_csize, opt_flow, opt_stop);
82 }
83 
84 void AsyncSerial::open(const std::string& devname, unsigned int baud_rate, asio::serial_port_base::parity opt_parity,
85  asio::serial_port_base::character_size opt_csize, asio::serial_port_base::flow_control opt_flow,
86  asio::serial_port_base::stop_bits opt_stop)
87 {
88  if (isOpen())
89  close();
90 
91  setErrorStatus(true); // If an exception is thrown, error_ remains true
92  pimpl->port.open(devname);
93 
94  pimpl->port.set_option(asio::serial_port_base::baud_rate(baud_rate));
95  pimpl->port.set_option(opt_parity);
96  pimpl->port.set_option(opt_csize);
97  pimpl->port.set_option(opt_flow);
98  pimpl->port.set_option(opt_stop);
99 
100  boost::asio::basic_serial_port<boost::asio::serial_port_service>::native_type native =
101  pimpl->port.native(); // serial_port_ is the boost's serial port class.
102  struct serial_struct serial_tempf;
103  ioctl(native, TIOCGSERIAL, &serial_tempf);
104  serial_tempf.flags |= ASYNC_LOW_LATENCY; // (0x2000)
105  ioctl(native, TIOCSSERIAL, &serial_tempf);
106 
107  // This gives some work to the io_service before it is started
108  pimpl->io.post(boost::bind(&AsyncSerial::doRead, this));
109 
110  thread t(boost::bind(&asio::io_service::run, &pimpl->io));
111  pimpl->backgroundThread.swap(t);
112  setErrorStatus(false); // If we get here, no error
113  pimpl->open = true; // Port is now open
114 }
115 
117 {
118  return pimpl->open;
119 }
120 
122 {
123  lock_guard<mutex> l(pimpl->errorMutex);
124  return pimpl->error;
125 }
126 
128 {
129  if (!isOpen())
130  return;
131 
132  pimpl->open = false;
133  pimpl->io.post(boost::bind(&AsyncSerial::doClose, this));
134  pimpl->backgroundThread.join();
135  pimpl->io.reset();
136  if (errorStatus())
137  {
138  throw(boost::system::system_error(boost::system::error_code(), "Error while closing the device"));
139  }
140 }
141 
142 void AsyncSerial::write(const char* data, size_t size)
143 {
144  {
145  lock_guard<mutex> l(pimpl->writeQueueMutex);
146  pimpl->writeQueue.insert(pimpl->writeQueue.end(), data, data + size);
147  }
148  pimpl->io.post(boost::bind(&AsyncSerial::doWrite, this));
149 }
150 
151 void AsyncSerial::write(const std::vector<char>& data)
152 {
153  {
154  lock_guard<mutex> l(pimpl->writeQueueMutex);
155  pimpl->writeQueue.insert(pimpl->writeQueue.end(), data.begin(), data.end());
156  }
157  pimpl->io.post(boost::bind(&AsyncSerial::doWrite, this));
158 }
159 
160 void AsyncSerial::writeString(const std::string& s)
161 {
162  {
163  lock_guard<mutex> l(pimpl->writeQueueMutex);
164  pimpl->writeQueue.insert(pimpl->writeQueue.end(), s.begin(), s.end());
165  }
166  pimpl->io.post(boost::bind(&AsyncSerial::doWrite, this));
167 }
168 
170 {
171  if (isOpen())
172  {
173  try
174  {
175  close();
176  }
177  catch (...)
178  {
179  // Don't throw from a destructor
180  }
181  }
182 }
183 
185 {
186  pimpl->port.async_read_some(
187  asio::buffer(pimpl->readBuffer, readBufferSize),
188  boost::bind(&AsyncSerial::readEnd, this, asio::placeholders::error, asio::placeholders::bytes_transferred));
189 
190  // asio::async_read(pimpl->port,asio::buffer(pimpl->readBuffer,readBufferSize),asio::transfer_exactly(54),
191  // boost::bind(&AsyncSerial::readEnd,
192  // this,
193  // asio::placeholders::error,
194  // asio::placeholders::bytes_transferred));
195 }
196 
197 void AsyncSerial::readEnd(const boost::system::error_code& error, size_t bytes_transferred)
198 {
199  if (error)
200  {
201 #ifdef __APPLE__
202  if (error.value() == 45)
203  {
204  // Bug on OS X, it might be necessary to repeat the setup
205  // http://osdir.com/ml/lib.boost.asio.user/2008-08/msg00004.html
206  doRead();
207  return;
208  }
209 #endif //__APPLE__
210  // error can be true even because the serial port was closed.
211  // In this case it is not a real error, so ignore
212  if (isOpen())
213  {
214  doClose();
215  setErrorStatus(true);
216  }
217  }
218  else
219  {
220  if (pimpl->callback)
221  {
222  pimpl->callback(pimpl->readBuffer, bytes_transferred);
223  }
224  doRead();
225  }
226 }
227 
229 {
230  // If a write operation is already in progress, do nothing
231  if (pimpl->writeBuffer == 0)
232  {
233  lock_guard<mutex> l(pimpl->writeQueueMutex);
234  pimpl->writeBufferSize = pimpl->writeQueue.size();
235  pimpl->writeBuffer.reset(new char[pimpl->writeQueue.size()]);
236  copy(pimpl->writeQueue.begin(), pimpl->writeQueue.end(), pimpl->writeBuffer.get());
237  pimpl->writeQueue.clear();
238  async_write(pimpl->port, asio::buffer(pimpl->writeBuffer.get(), pimpl->writeBufferSize),
239  boost::bind(&AsyncSerial::writeEnd, this, asio::placeholders::error));
240  }
241 }
242 
243 void AsyncSerial::writeEnd(const boost::system::error_code& error)
244 {
245  if (!error)
246  {
247  lock_guard<mutex> l(pimpl->writeQueueMutex);
248  if (pimpl->writeQueue.empty())
249  {
250  pimpl->writeBuffer.reset();
251  pimpl->writeBufferSize = 0;
252 
253  return;
254  }
255  pimpl->writeBufferSize = pimpl->writeQueue.size();
256  pimpl->writeBuffer.reset(new char[pimpl->writeQueue.size()]);
257  copy(pimpl->writeQueue.begin(), pimpl->writeQueue.end(), pimpl->writeBuffer.get());
258  pimpl->writeQueue.clear();
259  async_write(pimpl->port, asio::buffer(pimpl->writeBuffer.get(), pimpl->writeBufferSize),
260  boost::bind(&AsyncSerial::writeEnd, this, asio::placeholders::error));
261  }
262  else
263  {
264  setErrorStatus(true);
265  doClose();
266  }
267 }
268 
270 {
271  boost::system::error_code ec;
272  pimpl->port.cancel(ec);
273  if (ec)
274  setErrorStatus(true);
275  pimpl->port.close(ec);
276  if (ec)
277  setErrorStatus(true);
278 }
279 
281 {
282  lock_guard<mutex> l(pimpl->errorMutex);
283  pimpl->error = e;
284 }
285 
286 void AsyncSerial::setReadCallback(const boost::function<void(const char*, size_t)>& callback)
287 {
288  pimpl->callback = callback;
289 }
290 
292 {
293  pimpl->callback.clear();
294 }
295 
296 #else //__APPLE__
297 
298 #include <sys/types.h>
299 #include <sys/stat.h>
300 #include <fcntl.h>
301 #include <termios.h>
302 #include <unistd.h>
303 
304 class AsyncSerialImpl : private boost::noncopyable
305 {
306 public:
307  AsyncSerialImpl() : backgroundThread(), open(false), error(false)
308  {
309  }
310 
311  boost::thread backgroundThread;
312  bool open;
313  bool error;
314  mutable boost::mutex errorMutex;
315 
316  int fd;
317 
318  char readBuffer[AsyncSerial::readBufferSize];
319 
321  boost::function<void(const char*, size_t)> callback;
322 };
323 
325 {
326 }
327 
328 AsyncSerial::AsyncSerial(const std::string& devname, unsigned int baud_rate, asio::serial_port_base::parity opt_parity,
329  asio::serial_port_base::character_size opt_csize,
330  asio::serial_port_base::flow_control opt_flow, asio::serial_port_base::stop_bits opt_stop)
331  : pimpl(new AsyncSerialImpl)
332 {
333  open(devname, baud_rate, opt_parity, opt_csize, opt_flow, opt_stop);
334 }
335 
336 void AsyncSerial::open(const std::string& devname, unsigned int baud_rate, asio::serial_port_base::parity opt_parity,
337  asio::serial_port_base::character_size opt_csize, asio::serial_port_base::flow_control opt_flow,
338  asio::serial_port_base::stop_bits opt_stop)
339 {
340  if (isOpen())
341  close();
342 
343  setErrorStatus(true); // If an exception is thrown, error remains true
344 
345  struct termios new_attributes;
346  speed_t speed;
347  int status;
348 
349  // Open port
350  pimpl->fd = ::open(devname.c_str(), O_RDWR | O_NOCTTY | O_NONBLOCK);
351  if (pimpl->fd < 0)
352  throw(boost::system::system_error(boost::system::error_code(), "Failed to open port"));
353 
354  // Set Port parameters.
355  status = tcgetattr(pimpl->fd, &new_attributes);
356  if (status < 0 || !isatty(pimpl->fd))
357  {
358  ::close(pimpl->fd);
359  throw(boost::system::system_error(boost::system::error_code(), "Device is not a tty"));
360  }
361  new_attributes.c_iflag = IGNBRK;
362  new_attributes.c_oflag = 0;
363  new_attributes.c_lflag = 0;
364  new_attributes.c_cflag = (CS8 | CREAD | CLOCAL); // 8 data bit,Enable receiver,Ignore modem
365  /* In non canonical mode (Ctrl-C and other disabled, no echo,...) VMIN and VTIME work this way:
366  if the function read() has'nt read at least VMIN chars it waits until has read at least VMIN
367  chars (even if VTIME timeout expires); once it has read at least vmin chars, if subsequent
368  chars do not arrive before VTIME expires, it returns error; if a char arrives, it resets the
369  timeout, so the internal timer will again start from zero (for the nex char,if any)*/
370  new_attributes.c_cc[VMIN] = 1; // Minimum number of characters to read before returning error
371  new_attributes.c_cc[VTIME] = 1; // Set timeouts in tenths of second
372 
373  // Set baud rate
374  switch (baud_rate)
375  {
376  case 50:
377  speed = B50;
378  break;
379  case 75:
380  speed = B75;
381  break;
382  case 110:
383  speed = B110;
384  break;
385  case 134:
386  speed = B134;
387  break;
388  case 150:
389  speed = B150;
390  break;
391  case 200:
392  speed = B200;
393  break;
394  case 300:
395  speed = B300;
396  break;
397  case 600:
398  speed = B600;
399  break;
400  case 1200:
401  speed = B1200;
402  break;
403  case 1800:
404  speed = B1800;
405  break;
406  case 2400:
407  speed = B2400;
408  break;
409  case 4800:
410  speed = B4800;
411  break;
412  case 9600:
413  speed = B9600;
414  break;
415  case 19200:
416  speed = B19200;
417  break;
418  case 38400:
419  speed = B38400;
420  break;
421  case 57600:
422  speed = B57600;
423  break;
424  case 115200:
425  speed = B115200;
426  break;
427  case 230400:
428  speed = B230400;
429  break;
430  default:
431  {
432  ::close(pimpl->fd);
433  throw(boost::system::system_error(boost::system::error_code(), "Unsupported baud rate"));
434  }
435  }
436 
437  cfsetospeed(&new_attributes, speed);
438  cfsetispeed(&new_attributes, speed);
439 
440  // Make changes effective
441  status = tcsetattr(pimpl->fd, TCSANOW, &new_attributes);
442  if (status < 0)
443  {
444  ::close(pimpl->fd);
445  throw(boost::system::system_error(boost::system::error_code(), "Can't set port attributes"));
446  }
447 
448  // These 3 lines clear the O_NONBLOCK flag
449  status = fcntl(pimpl->fd, F_GETFL, 0);
450  if (status != -1)
451  fcntl(pimpl->fd, F_SETFL, status & ~O_NONBLOCK);
452 
453  setErrorStatus(false); // If we get here, no error
454  pimpl->open = true; // Port is now open
455 
456  thread t(bind(&AsyncSerial::doRead, this));
457  pimpl->backgroundThread.swap(t);
458 }
459 
460 bool AsyncSerial::isOpen() const
461 {
462  return pimpl->open;
463 }
464 
465 bool AsyncSerial::errorStatus() const
466 {
467  lock_guard<mutex> l(pimpl->errorMutex);
468  return pimpl->error;
469 }
470 
471 void AsyncSerial::close()
472 {
473  if (!isOpen())
474  return;
475 
476  pimpl->open = false;
477 
478  ::close(pimpl->fd); // The thread waiting on I/O should return
479 
480  pimpl->backgroundThread.join();
481  if (errorStatus())
482  {
483  throw(boost::system::system_error(boost::system::error_code(), "Error while closing the device"));
484  }
485 }
486 
487 void AsyncSerial::write(const char* data, size_t size)
488 {
489  if (::write(pimpl->fd, data, size) != size)
490  setErrorStatus(true);
491 }
492 
493 void AsyncSerial::write(const std::vector<char>& data)
494 {
495  if (::write(pimpl->fd, &data[0], data.size()) != data.size())
496  setErrorStatus(true);
497 }
498 
499 void AsyncSerial::writeString(const std::string& s)
500 {
501  if (::write(pimpl->fd, &s[0], s.size()) != s.size())
502  setErrorStatus(true);
503 }
504 
506 {
507  if (isOpen())
508  {
509  try
510  {
511  close();
512  }
513  catch (...)
514  {
515  // Don't throw from a destructor
516  }
517  }
518 }
519 
520 void AsyncSerial::doRead()
521 {
522  // Read loop in spawned thread
523  for (;;)
524  {
525  int received = ::read(pimpl->fd, pimpl->readBuffer, readBufferSize);
526  if (received < 0)
527  {
528  if (isOpen() == false)
529  return; // Thread interrupted because port closed
530  else
531  {
532  setErrorStatus(true);
533  continue;
534  }
535  }
536  if (pimpl->callback)
537  pimpl->callback(pimpl->readBuffer, received);
538  }
539 }
540 
541 void AsyncSerial::readEnd(const boost::system::error_code& error, size_t bytes_transferred)
542 {
543  // Not used
544 }
545 
547 {
548  // Not used
549 }
550 
551 void AsyncSerial::writeEnd(const boost::system::error_code& error)
552 {
553  // Not used
554 }
555 
557 {
558  // Not used
559 }
560 
561 void AsyncSerial::setErrorStatus(bool e)
562 {
563  lock_guard<mutex> l(pimpl->errorMutex);
564  pimpl->error = e;
565 }
566 
567 void AsyncSerial::setReadCallback(const function<void(const char*, size_t)>& callback)
568 {
569  pimpl->callback = callback;
570 }
571 
573 {
574  pimpl->callback.clear();
575 }
576 
577 #endif //__APPLE__
578 
579 //
580 // Class CallbackAsyncSerial
581 //
582 
584 {
585 }
586 
587 CallbackAsyncSerial::CallbackAsyncSerial(const std::string& devname, unsigned int baud_rate,
588  asio::serial_port_base::parity opt_parity,
589  asio::serial_port_base::character_size opt_csize,
590  asio::serial_port_base::flow_control opt_flow,
591  asio::serial_port_base::stop_bits opt_stop)
592  : AsyncSerial(devname, baud_rate, opt_parity, opt_csize, opt_flow, opt_stop)
593 {
594 }
595 
596 void CallbackAsyncSerial::setCallback(const boost::function<void(const char*, size_t)>& callback)
597 {
598  setReadCallback(callback);
599 }
600 
602 {
604 }
605 
607 {
609 }
bool errorStatus() const
boost::mutex writeQueueMutex
Mutex for access to writeQueue.
Definition: AsyncSerial.cpp:64
boost::shared_array< char > writeBuffer
Data being written.
Definition: AsyncSerial.cpp:62
boost::mutex errorMutex
Mutex for access to error.
Definition: AsyncSerial.cpp:58
void writeString(const std::string &s)
XmlRpcServer s
size_t writeBufferSize
Size of writeBuffer.
Definition: AsyncSerial.cpp:63
boost::asio::serial_port port
Serial port object.
Definition: AsyncSerial.cpp:54
void doClose()
static const int readBufferSize
Definition: AsyncSerial.h:116
void setErrorStatus(bool e)
boost::function< void(const char *, size_t)> callback
Read complete callback.
Definition: AsyncSerial.cpp:69
virtual ~AsyncSerial()=0
void writeEnd(const boost::system::error_code &error)
void setCallback(const boost::function< void(const char *, size_t)> &callback)
void setReadCallback(const boost::function< void(const char *, size_t)> &callback)
boost::thread backgroundThread
Thread that runs read/write operations.
Definition: AsyncSerial.cpp:55
void open(const std::string &devname, unsigned int baud_rate, boost::asio::serial_port_base::parity opt_parity=boost::asio::serial_port_base::parity(boost::asio::serial_port_base::parity::none), boost::asio::serial_port_base::character_size opt_csize=boost::asio::serial_port_base::character_size(8), boost::asio::serial_port_base::flow_control opt_flow=boost::asio::serial_port_base::flow_control(boost::asio::serial_port_base::flow_control::none), boost::asio::serial_port_base::stop_bits opt_stop=boost::asio::serial_port_base::stop_bits(boost::asio::serial_port_base::stop_bits::one))
Definition: AsyncSerial.cpp:84
std::vector< char > writeQueue
Data are queued here before they go in writeBuffer.
Definition: AsyncSerial.cpp:61
boost::asio::io_service io
Io service object.
Definition: AsyncSerial.cpp:53
void write(const char *data, size_t size)
void readEnd(const boost::system::error_code &error, size_t bytes_transferred)
bool error
Error flag.
Definition: AsyncSerial.cpp:57
bool open
True if port open.
Definition: AsyncSerial.cpp:56
void clearReadCallback()
bool isOpen() const
void doWrite()
virtual ~CallbackAsyncSerial()
boost::shared_ptr< AsyncSerialImpl > pimpl
Definition: AsyncSerial.h:150


xiaoqiang_driver
Author(s): Xie fusheng
autogenerated on Mon Jun 10 2019 15:53:12