LxSerial.cpp
Go to the documentation of this file.
00001 //============================================================================
00002 // Name        : LxSerial.cpp
00003 // Author      : Eelko van Breda,www.dbl.tudelft.nl
00004 // Version     : 0.1
00005 // Copyright   : Copyright (c) 2008 LGPL
00006 // Description : serial communicatin class linux
00007 //============================================================================
00008 
00009 #include <stdio.h>
00010 #include <stdlib.h>
00011 #include <unistd.h>
00012 #include <string.h>
00013 #include <sys/types.h>
00014 #include <sys/socket.h>
00015 #include <netinet/in.h>
00016 #include <netdb.h>
00017 #include <poll.h>
00018 #include <endian.h>
00019 
00020 #include "shared_serial/LxSerial.h"
00021 
00022 
00023 /*      constructor */
00024 LxSerial::LxSerial()
00025 {
00026         hPort                   = INVALID_DEVICE_HANDLE;
00027 //      b_initialised   = false;
00028         b_clear_echo    = false;
00029         b_hw_flow_control = false;
00030         b_socket = false;
00031 }
00032 
00033 /* return name of the port that was opened */
00034 std::string& LxSerial::get_port_name()
00035 {
00036         return s_port_name;
00037 }
00038 
00039 void LxSerial::set_port_type(LxSerial::PortType port_type)
00040 {
00041         switch (port_type)
00042         {
00043                 case RS232:
00044                         b_rts                           =       false;
00045                         break;
00046 
00047                 case RS485_FTDI:
00048                         b_rts                           =       false;
00049                         break;
00050 
00051                 case RS485_EXAR:
00052                         b_rts                           =       true;
00053                         b_clear_echo            =       true;
00054                         break;
00055 
00056                 case RS485_SMSC:
00057                         b_rts                           =       false;
00058                         b_clear_echo            =       true;
00059                         break;
00060                         
00061                 case TCP:
00062                         b_socket = true;
00063                         b_rts = false;
00064                         b_clear_echo = false;
00065                         break;
00066 
00067                 default:
00068                         perror("LxSerial: no port type specified");
00069                         break;
00070         }
00071 }
00072 
00073 /* open port */
00074 bool LxSerial::port_open(const std::string& portname, LxSerial::PortType port_type)
00075 {
00076         // Set port type
00077         set_port_type(port_type);
00078         
00079         if (b_socket)
00080         {
00081                 int optval = 1;
00082 
00083                 struct sockaddr_in addr;
00084                 struct hostent *server;
00085 
00086                 hPort = socket(AF_INET, SOCK_STREAM, 0);
00087                 setsockopt(hPort, SOL_SOCKET, SO_REUSEADDR, &optval, sizeof optval);
00088 
00089                 bzero((char *) &addr, sizeof(addr));
00090                 addr.sin_family = AF_INET;
00091 
00092                 std::string host_name   = portname.substr(0, portname.find(':'));
00093                 std::string port_number = portname.substr(portname.find(':')+1);
00094 
00095                 server = gethostbyname(host_name.c_str());
00096                 if (!server)
00097                 {
00098                         perror("unknown remote serial host name");
00099                         return false;
00100                 }
00101 
00102                 bcopy((char *)server->h_addr, (char *)&addr.sin_addr.s_addr, server->h_length);
00103                 addr.sin_port = htons(atoi(port_number.c_str()));
00104 
00105                 if (connect(hPort,(struct sockaddr *) &addr,sizeof(addr)) < 0)
00106                 {
00107                         perror("error connecting to remote serial host");
00108                         return false;
00109                 }
00110         }
00111         else
00112         {
00113                 // Open port
00114                 hPort = open(portname.c_str(), O_RDWR | O_NOCTTY);//|O_NDELAY);                                         // open the serial device
00115                                                                                                                                                                 // O_RDWR = open read an write
00116                                                                                                                                                                 // The O_NOCTTY flag tells UNIX that this program doesn't want to be the "controlling terminal" for that 
00117                                                                                                                                                                 // port. If you don't specify this then any input (such as keyboard abort signals and so forth) will affect 
00118                                                                                                                                                                 // your process. Programs like getty(1M/8) use this feature when starting the login process, but normally a 
00119                                                                                                                                                                 // user program does not want this behavior.
00120                                                                                                                                                                 // The O_NDELAY flag tells UNIX that this program doesn't care what state the DCD signal line is in ­ 
00121                                                                                                                                                                 // whether the other end of the port is up and running. If you do not specify this flag, your process will be 
00122                                                                                                                                                                 // put to sleep until the DCD signal line is the space voltage.
00123 
00124                 if (hPort < 0) {                                                                                                                        //check if port opened correctly
00125                         perror(" Could not open serial port, aborting");
00126                         return false;
00127                 }
00128 
00129 
00130                 tcgetattr(hPort, &options);                                                                     // get the current termios (com port options struct) from the kernel
00131                 tcgetattr(hPort, &old_options);                                                                 // get the current termios copy to restore on close
00132 
00133                 cfsetispeed(&options, B115200);                                                                 // set incomming baudrate to standard 9600, this can be changed with the function set_speed()
00134                 cfsetospeed(&options, B115200);                                                                 // set outgoing baudrate to standard 9600
00135 
00136                                                                                                                                         // c_cflag Control Options
00137                                                                                                                                         // |= (..) means enabled
00138                                                                                                                                         // &= ~(..) means not enabled
00139                 options.c_cflag |= (CLOCAL|CREAD|CS8);                                                          // CREAD = enanble receiver
00140                                                                                                                                         // CLOCAL = Local Line, do not change owner of port
00141                                                                                                                                         // CS8 = 8 databits
00142                 options.c_cflag &= ~(CRTSCTS|PARENB|CSTOPB);                                    // Disable HW flow control
00143                                                                                                                                         // no paritybit, PARENB = paritybit
00144                                                                                                                                         // 1 stop bit, CSTOPB = 2 stop bits (1 otherwise)
00145                 if (b_hw_flow_control){
00146                         options.c_cflag |= (CRTSCTS);                                                           // Enable HW flow control
00147                 }
00148 
00149                                                                                                                                         // c_lflag Line Options ( controls how input charackters are handeled by the serial driver
00150                 options.c_lflag &= ~(ECHO|ECHONL|ECHOE|ICANON|ISIG|IEXTEN);
00151 //      options.c_lflag &= ~(ECHO|ECHONL|ICANON|ISIG|IEXTEN);
00152                                                                                                                                         // ~(..) means not enabled
00153                                                                                                                                         // ECHO echoing of input characters
00154                                                                                                                                         // ECHOE echo erease character as BS-SP-BS
00155                                                                                                                                         // ECHONL mimics echo but doesn't move to next line when it ends
00156                                                                                                                                         // ICANON cononical input = line oriented input, else RAW
00157                                                                                                                                         // ISIG ENABLE SIGINTR, SIGSUSP, SIGDSUSP and SIGQUIT signals
00158                                                                                                                                         // IEXTERN = enable extended functions
00159 
00160                                                                                                                                         // c_iflag Input Options
00161                 options.c_iflag &= ~(IGNBRK|BRKINT|PARMRK|ISTRIP|INLCR|IGNCR|ICRNL|IXON|IXOFF);
00162 //      options.c_iflag &= ~(IGNBRK|BRKINT|PARMRK|ISTRIP|INLCR|IGNCR|ICRNL|IXON);
00163                                                                                                                                         // ~(..) means not enabled
00164                                                                                                                                         // IGNBRK ignore break condition
00165                                                                                                                                         // BRKINT send a SIGINT when a break condition is detected
00166                                                                                                                                         // PARMRK Mark parity errors
00167                                                                                                                                         // ISTRIP strip parity bits
00168                                                                                                                                         // INLCR map new line to CR
00169                                                                                                                                         // IGNCR ignore CR
00170                                                                                                                                         // ICRNL map CR to new line
00171                                                                                                                                         // IXON Enable software flow control (outgoing)
00172                                                                                                                                         // IXOFF Enable software flow control (incomming)
00173 
00174                                                                                                                                         // c_oflag output options
00175                 options.c_oflag &= ~(OPOST);
00176                                                                                                                                         // ~(..) means not enabled
00177                                                                                                                                         // OPOST postprocess output (if not set RAW output)
00178                                                                                                                                         // when OPOST is disabled all other other option bits of c-Oflag are ignored
00179 
00180                                                                                                                                         // c_cc control character array (control caracter options and timeouts
00181                                                                                                                                         // Timeout 0.005 sec for first byte, read minimum of 0 bytes
00182                                                                                                                                         // timeouts are ignored in cononical input or when NDELAY option is set.
00183                 options.c_cc[VMIN]     = 0;                                                                     // VMIN Minimum number of characters to read
00184                 options.c_cc[VTIME]    = WAIT_FOR_DATA_DSEC;                                    // Time to wait for data (tenths of seconds)
00185 
00186 //              fcntl(hPort, F_SETFL, FNDELAY); // don't wait for input when reading data
00187 
00188                 if (b_rts){                                                                                                             // if we are using RS_485_EXAR type, we clear the RTS signal
00189                         int msc = TIOCM_RTS;
00190                         ioctl(hPort, TIOCMBIC, &msc);                                                           // Clear RTS signal
00191                         usleep(100);                                                                                            // WAIT FOR SIGNAL TO BE CLEARD
00192                 }
00193 
00194 
00195 
00196                 if (tcsetattr(hPort,TCSANOW, &options)!=0){                                             // Set the new options for the port now
00197                         perror("Error: Could not set serial port settings");
00198                         return false;
00199                 }
00200 
00201                 usleep(100);                                                                                                    // additional wait for correct functionality
00202                 tcflush(hPort, TCIOFLUSH);                                                                              // flush terminal data
00203         }
00204 
00205         // Save port name
00206         s_port_name = portname;
00207 
00208         return true;
00209 }
00210 
00211 bool    LxSerial::is_port_open()
00212 {
00213         return hPort >= 0;
00214 }
00215 
00216 // speedcontrol */
00217 bool    LxSerial::set_speed( LxSerial::PortSpeed baudrate )
00218 {
00219         if (b_socket)
00220                 return false;
00221 
00222         cfsetispeed(&options, baudrate);                                                                //set incoming baud rate
00223         cfsetospeed(&options, baudrate);                                                                //set outgoing baud rate
00224 
00225         if (tcsetattr(hPort,TCSANOW, &options)!=0){                                             // Set the new options for the port now
00226                 perror("Error: Could not set serial port baudrate");
00227                 return false;
00228         }
00229         usleep(100);                                                                                                    // additional wait for correct functionality
00230         tcflush(hPort, TCIOFLUSH);                                                                              // flush terminal data
00231         return true;
00232 }
00233 
00234 bool LxSerial::set_speed_int(const int baudrate)
00235 {
00236         LxSerial::PortSpeed baud;
00237         // Baud rate conversion from index to real baud rate :(
00238         switch (baudrate)
00239         {
00240                 case 4000000:   baud = S4000000;        break;
00241                 case 3500000:   baud = S3500000;        break;
00242                 case 3000000:   baud = S3000000;        break;
00243                 case 2500000:   baud = S2500000;        break;
00244                 case 2000000:   baud = S2000000;        break;
00245                 case 1500000:   baud = S1500000;        break;
00246                 case 1152000:   baud = S1152000;        break;
00247                 case 1000000:   baud = S1000000;        break;
00248                 case 921600:    baud = S921600; break;
00249                 case 576000:    baud = S576000; break;
00250                 case 500000:    baud = S500000; break;
00251                 case 460800:    baud = S460800; break;
00252                 case 230400:    baud = S230400; break;
00253                 case 115200:    baud = S115200; break;
00254                 case 57600:             baud = S57600;  break;
00255                 case 38400:             baud = S38400;  break;
00256                 case 19200:             baud = S19200;  break;
00257                 case 9600:              baud = S9600;   break;
00258                 case 4800:              baud = S4800;   break;
00259                 case 2400:              baud = S2400;   break;
00260                 case 1800:              baud = S1800;   break;
00261                 case 1200:              baud = S1200;   break;
00262                 case 600:               baud = S600;    break;
00263                 case 300:               baud = S300;    break;
00264                 case 200:               baud = S200;    break;
00265                 case 150:               baud = S150;    break;
00266                 case 134:               baud = S134;    break;
00267                 case 110:               baud = S110;    break;
00268                 case 75:                baud = S75;             break;
00269                 case 50:                baud = S50;             break;
00270                 default:
00271                         printf("This is not a legal portspeed!\n");
00272                         return false;
00273         }
00274 
00275         set_speed(baud);
00276         return true;
00277 }
00278 
00279 // clear echoed characters from input and detect collisions on write, use for EXAR RS485
00280 void    LxSerial::set_clear_echo(bool clear)
00281 {
00282         b_clear_echo = clear;
00283 }
00284 
00285 // close the serial port
00286 bool    LxSerial::port_close()
00287 {
00288         if (hPort==INVALID_DEVICE_HANDLE)
00289                 return true;
00290 
00291         if (!b_socket)
00292         {
00293                 if (tcsetattr(hPort,TCSANOW, &old_options)!=0) {                                // restore the old port settings
00294                         perror("Warning: Could not restore serial port settings.");
00295                 }
00296         }
00297 
00298         if(close(hPort) == -1) {                                                                                //close serial port
00299                 perror("Error: Could not close serial port.");
00300                 return false;
00301         }
00302         hPort = INVALID_DEVICE_HANDLE;
00303         return true;
00304 }
00305 
00306 int             LxSerial::port_read(unsigned char* buffer, int numBytes) const
00307 {
00308         int nBytesRead = read(hPort, buffer, numBytes);
00309 
00310         #ifdef __DBG__
00311         printf("read  ");
00312         for (int i=0;i<nBytesRead;i++)
00313                 { printf("%02X ",buffer[i]); }
00314         printf("(%d)\n",nBytesRead);
00315         #endif
00316 
00317         return nBytesRead;
00318 }
00319 
00320 int     LxSerial::port_read(unsigned char* buffer, int numBytes, int seconds, int microseconds)
00321 {
00322         // Init time variables (they are decreased by wait_for_input)
00323         int s = seconds;
00324         int us = microseconds;
00325         int nBytesRead = 0;
00326         while (nBytesRead < numBytes)
00327         {
00328                 if( wait_for_input( &s, &us) )
00329                 {
00330                         int partialRead = read(hPort, buffer + nBytesRead, numBytes - nBytesRead); // Read data
00331                         nBytesRead += partialRead;
00332                 }
00333                 else if (nBytesRead < 0)
00334                 {
00335                         #ifdef __DBG__
00336                         printf("Read Timeout... \n");
00337                         #endif
00338                         return READ_ERROR;
00339                 }
00340                 else
00341                         break;
00342         }
00343 
00344         #ifdef __DBG__
00345         printf("read  ");
00346         for (int i=0;i<nBytesRead;i++)
00347                 { printf("%02X ",buffer[i]); }
00348         printf("(%d)\n",nBytesRead);
00349         #endif
00350 
00351         return nBytesRead;
00352 }
00353 
00354 bool    LxSerial::wait_for_input(int *seconds, int *microseconds)
00355 {
00356         fd_set readset;
00357         timeval timeout;
00358         timeout.tv_sec = *seconds;                                                                              // seconds
00359         timeout.tv_usec = *microseconds;                                                                        // microseconds
00360         FD_ZERO(&readset);                                                                                      // clear file discriptor
00361         FD_SET(hPort, &readset);                                                                                // set filediscripter for port
00362         int res = select(hPort+1, &readset, NULL, NULL, &timeout);      // wait till readable data is in the buffer
00363         *seconds = timeout.tv_sec;
00364         *microseconds = timeout.tv_usec;
00365         return res == 1;
00366 }
00367 
00368 int             LxSerial::port_write(unsigned char* buffer, int numBytes)
00369 {
00370         int msc = TIOCM_RTS;
00371         if (b_rts){                                                                                                             // control the RTS signal if needed
00372                 ioctl(hPort, TIOCMBIS, &msc);                                                           // before you write set RTS signal
00373                 usleep(1000);                                                                                           // wait until the RTS signal is high
00374         }
00375 
00376         int numBytesWritten = write(hPort, buffer, numBytes);                   // write data
00377 
00378         if (numBytes != numBytesWritten){
00379                 perror("Error while writing to serial port");
00380                 assert(numBytes == numBytesWritten);
00381         }
00382 
00383         #ifdef __DBG__
00384         printf("write ");
00385         for (int i=0;i<numBytes;i++)
00386                 { printf("%02X ",buffer[i]); }
00387         printf("(%d)",numBytesWritten);
00388         printf("\n");
00389         #endif
00390         
00391         tcdrain(hPort);                                                                                                 // Wait till all the data in the buffer is transmitted
00392 
00393         if (b_rts){                                                                                                             // control the RTS signal if needed
00394                 ioctl(hPort, TIOCMBIC, &msc);                                                           // Clear Ready To Send signal
00395         }
00396 
00397         if (b_clear_echo)
00398         {                                                                                               // Read echo from line and detect collisions if neened
00399                 unsigned char* echo_buffer = new unsigned char[numBytes];
00400                 int nBytesRead = 0;
00401                 int s = ECHO_WAIT_TIME_SEC;
00402                 int us = ECHO_WAIT_TIME_USEC;
00403                 while (nBytesRead < numBytesWritten)
00404                 {
00405                         if (wait_for_input(&s , &us))
00406                                 nBytesRead = read(hPort, echo_buffer + nBytesRead, numBytes - nBytesRead);              // Read back ECHO of sended data
00407                         else
00408                         {
00409                                 #ifdef __DBG__
00410                                 printf("echo read back timeout\n");
00411                                 #endif
00412                                 delete[] echo_buffer;
00413                                 return ECHO_TIMEOUT_ERROR;
00414                         }
00415                 }
00416 
00417 
00418                 #ifdef __DBG__
00419                 printf("echo  ");
00420                 for (int i=0;i<nBytesRead;i++)
00421                         { printf("%02X ",buffer[i]); }
00422                 printf("(%d)\n",nBytesRead);
00423                 #endif
00424 
00425                 if (nBytesRead!=numBytesWritten)
00426                 {
00427                         #ifdef __DBG__
00428                         printf("Warning: nr. of characters echoed not correct\n");
00429                         #endif
00430                         delete[] echo_buffer;
00431                         return READ_ERROR;
00432                 }
00433 
00434                 if (memcmp(buffer,echo_buffer, numBytes)!=0)
00435                 {
00436                         #ifdef __DBG__
00437                         printf("collition detect\n");
00438                         #endif
00439                         usleep(COLLISION_WAIT_TIME_USEC);                                                       //wait for a while
00440                         tcflush(hPort, TCIFLUSH);                                                               //empty all data that was in read buffer but has not been read
00441                         delete[] echo_buffer;
00442                         return COLLISION_DETECT_ERROR;
00443                 }
00444                 delete[] echo_buffer;
00445         }
00446 
00447         return numBytesWritten;
00448 }
00449 
00450 void LxSerial::flush_buffer()
00451 {
00452         tcflush(hPort, TCIOFLUSH);                                                                              // flush data buffer
00453 }
00454 
00455 LxSerial::~LxSerial()
00456 {
00457         if (hPort != INVALID_DEVICE_HANDLE)
00458                 port_close();
00459 }


shared_serial
Author(s): Wouter Caarls
autogenerated on Sun Jan 5 2014 11:06:47