rs_comm.cpp
Go to the documentation of this file.
1 // =============================================================================
2 // RS232C 用モジュール
3 //
4 // Filename: rs_comm.c
5 //
6 // =============================================================================
7 // Ver 1.0.0 2012/11/01
8 // =============================================================================
9 
10 //シリアル通信用
11 #include <sys/ioctl.h>
12 #include <fcntl.h>
13 #include <termios.h>
14 #include <string.h>
15 #include <unistd.h>
16 #include <stdio.h>
17 #include <leptrino/rs_comm.h>
18 
19 #define MAX_BUFF 10
20 #define MAX_LENGTH 255
21 
22 #define STS_IDLE 0
23 #define STS_WAIT_STX 1
24 #define STS_DATA 2
25 #define STS_WAIT_ETX 3
26 #define STS_WAIT_BCC 4
27 
28 static int Comm_RcvF = 0; //受信データ有フラグ
29 static int p_rd = 0, p_wr = 0; //受信リングバッファ読出し、書込みポインタ
30 static int fd = 0; //
31 static int rcv_n = 0; //受信文字数
32 
33 static UCHAR delim; //受信データデリミタ
34 static UCHAR rcv_buff[MAX_BUFF][MAX_LENGTH]; //受信リングバッファ
35 static UCHAR stmp[MAX_LENGTH]; //
36 
37 struct termios tio; //ポート設定構造体
38 
39 // ----------------------------------------------------------------------------------
40 // デバイスオープン
41 // ----------------------------------------------------------------------------------
42 // 引数 : dev .. シリアルポート
43 // 戻り値 : 正常時:0 エラー時:-1
44 // ----------------------------------------------------------------------------------
45 int Comm_Open(const char * dev)
46 {
47  //既にオープンしているときは一度閉じる
48  if (fd != 0)
49  Comm_Close();
50  //ポートオープン
51  fd = open(dev, O_RDWR | O_NDELAY | O_NOCTTY);
52  if (fd < 0)
53  return NG;
54  //デリミタ
55  delim = 0;
56 
57  return OK;
58 }
59 
60 // ----------------------------------------------------------------------------------
61 // デバイスクローズ
62 // ----------------------------------------------------------------------------------
63 // 引数 : non
64 // 戻り値 : non
65 // ----------------------------------------------------------------------------------
66 void Comm_Close()
67 {
68  if (fd > 0)
69  {
70  close(fd);
71  }
72  fd = 0;
73 
74  return;
75 }
76 
77 // ----------------------------------------------------------------------------------
78 // ポート設定
79 // ----------------------------------------------------------------------------------
80 // 引数 : boud .. ボーレート 9600 19200 ....
81 // : parity .. パリティー
82 // : bitlen .. ビット長
83 // : rts .. RTS制御
84 // : dtr .. DTR制御
85 // 戻り値 : non
86 // ----------------------------------------------------------------------------------
87 void Comm_Setup(long baud, int parity, int bitlen, int rts, int dtr, char code)
88 {
89  long brate;
90  long cflg;
91 
92  switch (baud)
93  {
94  case 2400:
95  brate = B2400;
96  break;
97  case 4800:
98  brate = B4800;
99  break;
100  case 9600:
101  brate = B9600;
102  break;
103  case 19200:
104  brate = B19200;
105  break;
106  case 38400:
107  brate = B38400;
108  break;
109  case 57600:
110  brate = B57600;
111  break;
112  case 115200:
113  brate = B115200;
114  break;
115  case 230400:
116  brate = B230400;
117  break;
118  case 460800:
119  brate = B460800;
120  break;
121  default:
122  brate = B9600;
123  break;
124  }
125  //パリティ
126  switch (parity)
127  {
128  case PAR_NON:
129  cflg = 0;
130  break;
131  case PAR_ODD:
132  cflg = PARENB | PARODD;
133  break;
134  default:
135  cflg = PARENB;
136  break;
137  }
138  //データ長
139  switch (bitlen)
140  {
141  case 7:
142  cflg |= CS7;
143  break;
144  default:
145  cflg |= CS8;
146  break;
147  }
148  //DTR
149  switch (dtr)
150  {
151  case 1:
152  cflg &= ~CLOCAL;
153  break;
154  default:
155  cflg |= CLOCAL;
156  break;
157  }
158  //RTS CTS
159  switch (rts)
160  {
161  case 0:
162  cflg &= ~CRTSCTS;
163  break;
164  default:
165  cflg |= CRTSCTS;
166  break;
167  }
168 
169  //ポート設定フラグ
170  tio.c_cflag = cflg | CREAD;
171  tio.c_lflag = 0;
172  tio.c_iflag = 0;
173  tio.c_oflag = 0;
174  tio.c_cc[VTIME] = 0;
175  tio.c_cc[VMIN] = 0;
176 
177  cfsetspeed(&tio, brate);
178  tcflush(fd, TCIFLUSH); //バッファの消去
179  tcsetattr(fd, TCSANOW, &tio); //属性の設定
180 
181  delim = code; //デリミタコード
182  return;
183 }
184 
185 // ----------------------------------------------------------------------------------
186 // 文字列送信
187 // ----------------------------------------------------------------------------------
188 // 引数 : buff .. 文字列バッファ
189 // : l .. 送信文字数
190 // 戻り値 : 1:OK -1:NG
191 // ----------------------------------------------------------------------------------
192 int Comm_SendData(UCHAR *buff, int l)
193 {
194  if (fd <= 0)
195  return -1;
196 
197  int count = write(fd, buff, l);
198  if(count != l)
199  return NG;
200 
201  return OK;
202 }
203 
204 // ----------------------------------------------------------------------------------
205 // 受信データ取得
206 // ----------------------------------------------------------------------------------
207 // 引数 : buff .. 文字列バッファ
208 // 戻り値 : 受信文字数
209 // ----------------------------------------------------------------------------------
211 {
212  int l = rcv_buff[p_rd][0];
213 
214  if (p_wr == p_rd)
215  return 0;
216 
217  memcpy(buff, &rcv_buff[p_rd][0], l);
218  p_rd++;
219  if (p_rd >= MAX_BUFF)
220  p_rd = 0;
221 
222  l = strlen((char*)buff);
223 
224  return l;
225 }
226 
227 // ----------------------------------------------------------------------------------
228 // 受信有無確認
229 // ----------------------------------------------------------------------------------
230 // 引数 : non
231 // 戻り値 : 0:なし 0以外:あり
232 // ----------------------------------------------------------------------------------
234 {
235  return p_wr - p_rd;
236 }
237 
238 // ----------------------------------------------------------------------------------
239 // 受信監視スレッド
240 // ----------------------------------------------------------------------------------
241 // 引数 : pParam ..
242 // 戻り値 : non
243 // ----------------------------------------------------------------------------------
244 unsigned char rbuff[MAX_LENGTH];
245 unsigned char ucBCC;
246 void Comm_Rcv(void)
247 {
248  int rt = 0;
249  unsigned char ch;
250  static int RcvSts = 0;
251 
252  while (1)
253  {
254  rt = read(fd, rbuff, 1);
255  //受信データあり
256  if (rt > 0)
257  {
258  rbuff[rt] = 0;
259  ch = rbuff[0];
260 
261  switch (RcvSts)
262  {
263  case STS_IDLE:
264  ucBCC = 0; /* BCC */
265  rcv_n = 0;
266  if (ch == CHR_DLE)
267  RcvSts = STS_WAIT_STX;
268  break;
269  case STS_WAIT_STX:
270  if (ch == CHR_STX)
271  { /* STXがあれば次はデータ */
272  RcvSts = STS_DATA;
273  }
274  else
275  { /* STXでなければ元に戻る */
276  RcvSts = STS_IDLE;
277  }
278  break;
279  case STS_DATA:
280  if (ch == CHR_DLE)
281  { /* DLEがあれば次はETX */
282  RcvSts = STS_WAIT_ETX;
283  }
284  else
285  { /* 受信データ保存 */
286  stmp[rcv_n] = ch;
287  ucBCC ^= ch; /* BCC */
288  rcv_n++;
289  }
290  break;
291  case STS_WAIT_ETX:
292  if (ch == CHR_DLE)
293  { /* DLEならばデータである */
294  stmp[rcv_n] = ch;
295  ucBCC ^= ch; /* BCC */
296  rcv_n++;
297  RcvSts = STS_DATA;
298  }
299  else if (ch == CHR_ETX)
300  { /* ETXなら次はBCC */
301  RcvSts = STS_WAIT_BCC;
302  ucBCC ^= ch; /* BCC */
303  }
304  else if (ch == CHR_STX)
305  { /* STXならリセット */
306  ucBCC = 0; /* BCC */
307  rcv_n = 0;
308  RcvSts = STS_DATA;
309  }
310  else
311  {
312  ucBCC = 0; /* BCC */
313  rcv_n = 0;
314  RcvSts = STS_IDLE;
315  }
316  break;
317  case STS_WAIT_BCC:
318  if (ucBCC == ch)
319  { /* BCC一致 */
320  //作成された文字列をリングバッファへコピー
321  memcpy(rcv_buff[p_wr], stmp, rcv_n);
322  p_wr++;
323  if (p_wr >= MAX_BUFF)
324  p_wr = 0;
325  }
326  /* 次のデータ受信に備える */
327  ucBCC = 0; /* BCC */
328  rcv_n = 0;
329  RcvSts = STS_IDLE;
330  break;
331  default:
332  RcvSts = STS_IDLE;
333  break;
334  }
335 
336  if (rcv_n > MAX_LENGTH)
337  {
338  ucBCC = 0;
339  rcv_n = 0;
340  RcvSts = STS_IDLE;
341  }
342  }
343  else
344  {
345  break;
346  }
347 
348  //受信完了フラグ
349  if (p_rd != p_wr)
350  {
351  Comm_RcvF = 1;
352  }
353  else
354  {
355  Comm_RcvF = 0;
356  }
357  }
358 }
#define PAR_NON
Definition: rs_comm.h:17
static UCHAR stmp[MAX_LENGTH]
Definition: rs_comm.cpp:35
#define STS_WAIT_STX
Definition: rs_comm.cpp:23
#define PAR_ODD
Definition: rs_comm.h:18
static int Comm_RcvF
Definition: rs_comm.cpp:28
#define STS_DATA
Definition: rs_comm.cpp:24
#define CHR_ETX
Definition: rs_comm.h:25
#define STS_IDLE
Definition: rs_comm.cpp:22
int Comm_CheckRcv()
Definition: rs_comm.cpp:233
unsigned char rbuff[MAX_LENGTH]
Definition: rs_comm.cpp:244
unsigned char UCHAR
Definition: pCommon.h:11
static int p_rd
Definition: rs_comm.cpp:29
struct termios tio
Definition: rs_comm.cpp:37
void Comm_Rcv(void)
Definition: rs_comm.cpp:246
static UCHAR rcv_buff[MAX_BUFF][MAX_LENGTH]
Definition: rs_comm.cpp:34
static UCHAR delim
Definition: rs_comm.cpp:33
#define NG
Definition: pCommon.h:22
#define STS_WAIT_ETX
Definition: rs_comm.cpp:25
#define MAX_LENGTH
Definition: rs_comm.cpp:20
void Comm_Close()
Definition: rs_comm.cpp:66
unsigned char ucBCC
Definition: rs_comm.cpp:245
#define CHR_DLE
Definition: rs_comm.h:31
#define OK
Definition: pCommon.h:21
int Comm_SendData(UCHAR *buff, int l)
Definition: rs_comm.cpp:192
#define STS_WAIT_BCC
Definition: rs_comm.cpp:26
int Comm_Open(const char *dev)
Definition: rs_comm.cpp:45
#define CHR_STX
Definition: rs_comm.h:24
static int rcv_n
Definition: rs_comm.cpp:31
static int fd
Definition: rs_comm.cpp:30
int Comm_GetRcvData(UCHAR *buff)
Definition: rs_comm.cpp:210
void Comm_Setup(long baud, int parity, int bitlen, int rts, int dtr, char code)
Definition: rs_comm.cpp:87
static int p_wr
Definition: rs_comm.cpp:29
#define MAX_BUFF
Definition: rs_comm.cpp:19


leptrino_force_torque
Author(s):
autogenerated on Sun Oct 6 2019 03:45:38