serial.cc
Go to the documentation of this file.
00001 /* Copyright 2012 William Woodall and John Harrison */
00002 #include <algorithm>
00003 
00004 #if !defined(_WIN32) && !defined(__OpenBSD__) && !defined(__FreeBSD__)
00005 # include <alloca.h>
00006 #endif
00007 
00008 #if defined (__MINGW32__)
00009 # define alloca __builtin_alloca
00010 #endif
00011 
00012 #include "serial/serial.h"
00013 
00014 #ifdef _WIN32
00015 #include "serial/impl/win.h"
00016 #else
00017 #include "serial/impl/unix.h"
00018 #endif
00019 
00020 using std::invalid_argument;
00021 using std::min;
00022 using std::numeric_limits;
00023 using std::vector;
00024 using std::size_t;
00025 using std::string;
00026 
00027 using serial::Serial;
00028 using serial::SerialException;
00029 using serial::IOException;
00030 using serial::bytesize_t;
00031 using serial::parity_t;
00032 using serial::stopbits_t;
00033 using serial::flowcontrol_t;
00034 
00035 class Serial::ScopedReadLock {
00036 public:
00037   ScopedReadLock(SerialImpl *pimpl) : pimpl_(pimpl) {
00038     this->pimpl_->readLock();
00039   }
00040   ~ScopedReadLock() {
00041     this->pimpl_->readUnlock();
00042   }
00043 private:
00044   // Disable copy constructors
00045   ScopedReadLock(const ScopedReadLock&);
00046   const ScopedReadLock& operator=(ScopedReadLock);
00047 
00048   SerialImpl *pimpl_;
00049 };
00050 
00051 class Serial::ScopedWriteLock {
00052 public:
00053   ScopedWriteLock(SerialImpl *pimpl) : pimpl_(pimpl) {
00054     this->pimpl_->writeLock();
00055   }
00056   ~ScopedWriteLock() {
00057     this->pimpl_->writeUnlock();
00058   }
00059 private:
00060   // Disable copy constructors
00061   ScopedWriteLock(const ScopedWriteLock&);
00062   const ScopedWriteLock& operator=(ScopedWriteLock);
00063   SerialImpl *pimpl_;
00064 };
00065 
00066 Serial::Serial (const string &port, uint32_t baudrate, serial::Timeout timeout,
00067                 bytesize_t bytesize, parity_t parity, stopbits_t stopbits,
00068                 flowcontrol_t flowcontrol)
00069  : pimpl_(new SerialImpl (port, baudrate, bytesize, parity,
00070                                            stopbits, flowcontrol))
00071 {
00072   pimpl_->setTimeout(timeout);
00073 }
00074 
00075 Serial::~Serial ()
00076 {
00077   delete pimpl_;
00078 }
00079 
00080 void
00081 Serial::open ()
00082 {
00083   pimpl_->open ();
00084 }
00085 
00086 void
00087 Serial::close ()
00088 {
00089   pimpl_->close ();
00090 }
00091 
00092 bool
00093 Serial::isOpen () const
00094 {
00095   return pimpl_->isOpen ();
00096 }
00097 
00098 size_t
00099 Serial::available ()
00100 {
00101   return pimpl_->available ();
00102 }
00103 
00104 bool
00105 Serial::waitReadable ()
00106 {
00107   serial::Timeout timeout(pimpl_->getTimeout ());
00108   return pimpl_->waitReadable(timeout.read_timeout_constant);
00109 }
00110 
00111 void
00112 Serial::waitByteTimes (size_t count)
00113 {
00114   pimpl_->waitByteTimes(count);
00115 }
00116 
00117 size_t
00118 Serial::read_ (uint8_t *buffer, size_t size)
00119 {
00120   return this->pimpl_->read (buffer, size);
00121 }
00122 
00123 size_t
00124 Serial::read (uint8_t *buffer, size_t size)
00125 {
00126   ScopedReadLock lock(this->pimpl_);
00127   return this->pimpl_->read (buffer, size);
00128 }
00129 
00130 size_t
00131 Serial::read (std::vector<uint8_t> &buffer, size_t size)
00132 {
00133   ScopedReadLock lock(this->pimpl_);
00134   uint8_t *buffer_ = new uint8_t[size];
00135   size_t bytes_read = 0;
00136 
00137   try {
00138     bytes_read = this->pimpl_->read (buffer_, size);
00139   }
00140   catch (const std::exception &e) {
00141     delete[] buffer_;
00142     throw;
00143   }
00144 
00145   buffer.insert (buffer.end (), buffer_, buffer_+bytes_read);
00146   delete[] buffer_;
00147   return bytes_read;
00148 }
00149 
00150 size_t
00151 Serial::read (std::string &buffer, size_t size)
00152 {
00153   ScopedReadLock lock(this->pimpl_);
00154   uint8_t *buffer_ = new uint8_t[size];
00155   size_t bytes_read = 0;
00156   try {
00157     bytes_read = this->pimpl_->read (buffer_, size);
00158   }
00159   catch (const std::exception &e) {
00160     delete[] buffer_;
00161     throw;
00162   }
00163   buffer.append (reinterpret_cast<const char*>(buffer_), bytes_read);
00164   delete[] buffer_;
00165   return bytes_read;
00166 }
00167 
00168 string
00169 Serial::read (size_t size)
00170 {
00171   std::string buffer;
00172   this->read (buffer, size);
00173   return buffer;
00174 }
00175 
00176 size_t
00177 Serial::readline (string &buffer, size_t size, string eol)
00178 {
00179   ScopedReadLock lock(this->pimpl_);
00180   size_t eol_len = eol.length ();
00181   uint8_t *buffer_ = static_cast<uint8_t*>
00182                               (alloca (size * sizeof (uint8_t)));
00183   size_t read_so_far = 0;
00184   while (true)
00185   {
00186     size_t bytes_read = this->read_ (buffer_ + read_so_far, 1);
00187     read_so_far += bytes_read;
00188     if (bytes_read == 0) {
00189       break; // Timeout occured on reading 1 byte
00190     }
00191     if (string (reinterpret_cast<const char*>
00192          (buffer_ + read_so_far - eol_len), eol_len) == eol) {
00193       break; // EOL found
00194     }
00195     if (read_so_far == size) {
00196       break; // Reached the maximum read length
00197     }
00198   }
00199   buffer.append(reinterpret_cast<const char*> (buffer_), read_so_far);
00200   return read_so_far;
00201 }
00202 
00203 string
00204 Serial::readline (size_t size, string eol)
00205 {
00206   std::string buffer;
00207   this->readline (buffer, size, eol);
00208   return buffer;
00209 }
00210 
00211 vector<string>
00212 Serial::readlines (size_t size, string eol)
00213 {
00214   ScopedReadLock lock(this->pimpl_);
00215   std::vector<std::string> lines;
00216   size_t eol_len = eol.length ();
00217   uint8_t *buffer_ = static_cast<uint8_t*>
00218     (alloca (size * sizeof (uint8_t)));
00219   size_t read_so_far = 0;
00220   size_t start_of_line = 0;
00221   while (read_so_far < size) {
00222     size_t bytes_read = this->read_ (buffer_+read_so_far, 1);
00223     read_so_far += bytes_read;
00224     if (bytes_read == 0) {
00225       if (start_of_line != read_so_far) {
00226         lines.push_back (
00227           string (reinterpret_cast<const char*> (buffer_ + start_of_line),
00228             read_so_far - start_of_line));
00229       }
00230       break; // Timeout occured on reading 1 byte
00231     }
00232     if (string (reinterpret_cast<const char*>
00233          (buffer_ + read_so_far - eol_len), eol_len) == eol) {
00234       // EOL found
00235       lines.push_back(
00236         string(reinterpret_cast<const char*> (buffer_ + start_of_line),
00237           read_so_far - start_of_line));
00238       start_of_line = read_so_far;
00239     }
00240     if (read_so_far == size) {
00241       if (start_of_line != read_so_far) {
00242         lines.push_back(
00243           string(reinterpret_cast<const char*> (buffer_ + start_of_line),
00244             read_so_far - start_of_line));
00245       }
00246       break; // Reached the maximum read length
00247     }
00248   }
00249   return lines;
00250 }
00251 
00252 size_t
00253 Serial::write (const string &data)
00254 {
00255   ScopedWriteLock lock(this->pimpl_);
00256   return this->write_ (reinterpret_cast<const uint8_t*>(data.c_str()),
00257                        data.length());
00258 }
00259 
00260 size_t
00261 Serial::write (const std::vector<uint8_t> &data)
00262 {
00263   ScopedWriteLock lock(this->pimpl_);
00264   return this->write_ (&data[0], data.size());
00265 }
00266 
00267 size_t
00268 Serial::write (const uint8_t *data, size_t size)
00269 {
00270   ScopedWriteLock lock(this->pimpl_);
00271   return this->write_(data, size);
00272 }
00273 
00274 size_t
00275 Serial::write_ (const uint8_t *data, size_t length)
00276 {
00277   return pimpl_->write (data, length);
00278 }
00279 
00280 void
00281 Serial::setPort (const string &port)
00282 {
00283   ScopedReadLock rlock(this->pimpl_);
00284   ScopedWriteLock wlock(this->pimpl_);
00285   bool was_open = pimpl_->isOpen ();
00286   if (was_open) close();
00287   pimpl_->setPort (port);
00288   if (was_open) open ();
00289 }
00290 
00291 string
00292 Serial::getPort () const
00293 {
00294   return pimpl_->getPort ();
00295 }
00296 
00297 void
00298 Serial::setTimeout (serial::Timeout &timeout)
00299 {
00300   pimpl_->setTimeout (timeout);
00301 }
00302 
00303 serial::Timeout
00304 Serial::getTimeout () const {
00305   return pimpl_->getTimeout ();
00306 }
00307 
00308 void
00309 Serial::setBaudrate (uint32_t baudrate)
00310 {
00311   pimpl_->setBaudrate (baudrate);
00312 }
00313 
00314 uint32_t
00315 Serial::getBaudrate () const
00316 {
00317   return uint32_t(pimpl_->getBaudrate ());
00318 }
00319 
00320 void
00321 Serial::setBytesize (bytesize_t bytesize)
00322 {
00323   pimpl_->setBytesize (bytesize);
00324 }
00325 
00326 bytesize_t
00327 Serial::getBytesize () const
00328 {
00329   return pimpl_->getBytesize ();
00330 }
00331 
00332 void
00333 Serial::setParity (parity_t parity)
00334 {
00335   pimpl_->setParity (parity);
00336 }
00337 
00338 parity_t
00339 Serial::getParity () const
00340 {
00341   return pimpl_->getParity ();
00342 }
00343 
00344 void
00345 Serial::setStopbits (stopbits_t stopbits)
00346 {
00347   pimpl_->setStopbits (stopbits);
00348 }
00349 
00350 stopbits_t
00351 Serial::getStopbits () const
00352 {
00353   return pimpl_->getStopbits ();
00354 }
00355 
00356 void
00357 Serial::setFlowcontrol (flowcontrol_t flowcontrol)
00358 {
00359   pimpl_->setFlowcontrol (flowcontrol);
00360 }
00361 
00362 flowcontrol_t
00363 Serial::getFlowcontrol () const
00364 {
00365   return pimpl_->getFlowcontrol ();
00366 }
00367 
00368 void Serial::flush ()
00369 {
00370   ScopedReadLock rlock(this->pimpl_);
00371   ScopedWriteLock wlock(this->pimpl_);
00372   pimpl_->flush ();
00373 }
00374 
00375 void Serial::flushInput ()
00376 {
00377   ScopedReadLock lock(this->pimpl_);
00378   pimpl_->flushInput ();
00379 }
00380 
00381 void Serial::flushOutput ()
00382 {
00383   ScopedWriteLock lock(this->pimpl_);
00384   pimpl_->flushOutput ();
00385 }
00386 
00387 void Serial::sendBreak (int duration)
00388 {
00389   pimpl_->sendBreak (duration);
00390 }
00391 
00392 void Serial::setBreak (bool level)
00393 {
00394   pimpl_->setBreak (level);
00395 }
00396 
00397 void Serial::setRTS (bool level)
00398 {
00399   pimpl_->setRTS (level);
00400 }
00401 
00402 void Serial::setDTR (bool level)
00403 {
00404   pimpl_->setDTR (level);
00405 }
00406 
00407 bool Serial::waitForChange()
00408 {
00409   return pimpl_->waitForChange();
00410 }
00411 
00412 bool Serial::getCTS ()
00413 {
00414   return pimpl_->getCTS ();
00415 }
00416 
00417 bool Serial::getDSR ()
00418 {
00419   return pimpl_->getDSR ();
00420 }
00421 
00422 bool Serial::getRI ()
00423 {
00424   return pimpl_->getRI ();
00425 }
00426 
00427 bool Serial::getCD ()
00428 {
00429   return pimpl_->getCD ();
00430 }


serial
Author(s): William Woodall , John Harrison
autogenerated on Thu Mar 28 2019 03:29:52