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


serial
Author(s): William Woodall , John Harrison
autogenerated on Mon Oct 6 2014 07:34:37