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


ess_imu_ros1_uart_driver
Author(s):
autogenerated on Sun Jun 4 2023 02:59:29