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


husky_base
Author(s): Mike Purvis , Paul Bovbel
autogenerated on Sat Jun 8 2019 18:26:01