win.cc
Go to the documentation of this file.
00001 #if defined(_WIN32)
00002 
00003 /* Copyright 2012 William Woodall and John Harrison */
00004 
00005 #include <sstream>
00006 
00007 #include "serial/impl/win.h"
00008 
00009 using std::string;
00010 using std::wstring;
00011 using std::stringstream;
00012 using std::invalid_argument;
00013 using serial::Serial;
00014 using serial::Timeout;
00015 using serial::bytesize_t;
00016 using serial::parity_t;
00017 using serial::stopbits_t;
00018 using serial::flowcontrol_t;
00019 using serial::SerialException;
00020 using serial::PortNotOpenedException;
00021 using serial::IOException;
00022 
00023 inline wstring
00024 _prefix_port_if_needed(const wstring &input)
00025 {
00026   static wstring windows_com_port_prefix = L"\\\\.\\";
00027   if (input.compare(windows_com_port_prefix) != 0)
00028   {
00029     return windows_com_port_prefix + input;
00030   }
00031   return input;
00032 }
00033 
00034 Serial::SerialImpl::SerialImpl (const string &port, unsigned long baudrate,
00035                                 bytesize_t bytesize,
00036                                 parity_t parity, stopbits_t stopbits,
00037                                 flowcontrol_t flowcontrol)
00038   : port_ (port.begin(), port.end()), fd_ (INVALID_HANDLE_VALUE), is_open_ (false),
00039     baudrate_ (baudrate), parity_ (parity),
00040     bytesize_ (bytesize), stopbits_ (stopbits), flowcontrol_ (flowcontrol)
00041 {
00042   if (port_.empty () == false)
00043     open ();
00044   read_mutex = CreateMutex(NULL, false, NULL);
00045   write_mutex = CreateMutex(NULL, false, NULL);
00046 }
00047 
00048 Serial::SerialImpl::~SerialImpl ()
00049 {
00050   this->close();
00051   CloseHandle(read_mutex);
00052   CloseHandle(write_mutex);
00053 }
00054 
00055 void
00056 Serial::SerialImpl::open ()
00057 {
00058   if (port_.empty ()) {
00059     throw invalid_argument ("Empty port is invalid.");
00060   }
00061   if (is_open_ == true) {
00062     throw SerialException ("Serial port already open.");
00063   }
00064 
00065   // See: https://github.com/wjwwood/serial/issues/84
00066   wstring port_with_prefix = _prefix_port_if_needed(port_);
00067   LPCWSTR lp_port = port_with_prefix.c_str();
00068   fd_ = CreateFileW(lp_port,
00069                     GENERIC_READ | GENERIC_WRITE,
00070                     0,
00071                     0,
00072                     OPEN_EXISTING,
00073                     FILE_ATTRIBUTE_NORMAL,
00074                     0);
00075 
00076   if (fd_ == INVALID_HANDLE_VALUE) {
00077     DWORD create_file_err = GetLastError();
00078         stringstream ss;
00079     switch (create_file_err) {
00080     case ERROR_FILE_NOT_FOUND:
00081       // Use this->getPort to convert to a std::string
00082       ss << "Specified port, " << this->getPort() << ", does not exist.";
00083       THROW (IOException, ss.str().c_str());
00084     default:
00085       ss << "Unknown error opening the serial port: " << create_file_err;
00086       THROW (IOException, ss.str().c_str());
00087     }
00088   }
00089 
00090   reconfigurePort();
00091   is_open_ = true;
00092 }
00093 
00094 void
00095 Serial::SerialImpl::reconfigurePort ()
00096 {
00097   if (fd_ == INVALID_HANDLE_VALUE) {
00098     // Can only operate on a valid file descriptor
00099     THROW (IOException, "Invalid file descriptor, is the serial port open?");
00100   }
00101 
00102   DCB dcbSerialParams = {0};
00103 
00104   dcbSerialParams.DCBlength=sizeof(dcbSerialParams);
00105 
00106   if (!GetCommState(fd_, &dcbSerialParams)) {
00107     //error getting state
00108     THROW (IOException, "Error getting the serial port state.");
00109   }
00110 
00111   // setup baud rate
00112   switch (baudrate_) {
00113 #ifdef CBR_0
00114   case 0: dcbSerialParams.BaudRate = CBR_0; break;
00115 #endif
00116 #ifdef CBR_50
00117   case 50: dcbSerialParams.BaudRate = CBR_50; break;
00118 #endif
00119 #ifdef CBR_75
00120   case 75: dcbSerialParams.BaudRate = CBR_75; break;
00121 #endif
00122 #ifdef CBR_110
00123   case 110: dcbSerialParams.BaudRate = CBR_110; break;
00124 #endif
00125 #ifdef CBR_134
00126   case 134: dcbSerialParams.BaudRate = CBR_134; break;
00127 #endif
00128 #ifdef CBR_150
00129   case 150: dcbSerialParams.BaudRate = CBR_150; break;
00130 #endif
00131 #ifdef CBR_200
00132   case 200: dcbSerialParams.BaudRate = CBR_200; break;
00133 #endif
00134 #ifdef CBR_300
00135   case 300: dcbSerialParams.BaudRate = CBR_300; break;
00136 #endif
00137 #ifdef CBR_600
00138   case 600: dcbSerialParams.BaudRate = CBR_600; break;
00139 #endif
00140 #ifdef CBR_1200
00141   case 1200: dcbSerialParams.BaudRate = CBR_1200; break;
00142 #endif
00143 #ifdef CBR_1800
00144   case 1800: dcbSerialParams.BaudRate = CBR_1800; break;
00145 #endif
00146 #ifdef CBR_2400
00147   case 2400: dcbSerialParams.BaudRate = CBR_2400; break;
00148 #endif
00149 #ifdef CBR_4800
00150   case 4800: dcbSerialParams.BaudRate = CBR_4800; break;
00151 #endif
00152 #ifdef CBR_7200
00153   case 7200: dcbSerialParams.BaudRate = CBR_7200; break;
00154 #endif
00155 #ifdef CBR_9600
00156   case 9600: dcbSerialParams.BaudRate = CBR_9600; break;
00157 #endif
00158 #ifdef CBR_14400
00159   case 14400: dcbSerialParams.BaudRate = CBR_14400; break;
00160 #endif
00161 #ifdef CBR_19200
00162   case 19200: dcbSerialParams.BaudRate = CBR_19200; break;
00163 #endif
00164 #ifdef CBR_28800
00165   case 28800: dcbSerialParams.BaudRate = CBR_28800; break;
00166 #endif
00167 #ifdef CBR_57600
00168   case 57600: dcbSerialParams.BaudRate = CBR_57600; break;
00169 #endif
00170 #ifdef CBR_76800
00171   case 76800: dcbSerialParams.BaudRate = CBR_76800; break;
00172 #endif
00173 #ifdef CBR_38400
00174   case 38400: dcbSerialParams.BaudRate = CBR_38400; break;
00175 #endif
00176 #ifdef CBR_115200
00177   case 115200: dcbSerialParams.BaudRate = CBR_115200; break;
00178 #endif
00179 #ifdef CBR_128000
00180   case 128000: dcbSerialParams.BaudRate = CBR_128000; break;
00181 #endif
00182 #ifdef CBR_153600
00183   case 153600: dcbSerialParams.BaudRate = CBR_153600; break;
00184 #endif
00185 #ifdef CBR_230400
00186   case 230400: dcbSerialParams.BaudRate = CBR_230400; break;
00187 #endif
00188 #ifdef CBR_256000
00189   case 256000: dcbSerialParams.BaudRate = CBR_256000; break;
00190 #endif
00191 #ifdef CBR_460800
00192   case 460800: dcbSerialParams.BaudRate = CBR_460800; break;
00193 #endif
00194 #ifdef CBR_921600
00195   case 921600: dcbSerialParams.BaudRate = CBR_921600; break;
00196 #endif
00197   default:
00198     // Try to blindly assign it
00199     dcbSerialParams.BaudRate = baudrate_;
00200   }
00201 
00202   // setup char len
00203   if (bytesize_ == eightbits)
00204     dcbSerialParams.ByteSize = 8;
00205   else if (bytesize_ == sevenbits)
00206     dcbSerialParams.ByteSize = 7;
00207   else if (bytesize_ == sixbits)
00208     dcbSerialParams.ByteSize = 6;
00209   else if (bytesize_ == fivebits)
00210     dcbSerialParams.ByteSize = 5;
00211   else
00212     throw invalid_argument ("invalid char len");
00213 
00214   // setup stopbits
00215   if (stopbits_ == stopbits_one)
00216     dcbSerialParams.StopBits = ONESTOPBIT;
00217   else if (stopbits_ == stopbits_one_point_five)
00218     dcbSerialParams.StopBits = ONE5STOPBITS;
00219   else if (stopbits_ == stopbits_two)
00220     dcbSerialParams.StopBits = TWOSTOPBITS;
00221   else
00222     throw invalid_argument ("invalid stop bit");
00223 
00224   // setup parity
00225   if (parity_ == parity_none) {
00226     dcbSerialParams.Parity = NOPARITY;
00227   } else if (parity_ == parity_even) {
00228     dcbSerialParams.Parity = EVENPARITY;
00229   } else if (parity_ == parity_odd) {
00230     dcbSerialParams.Parity = ODDPARITY;
00231   } else if (parity_ == parity_mark) {
00232     dcbSerialParams.Parity = MARKPARITY;
00233   } else if (parity_ == parity_space) {
00234     dcbSerialParams.Parity = SPACEPARITY;
00235   } else {
00236     throw invalid_argument ("invalid parity");
00237   }
00238 
00239   // setup flowcontrol
00240   if (flowcontrol_ == flowcontrol_none) {
00241     dcbSerialParams.fOutxCtsFlow = false;
00242     dcbSerialParams.fRtsControl = RTS_CONTROL_DISABLE;
00243     dcbSerialParams.fOutX = false;
00244     dcbSerialParams.fInX = false;
00245   }
00246   if (flowcontrol_ == flowcontrol_software) {
00247     dcbSerialParams.fOutxCtsFlow = false;
00248     dcbSerialParams.fRtsControl = RTS_CONTROL_DISABLE;
00249     dcbSerialParams.fOutX = true;
00250     dcbSerialParams.fInX = true;
00251   }
00252   if (flowcontrol_ == flowcontrol_hardware) {
00253     dcbSerialParams.fOutxCtsFlow = true;
00254     dcbSerialParams.fRtsControl = RTS_CONTROL_HANDSHAKE;
00255     dcbSerialParams.fOutX = false;
00256     dcbSerialParams.fInX = false;
00257   }
00258 
00259   // activate settings
00260   if (!SetCommState(fd_, &dcbSerialParams)){
00261     CloseHandle(fd_);
00262     THROW (IOException, "Error setting serial port settings.");
00263   }
00264 
00265   // Setup timeouts
00266   COMMTIMEOUTS timeouts = {0};
00267   timeouts.ReadIntervalTimeout = timeout_.inter_byte_timeout;
00268   timeouts.ReadTotalTimeoutConstant = timeout_.read_timeout_constant;
00269   timeouts.ReadTotalTimeoutMultiplier = timeout_.read_timeout_multiplier;
00270   timeouts.WriteTotalTimeoutConstant = timeout_.write_timeout_constant;
00271   timeouts.WriteTotalTimeoutMultiplier = timeout_.write_timeout_multiplier;
00272   if (!SetCommTimeouts(fd_, &timeouts)) {
00273     THROW (IOException, "Error setting timeouts.");
00274   }
00275 }
00276 
00277 void
00278 Serial::SerialImpl::close ()
00279 {
00280   if (is_open_ == true) {
00281     if (fd_ != INVALID_HANDLE_VALUE) {
00282       int ret;
00283       ret = CloseHandle(fd_);
00284       if (ret == 0) {
00285         stringstream ss;
00286         ss << "Error while closing serial port: " << GetLastError();
00287         THROW (IOException, ss.str().c_str());
00288       } else {
00289         fd_ = INVALID_HANDLE_VALUE;
00290       }
00291     }
00292     is_open_ = false;
00293   }
00294 }
00295 
00296 bool
00297 Serial::SerialImpl::isOpen () const
00298 {
00299   return is_open_;
00300 }
00301 
00302 size_t
00303 Serial::SerialImpl::available ()
00304 {
00305   if (!is_open_) {
00306     return 0;
00307   }
00308   COMSTAT cs;
00309   if (!ClearCommError(fd_, NULL, &cs)) {
00310     stringstream ss;
00311     ss << "Error while checking status of the serial port: " << GetLastError();
00312     THROW (IOException, ss.str().c_str());
00313   }
00314   return static_cast<size_t>(cs.cbInQue);
00315 }
00316 
00317 bool
00318 Serial::SerialImpl::waitReadable (uint32_t /*timeout*/)
00319 {
00320   THROW (IOException, "waitReadable is not implemented on Windows.");
00321   return false;
00322 }
00323 
00324 void
00325 Serial::SerialImpl::waitByteTimes (size_t /*count*/)
00326 {
00327   THROW (IOException, "waitByteTimes is not implemented on Windows.");
00328 }
00329 
00330 size_t
00331 Serial::SerialImpl::read (uint8_t *buf, size_t size)
00332 {
00333   if (!is_open_) {
00334     throw PortNotOpenedException ("Serial::read");
00335   }
00336   DWORD bytes_read;
00337   if (!ReadFile(fd_, buf, static_cast<DWORD>(size), &bytes_read, NULL)) {
00338     stringstream ss;
00339     ss << "Error while reading from the serial port: " << GetLastError();
00340     THROW (IOException, ss.str().c_str());
00341   }
00342   return (size_t) (bytes_read);
00343 }
00344 
00345 size_t
00346 Serial::SerialImpl::write (const uint8_t *data, size_t length)
00347 {
00348   if (is_open_ == false) {
00349     throw PortNotOpenedException ("Serial::write");
00350   }
00351   DWORD bytes_written;
00352   if (!WriteFile(fd_, data, static_cast<DWORD>(length), &bytes_written, NULL)) {
00353     stringstream ss;
00354     ss << "Error while writing to the serial port: " << GetLastError();
00355     THROW (IOException, ss.str().c_str());
00356   }
00357   return (size_t) (bytes_written);
00358 }
00359 
00360 void
00361 Serial::SerialImpl::setPort (const string &port)
00362 {
00363   port_ = wstring(port.begin(), port.end());
00364 }
00365 
00366 string
00367 Serial::SerialImpl::getPort () const
00368 {
00369   return string(port_.begin(), port_.end());
00370 }
00371 
00372 void
00373 Serial::SerialImpl::setTimeout (serial::Timeout &timeout)
00374 {
00375   timeout_ = timeout;
00376   if (is_open_) {
00377     reconfigurePort ();
00378   }
00379 }
00380 
00381 serial::Timeout
00382 Serial::SerialImpl::getTimeout () const
00383 {
00384   return timeout_;
00385 }
00386 
00387 void
00388 Serial::SerialImpl::setBaudrate (unsigned long baudrate)
00389 {
00390   baudrate_ = baudrate;
00391   if (is_open_) {
00392     reconfigurePort ();
00393   }
00394 }
00395 
00396 unsigned long
00397 Serial::SerialImpl::getBaudrate () const
00398 {
00399   return baudrate_;
00400 }
00401 
00402 void
00403 Serial::SerialImpl::setBytesize (serial::bytesize_t bytesize)
00404 {
00405   bytesize_ = bytesize;
00406   if (is_open_) {
00407     reconfigurePort ();
00408   }
00409 }
00410 
00411 serial::bytesize_t
00412 Serial::SerialImpl::getBytesize () const
00413 {
00414   return bytesize_;
00415 }
00416 
00417 void
00418 Serial::SerialImpl::setParity (serial::parity_t parity)
00419 {
00420   parity_ = parity;
00421   if (is_open_) {
00422     reconfigurePort ();
00423   }
00424 }
00425 
00426 serial::parity_t
00427 Serial::SerialImpl::getParity () const
00428 {
00429   return parity_;
00430 }
00431 
00432 void
00433 Serial::SerialImpl::setStopbits (serial::stopbits_t stopbits)
00434 {
00435   stopbits_ = stopbits;
00436   if (is_open_) {
00437     reconfigurePort ();
00438   }
00439 }
00440 
00441 serial::stopbits_t
00442 Serial::SerialImpl::getStopbits () const
00443 {
00444   return stopbits_;
00445 }
00446 
00447 void
00448 Serial::SerialImpl::setFlowcontrol (serial::flowcontrol_t flowcontrol)
00449 {
00450   flowcontrol_ = flowcontrol;
00451   if (is_open_) {
00452     reconfigurePort ();
00453   }
00454 }
00455 
00456 serial::flowcontrol_t
00457 Serial::SerialImpl::getFlowcontrol () const
00458 {
00459   return flowcontrol_;
00460 }
00461 
00462 void
00463 Serial::SerialImpl::flush ()
00464 {
00465   if (is_open_ == false) {
00466     throw PortNotOpenedException ("Serial::flush");
00467   }
00468   FlushFileBuffers (fd_);
00469 }
00470 
00471 void
00472 Serial::SerialImpl::flushInput ()
00473 {
00474   if (is_open_ == false) {
00475     throw PortNotOpenedException("Serial::flushInput");
00476   }
00477   PurgeComm(fd_, PURGE_RXCLEAR);
00478 }
00479 
00480 void
00481 Serial::SerialImpl::flushOutput ()
00482 {
00483   if (is_open_ == false) {
00484     throw PortNotOpenedException("Serial::flushOutput");
00485   }
00486   PurgeComm(fd_, PURGE_TXCLEAR);
00487 }
00488 
00489 void
00490 Serial::SerialImpl::sendBreak (int /*duration*/)
00491 {
00492   THROW (IOException, "sendBreak is not supported on Windows.");
00493 }
00494 
00495 void
00496 Serial::SerialImpl::setBreak (bool level)
00497 {
00498   if (is_open_ == false) {
00499     throw PortNotOpenedException ("Serial::setBreak");
00500   }
00501   if (level) {
00502     EscapeCommFunction (fd_, SETBREAK);
00503   } else {
00504     EscapeCommFunction (fd_, CLRBREAK);
00505   }
00506 }
00507 
00508 void
00509 Serial::SerialImpl::setRTS (bool level)
00510 {
00511   if (is_open_ == false) {
00512     throw PortNotOpenedException ("Serial::setRTS");
00513   }
00514   if (level) {
00515     EscapeCommFunction (fd_, SETRTS);
00516   } else {
00517     EscapeCommFunction (fd_, CLRRTS);
00518   }
00519 }
00520 
00521 void
00522 Serial::SerialImpl::setDTR (bool level)
00523 {
00524   if (is_open_ == false) {
00525     throw PortNotOpenedException ("Serial::setDTR");
00526   }
00527   if (level) {
00528     EscapeCommFunction (fd_, SETDTR);
00529   } else {
00530     EscapeCommFunction (fd_, CLRDTR);
00531   }
00532 }
00533 
00534 bool
00535 Serial::SerialImpl::waitForChange ()
00536 {
00537   if (is_open_ == false) {
00538     throw PortNotOpenedException ("Serial::waitForChange");
00539   }
00540   DWORD dwCommEvent;
00541 
00542   if (!SetCommMask(fd_, EV_CTS | EV_DSR | EV_RING | EV_RLSD)) {
00543     // Error setting communications mask
00544     return false;
00545   }
00546 
00547   if (!WaitCommEvent(fd_, &dwCommEvent, NULL)) {
00548     // An error occurred waiting for the event.
00549     return false;
00550   } else {
00551     // Event has occurred.
00552     return true;
00553   }
00554 }
00555 
00556 bool
00557 Serial::SerialImpl::getCTS ()
00558 {
00559   if (is_open_ == false) {
00560     throw PortNotOpenedException ("Serial::getCTS");
00561   }
00562   DWORD dwModemStatus;
00563   if (!GetCommModemStatus(fd_, &dwModemStatus)) {
00564     THROW (IOException, "Error getting the status of the CTS line.");
00565   }
00566 
00567   return (MS_CTS_ON & dwModemStatus) != 0;
00568 }
00569 
00570 bool
00571 Serial::SerialImpl::getDSR ()
00572 {
00573   if (is_open_ == false) {
00574     throw PortNotOpenedException ("Serial::getDSR");
00575   }
00576   DWORD dwModemStatus;
00577   if (!GetCommModemStatus(fd_, &dwModemStatus)) {
00578     THROW (IOException, "Error getting the status of the DSR line.");
00579   }
00580 
00581   return (MS_DSR_ON & dwModemStatus) != 0;
00582 }
00583 
00584 bool
00585 Serial::SerialImpl::getRI()
00586 {
00587   if (is_open_ == false) {
00588     throw PortNotOpenedException ("Serial::getRI");
00589   }
00590   DWORD dwModemStatus;
00591   if (!GetCommModemStatus(fd_, &dwModemStatus)) {
00592     THROW (IOException, "Error getting the status of the RI line.");
00593   }
00594 
00595   return (MS_RING_ON & dwModemStatus) != 0;
00596 }
00597 
00598 bool
00599 Serial::SerialImpl::getCD()
00600 {
00601   if (is_open_ == false) {
00602     throw PortNotOpenedException ("Serial::getCD");
00603   }
00604   DWORD dwModemStatus;
00605   if (!GetCommModemStatus(fd_, &dwModemStatus)) {
00606     // Error in GetCommModemStatus;
00607     THROW (IOException, "Error getting the status of the CD line.");
00608   }
00609 
00610   return (MS_RLSD_ON & dwModemStatus) != 0;
00611 }
00612 
00613 void
00614 Serial::SerialImpl::readLock()
00615 {
00616   if (WaitForSingleObject(read_mutex, INFINITE) != WAIT_OBJECT_0) {
00617     THROW (IOException, "Error claiming read mutex.");
00618   }
00619 }
00620 
00621 void
00622 Serial::SerialImpl::readUnlock()
00623 {
00624   if (!ReleaseMutex(read_mutex)) {
00625     THROW (IOException, "Error releasing read mutex.");
00626   }
00627 }
00628 
00629 void
00630 Serial::SerialImpl::writeLock()
00631 {
00632   if (WaitForSingleObject(write_mutex, INFINITE) != WAIT_OBJECT_0) {
00633     THROW (IOException, "Error claiming write mutex.");
00634   }
00635 }
00636 
00637 void
00638 Serial::SerialImpl::writeUnlock()
00639 {
00640   if (!ReleaseMutex(write_mutex)) {
00641     THROW (IOException, "Error releasing write mutex.");
00642   }
00643 }
00644 
00645 #endif // #if defined(_WIN32)
00646 


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