serial.c
Go to the documentation of this file.
1 // Copyright (c) 2010-2016 The YP-Spur Authors, except where otherwise indicated.
2 //
3 // Permission is hereby granted, free of charge, to any person obtaining a copy
4 // of this software and associated documentation files (the "Software"), to
5 // deal in the Software without restriction, including without limitation the
6 // rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
7 // sell copies of the Software, and to permit persons to whom the Software is
8 // furnished to do so, subject to the following conditions:
9 //
10 // The above copyright notice and this permission notice shall be included in
11 // all copies or substantial portions of the Software.
12 //
13 // THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
14 // IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
15 // FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL
16 // THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
17 // LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
18 // OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
19 // SOFTWARE.
20 
21 #include <math.h>
22 #include <stdio.h>
23 #include <string.h>
24 #include <strings.h>
25 #include <unistd.h>
26 
27 #include <fcntl.h>
28 #include <sys/stat.h>
29 #include <sys/time.h>
30 #include <sys/types.h>
31 
32 #ifdef HAVE_CONFIG_H
33 #include <config.h>
34 #endif // HAVE_CONFIG_H
35 
36 /* ボディパラメータ */
37 #include <shvel-param.h>
38 
39 /* yp-spur用 */
40 #include <serial.h>
41 #include <communication.h>
42 #include <utility.h>
43 #include <param.h>
44 #include <ypspur-coordinator.h>
45 #include <yprintf.h>
46 
47 #include <errno.h>
48 double SER_BAUDRATE;
49 
50 /* serial */
51 #if !defined(__MINGW32__)
52 
53 // Unix用コード
54 #include <sys/select.h>
55 #include <sys/termios.h>
56 int g_device_port = 0;
57 struct termios g_oldtio;
58 
59 #else
60 
61 // Windows用コード
62 #include <windows.h>
63 HANDLE g_hdevices = NULL;
64 DCB g_olddcb;
65 COMMTIMEOUTS g_oldcto;
66 
67 #endif // !defined(__MINGW32__)
68 
69 #if !defined(__MINGW32__)
70 speed_t i2baud(int baud)
71 {
72  switch (baud)
73  {
74  case 0:
75  return B0;
76  case 9600:
77  return B9600;
78  case 19200:
79  return B19200;
80  case 38400:
81  return B38400;
82 #ifdef B57600
83  case 57600:
84  return B57600;
85 #endif // B57600
86 #ifdef B128000
87  case 128000:
88  return B128000;
89 #endif // B128000
90 #ifdef B115200
91  case 115200:
92  return B115200;
93 #endif // B115200
94 #ifdef B230400
95  case 230400:
96  return B230400;
97 #endif // B230400
98 #ifdef B460800
99  case 460800:
100  return B460800;
101 #endif // B460800
102 #ifdef B576000
103  case 576000:
104  return B576000;
105 #endif // B576000
106 #ifdef B921600
107  case 921600:
108  return B921600;
109 #endif // B921600
110  }
111  return -1;
112 }
113 
114 int baud2i(speed_t baud)
115 {
116  switch (baud)
117  {
118  case B0:
119  return 0;
120  case B9600:
121  return 9600;
122  case B19200:
123  return 19200;
124  case B38400:
125  return 38400;
126 #ifdef B57600
127  case B57600:
128  return 57600;
129 #endif // B57600
130 #ifdef B128000
131  case B128000:
132  return 128000;
133 #endif // B128000
134 #ifdef B115200
135  case B115200:
136  return 115200;
137 #endif // B115200
138 #ifdef B230400
139  case B230400:
140  return 230400;
141 #endif // B230400
142 #ifdef B460800
143  case B460800:
144  return 460800;
145 #endif // B460800
146 #ifdef B576000
147  case B576000:
148  return 576000;
149 #endif // B576000
150 #ifdef B921600
151  case B921600:
152  return 921600;
153 #endif // B921600
154  }
155  return -1;
156 }
157 #else
158 DWORD i2baud(int baud)
159 {
160  switch (baud)
161  {
162  case 9600:
163  return CBR_9600;
164  case 19200:
165  return CBR_19200;
166  case 38400:
167  return CBR_38400;
168  case 115200:
169  return CBR_115200;
170  case 128000:
171  return CBR_128000;
172  }
173  return CBR_110;
174 }
175 #endif // !defined(__MINGW32__)
176 
177 // ポートが接続可能か調べる
178 int serial_tryconnect(char *device_name)
179 {
180 #if !defined(__MINGW32__)
181  // Unix用
182  g_device_port = open(device_name, O_RDWR);
183  if (g_device_port < 0)
184  {
185  return 0;
186  }
187  close(g_device_port);
188 #else
189  // Windows用
190  // ファイルハンドラの作成
191  g_hdevices = CreateFile(device_name, GENERIC_WRITE, 0, 0, OPEN_EXISTING, 0, 0);
192  if (g_hdevices == INVALID_HANDLE_VALUE)
193  {
194  return 0;
195  }
196  CloseHandle(g_hdevices);
197 #endif // !defined(__MINGW32__)
198  return 1;
199 }
200 
201 int recieve_throw(char *buf, int len, double t, void *data)
202 {
203  buf[len] = 0;
204  strcat((char *)data, buf);
205  if (strstr((char *)data, "\n\n"))
206  {
207  return -2;
208  }
209  return 0;
210 }
211 
217 {
218 #if !defined(__MINGW32__)
219  struct termios newtio;
220  int ret, errnum;
221  char buf[2048];
222 
223  memset(&newtio, 0, sizeof(newtio)); // 新しいポートの設定の構造体をクリアする
224 
225  // シリアルのボーレートを設定
226  // 8bit 通信
227  // スタートビット1
228  // エンドビット1
229  // パリティー無し
230  // 合計 10bit
231 
232  newtio.c_cflag = CS8 | CLOCAL | CREAD | CRTSCTS;
233  errno = 0;
234  ret = cfsetispeed(&newtio, i2baud(baud));
235  if (ret < 0)
236  {
237  errnum = errno;
238  yprintf(OUTPUT_LV_ERROR, "Error: Failed to set input baud rate to %d\n", baud);
239  yprintf(OUTPUT_LV_DEBUG, "Error: cfsetispeed: %s(%d)\n", strerror(errnum), errnum);
240  return 0;
241  }
242  errno = 0;
243  ret = cfsetospeed(&newtio, i2baud(baud));
244  if (ret < 0)
245  {
246  errnum = errno;
247  yprintf(OUTPUT_LV_ERROR, "Error: Failed to set output baud rate to %d\n", baud);
248  yprintf(OUTPUT_LV_DEBUG, "Error: cfsetospeed: %s(%d)\n", strerror(errnum), errnum);
249  return 0;
250  }
251  SER_BAUDRATE = (double)baud;
252  newtio.c_iflag = IGNPAR; // パリティエラーのデータは無視する
253  newtio.c_oflag = 0; // Disable implementation dependent processing
254 
255  newtio.c_cc[VTIME] = 0; /* キャラクタ間タイマを使わない */
256  newtio.c_cc[VMIN] = 1; /* 1文字来るまで,読み込みをブロックする */
257 
258  if (tcsetattr(g_device_port, TCSAFLUSH, &newtio))
259  {
260  errnum = errno;
261  yprintf(OUTPUT_LV_ERROR, "Error: Failed to set attribute of serial port\n");
262  yprintf(OUTPUT_LV_DEBUG, "Error: tcsetattr: %s(%d)\n", strerror(errnum), errnum);
263  return 0;
264  }
265 
266  { // ---> check bit rate
267  struct termios term;
268  speed_t isp, osp;
269  errno = 0;
270 
271  ret = tcgetattr(g_device_port, &term);
272  if (ret < 0)
273  {
274  errnum = errno;
275  yprintf(OUTPUT_LV_ERROR, "Error: Failed to get attribute of serial port\n");
276  yprintf(OUTPUT_LV_DEBUG, "Error: tcgetattr: %s(%d)\n", strerror(errnum), errnum);
277  return 0;
278  }
279  isp = cfgetispeed(&term);
280  osp = cfgetospeed(&term);
281 
282  if (baud2i(isp) != baud || baud2i(osp) != baud)
283  {
284  // fail to set bit rate
285  yprintf(OUTPUT_LV_ERROR, "Error: Requested baudrate is %d/%d, \n but sellected baudrate is %d/%d.\n",
286  baud, baud, baud2i(isp), baud2i(osp));
287  return 0;
288  }
289  } // <--- check bit rate
290 
292  {
293  ret = write(g_device_port, "\n\nVV\n\n", 6);
294  yp_usleep(10000);
296  }
297 #else
298  // Windows用
299  DCB dcb;
300 
301  // シリアルポートの状態操作
302  GetCommState(g_hdevices, &dcb); // シリアルポートの状態を取得
303  dcb.fBinary = 1;
304  dcb.fParity = 0;
305  dcb.fOutxCtsFlow = 0;
306  dcb.fOutxDsrFlow = 0;
307  dcb.fDtrControl = DTR_CONTROL_DISABLE;
308  dcb.fDsrSensitivity = FALSE;
309  dcb.Parity = NOPARITY;
310  dcb.StopBits = ONESTOPBIT;
311  dcb.ByteSize = 8;
312  dcb.BaudRate = i2baud(baud);
313  SER_BAUDRATE = (double)baud;
314  SetCommState(g_hdevices, &dcb); // シリアルポートの状態を設定
315 #endif // !defined(__MINGW32__)
316  return 1;
317 }
318 
319 // ポートをオープンして 通信の準備をする
320 int serial_connect(char *device_name)
321 {
322 #if !defined(__MINGW32__)
323  g_device_port = open(device_name, O_RDWR);
324 
325  if (g_device_port < 0)
326  {
327  yprintf(OUTPUT_LV_ERROR, "Error: Can't open serial port.\n");
328  return 0;
329  }
330 
331  tcgetattr(g_device_port, &g_oldtio);
332 
334 #else
335  // Windows用
336  // DCB dcb;
337  COMMTIMEOUTS cto;
338 
339  // ファイルハンドラの作成
340  g_hdevices = CreateFile(device_name, GENERIC_WRITE | GENERIC_READ, 0, 0, OPEN_EXISTING, FILE_ATTRIBUTE_NORMAL, 0);
341  if (g_hdevices == INVALID_HANDLE_VALUE)
342  {
343  return 0;
344  }
345  // シリアルポートの状態操作
346  GetCommState(g_hdevices, &g_olddcb); // シリアルポートの状態を取得
348 
349  // シリアルポートのタイムアウト状態操作
350  GetCommTimeouts(g_hdevices, &cto); // タイムアウトの設定状態を取得
351  GetCommTimeouts(g_hdevices, &g_oldcto); // タイムアウトの設定状態を取得
352  cto.ReadIntervalTimeout = 0;
353  cto.ReadTotalTimeoutMultiplier = 0;
354  cto.ReadTotalTimeoutConstant = 1000;
355  cto.WriteTotalTimeoutMultiplier = 0;
356  cto.WriteTotalTimeoutConstant = 1000;
357  SetCommTimeouts(g_hdevices, &cto); // タイムアウトの状態を設定
358 #endif // !defined(__MINGW32__)
359  return 1;
360 }
361 
362 // ポートを閉じる
363 int serial_close(void)
364 {
365 #if !defined(__MINGW32__)
366  // Unix用
367  // 設定を元に戻す
368  if (g_device_port != 0)
369  {
370  tcsetattr(g_device_port, TCSANOW, &g_oldtio);
371  close(g_device_port);
372  g_device_port = 0;
373  }
374 #else
375  // Windows用
376  if (g_hdevices != NULL)
377  {
378  SetCommState(g_hdevices, &g_olddcb); // シリアルポートの状態を設定
379  SetCommTimeouts(g_hdevices, &g_oldcto); // タイムアウトの状態を設定
380  CloseHandle(g_hdevices);
381  g_hdevices = NULL;
382  }
383 #endif // !defined(__MINGW32__)
384 
385  return 1;
386 }
387 
388 void serial_flush_in(void)
389 {
390 #if !defined(__MINGW32__)
391  // Unix用
392  tcflush(g_device_port, TCIFLUSH);
393 #else
394  // Windows用
395  char buf[4096];
396 
397  DWORD len;
398  DWORD ret;
399  COMSTAT state;
400 
401  while (1)
402  {
403  ClearCommError(g_hdevices, &ret, &state);
404  len = state.cbInQue;
405 
406  if (len > 0)
407  {
408  if (len > 4000)
409  len = 4000;
410  if (!ReadFile(g_hdevices, buf, len, &len, NULL))
411  {
412  return;
413  }
414  break;
415  }
416  else if (len == 0)
417  break;
418  yp_usleep(5000);
419  }
420 #endif // !defined(__MINGW32__)
421 }
422 
424 {
425 #if !defined(__MINGW32__)
426  // Unix用
427  tcflush(g_device_port, TCOFLUSH);
428 #else
429 // Windows用
430 #endif // !defined(__MINGW32__)
431 }
432 
433 // シリアルポートからの受信処理
434 int serial_recieve(int (*serial_event)(char *, int, double, void *), void *data)
435 {
436  char buf[4096];
437  double receive_time;
438  int retval;
439 
440  while (1)
441  {
442 #if !defined(__MINGW32__)
443  // Unix用
444  fd_set rfds;
445  struct timeval tv;
446  size_t len;
447 
448  // [s] -> [us]
449  long long int timeout_us = p(YP_PARAM_DEVICE_TIMEOUT, 0) * 1000000;
450  if (timeout_us == 0)
451  {
452  // Default timeout before loading parameter file.
453  timeout_us = 200000;
454  }
455  tv.tv_sec = timeout_us / 1000000;
456  tv.tv_usec = timeout_us % 1000000;
457  FD_ZERO(&rfds);
458  FD_SET(g_device_port, &rfds);
459 
460  retval = select(g_device_port + 1, &rfds, NULL, NULL, &tv);
461  if (retval < 0)
462  {
463  int errnum;
464  errnum = errno;
465  yprintf(OUTPUT_LV_DEBUG, "Error: Select in serial_recieve failed. (%s)\n", strerror(errnum));
466  return -1;
467  }
468  else if (retval == 0)
469  {
470  yprintf(OUTPUT_LV_DEBUG, "Error: Select timed out\n");
471  return -1;
472  }
473  receive_time = get_time();
474 
475  len = read(g_device_port, buf, 4000);
476  if (len < 0)
477  {
478  int errnum;
479  errnum = errno;
480  yprintf(OUTPUT_LV_DEBUG, "Error: Read in serial_recieve failed. (%s)\n", strerror(errnum));
481  return -1;
482  }
483  else if (len == 0)
484  {
485  yprintf(OUTPUT_LV_DEBUG, "Error: Read timed out\n");
486  return -1;
487  }
488 #else
489  // Windows用
490  DWORD len;
491  DWORD ret;
492  COMSTAT state;
493  int timeout_count;
494 
495  timeout_count = 0;
496  while (1)
497  {
498  if (!ClearCommError(g_hdevices, &ret, &state))
499  return -1;
500  if (ret)
501  return -1;
502  len = state.cbInQue;
503  if (len > 4000)
504  len = 4000;
505  if (len > 0)
506  break;
507  yp_usleep(5000);
508  timeout_count++;
509  if (timeout_count > 500 / 5)
510  return -1;
511  }
512  receive_time = get_time();
513  if (!ReadFile(g_hdevices, buf, len, &len, NULL))
514  {
515  return -1;
516  }
517  buf[len] = 0;
518 #endif // !defined(__MINGW32__)
519  buf[len] = 0;
520 
521  if (len > 0)
522  {
523  retval = serial_event(buf, len, receive_time, data);
524  if (retval < 0)
525  return retval;
526  }
527  }
528 }
529 
530 int encode_write(char *data, int len)
531 {
532  unsigned char buf[128];
533  int encode_len, ret;
534 
535  buf[0] = COMMUNICATION_START_BYTE;
536  encode_len = encode((unsigned char *)data, len, buf + 1, 126);
537  buf[encode_len + 1] = COMMUNICATION_END_BYTE;
538 
539  ret = serial_write((char *)buf, encode_len + 2);
540  if (ret <= 0)
541  {
542  return -1;
543  }
545 
546  return 0;
547 }
548 
549 int encode_int_write(char *data, int len)
550 {
551  unsigned char buf[128];
552  int encode_len, ret;
553 
554  buf[0] = COMMUNICATION_INT_BYTE;
555  encode_len = encode((unsigned char *)data, len, buf + 1, 126);
556  buf[encode_len + 1] = COMMUNICATION_END_BYTE;
557 
558  ret = serial_write((char *)buf, encode_len + 2);
559  if (ret <= 0)
560  {
561  return -1;
562  }
564 
565  return 0;
566 }
567 
568 int serial_write(char *buf, int len)
569 {
570 #if !defined(__MINGW32__)
571  // Unix用
572  int ret;
573 #else
574  // Windows用
575  DWORD ret;
576 #endif // !defined(__MINGW32__)
577 
578  do
579  {
580 #if !defined(__MINGW32__)
581  // Unix用
582  ret = write(g_device_port, buf, len);
583 #else
584  // Windows用
585  buf[len] = 0;
586  WriteFile(g_hdevices, buf, len, (LPDWORD)&ret, 0);
587 #endif // !defined(__MINGW32__)
588  // printf("SEND: %s - %d(%d)\n",buf,len,ret);fflush(stdout);
589  if (ret <= 0 && len > 0)
590  {
591  return -1;
592  }
593  len -= ret;
594  buf += ret;
595  } while (len > 0);
596 
597 #ifdef __APPLE__
598  yp_usleep(100);
599 #endif // __APPLE__
600  return 1;
601 }
void yp_usleep(int usec)
Definition: utility.c:54
double get_time(void)
Definition: utility.c:45
#define DEFAULT_BAUDRATE
Definition: serial.h:27
void serial_flush_out(void)
Definition: serial.c:423
int encode_write(char *data, int len)
Definition: serial.c:530
int serial_close(void)
Definition: serial.c:363
double p(YPSpur_param id, enum motor_id motor)
Definition: param.c:79
int serial_change_baudrate(int baud)
ボーレートを変更する
Definition: serial.c:216
int recieve_throw(char *buf, int len, double t, void *data)
Definition: serial.c:201
#define COMMUNICATION_END_BYTE
Definition: communication.h:26
int serial_write(char *buf, int len)
Definition: serial.c:568
double SER_BAUDRATE
Definition: serial.c:48
speed_t i2baud(int baud)
Definition: serial.c:70
int baud2i(speed_t baud)
Definition: serial.c:114
int serial_recieve(int(*serial_event)(char *, int, double, void *), void *data)
Definition: serial.c:434
int encode_int_write(char *data, int len)
Definition: serial.c:549
void yprintf(ParamOutputLv level, const char *format,...)
Definition: yprintf.c:32
void serial_flush_in(void)
Definition: serial.c:388
int state(YPSpur_state id)
Definition: param.c:64
int g_device_port
Definition: serial.c:56
int option(ParamOptions option)
Definition: param.c:99
struct termios g_oldtio
Definition: serial.c:57
#define COMMUNICATION_INT_BYTE
Definition: communication.h:25
int serial_connect(char *device_name)
Definition: serial.c:320
int serial_tryconnect(char *device_name)
Definition: serial.c:178
int encode(const unsigned char *src, int len, unsigned char *dst, int buf_max)
エンコード
Definition: communication.c:42
#define COMMUNICATION_START_BYTE
Definition: communication.h:24


yp-spur
Author(s):
autogenerated on Fri May 7 2021 02:12:17