linux_serial.cpp
Go to the documentation of this file.
00001 
00047 #if !defined(LINUX_SERIAL_H) && !defined(win_x86)
00048 #define LINUX_SERIAL_H
00049 #include "roch_base/core/serial.h"  /* Std. function protos */
00050 #include <stdio.h>   /* Standard input/output definitions */
00051 #include <string.h>  /* String function definitions */
00052 #include <unistd.h>  /* UNIX standard function definitions */
00053 #include <fcntl.h>   /* File control definitions */
00054 #include <errno.h>   /* Error number definitions */
00055 #include <termios.h> /* POSIX terminal control definitions */
00056 #include <stdlib.h>  /* Malloc */
00057 #include <assert.h>
00058 
00059 namespace sawyer{
00060   
00061   int roch_driver::OpenSerial(void **handle, const char *port_name)
00062 {
00063 
00064   int fd; /* File descriptor for the port */
00065 
00066   fd = open(port_name, O_RDWR | O_NOCTTY | O_NDELAY);
00067   if (fd == -1)
00068   {
00069     fprintf(stderr, "Unable to open %s\n\r", port_name);
00070     return -3;
00071   }
00072 
00073   // Verify it is a serial port
00074   if (!isatty(fd))
00075   {
00076     close(fd);
00077     fprintf(stderr, "%s is not a serial port\n", port_name);
00078     return -3;
00079   }
00080 
00081   *handle = (int *) malloc(sizeof(int));
00082   **(int **) handle = fd;
00083   return fd;
00084 }
00085 
00086 int roch_driver::SetupSerial(void *handle)
00087 {
00088   struct termios options;
00089 
00090   // Get the current options for the port...
00091   tcgetattr(*(int *) handle, &options);
00092 
00093   // 8 bits, 1 stop, no parity
00094   options.c_cflag = 0;
00095   options.c_cflag |= CS8;         // 8-bit input
00096 
00097   // Enable the receiver and set local mode...
00098   options.c_cflag |= (CLOCAL | CREAD);
00099 
00100   // Set the baud rates to 115200...
00101   cfsetispeed(&options, B115200);
00102   cfsetospeed(&options, B115200);
00103 
00104   // No input processing
00105   options.c_iflag = 0;
00106 
00107   // No output processing
00108   options.c_oflag = 0;
00109 
00110   // No line processing
00111   options.c_lflag = 0;
00112 
00113   // read timeout
00114   options.c_cc[VMIN] = 0;    // non-blocking
00115   options.c_cc[VTIME] = 1;    // always return after 0.1 seconds
00116 
00117   // Set the new options for the port...
00118   tcsetattr(*(int *) handle, TCSAFLUSH, &options);
00119 
00120   return 0;
00121 }
00122 
00123 int roch_driver::WriteData(void *handle, const char *buffer, int length)
00124 {
00125   
00126   int n = write(*(int *) handle, buffer, length);
00127   
00128   if (n < 0)
00129   {
00130     fprintf(stderr, "Error in serial write\r\n");
00131     return -1;
00132   }
00133   //serial port output monitor
00134 
00135 #ifdef TX_DEBUG
00136         printf("TX:");
00137         int i;
00138         for (i=0; i<length; ++i) printf(" %x", (unsigned char)(buffer[i]));
00139         printf("\r\n");
00140 
00141 #endif
00142   return n;
00143 }
00144 
00145 
00146 int roch_driver::ReadData(void *handle, char *buffer, int length)
00147 {
00148   int bytesRead = read(*(int *) handle, buffer, length);
00149 
00150   if (bytesRead <= 0)
00151   {
00152     return 0;
00153   }
00154   
00155   // serial port input monitor
00156 #ifdef RX_DEBUG1
00157         printf("RX:");
00158         int i;
00159         for (i=0; i<bytesRead; ++i) printf(" %x", (unsigned char)buffer[i]);
00160         printf("\r\n");
00161 #endif
00162   return bytesRead;
00163 }
00164 
00165 int roch_driver::CloseSerial(void *handle)
00166 {
00167   if (NULL == handle)
00168   {
00169     return 0;
00170   }
00171   close(*(int *) handle);
00172   free(handle);
00173   return 0;
00174 }
00175   
00176 };
00177 
00178 #endif // LINUX_SERIAL


roch_base
Author(s): Mike Purvis , Paul Bovbel , Carl
autogenerated on Sat Jun 8 2019 20:32:33