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


shared_serial
Author(s): Wouter Caarls
autogenerated on Thu Jun 6 2019 19:47:36