31 #include <boost/bind.hpp>    32 #include <sys/ioctl.h>    33 #include <linux/serial.h>    38 using namespace boost;
    53   boost::asio::io_service 
io;       
    54   boost::asio::serial_port 
port;    
    69   boost::function<void(const char*, size_t)> 
callback;
    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)
    81   open(devname, baud_rate, opt_parity, opt_csize, opt_flow, opt_stop);
    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)
    92   pimpl->port.open(devname);
    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);
   100   boost::asio::basic_serial_port<boost::asio::serial_port_service>::native_type native =
   101       pimpl->port.native();  
   102   struct serial_struct serial_tempf;
   103   ioctl(native, TIOCGSERIAL, &serial_tempf);
   104   serial_tempf.flags |= ASYNC_LOW_LATENCY;  
   105   ioctl(native, TIOCSSERIAL, &serial_tempf);
   110   thread t(boost::bind(&asio::io_service::run, &
pimpl->io));
   111   pimpl->backgroundThread.swap(t);
   123   lock_guard<mutex> l(
pimpl->errorMutex);
   134   pimpl->backgroundThread.join();
   138     throw(boost::system::system_error(boost::system::error_code(), 
"Error while closing the device"));
   145     lock_guard<mutex> l(
pimpl->writeQueueMutex);
   146     pimpl->writeQueue.insert(
pimpl->writeQueue.end(), 
data, data + size);
   154     lock_guard<mutex> l(
pimpl->writeQueueMutex);
   155     pimpl->writeQueue.insert(
pimpl->writeQueue.end(), data.begin(), data.end());
   163     lock_guard<mutex> l(
pimpl->writeQueueMutex);
   164     pimpl->writeQueue.insert(
pimpl->writeQueue.end(), s.begin(), s.end());
   186   pimpl->port.async_read_some(
   188       boost::bind(&
AsyncSerial::readEnd, 
this, asio::placeholders::error, asio::placeholders::bytes_transferred));
   202     if (error.value() == 45)
   222       pimpl->callback(
pimpl->readBuffer, bytes_transferred);
   231   if (
pimpl->writeBuffer == 0)
   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),
   247     lock_guard<mutex> l(
pimpl->writeQueueMutex);
   248     if (
pimpl->writeQueue.empty())
   250       pimpl->writeBuffer.reset();
   251       pimpl->writeBufferSize = 0;
   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),
   271   boost::system::error_code ec;
   272   pimpl->port.cancel(ec);
   275   pimpl->port.close(ec);
   282   lock_guard<mutex> l(
pimpl->errorMutex);
   288   pimpl->callback = callback;
   293   pimpl->callback.clear();
   298 #include <sys/types.h>   299 #include <sys/stat.h>   311   boost::thread backgroundThread;   
   314   mutable boost::mutex errorMutex;  
   321   boost::function<void(const char*, size_t)> callback;
   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)
   333   open(devname, baud_rate, opt_parity, opt_csize, opt_flow, opt_stop);
   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)
   345   struct termios new_attributes;
   350   pimpl->fd = 
::open(devname.c_str(), O_RDWR | O_NOCTTY | O_NONBLOCK);
   352     throw(boost::system::system_error(boost::system::error_code(), 
"Failed to open port"));
   355   status = tcgetattr(
pimpl->fd, &new_attributes);
   356   if (status < 0 || !isatty(
pimpl->fd))
   359     throw(boost::system::system_error(boost::system::error_code(), 
"Device is not a tty"));
   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);  
   370   new_attributes.c_cc[VMIN] = 1;   
   371   new_attributes.c_cc[VTIME] = 1;  
   433       throw(boost::system::system_error(boost::system::error_code(), 
"Unsupported baud rate"));
   437   cfsetospeed(&new_attributes, speed);
   438   cfsetispeed(&new_attributes, speed);
   441   status = tcsetattr(
pimpl->fd, TCSANOW, &new_attributes);
   445     throw(boost::system::system_error(boost::system::error_code(), 
"Can't set port attributes"));
   449   status = fcntl(
pimpl->fd, F_GETFL, 0);
   451     fcntl(
pimpl->fd, F_SETFL, status & ~O_NONBLOCK);
   457   pimpl->backgroundThread.swap(t);
   467   lock_guard<mutex> l(
pimpl->errorMutex);
   480   pimpl->backgroundThread.join();
   483     throw(boost::system::system_error(boost::system::error_code(), 
"Error while closing the device"));
   495   if (::
write(
pimpl->fd, &data[0], data.size()) != data.size())
   501   if (::
write(
pimpl->fd, &s[0], s.size()) != s.size())
   563   lock_guard<mutex> l(
pimpl->errorMutex);
   569   pimpl->callback = callback;
   574   pimpl->callback.clear();
   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)
 
boost::mutex writeQueueMutex
Mutex for access to writeQueue. 
boost::shared_array< char > writeBuffer
Data being written. 
boost::mutex errorMutex
Mutex for access to error. 
void writeString(const std::string &s)
size_t writeBufferSize
Size of writeBuffer. 
boost::asio::serial_port port
Serial port object. 
static const int readBufferSize
void setErrorStatus(bool e)
boost::function< void(const char *, size_t)> callback
Read complete callback. 
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. 
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))
std::vector< char > writeQueue
Data are queued here before they go in writeBuffer. 
boost::asio::io_service io
Io service object. 
void write(const char *data, size_t size)
void readEnd(const boost::system::error_code &error, size_t bytes_transferred)
bool open
True if port open. 
virtual ~CallbackAsyncSerial()
boost::shared_ptr< AsyncSerialImpl > pimpl