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 = this->pimpl_->read (buffer_, size);
00136   buffer.insert (buffer.end (), buffer_, buffer_+bytes_read);
00137   delete[] buffer_;
00138   return bytes_read;
00139 }
00140 
00141 size_t
00142 Serial::read (std::string &buffer, size_t size)
00143 {
00144   ScopedReadLock lock(this->pimpl_);
00145   uint8_t *buffer_ = new uint8_t[size];
00146   size_t bytes_read = this->pimpl_->read (buffer_, size);
00147   buffer.append (reinterpret_cast<const char*>(buffer_), bytes_read);
00148   delete[] buffer_;
00149   return bytes_read;
00150 }
00151 
00152 string
00153 Serial::read (size_t size)
00154 {
00155   std::string buffer;
00156   this->read (buffer, size);
00157   return buffer;
00158 }
00159 
00160 size_t
00161 Serial::readline (string &buffer, size_t size, string eol)
00162 {
00163   ScopedReadLock lock(this->pimpl_);
00164   size_t eol_len = eol.length ();
00165   uint8_t *buffer_ = static_cast<uint8_t*>
00166                               (alloca (size * sizeof (uint8_t)));
00167   size_t read_so_far = 0;
00168   while (true)
00169   {
00170     size_t bytes_read = this->read_ (buffer_ + read_so_far, 1);
00171     read_so_far += bytes_read;
00172     if (bytes_read == 0) {
00173       break; // Timeout occured on reading 1 byte
00174     }
00175     if (string (reinterpret_cast<const char*>
00176          (buffer_ + read_so_far - eol_len), eol_len) == eol) {
00177       break; // EOL found
00178     }
00179     if (read_so_far == size) {
00180       break; // Reached the maximum read length
00181     }
00182   }
00183   buffer.append(reinterpret_cast<const char*> (buffer_), read_so_far);
00184   return read_so_far;
00185 }
00186 
00187 string
00188 Serial::readline (size_t size, string eol)
00189 {
00190   std::string buffer;
00191   this->readline (buffer, size, eol);
00192   return buffer;
00193 }
00194 
00195 vector<string>
00196 Serial::readlines (size_t size, string eol)
00197 {
00198   ScopedReadLock lock(this->pimpl_);
00199   std::vector<std::string> lines;
00200   size_t eol_len = eol.length ();
00201   uint8_t *buffer_ = static_cast<uint8_t*>
00202     (alloca (size * sizeof (uint8_t)));
00203   size_t read_so_far = 0;
00204   size_t start_of_line = 0;
00205   while (read_so_far < size) {
00206     size_t bytes_read = this->read_ (buffer_+read_so_far, 1);
00207     read_so_far += bytes_read;
00208     if (bytes_read == 0) {
00209       if (start_of_line != read_so_far) {
00210         lines.push_back (
00211           string (reinterpret_cast<const char*> (buffer_ + start_of_line),
00212             read_so_far - start_of_line));
00213       }
00214       break; // Timeout occured on reading 1 byte
00215     }
00216     if (string (reinterpret_cast<const char*>
00217          (buffer_ + read_so_far - eol_len), eol_len) == eol) {
00218       // EOL found
00219       lines.push_back(
00220         string(reinterpret_cast<const char*> (buffer_ + start_of_line),
00221           read_so_far - start_of_line));
00222       start_of_line = read_so_far;
00223     }
00224     if (read_so_far == size) {
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; // Reached the maximum read length
00231     }
00232   }
00233   return lines;
00234 }
00235 
00236 size_t
00237 Serial::write (const string &data)
00238 {
00239   ScopedWriteLock lock(this->pimpl_);
00240   return this->write_ (reinterpret_cast<const uint8_t*>(data.c_str()),
00241                        data.length());
00242 }
00243 
00244 size_t
00245 Serial::write (const std::vector<uint8_t> &data)
00246 {
00247   ScopedWriteLock lock(this->pimpl_);
00248   return this->write_ (&data[0], data.size());
00249 }
00250 
00251 size_t
00252 Serial::write (const uint8_t *data, size_t size)
00253 {
00254   ScopedWriteLock lock(this->pimpl_);
00255   return this->write_(data, size);
00256 }
00257 
00258 size_t
00259 Serial::write_ (const uint8_t *data, size_t length)
00260 {
00261   return pimpl_->write (data, length);
00262 }
00263 
00264 void
00265 Serial::setPort (const string &port)
00266 {
00267   ScopedReadLock rlock(this->pimpl_);
00268   ScopedWriteLock wlock(this->pimpl_);
00269   bool was_open = pimpl_->isOpen ();
00270   if (was_open) close();
00271   pimpl_->setPort (port);
00272   if (was_open) open ();
00273 }
00274 
00275 string
00276 Serial::getPort () const
00277 {
00278   return pimpl_->getPort ();
00279 }
00280 
00281 void
00282 Serial::setTimeout (serial::Timeout &timeout)
00283 {
00284   pimpl_->setTimeout (timeout);
00285 }
00286 
00287 serial::Timeout
00288 Serial::getTimeout () const {
00289   return pimpl_->getTimeout ();
00290 }
00291 
00292 void
00293 Serial::setBaudrate (uint32_t baudrate)
00294 {
00295   pimpl_->setBaudrate (baudrate);
00296 }
00297 
00298 uint32_t
00299 Serial::getBaudrate () const
00300 {
00301   return uint32_t(pimpl_->getBaudrate ());
00302 }
00303 
00304 void
00305 Serial::setBytesize (bytesize_t bytesize)
00306 {
00307   pimpl_->setBytesize (bytesize);
00308 }
00309 
00310 bytesize_t
00311 Serial::getBytesize () const
00312 {
00313   return pimpl_->getBytesize ();
00314 }
00315 
00316 void
00317 Serial::setParity (parity_t parity)
00318 {
00319   pimpl_->setParity (parity);
00320 }
00321 
00322 parity_t
00323 Serial::getParity () const
00324 {
00325   return pimpl_->getParity ();
00326 }
00327 
00328 void
00329 Serial::setStopbits (stopbits_t stopbits)
00330 {
00331   pimpl_->setStopbits (stopbits);
00332 }
00333 
00334 stopbits_t
00335 Serial::getStopbits () const
00336 {
00337   return pimpl_->getStopbits ();
00338 }
00339 
00340 void
00341 Serial::setFlowcontrol (flowcontrol_t flowcontrol)
00342 {
00343   pimpl_->setFlowcontrol (flowcontrol);
00344 }
00345 
00346 flowcontrol_t
00347 Serial::getFlowcontrol () const
00348 {
00349   return pimpl_->getFlowcontrol ();
00350 }
00351 
00352 void Serial::flush ()
00353 {
00354   ScopedReadLock rlock(this->pimpl_);
00355   ScopedWriteLock wlock(this->pimpl_);
00356   pimpl_->flush ();
00357 }
00358 
00359 void Serial::flushInput ()
00360 {
00361   ScopedReadLock lock(this->pimpl_);
00362   pimpl_->flushInput ();
00363 }
00364 
00365 void Serial::flushOutput ()
00366 {
00367   ScopedWriteLock lock(this->pimpl_);
00368   pimpl_->flushOutput ();
00369 }
00370 
00371 void Serial::sendBreak (int duration)
00372 {
00373   pimpl_->sendBreak (duration);
00374 }
00375 
00376 void Serial::setBreak (bool level)
00377 {
00378   pimpl_->setBreak (level);
00379 }
00380 
00381 void Serial::setRTS (bool level)
00382 {
00383   pimpl_->setRTS (level);
00384 }
00385 
00386 void Serial::setDTR (bool level)
00387 {
00388   pimpl_->setDTR (level);
00389 }
00390 
00391 bool Serial::waitForChange()
00392 {
00393   return pimpl_->waitForChange();
00394 }
00395 
00396 bool Serial::getCTS ()
00397 {
00398   return pimpl_->getCTS ();
00399 }
00400 
00401 bool Serial::getDSR ()
00402 {
00403   return pimpl_->getDSR ();
00404 }
00405 
00406 bool Serial::getRI ()
00407 {
00408   return pimpl_->getRI ();
00409 }
00410 
00411 bool Serial::getCD ()
00412 {
00413   return pimpl_->getCD ();
00414 }


serial
Author(s): William Woodall , John Harrison
autogenerated on Sat Jan 21 2017 03:55:47