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 <fcntl.h>
00021 #include <sys/ioctl.h>
00022 #include <termios.h>
00023 #include <cstdlib> // div
00024 #include <ecl/exceptions/standard_exception.hpp>
00025 #include <ecl/exceptions/macros.hpp>
00026 #include "../../include/ecl/devices/serial_pos.hpp"
00027 #include "../../include/ecl/devices/detail/error_handler_pos.hpp"
00028 
00029 /*****************************************************************************
00030 ** Namespaces
00031 *****************************************************************************/
00032 
00033 namespace ecl {
00034 
00035 /*****************************************************************************
00036 ** Using
00037 *****************************************************************************/
00038 
00039 using std::string;
00040 using ecl::InvalidInputError;
00041 using ecl::OpenError;
00042 using ecl::StandardException;
00043 
00044 /*****************************************************************************
00045 ** Implementation [Serial][C&D]
00046 *****************************************************************************/
00047 
00048 Serial::Serial(const std::string& port_name, const BaudRate &baud_rate, const DataBits &data_bits,
00049                 const StopBits &stop_bits, const Parity &parity ) ecl_throw_decl(StandardException) :
00050                                 port(port_name),
00051                                 read_timeout_ms(5000),
00052                                 error_handler(NoError)
00053 {
00054         ecl_try {
00055                 open(port_name, baud_rate, data_bits, stop_bits, parity);
00056         } ecl_catch( const StandardException &e ) {
00057                 ecl_throw(StandardException(LOC,e));
00058         }
00059 }
00060 
00061 Serial::~Serial() {
00062         close();
00063 }
00064 
00065 /*****************************************************************************
00066 ** Implementation [Serial][Open]
00067 *****************************************************************************/
00068 
00069 bool Serial::open(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 
00072         /*********************
00073         ** Input Checks
00074         **********************/
00075         if ( stop_bits == StopBits_15 ) {
00076                 ecl_throw(StandardException(LOC,ConfigurationError,"Standard serial device does not accept StopBits_15 as valid (used in ftdi)."));
00077                 error_handler = InvalidArgError;
00078         is_open = false;
00079                 return false;
00080         }
00081 
00082         if ( open() ) {
00083                 close();
00084         }
00085         port = port_name;
00086         // One curious thing here is O_NONBLOCK. If you do not specify this, it will try
00087         // and wait till the line has an 'other' end. Which it can't possibly know, so
00088         // it will effectively block here forever.
00089     file_descriptor = ::open( port_name.c_str(), O_RDWR | O_NOCTTY | O_NONBLOCK );
00090     if ( file_descriptor == -1 ) {
00091         ecl_throw(devices::open_exception(LOC,port_name));
00092         error_handler = devices::open_error();
00093         is_open = false;
00094         return false;
00095     }
00096 
00097     static const int baud_rate_flags[] = { B110, B300, B600, B1200, B2400, B4800, B9600, B19200, B38400, B57600, B115200, B921600 };
00098     static const int data_bits_flags[] = { CS5, CS6, CS7, CS8 };
00099 
00100     /*********************
00101     ** Current Settings
00102     **********************/
00103 //    tcgetattr(file_descriptor,&options); // Need?
00104 
00105     /******************************************
00106     ** Flow Control
00107     *******************************************/
00108     // Turn off the O_NONBLOCK we set back when opening (we want by default
00109     // blocking and timeouts etc to occur).
00110     // Using 0 as the argument here resets the file status flags to defaults.
00111     fcntl(file_descriptor, F_SETFL, 0);
00112     // this came from ros' hokoyu node code for setting a lock on the device file descriptor
00113     // useful if you want to make sure other devices dont mess with your device!
00114     struct flock file_lock;
00115     file_lock.l_type = F_WRLCK;
00116     file_lock.l_whence = SEEK_SET;
00117     file_lock.l_start = 0;
00118     file_lock.l_len   = 0;
00119     file_lock.l_pid   = getpid();
00120     if (fcntl(file_descriptor, F_SETLK, &file_lock) != 0) {
00121         ecl_throw_decl(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.")));
00122         error_handler = IsLockedError;
00123         is_open = false;
00124         return false;
00125     }
00126 
00127     /******************************************
00128     ** Initialise flags
00129     *******************************************/
00130     options.c_cflag = 0;
00131     options.c_iflag = 0;
00132     options.c_lflag = 0;
00133     options.c_oflag = 0;
00134 
00135     /*********************
00136     ** Baud rates
00137     **********************/
00138     cfsetispeed(&options, baud_rate_flags[baud_rate]);
00139 
00140     /*********************
00141     ** Ownership
00142     **********************/
00143     /*
00144      * CLOCAL and CREAD should always be set.
00145      * They make sure the owner of the port is
00146      * not changed by the program.
00147      */
00148     options.c_cflag |= CLOCAL;
00149     options.c_cflag |= CREAD;
00150 
00151     /*********************
00152     ** Disable Flow control
00153     **********************/
00154     #if defined(CRTSCTS)
00155          options.c_cflag &= ~CRTSCTS;    // Disable hardware flow control (old)
00156     #elif defined (CNEW_RTSCTS)
00157          options.c_cflag &= ~CNEW_RTSCTS;    // Disable hardware flow control (new)
00158     #endif
00159 
00160     /*********************
00161     ** StopBits
00162     **********************/
00163      if ( stop_bits == StopBits_1 ) {
00164          options.c_cflag &= ~CSTOPB;     // One stop bit only
00165      } else {
00166          options.c_cflag |= CSTOPB;      // Two stop bits.
00167      }
00168 
00169      /******************************************
00170      ** DataBits
00171      *******************************************/
00172      options.c_cflag &= ~CSIZE;         // Mask (i.e. reset) character size bits
00173      options.c_cflag |= data_bits_flags[data_bits]; // Now set the # data bits
00174 
00175     /******************************************
00176     ** Processing
00177     *******************************************/
00178     options.c_lflag &= ~(ICANON | ECHO | ECHOE | ISIG); // raw, no echoing or waiting till a flush or signals
00179     // options.c_lflag |= (ICANON | ECHO | ECHOE); // like a chat session
00180 
00181     /******************************************
00182     ** Input Options
00183     *******************************************/
00184     options.c_iflag &= ~(IXON | IXOFF | IXANY); // Disable software flow control
00185 
00186     /******************************************
00187     ** Output Options
00188     *******************************************/
00189 //    options.c_oflag |= OPOST; // Perform a little post processing
00190 //    options.c_oflag |= ONLCR; // Man NL to NL-CR
00191 
00192     /*********************
00193      ** Parity
00194      **********************/
00195      if ( parity == NoParity ) {
00196          options.c_cflag &= ~PARENB;     // No Parity
00197      } else if ( parity == EvenParity ) {
00198          options.c_iflag |= (INPCK | ISTRIP); // Enable parity check and strip parity bit
00199          options.c_cflag |= PARENB;
00200          options.c_cflag &= ~PARODD;
00201      } else { // OddParity
00202          options.c_iflag |= (INPCK | ISTRIP); // Enable parity check and strip parity bit
00203          options.c_cflag |= PARENB;
00204          options.c_cflag |= PARODD;
00205      }
00206 
00207     /******************************************
00208     ** Enable
00209     *******************************************
00210     * TCSANOW - make changes immediately
00211     * TCSADRAIN - wait till everything is transmitted
00212     * TCSAFLUSH - clear input/output buffers and change
00213     *******************************************/
00214     tcsetattr(file_descriptor,TCSAFLUSH,&options);
00215 
00216     block(5000);
00217 
00218     is_open = true;
00219     error_handler = NoError;
00220     return true;
00221 }
00222 void Serial::close() {
00223         if ( open() ) {
00224                 // should check return values here, it does have some, EBADF/EINTR/EIO
00225                 ::close(file_descriptor);
00226             is_open = false;
00227         }
00228 }
00229 
00230 /*****************************************************************************
00231 ** Implementation [Serial][Reading Modes]
00232 *****************************************************************************/
00233 
00234 void Serial::block(const unsigned long &timeout) {
00235         if ( timeout < 100 ) {
00236                 if ( timeout < 5 ) {
00237                         fake_snooze.period(ecl::Duration(0.001));
00238                         fake_loop_count = timeout;
00239                 } else if ( timeout < 20 ) {
00240                         fake_snooze.period(ecl::Duration(0.002));
00241                         div_t d = div(timeout,2);
00242                         if ( d.rem == 0 ) {
00243                                 fake_loop_count = d.quot;
00244                         } else {
00245                                 fake_loop_count = d.quot + 1;
00246                         }
00247                 } else {
00248                         fake_snooze.period(ecl::Duration(0.005));
00249                         div_t d = div(timeout,5);
00250                         if ( d.rem == 0 ) {
00251                                 fake_loop_count = d.quot;
00252                         } else {
00253                                 fake_loop_count = d.quot + 1;
00254                         }
00255                 }
00256                 this->unblock();
00257         } else {
00258                 options.c_cc[VMIN] = 0;
00259                  // VTIME is in tenths of a second
00260                 if ( timeout < 100 ) { // just in case we're not running in debug mode or exceptions are disabled.
00261                         options.c_cc[VTIME] = static_cast<unsigned char>(1); // 100/100
00262                 } else {
00263                         options.c_cc[VTIME] = static_cast<unsigned char>(timeout/100);
00264                 }
00265                 tcsetattr(file_descriptor, TCSAFLUSH, &options);
00266         }
00267         read_timeout_ms = timeout;
00268 }
00269 
00270 void Serial::unblock() {
00271     options.c_cc[VMIN] = 0;
00272     options.c_cc[VTIME] = 0;
00273     tcsetattr(file_descriptor, TCSAFLUSH, &options);
00274         read_timeout_ms = 5000; // just so we don't trigger fake_read calls in read(xxx)
00275 }
00276 
00277 /*****************************************************************************
00278 ** Implementation [Serial][Reading]
00279 *****************************************************************************/
00280 long Serial::remaining() {
00281     long bytes = 0;
00282     ioctl(file_descriptor, FIONREAD, &bytes);
00283     return bytes;
00284 }
00285 
00286 } // namespace ecl
00287 #endif /* ECL_IS_POSIX */


ecl_devices
Author(s): Daniel Stonier (d.stonier@gmail.com)
autogenerated on Thu Jan 2 2014 11:12:50