serial_pos.cpp
Go to the documentation of this file.
00001 
00009 /*****************************************************************************
00010  ** Platform Check
00011  *****************************************************************************/
00012 
00013 #include <ecl/config/ecl.hpp>
00014 #ifdef ECL_IS_POSIX
00015 
00016 /*****************************************************************************
00017  ** Includes
00018  *****************************************************************************/
00019 
00020 #include <errno.h>
00021 #include <fcntl.h>
00022 #include <sys/ioctl.h>
00023 #include <termios.h>
00024 #include <cstdlib> // div
00025 #include <unistd.h> // access
00026 #include <ecl/exceptions/standard_exception.hpp>
00027 #include <ecl/exceptions/macros.hpp>
00028 #include "../../include/ecl/devices/serial_pos.hpp"
00029 #include "../../include/ecl/devices/detail/error_handler.hpp"
00030 
00031 /*****************************************************************************
00032  ** Platform Checks
00033  *****************************************************************************/
00034 
00035 #include <ecl/config.hpp>
00036 // B921600 baud rate macro is not part of the posix specification (see
00037 // http://digilander.libero.it/robang/rubrica/serial.htm#3_1_1). However
00038 // FreeBSD has had it for at least four years and linux quite some time too.
00039 // Apple Macs however do not currently have it, so we help it here.
00040 #if defined(ECL_IS_APPLE)
00041   #ifndef B460800
00042     #define B460800 460800
00043   #endif
00044   #ifndef B921600
00045     #define B921600 921600
00046   #endif
00047 #endif
00048 
00049 /*****************************************************************************
00050  ** Namespaces
00051  *****************************************************************************/
00052 
00053 namespace ecl
00054 {
00055 
00056 /*****************************************************************************
00057  ** Using
00058  *****************************************************************************/
00059 
00060 using std::string;
00061 using ecl::InvalidInputError;
00062 using ecl::OpenError;
00063 using ecl::StandardException;
00064 
00065 /*****************************************************************************
00066  ** Implementation [Serial][C&D]
00067  *****************************************************************************/
00068 
00069 Serial::Serial(const std::string& port_name, const BaudRate &baud_rate, const DataBits &data_bits,
00070                const StopBits &stop_bits, const Parity &parity) ecl_throw_decl(StandardException) :
00071     port(port_name), read_timeout_ms(5000), error_handler(NoError)
00072 {
00073   ecl_try
00074   {
00075     open(port_name, baud_rate, data_bits, stop_bits, parity);
00076   } ecl_catch( const StandardException &e ) {
00077     ecl_throw(StandardException(LOC,e));
00078   }
00079 }
00080 
00081 Serial::~Serial()
00082 {
00083   close();
00084 }
00085 
00086 /*****************************************************************************
00087  ** Implementation [Serial][Open]
00088  *****************************************************************************/
00089 
00090 bool Serial::open(const std::string& port_name, const BaudRate &baud_rate, const DataBits &data_bits,
00091                   const StopBits &stop_bits, const Parity &parity) ecl_throw_decl(StandardException)
00092 {
00093 
00094   /*********************
00095    ** Input Checks
00096    **********************/
00097   if (stop_bits == StopBits_15)
00098   {
00099     ecl_throw(
00100         StandardException(LOC,ConfigurationError,"Standard serial device does not accept StopBits_15 as valid (used in ftdi)."));
00101     error_handler = InvalidArgError;
00102     is_open = false;
00103     return false;
00104   }
00105 
00106   if (open())
00107   {
00108     close();
00109   }
00110   port = port_name;
00111   // One curious thing here is O_NONBLOCK. If you do not specify this, it will try
00112   // and wait till the line has an 'other' end. Which it can't possibly know, so
00113   // it will effectively block here forever.
00114   file_descriptor = ::open(port_name.c_str(), O_RDWR | O_NOCTTY | O_NONBLOCK);
00115   if (file_descriptor == -1)
00116   {
00117     ecl_throw(devices::open_exception(LOC,port_name));
00118     error_handler = devices::open_error();
00119     is_open = false;
00120     return false;
00121   }
00122 
00123   static const int baud_rate_flags[] = {B110, B300, B600, B1200, B2400, B4800, B9600, B19200, B38400, B57600, B115200,
00124                                         B230400, B460800, B921600};
00125   if (baud_rate >= (sizeof(baud_rate_flags) / sizeof(B110)))
00126   {
00127     ecl_throw(StandardException(LOC,ConfigurationError,"Selected baudrate is not supported."));
00128     error_handler = InvalidArgError;
00129     is_open = false;
00130     return false;
00131   }
00132   static const int data_bits_flags[] = {CS5, CS6, CS7, CS8};
00133 
00134   /*********************
00135    ** Current Settings
00136    **********************/
00137 //    tcgetattr(file_descriptor,&options); // Need?
00138   /******************************************
00139    ** Flow Control
00140    *******************************************/
00141   // Turn off the O_NONBLOCK we set back when opening (we want by default
00142   // blocking and timeouts etc to occur).
00143   // Using 0 as the argument here resets the file status flags to defaults.
00144   fcntl(file_descriptor, F_SETFL, 0);
00145   // this came from ros' hokoyu node code for setting a lock on the device file descriptor
00146   // useful if you want to make sure other devices dont mess with your device!
00147   struct flock file_lock;
00148   file_lock.l_type = F_WRLCK;
00149   file_lock.l_whence = SEEK_SET;
00150   file_lock.l_start = 0;
00151   file_lock.l_len = 0;
00152   file_lock.l_pid = getpid();
00153   if (fcntl(file_descriptor, F_SETLK, &file_lock) != 0)
00154   {
00155     ecl_throw_decl(
00156         StandardException(LOC,OpenError,std::string("Device is already locked. Try 'lsof | grep ") + port + std::string("' to find other processes that currently have the port open (if the device is a symbolic link you may need to replace the device name with the device that it is pointing to) [posix error in case it is something else: " + std::to_string(errno))));
00157     error_handler = IsLockedError;
00158     is_open = false;
00159     return false;
00160   }
00161 
00162   /******************************************
00163    ** Initialise flags
00164    *******************************************/
00165   options.c_cflag = 0;
00166   options.c_iflag = 0;
00167   options.c_lflag = 0;
00168   options.c_oflag = 0;
00169 
00170   /*********************
00171    ** Baud rates
00172    **********************/
00173   if (cfsetspeed(&options, baud_rate_flags[baud_rate]) < 0)
00174   {
00175     ecl_throw(StandardException(LOC,ConfigurationError,"Setting speed failed."));
00176     error_handler = InvalidArgError;
00177     is_open = false;
00178     return false;
00179   }
00180 
00181   /*********************
00182    ** Ownership
00183    **********************/
00184   /*
00185    * CLOCAL and CREAD should always be set.
00186    * They make sure the owner of the port is
00187    * not changed by the program.
00188    */
00189   options.c_cflag |= CLOCAL;
00190   options.c_cflag |= CREAD;
00191 
00192   /*********************
00193    ** Disable Flow control
00194    **********************/
00195 #if defined(CRTSCTS)
00196   options.c_cflag &= ~CRTSCTS; // Disable hardware flow control (old)
00197 #elif defined (CNEW_RTSCTS)
00198   options.c_cflag &= ~CNEW_RTSCTS; // Disable hardware flow control (new)
00199 #endif
00200 
00201   /*********************
00202    ** StopBits
00203    **********************/
00204   if (stop_bits == StopBits_1)
00205   {
00206     options.c_cflag &= ~CSTOPB; // One stop bit only
00207   }
00208   else
00209   {
00210     options.c_cflag |= CSTOPB; // Two stop bits.
00211   }
00212 
00213   /******************************************
00214    ** DataBits
00215    *******************************************/
00216   options.c_cflag &= ~CSIZE; // Mask (i.e. reset) character size bits
00217   options.c_cflag |= data_bits_flags[data_bits]; // Now set the # data bits
00218 
00219   /******************************************
00220    ** Processing
00221    *******************************************/
00222   options.c_lflag &= ~(ICANON | ECHO | ECHOE | ISIG); // raw, no echoing or waiting till a flush or signals
00223   // options.c_lflag |= (ICANON | ECHO | ECHOE); // like a chat session
00224 
00225   /******************************************
00226    ** Input Options
00227    *******************************************/
00228   options.c_iflag &= ~(IXON | IXOFF | IXANY); // Disable software flow control
00229 
00230   /******************************************
00231    ** Output Options
00232    *******************************************/
00233 //    options.c_oflag |= OPOST; // Perform a little post processing
00234 //    options.c_oflag |= ONLCR; // Man NL to NL-CR
00235   /*********************
00236    ** Parity
00237    **********************/
00238   if (parity == NoParity)
00239   {
00240     options.c_cflag &= ~PARENB; // No Parity
00241   }
00242   else if (parity == EvenParity)
00243   {
00244     options.c_iflag |= (INPCK | ISTRIP); // Enable parity check and strip parity bit
00245     options.c_cflag |= PARENB;
00246     options.c_cflag &= ~PARODD;
00247   }
00248   else
00249   { // OddParity
00250     options.c_iflag |= (INPCK | ISTRIP); // Enable parity check and strip parity bit
00251     options.c_cflag |= PARENB;
00252     options.c_cflag |= PARODD;
00253   }
00254 
00255   /******************************************
00256    ** Enable
00257    *******************************************
00258    * TCSANOW - make changes immediately
00259    * TCSADRAIN - wait till everything is transmitted, don't do anything with unread data.
00260    * TCSAFLUSH - wait till everything is transmitted, also clear unread data.
00261    *******************************************/
00262   tcsetattr(file_descriptor, TCSAFLUSH, &options);
00263 
00264   /******************************************
00265   ** Reset Status
00266   *******************************************/
00267   if ( read_timeout_ms == NonBlocking ) {
00268     unblock();
00269   } else {
00270     block(read_timeout_ms);
00271   }
00272   clear();
00273 
00274   is_open = true;
00275   error_handler = NoError;
00276   return true;
00277 }
00278 
00279 void Serial::close()
00280 {
00281   if (is_open)
00282   {
00283     // should check return values here, it does have some, EBADF/EINTR/EIO
00284     ::close(file_descriptor);
00285     is_open = false;
00286   }
00287 }
00288 
00289 bool Serial::open()
00290 {
00291   if ( is_open ) {
00292     if ( access(port.c_str(), F_OK ) == -1 ) {
00293       close();
00294     }
00295   }
00296   return is_open;
00297 }
00298 
00299 /*****************************************************************************
00300  ** Implementation [Serial][Reading Modes]
00301  *****************************************************************************/
00302 
00303 void Serial::block(const unsigned long &timeout)
00304 {
00305   if (timeout < 100)
00306   {
00307     if (timeout < 5)
00308     {
00309       fake_snooze.period(ecl::Duration(0.001));
00310       fake_loop_count = timeout;
00311     }
00312     else if (timeout < 20)
00313     {
00314       fake_snooze.period(ecl::Duration(0.002));
00315       div_t d = div(timeout, 2);
00316       if (d.rem == 0)
00317       {
00318         fake_loop_count = d.quot;
00319       }
00320       else
00321       {
00322         fake_loop_count = d.quot + 1;
00323       }
00324     }
00325     else
00326     {
00327       fake_snooze.period(ecl::Duration(0.005));
00328       div_t d = div(timeout, 5);
00329       if (d.rem == 0)
00330       {
00331         fake_loop_count = d.quot;
00332       }
00333       else
00334       {
00335         fake_loop_count = d.quot + 1;
00336       }
00337     }
00338     this->unblock();
00339   }
00340   else
00341   {
00342     options.c_cc[VMIN] = 0;
00343     // VTIME is in tenths of a second
00344     if (timeout < 100)
00345     { // just in case we're not running in debug mode or exceptions are disabled.
00346       options.c_cc[VTIME] = static_cast<unsigned char>(1); // 100/100
00347     }
00348     else
00349     {
00350       options.c_cc[VTIME] = static_cast<unsigned char>(timeout / 100);
00351     }
00352     tcsetattr(file_descriptor, TCSAFLUSH, &options);
00353   }
00354   read_timeout_ms = timeout;
00355 }
00356 
00357 void Serial::unblock()
00358 {
00359   options.c_cc[VMIN] = 0;
00360   options.c_cc[VTIME] = 0;
00361   tcsetattr(file_descriptor, TCSAFLUSH, &options);
00362   read_timeout_ms = NonBlocking;
00363 }
00364 
00365 /*****************************************************************************
00366  ** Implementation [Serial][Reading]
00367  *****************************************************************************/
00368 long Serial::remaining()
00369 {
00370   long bytes = 0;
00371   ioctl(file_descriptor, FIONREAD, &bytes);
00372   return bytes;
00373 }
00374 
00375 } // namespace ecl
00376 #endif /* ECL_IS_POSIX */


ecl_devices
Author(s): Daniel Stonier
autogenerated on Thu Jun 6 2019 21:18:03