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 
291  ret = write(g_device_port, "\n\nVV\n\n", 6);
292  yp_usleep(10000);
294 #else
295  // Windows用
296  DCB dcb;
297 
298  // シリアルポートの状態操作
299  GetCommState(g_hdevices, &dcb); // シリアルポートの状態を取得
300  dcb.fBinary = 1;
301  dcb.fParity = 0;
302  dcb.fOutxCtsFlow = 0;
303  dcb.fOutxDsrFlow = 0;
304  dcb.fDtrControl = DTR_CONTROL_DISABLE;
305  dcb.fDsrSensitivity = FALSE;
306  dcb.Parity = NOPARITY;
307  dcb.StopBits = ONESTOPBIT;
308  dcb.ByteSize = 8;
309  dcb.BaudRate = i2baud(baud);
310  SER_BAUDRATE = (double)baud;
311  SetCommState(g_hdevices, &dcb); // シリアルポートの状態を設定
312 #endif // !defined(__MINGW32__)
313  return 1;
314 }
315 
316 // ポートをオープンして 通信の準備をする
317 int serial_connect(char *device_name)
318 {
319 #if !defined(__MINGW32__)
320  g_device_port = open(device_name, O_RDWR);
321 
322  if (g_device_port < 0)
323  {
324  yprintf(OUTPUT_LV_ERROR, "Error: Can't open serial port.\n");
325  return 0;
326  }
327 
328  tcgetattr(g_device_port, &g_oldtio);
329 
331 #else
332  // Windows用
333  // DCB dcb;
334  COMMTIMEOUTS cto;
335 
336  // ファイルハンドラの作成
337  g_hdevices = CreateFile(device_name, GENERIC_WRITE | GENERIC_READ, 0, 0, OPEN_EXISTING, FILE_ATTRIBUTE_NORMAL, 0);
338  if (g_hdevices == INVALID_HANDLE_VALUE)
339  {
340  return 0;
341  }
342  // シリアルポートの状態操作
343  GetCommState(g_hdevices, &g_olddcb); // シリアルポートの状態を取得
345 
346  // シリアルポートのタイムアウト状態操作
347  GetCommTimeouts(g_hdevices, &cto); // タイムアウトの設定状態を取得
348  GetCommTimeouts(g_hdevices, &g_oldcto); // タイムアウトの設定状態を取得
349  cto.ReadIntervalTimeout = 0;
350  cto.ReadTotalTimeoutMultiplier = 0;
351  cto.ReadTotalTimeoutConstant = 1000;
352  cto.WriteTotalTimeoutMultiplier = 0;
353  cto.WriteTotalTimeoutConstant = 1000;
354  SetCommTimeouts(g_hdevices, &cto); // タイムアウトの状態を設定
355 #endif // !defined(__MINGW32__)
356  return 1;
357 }
358 
359 // ポートを閉じる
360 int serial_close(void)
361 {
362 #if !defined(__MINGW32__)
363  // Unix用
364  // 設定を元に戻す
365  if (g_device_port != 0)
366  {
367  tcsetattr(g_device_port, TCSANOW, &g_oldtio);
368  close(g_device_port);
369  g_device_port = 0;
370  }
371 #else
372  // Windows用
373  if (g_hdevices != NULL)
374  {
375  SetCommState(g_hdevices, &g_olddcb); // シリアルポートの状態を設定
376  SetCommTimeouts(g_hdevices, &g_oldcto); // タイムアウトの状態を設定
377  CloseHandle(g_hdevices);
378  g_hdevices = NULL;
379  }
380 #endif // !defined(__MINGW32__)
381 
382  return 1;
383 }
384 
385 void serial_flush_in(void)
386 {
387 #if !defined(__MINGW32__)
388  // Unix用
389  tcflush(g_device_port, TCIFLUSH);
390 #else
391  // Windows用
392  char buf[4096];
393 
394  DWORD len;
395  DWORD ret;
396  COMSTAT state;
397 
398  while (1)
399  {
400  ClearCommError(g_hdevices, &ret, &state);
401  len = state.cbInQue;
402 
403  if (len > 0)
404  {
405  if (len > 4000)
406  len = 4000;
407  if (!ReadFile(g_hdevices, buf, len, &len, NULL))
408  {
409  return;
410  }
411  break;
412  }
413  else if (len == 0)
414  break;
415  yp_usleep(5000);
416  }
417 #endif // !defined(__MINGW32__)
418 }
419 
421 {
422 #if !defined(__MINGW32__)
423  // Unix用
424  tcflush(g_device_port, TCOFLUSH);
425 #else
426 // Windows用
427 #endif // !defined(__MINGW32__)
428 }
429 
430 // シリアルポートからの受信処理
431 int serial_recieve(int (*serial_event)(char *, int, double, void *), void *data)
432 {
433  char buf[4096];
434  double receive_time;
435  int retval;
436 
437  while (1)
438  {
439 #if !defined(__MINGW32__)
440  // Unix用
441  fd_set rfds;
442  struct timeval tv;
443  size_t len;
444 
445  tv.tv_sec = 0;
446  tv.tv_usec = 200000;
447  FD_ZERO(&rfds);
448  FD_SET(g_device_port, &rfds);
449 
450  retval = select(g_device_port + 1, &rfds, NULL, NULL, &tv);
451  if (retval < 0)
452  {
453  int errnum;
454  errnum = errno;
455  yprintf(OUTPUT_LV_DEBUG, "Error: Select in serial_recieve failed. (%s)\n", strerror(errnum));
456  return -1;
457  }
458  else if (retval == 0)
459  {
460  yprintf(OUTPUT_LV_DEBUG, "Error: Select timed out\n");
461  return -1;
462  }
463  receive_time = get_time();
464 
465  len = read(g_device_port, buf, 4000);
466  if (len < 0)
467  {
468  int errnum;
469  errnum = errno;
470  yprintf(OUTPUT_LV_DEBUG, "Error: Read in serial_recieve failed. (%s)\n", strerror(errnum));
471  return -1;
472  }
473  else if (len == 0)
474  {
475  yprintf(OUTPUT_LV_DEBUG, "Error: Read timed out\n");
476  return -1;
477  }
478 #else
479  // Windows用
480  DWORD len;
481  DWORD ret;
482  COMSTAT state;
483  int timeout_count;
484 
485  timeout_count = 0;
486  while (1)
487  {
488  if (!ClearCommError(g_hdevices, &ret, &state))
489  return -1;
490  if (ret)
491  return -1;
492  len = state.cbInQue;
493  if (len > 4000)
494  len = 4000;
495  if (len > 0)
496  break;
497  yp_usleep(5000);
498  timeout_count++;
499  if (timeout_count > 500 / 5)
500  return -1;
501  }
502  receive_time = get_time();
503  if (!ReadFile(g_hdevices, buf, len, &len, NULL))
504  {
505  return -1;
506  }
507  buf[len] = 0;
508 #endif // !defined(__MINGW32__)
509  buf[len] = 0;
510 
511  if (len > 0)
512  {
513  retval = serial_event(buf, len, receive_time, data);
514  if (retval < 0)
515  return retval;
516  }
517  }
518 }
519 
520 int encode_write(char *data, int len)
521 {
522  unsigned char buf[128];
523  int encode_len, ret;
524 
525  buf[0] = COMMUNICATION_START_BYTE;
526  encode_len = encode((unsigned char *)data, len, buf + 1, 126);
527  buf[encode_len + 1] = COMMUNICATION_END_BYTE;
528 
529  ret = serial_write((char *)buf, encode_len + 2);
530  if (ret <= 0)
531  {
532  return -1;
533  }
535 
536  return 0;
537 }
538 
539 int serial_write(char *buf, int len)
540 {
541 #if !defined(__MINGW32__)
542  // Unix用
543  int ret;
544 #else
545  // Windows用
546  DWORD ret;
547 #endif // !defined(__MINGW32__)
548 
549  do
550  {
551 #if !defined(__MINGW32__)
552  // Unix用
553  ret = write(g_device_port, buf, len);
554 #else
555  // Windows用
556  buf[len] = 0;
557  WriteFile(g_hdevices, buf, len, (LPDWORD)&ret, 0);
558 #endif // !defined(__MINGW32__)
559  // printf("SEND: %s - %d(%d)\n",buf,len,ret);fflush(stdout);
560  if (ret <= 0 && len > 0)
561  {
562  return -1;
563  }
564  len -= ret;
565  buf += ret;
566  } while (len > 0);
567 
568 #ifdef __APPLE__
569  yp_usleep(100);
570 #endif // __APPLE__
571  return 1;
572 }
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:420
int encode_write(char *data, int len)
Definition: serial.c:520
int serial_close(void)
Definition: serial.c:360
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:539
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:431
void yprintf(ParamOutputLv level, const char *format,...)
Definition: yprintf.c:32
void serial_flush_in(void)
Definition: serial.c:385
int state(YPSpur_state id)
Definition: param.c:64
int g_device_port
Definition: serial.c:56
struct termios g_oldtio
Definition: serial.c:57
int serial_connect(char *device_name)
Definition: serial.c:317
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 Sat May 11 2019 02:08:24