serial.cc
Go to the documentation of this file.
00001 
00020 #include <stdio.h>
00021 #include <fcntl.h>
00022 #include <sys/time.h>
00023 #include <unistd.h>
00024 
00025 #include "serial.h"
00026 #include <string.h>
00027 #include <errno.h>
00028 
00029 SerialDevice::~SerialDevice(){
00030   if (tty_fd_slot != -1) {
00031     empty_serial (tty_fd_slot);
00032     close_serial (tty_fd_slot);
00033   }
00034 }
00035 SerialDevice::SerialDevice(){
00036   tty_fd_slot = -1;
00037   strcpy(device_name,"");
00038 }
00039 
00040 
00041 /******************************************************************************
00042  ***
00043  *** Name:       open_serial
00044  ***
00045  *** Purpose:    oeffnet ein serielles Device
00046  ***
00047  *** Parameters: devicename (z.B. "/dev/ttyS4") und flags (z.B. CS8|B9600 ) 
00048  ***
00049  *** Returns:    filedescriptor, bzw. -1 im Fehlerfall
00050  ***
00051  ******************************************************************************
00052  */
00053 
00054 int  SerialDevice::open_serial (const char *p_tty_name)
00055 {
00056    struct termio tty_set;
00057    int tty_fd = -1;
00058     
00059    if ( (tty_fd = open(p_tty_name, O_RDWR |O_NOCTTY)) < 0 )//NONBLOCK
00060      {
00061        printf("ERROR: Couldn't open port %s!\n", p_tty_name);
00062        perror(NULL);
00063        return (-1);
00064      }
00065    
00066    if (ioctl(tty_fd, TCGETA, &tty_set ) == -1 )
00067      {
00068        printf("ERROR: ioctl() failed to read settings!\n");
00069        perror(NULL);
00070        return (-1);
00071      }
00072    
00073    tty_set.c_cflag = (B115200 | CS8 | CLOCAL | CREAD);
00074    tty_set.c_iflag = IXOFF;
00075    tty_set.c_lflag = 0;
00076    tty_set.c_oflag = 0;
00077    tty_set.c_cc[VTIME]    = 20;
00078    tty_set.c_cc[VMIN]     = 0;
00079 
00080    if (ioctl(tty_fd, TCSETAW, &tty_set ) == -1 ) 
00081      {
00082        printf("ERROR: ioctl() failed to set settings!\n");
00083        perror(NULL);
00084        return (-1);
00085      }
00086 
00087    tty_fd_slot = tty_fd;
00088    strcpy(device_name,p_tty_name);
00089    return (tty_fd);
00090 }
00091 
00092 /******************************************************************************
00093  ***
00094  *** Name:       change_baud_serial
00095  ***
00096  *** Purpose:    stellt die Geschwindigkeit der seriellen Schnittstelle um
00097  ***
00098  *** Parameters: filedescriptor und neue Geschwindigkeit (z.B. B38400)
00099  ***
00100  *** Returns:    STATUS_OK, bzw. STATUS_ERROR im Fehlerfall
00101  ***
00102  ******************************************************************************
00103  */
00104 
00105 long SerialDevice::change_baud_serial (int tty_fd, speed_t speed)
00106  {
00107    struct termio tty_set;
00108 
00109    if (ioctl(tty_fd, TCGETA, &tty_set ) == -1 ) 
00110      {
00111        printf("ERROR: ioctl() failed to read settings!\n");
00112        perror(NULL);
00113        return (STATUS_ERROR);
00114      }
00115    
00116    tty_set.c_cflag &= ~CBAUD;
00117    tty_set.c_cflag |= speed;
00118    
00119    if (ioctl(tty_fd, TCSETAW, &tty_set ) == -1 ) 
00120      {
00121        printf("ERROR: ioctl() failed to set settings!\n");
00122        perror(NULL);
00123        return (STATUS_ERROR);
00124      }
00125 
00126    return (STATUS_OK);
00127  }
00128 
00129 /******************************************************************************
00130  ***
00131  *** Name:       write_serial
00132  ***
00133  *** Purpose:    Schickt Daten an die serielle Schnittstelle
00134  ***
00135  *** Parameters: filedescriptor, Pointer auf Speicher, Zahl der zu versendenden bytes
00136  ***
00137  *** Returns:    STATUS_OK, bzw. STATUS_ERROR im Fehlerfall
00138  ***
00139  ******************************************************************************
00140  */
00141 
00142 long SerialDevice::write_serial(int tty_fd, unsigned char *p_buffer, long nb_byte)
00143  {
00144    int bytes_out;
00145 
00146    if (( bytes_out = write(tty_fd, p_buffer, nb_byte)) < nb_byte)
00147      {
00148        printf("ERROR: write() failed!\n");
00149        perror(NULL);
00150        return (STATUS_ERROR);
00151      };
00152 
00153    return (STATUS_OK);
00154  }
00155 
00156 /******************************************************************************
00157  ***
00158  *** Name:       read_serial
00159  ***
00160  *** Purpose:    Liest Daten von der seriellen Schnittstelle. Liegen gerade
00161  ***             keine Daten an, wird eine 20tel Sekunde darauf gewartet!
00162  ***
00163  *** Parameters: filedescriptor, Pointer auf Speicherbereich, maximale 
00164  ***             Zahl der zu lesenden bytes
00165  ***
00166  *** Returns:    Zahl der gelesenen bytes
00167  ***
00168  ******************************************************************************
00169  */
00170 
00171 long SerialDevice::read_serial(int tty_fd, unsigned char *p_buffer, long nb_bytes_max)
00172  {
00173    struct timeval tz;
00174    fd_set fds;
00175    int tries       = 0;
00176    int qu_new      = 0;
00177    int bytes_read  = 0;
00178    int ready       = STATUS_ERROR;
00179   
00180    /* read max nb_bytes_max bytes */
00181 
00182    while (tries < 2 && !ready)
00183      {
00184        tz.tv_sec  = 1;
00185        tz.tv_usec = 0;
00186        
00187        FD_ZERO(&fds);
00188        FD_SET(tty_fd, &fds);
00189        if (select(FD_SETSIZE, &fds, 0, 0, &tz) > 0)
00190          {
00191            qu_new = read(tty_fd, &p_buffer[bytes_read], (nb_bytes_max - bytes_read));
00192            if (qu_new > 0)
00193              bytes_read += qu_new;
00194            else
00195              tries++;
00196            ready = (bytes_read == nb_bytes_max);
00197          }
00198        else
00199          tries++;
00200      }
00201 
00202    return(bytes_read);
00203  }
00204 
00205 /******************************************************************************
00206  ***
00207  *** Name:      close_serial
00208  ***
00209  *** Purpose:   schliesst das serielle device
00210  ***
00211  *** Parameter: filedescriptor
00212  ***
00213  ******************************************************************************
00214  */
00215 
00216 void SerialDevice::close_serial (int tty_fd)
00217  {
00218    close(tty_fd);
00219  }
00220 
00221 /******************************************************************************
00222  ***
00223  *** Name:       wait_for_serial
00224  ***
00225  *** Purpose:    Wartet maximal eine vorgegebene Zeit auf das Eintreffen von 
00226  ***             Daten an der seriellen Schnittstelle
00227  ***
00228  *** Parameters: filedescriptor, maximale Wartezeit
00229  ***
00230  *** Returns:    STATUS_OK wenn Daten anliegen, bzw. STATUS_ERROR wenn nicht
00231  ***
00232  ******************************************************************************
00233  */
00234 
00235 long SerialDevice::wait_for_serial(int tty_fd, long max_time_secs)
00236  {
00237    struct timeval tz;
00238    fd_set fds;
00239 
00240    while (max_time_secs--)
00241      {
00242        tz.tv_sec  = 1;
00243        tz.tv_usec = 0;
00244        
00245        FD_ZERO (&fds);
00246        FD_SET(tty_fd, &fds);
00247        
00248        if (select(FD_SETSIZE, &fds, 0, 0, &tz) > 0)
00249          return (STATUS_OK);
00250      }  
00251 
00252    return (STATUS_ERROR);
00253  }
00254 
00255 
00256 /******************************************************************************
00257  ***
00258  *** Name:       empty_serial
00259  ***
00260  *** Purpose:    Loescht den Eingangspuffer der seriellen Schnittstelle
00261  ***
00262  *** Caveats:    Noch nicht getestet... (see manpage zu termios)
00263  ***
00264  *** Parameters: filedescriptor
00265  ***
00266  *** Returns:    STATUS_OK, bzw. STATUS_ERROR im Fehlerfall
00267  ***
00268  ******************************************************************************
00269  */
00270 
00271 long SerialDevice::empty_serial(int tty_fd)
00272  {
00273    if (-1 == tcflush (tty_fd, TCIFLUSH))
00274      return (STATUS_ERROR);
00275    else
00276      return (STATUS_OK);
00277  }
00278 
00279 
00280 
00281 
00282 
00283 
00284 
00285 
00286 
00287 
00288 
00289 
00290 
00291 
00292 
00293 
00294 


asr_flock_of_birds
Author(s): Bernhardt Andre, Engelmann Stephan, Giesler Björn, Heller Florian, Jäkel Rainer, Nguyen Trung, Pardowitz Michael, Weckesser Peter, Yi Xie, Zöllner Raoul
autogenerated on Sat Jun 8 2019 19:36:21