hcl_uart.c
Go to the documentation of this file.
1 //==============================================================================
2 //
3 // hcl_uart.c - Seiko Epson Hardware Control Library
4 //
5 // This layer of indirection is added to allow the sample code to call generic
6 // UART functions to work on multiple hardware platforms. This is the Linux
7 // TERMIOS specific implementation.
8 //
9 //
10 // THE SOFTWARE IS RELEASED INTO THE PUBLIC DOMAIN.
11 // THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED,
12 // INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, NONINFRINGEMENT,
13 // SECURITY, SATISFACTORY QUALITY, AND FITNESS FOR A PARTICULAR PURPOSE. IN NO EVENT
14 // SHALL EPSON BE LIABLE FOR ANY LOSS, DAMAGE OR CLAIM, ARISING FROM OR IN CONNECTION
15 // WITH THE SOFTWARE OR THE USE OF THE SOFTWARE.
16 //
17 //==============================================================================
18 #include <termios.h> // terminal io (serial port) interface
19 #include <fcntl.h> // File control definitions
20 #include <errno.h> // Error number definitions
21 #include <unistd.h>
22 #include <stdint.h>
23 #include <sys/ioctl.h> // Needed for ioctl library functions
24 #include <assert.h>
25 #include <stdio.h>
26 #include <string.h>
27 #include "hcl.h"
28 #include "hcl_uart.h"
29 #include "sensor_epsonCommon.h"
30 
31 #define TRUE 1
32 #define FALSE 0
33 
34 extern const char *IMUSERIAL;
35 extern int comPort;
36 
37 typedef int ComPortHandle;
38 typedef unsigned char Byte;
39 
40 
41 /*****************************************************************************
42 ** Function name: purgeComPort
43 ** Description: Clears the com port's read and write buffers
44 ** Parameters: COM port handle
45 ** Return value: 1=success, 0=fail
46 *****************************************************************************/
47 int purgeComPort(ComPortHandle comPortHandle)
48 {
49  if (tcflush(comPortHandle,TCIOFLUSH)==-1)
50  {
51  printf("flush failed\n");
52  return FALSE;
53  }
54  return TRUE;
55 }
56 
57 
58 /*****************************************************************************
59 ** Function name: openComPort
60 ** Description: Opens a com port with the settings for communicating
61 ** with a Epson IMU. Com port is opened in raw mode and
62 ** will timeout on reads after 1 second
63 ** Parameters: Pointer to device name, Baudrate
64 ** Return value: COM port handle if successful, -1=fail
65 *****************************************************************************/
66 ComPortHandle openComPort(const char* comPortPath, int baudRate)
67 {
68 // Read/Write, Not Controlling Terminal
69  ComPortHandle comPort = open(comPortPath, O_RDWR | O_NOCTTY);
70  //ComPortHandle comPort = open(comPortPath, O_RDWR | O_NOCTTY | O_NDELAY); // O_NDELAY means non-blocking I/O, results in unstable reads and writes
71 
72  if (comPort== -1) // Opening of port failed
73  {
74  printf("Unable to open com Port %s\n Errno = %i\n", comPortPath, errno);
75  return -1;
76  }
77 
78 // Get the current options for the port...
79  struct termios options;
80  tcgetattr(comPort, &options);
81 
82 // Set the baud rate to 460800
83  cfsetospeed(&options, baudRate);
84  cfsetispeed(&options, baudRate);
85 
86 // Turn off character processing
87 // Clear current char size mask
88 // Force 8 bit input
89  options.c_cflag &= ~CSIZE; // Mask the character size bits
90  options.c_cflag |= CS8;
91 
92 // Set the number of stop bits to 1
93  options.c_cflag &= ~CSTOPB;
94 
95 // Set parity to None
96  options.c_cflag &= ~PARENB;
97 
98 // Set for no input processing
99  options.c_iflag = 0;
100 
101 // From https://en.wikibooks.org/wiki/Serial_Programming/termios
102 // Input flags - Turn off input processing
103 // convert break to null byte, no CR to NL translation,
104 // no NL to CR translation, don't mark parity errors or breaks
105 // no input parity check, don't strip high bit off,
106 // no XON/XOFF software flow control
107 // options.c_iflag &= ~(IGNPAR | IGNBRK | BRKINT | IGNCR | ICRNL |
108 // INLCR | PARMRK | INPCK | ISTRIP | IXON | IXOFF | IXANY);
109 
110 // Output flags - Turn off output processing
111 
112  // From http://www.cmrr.umn.edu/~strupp/serial.html
113  //options.c_oflag &= ~OPOST;
114  options.c_oflag = 0; // raw output
115 
116 // No line processing
117 // echo off, echo newline off, canonical mode off,
118 // extended input processing off, signal chars off
119 
120  // From http://www.cmrr.umn.edu/~strupp/serial.html
121  // options.c_lflag &= ~(ICANON | ECHO | ECHOE | ISIG);options.c_lflag &= ~(ICANON | ECHO | ECHOE | ISIG);
122  options.c_lflag = 0; // raw input
123 
124 // From http://www.cmrr.umn.edu/~strupp/serial.html
125 // Timeouts are ignored in canonical input mode or when the NDELAY option is set on the file via open or fcntl.
126 // VMIN specifies the minimum number of characters to read.
127 // 1) If VMIN is set to 0, then the VTIME value specifies the time to wait for every characters to be read.
128 // The read call will return even if less than specified from the read request.
129 // 2) If VMIN is non-zero, VTIME specifies the time to wait for the first character.
130 // If first character is received within the specified VTIME, then it won't return until VMIN number of characters are received.
131 // So any read call can return either 0 characters or N-specified characters, but nothing inbetween.
132 // It will block forever if RX characters are not in multiples of VMIN.
133 // 3) VTIME specifies the amount of time to wait for incoming characters in tenths of seconds.
134 // If VTIME is set to 0 (the default), reads will block (wait) indefinitely unless the NDELAY option is set on the port with open or fcntl
135 // Setting VTIME = 0, makes UART reads blocking, try experimenting with value to prevent hanging waiting for reads
136 
137 // Current setting below: Non-blocking reads with first character recv timeout of 2 seconds
138  options.c_cc[VMIN] = 4; // block reading until VMIN 4 of characters are read.
139  options.c_cc[VTIME] = 20; // Inter-Character Timer -- i.e. timeout= x*.1 s = 2 seconds
140 
141 // Set local mode and enable the receiver
142  options.c_cflag |= (CLOCAL | CREAD);
143 
144 // Purge serial port buffers
145  purgeComPort(comPort);
146 
147 // Set the new options for the port...
148  int status=tcsetattr(comPort, TCSANOW, &options);
149 
150  if (status != 0) //For error message
151  {
152  printf("Configuring comport failed\n");
153  return status;
154  }
155 
156 // Purge serial port buffers
157  purgeComPort(comPort);
158 
159  return comPort;
160 }
161 
162 
163 /*****************************************************************************
164 ** Function name: closeComPort
165 ** Description: Closes a Com port (previously opened with OpenComPort)
166 ** Parameters: COM port handle
167 ** Return value: None
168 *****************************************************************************/
170 {
171  close(comPort);
172 }
173 
174 
175 /*****************************************************************************
176 ** Function name: readComPort
177 ** Description: Read the specified number of bytes from the COM port
178 ** Parameters: COM port handle, pointer to output char array, # of bytes to read
179 ** Return value: # of bytes returned by COM port, or -1=fail
180 *****************************************************************************/
181 int readComPort(ComPortHandle comPort, unsigned char* bytes, int bytesToRead)
182 {
183  int bytesRead = read(comPort, bytes, bytesToRead);
184  return bytesRead;
185 }
186 
187 
188 /*****************************************************************************
189 ** Function name: writeComPort
190 ** Description: Write specified number of bytes to the COM port
191 ** Parameters: COM port handle, pointer to input char array, # of bytes to send
192 ** Return value: # of bytes sent, or -1=fail
193 *****************************************************************************/
194 int writeComPort(ComPortHandle comPort, unsigned char* bytesToWrite, int size)
195 {
196  return write(comPort, bytesToWrite, size);
197 }
198 
199 
200 /*****************************************************************************
201 ** Function name: numBytesReadComPort
202 ** Description: Returns number of bytes in COM port read buffer
203 ** Purpose is to check if data is available
204 ** Parameters: COM port handle
205 ** Return value: # of bytes in the COM port receive buffer
206 *****************************************************************************/
208 {
209  int numBytes;
210 
211  ioctl(comPort, FIONREAD, &numBytes);
212  return numBytes;
213 }
214 
215 
216 /*****************************************************************************
217 ** Function name: uartInit
218 ** Description: Initialize the COM port (open)
219 ** Parameters: Pointer to device name, Baudrate
220 ** Return value: COM port handle if successful, -1=fail
221 *****************************************************************************/
222 int uartInit(const char* comPortPath, int baudRate)
223 {
224  printf("Attempting to open port...%s\n",comPortPath);
225  comPort = openComPort(comPortPath, baudRate);
226  return comPort;
227 }
228 
229 
230 /*****************************************************************************
231 ** Function name: uartRelease
232 ** Description: Release the COM port (close)
233 ** Parameters: COM port handle
234 ** Return value: 1=success
235 *****************************************************************************/
237 {
238  seDelayMicroSecs(100000); // Provide 100msec delay for any pending transfer to complete
239  closeComPort(comPort);
240  return 1;
241 }
void closeComPort(ComPortHandle comPort)
Definition: hcl_uart.c:169
#define FALSE
Definition: hcl_uart.c:32
#define TRUE
Definition: hcl_uart.c:31
const char * IMUSERIAL
int uartInit(const char *comPortPath, int baudRate)
Definition: hcl_uart.c:222
int numBytesReadComPort(ComPortHandle comPort)
Definition: hcl_uart.c:207
int ComPortHandle
Definition: hcl_uart.c:37
void seDelayMicroSecs(uint32_t micros)
Definition: hcl_linux.c:67
int writeComPort(ComPortHandle comPort, unsigned char *bytesToWrite, int size)
Definition: hcl_uart.c:194
int readComPort(ComPortHandle comPort, unsigned char *bytes, int bytesToRead)
Definition: hcl_uart.c:181
int uartRelease(ComPortHandle comPort)
Definition: hcl_uart.c:236
ComPortHandle openComPort(const char *comPortPath, int baudRate)
Definition: hcl_uart.c:66
int purgeComPort(ComPortHandle comPortHandle)
Definition: hcl_uart.c:47
unsigned char Byte
Definition: hcl_uart.c:38


epson_g364_imu_driver
Author(s):
autogenerated on Mon Jun 10 2019 13:12:32