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 
20 #include <assert.h>
21 #include <errno.h> // Error number definitions
22 #include <fcntl.h> // File control definitions
23 #include <stdint.h>
24 #include <stdio.h>
25 #include <string.h>
26 #include <sys/ioctl.h> // Needed for ioctl library functions
27 #include <termios.h> // terminal io (serial port) interface
28 #include <unistd.h>
29 
30 #include "hcl.h"
31 #include "hcl_uart.h"
32 #include "sensor_epsonCommon.h"
33 
34 extern const char* IMUSERIAL;
35 static int fd_serial;
36 
37 // Local function prototypes
38 int openComPort(const char* comPortPath, speed_t baudRate);
39 void closeComPort(void);
40 int deviceOk(void);
41 
42 /*****************************************************************************
43 ** Function name: uartInit
44 ** Description: Initialize the COM port with the settings for
45 ** communicating with the connected Epson IMU.
46 ** Call this function instead of openComPort().
47 ** Parameters: Pointer to device name, baudrate
48 ** Return value: OK or NG
49 *****************************************************************************/
50 int uartInit(const char* comPortPath, int baudrate) {
51  printf("Attempting to open port...%s", comPortPath);
52 
53  speed_t baudRate;
54 
55  switch (baudrate) {
56  case BAUD_2000000:
57  baudRate = B2000000;
58  break;
59  case BAUD_1500000:
60  baudRate = B1500000;
61  break;
62  case BAUD_1000000:
63  baudRate = B1000000;
64  break;
65  case BAUD_921600:
66  baudRate = B921600;
67  break;
68  case BAUD_460800:
69  baudRate = B460800;
70  break;
71  case BAUD_230400:
72  baudRate = B230400;
73  break;
74  default:
75  printf("Invalid baudrate\n");
76  return NG;
77  }
78 
79  if (!openComPort(comPortPath, baudRate)) {
80  return NG;
81  }
82 
83  if (!deviceOk()) {
84  printf("Invalid device response\n");
85  return NG;
86  }
87  return OK;
88 }
89 
90 /*****************************************************************************
91 ** Function name: uartRelease
92 ** Description: Release the COM port (close) after a 100msec delay
93 ** and closing the com port to the Epson IMU.
94 ** Call this function instead of closeComPort().
95 ** Parameters: COM port handle
96 ** Return value: OK
97 *****************************************************************************/
98 int uartRelease(void) {
99  seDelayMS(100); // Provide 100msec delay for any pending transfer to complete
100  closeComPort();
101  return OK;
102 }
103 
104 /*****************************************************************************
105 ** Function name: readComPort
106 ** Description: Read the specified number of bytes from the COM port
107 ** Parameters: COM port handle, pointer to output char array, # of
108 ** bytes to read
109 ** Return value: # of bytes returned by COM port, or -1=NG
110 *****************************************************************************/
111 int readComPort(unsigned char* bytesToRead, int size) {
112  return read(fd_serial, bytesToRead, size);
113 }
114 
115 /*****************************************************************************
116 ** Function name: writeComPort
117 ** Description: Write specified number of bytes to the COM port
118 ** Parameters: COM port handle, pointer to input char array, # of bytes
119 ** to send
120 ** Return value: # of bytes sent, or -1=NG
121 *****************************************************************************/
122 int writeComPort(unsigned char* bytesToWrite, int size) {
123  return write(fd_serial, bytesToWrite, size);
124 }
125 
126 /*****************************************************************************
127 ** Function name: numBytesReadComPort
128 ** Description: Returns number of bytes in COM port read buffer
129 ** Purpose is to check if data is available
130 ** Parameters: COM port handle
131 ** Return value: # of bytes in the COM port receive buffer
132 *****************************************************************************/
134  int numBytes;
135 
136  ioctl(fd_serial, FIONREAD, &numBytes);
137  return numBytes;
138 }
139 
140 /*****************************************************************************
141 ** Function name: purgeComPort
142 ** Description: Clears the com port's read and write buffers
143 ** Parameters: COM port handle
144 ** Return value: OK or NG
145 *****************************************************************************/
146 int purgeComPort(void) {
147  if (tcflush(fd_serial, TCIOFLUSH) == -1) {
148  printf("flush failed\n");
149  return NG;
150  }
151  return OK;
152 }
153 
154 /*****************************************************************************
155 ** Function name: openComPort
156 ** Description: Com port is opened in raw mode and
157 ** will timeout on reads after 2 second.
158 ** This will return a NG if the port could not open or
159 ** the port options could not be set.
160 ** This is not intended to be called directly, but is
161 ** called from uartInit()
162 ** Parameters: Pointer to device name, Baudrate
163 ** Return value: OK or NG
164 *****************************************************************************/
165 int openComPort(const char* comPortPath, speed_t baudRate) {
166  // Read/Write, Not Controlling Terminal
167  fd_serial = open(comPortPath, O_RDWR | O_NOCTTY);
168 
169  if (fd_serial < 0) // Opening of port is NG
170  {
171  printf("...Unable to open com Port %s\n", comPortPath);
172  return NG;
173  }
174 
175  // Get the current options for the port...
176  struct termios options;
177  tcgetattr(fd_serial, &options);
178 
179  // Set the baud rate to 460800
180  cfsetospeed(&options, baudRate);
181  cfsetispeed(&options, baudRate);
182 
183  // From https://en.wikibooks.org/wiki/Serial_Programming/termios
184  // Input flags - Turn off input processing
185  // convert break to null byte, no CR to NL translation,
186  // no NL to CR translation, don't mark parity errors or breaks
187  // no input parity check, don't strip high bit off,
188  // no XON/XOFF software flow control
189  options.c_iflag &=
190  ~(IGNBRK | BRKINT | ICRNL | INLCR | PARMRK | INPCK | ISTRIP | IXON);
191 
192  options.c_oflag = 0; // raw output
193 
194  // No line processing
195  // echo off, echo newline off, canonical mode off,
196  // extended input processing off, signal chars off
197 
198  options.c_lflag &= ~(ECHO | ECHONL | ICANON | IEXTEN | ISIG);
199 
200  // Turn off character processing
201  // clear current char size mask, no parity checking,
202  // no output processing, force 8 bit input
203 
204  options.c_cflag &= ~(CSIZE | PARENB);
205  options.c_cflag |= CS8;
206 
207  // From http://www.cmrr.umn.edu/~strupp/serial.html
208  // Timeouts are ignored in canonical input mode or when the NDELAY option is
209  // set on the file via open or fcntl. VMIN specifies the minimum number of
210  // characters to read. 1) If VMIN is set to 0, then the VTIME value specifies
211  // the time to wait for every characters to be read. The read call will return
212  // even if less than specified from the read request. 2) If VMIN is non-zero,
213  // VTIME specifies the time to wait for the first character. If first
214  // character is received within the specified VTIME, then it won't return
215  // until VMIN number of characters are received. So any read call can return
216  // either 0 characters or N-specified characters, but nothing inbetween. It
217  // will block forever if RX characters are not in multiples of VMIN. 3) VTIME
218  // specifies the amount of time to wait for incoming characters in tenths of
219  // seconds. If VTIME is set to 0 (the default), reads will block (wait)
220  // indefinitely unless the NDELAY option is set on the port with open or fcntl
221  // Setting VTIME = 0, makes UART reads blocking, try experimenting with value
222  // to prevent hanging waiting for reads
223 
224  options.c_cc[VMIN] = 0; // No min # of characters to read
225  options.c_cc[VTIME] = 20; // Timeout for 1st character is X*0.1secs = 2secs
226 
227  // Set local mode and enable the receiver
228  options.c_cflag |= (CLOCAL | CREAD);
229 
230  // Change attributes when output has drained; also flush pending input.
231  int status = tcsetattr(fd_serial, TCSAFLUSH, &options);
232 
233  if (status != 0) // For error message
234  {
235  printf("Configuring comport failed\n");
236  closeComPort();
237  return NG;
238  }
239 
240  // Purge serial port buffers
241  purgeComPort();
242 
243  return OK;
244 }
245 
246 /*****************************************************************************
247 ** Function name: closeComPort
248 ** Description: Closes a Com port (previously opened with OpenComPort)
249 ** This is not intended to be called directly, but is
250 ** called from uartRelease()
251 ** Parameters: COM port handle
252 ** Return value: None
253 *****************************************************************************/
254 void closeComPort(void) { close(fd_serial); }
255 
256 /*****************************************************************************
257 ** Function name: deviceOk
258 ** Description: (Optional) Checks for Epson device.
259 ** Attempts to recover if UART interface to device
260 ** is inconsistent
261 ** Parameters: None
262 ** Return value: OK or NG
263 *****************************************************************************/
264 int deviceOk(void) {
265  int retry_count = 5;
266  unsigned char response[4] = {0};
267  unsigned char SET_WIN_ID0[] = {0xFE, 0x00, 0x0D};
268  unsigned char SET_CONFIG_MODE[] = {0x83, 0x02, 0x0D};
269  unsigned char GET_ID[] = {0x4C, 0x00, 0x0D};
270  unsigned char DELIMITER_[] = {0x0D};
271  const unsigned short ID_VAL_ = 0x5345;
272  unsigned short resp16;
273 
274  while (retry_count > 0) {
275  int num_rcv_bytes;
276  writeComPort(SET_WIN_ID0, 3);
277  epsonStall();
278 
279  writeComPort(SET_CONFIG_MODE, 3);
280  epsonStall();
281 
282  seDelayMS(100); // delay for pending transfer to complete
283  purgeComPort();
284  num_rcv_bytes = numBytesReadComPort();
285 
286  // If receive buffer is empty, and ID register check is ok, then return OK
287  if (num_rcv_bytes == 0) {
288  writeComPort(GET_ID, 3);
289  epsonStall();
290 
291  num_rcv_bytes = readComPort(&response[0], 4);
292  if (num_rcv_bytes == 4) {
293  resp16 = (unsigned short)response[1] << 8 | (unsigned short)response[2];
294  if (resp16 == ID_VAL_) {
295  return OK;
296  }
297  }
298  }
299  // If receive buffer is not empty or ID check fails,
300  // send a DELIMITER byte and go thru loop again
301  writeComPort(DELIMITER_, 1);
302  retry_count--;
303  }
304  return NG;
305 }
response
const std::string response
sensor_epsonCommon.h
seDelayMS
void seDelayMS(uint32_t millis)
Definition: hcl_linux.c:47
fd_serial
static int fd_serial
Definition: hcl_uart.c:35
closeComPort
void closeComPort(void)
Definition: hcl_uart.c:254
purgeComPort
int purgeComPort(void)
Definition: hcl_uart.c:146
BAUD_230400
#define BAUD_230400
Definition: hcl_uart.h:27
BAUD_1500000
#define BAUD_1500000
Definition: hcl_uart.h:23
IMUSERIAL
const char * IMUSERIAL
Definition: main_csvlogger.c:41
writeComPort
int writeComPort(unsigned char *bytesToWrite, int size)
Definition: hcl_uart.c:122
hcl.h
epsonStall
#define epsonStall()
Definition: sensor_epsonSpi.h:32
BAUD_1000000
#define BAUD_1000000
Definition: hcl_uart.h:24
BAUD_460800
#define BAUD_460800
Definition: hcl_uart.h:26
BAUD_921600
#define BAUD_921600
Definition: hcl_uart.h:25
uartInit
int uartInit(const char *comPortPath, int baudrate)
Definition: hcl_uart.c:50
BAUD_2000000
#define BAUD_2000000
Definition: hcl_uart.h:22
openComPort
int openComPort(const char *comPortPath, speed_t baudRate)
Definition: hcl_uart.c:165
uartRelease
int uartRelease(void)
Definition: hcl_uart.c:98
numBytesReadComPort
int numBytesReadComPort(void)
Definition: hcl_uart.c:133
deviceOk
int deviceOk(void)
Definition: hcl_uart.c:264
NG
#define NG
Definition: hcl.h:30
assert.h
OK
#define OK
Definition: hcl.h:26
readComPort
int readComPort(unsigned char *bytesToRead, int size)
Definition: hcl_uart.c:111
hcl_uart.h


ess_imu_driver
Author(s):
autogenerated on Wed Dec 11 2024 03:06:30