modbus-rtu.c
Go to the documentation of this file.
1 /*
2  * Copyright © 2001-2011 Stéphane Raimbault <stephane.raimbault@gmail.com>
3  *
4  * This library is free software; you can redistribute it and/or
5  * modify it under the terms of the GNU Lesser General Public
6  * License as published by the Free Software Foundation; either
7  * version 2.1 of the License, or (at your option) any later version.
8  *
9  * This library is distributed in the hope that it will be useful,
10  * but WITHOUT ANY WARRANTY; without even the implied warranty of
11  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
12  * Lesser General Public License for more details.
13  *
14  * You should have received a copy of the GNU Lesser General Public
15  * License along with this library; if not, write to the Free Software
16  * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA
17  */
18 
19 #include <stdio.h>
20 #include <stdlib.h>
21 #include <errno.h>
22 #include <fcntl.h>
23 #include <string.h>
24 #ifndef _MSC_VER
25 #include <unistd.h>
26 #endif
27 #include <assert.h>
28 
30 
31 #include "libmodbus/modbus-rtu.h"
33 
34 #if HAVE_DECL_TIOCSRS485
35 #include <sys/ioctl.h>
36 #include <linux/serial.h>
37 #endif
38 
39 /* Table of CRC values for high-order byte */
40 static const uint8_t table_crc_hi[] = {
41  0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0,
42  0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41,
43  0x00, 0xC1, 0x81, 0x40, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0,
44  0x80, 0x41, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40,
45  0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1,
46  0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41,
47  0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1,
48  0x81, 0x40, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41,
49  0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0,
50  0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x00, 0xC1, 0x81, 0x40,
51  0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1,
52  0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40,
53  0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0,
54  0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x00, 0xC1, 0x81, 0x40,
55  0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0,
56  0x80, 0x41, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40,
57  0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0,
58  0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41,
59  0x00, 0xC1, 0x81, 0x40, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0,
60  0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41,
61  0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0,
62  0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x00, 0xC1, 0x81, 0x40,
63  0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1,
64  0x81, 0x40, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41,
65  0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0,
66  0x80, 0x41, 0x00, 0xC1, 0x81, 0x40
67 };
68 
69 /* Table of CRC values for low-order byte */
70 static const uint8_t table_crc_lo[] = {
71  0x00, 0xC0, 0xC1, 0x01, 0xC3, 0x03, 0x02, 0xC2, 0xC6, 0x06,
72  0x07, 0xC7, 0x05, 0xC5, 0xC4, 0x04, 0xCC, 0x0C, 0x0D, 0xCD,
73  0x0F, 0xCF, 0xCE, 0x0E, 0x0A, 0xCA, 0xCB, 0x0B, 0xC9, 0x09,
74  0x08, 0xC8, 0xD8, 0x18, 0x19, 0xD9, 0x1B, 0xDB, 0xDA, 0x1A,
75  0x1E, 0xDE, 0xDF, 0x1F, 0xDD, 0x1D, 0x1C, 0xDC, 0x14, 0xD4,
76  0xD5, 0x15, 0xD7, 0x17, 0x16, 0xD6, 0xD2, 0x12, 0x13, 0xD3,
77  0x11, 0xD1, 0xD0, 0x10, 0xF0, 0x30, 0x31, 0xF1, 0x33, 0xF3,
78  0xF2, 0x32, 0x36, 0xF6, 0xF7, 0x37, 0xF5, 0x35, 0x34, 0xF4,
79  0x3C, 0xFC, 0xFD, 0x3D, 0xFF, 0x3F, 0x3E, 0xFE, 0xFA, 0x3A,
80  0x3B, 0xFB, 0x39, 0xF9, 0xF8, 0x38, 0x28, 0xE8, 0xE9, 0x29,
81  0xEB, 0x2B, 0x2A, 0xEA, 0xEE, 0x2E, 0x2F, 0xEF, 0x2D, 0xED,
82  0xEC, 0x2C, 0xE4, 0x24, 0x25, 0xE5, 0x27, 0xE7, 0xE6, 0x26,
83  0x22, 0xE2, 0xE3, 0x23, 0xE1, 0x21, 0x20, 0xE0, 0xA0, 0x60,
84  0x61, 0xA1, 0x63, 0xA3, 0xA2, 0x62, 0x66, 0xA6, 0xA7, 0x67,
85  0xA5, 0x65, 0x64, 0xA4, 0x6C, 0xAC, 0xAD, 0x6D, 0xAF, 0x6F,
86  0x6E, 0xAE, 0xAA, 0x6A, 0x6B, 0xAB, 0x69, 0xA9, 0xA8, 0x68,
87  0x78, 0xB8, 0xB9, 0x79, 0xBB, 0x7B, 0x7A, 0xBA, 0xBE, 0x7E,
88  0x7F, 0xBF, 0x7D, 0xBD, 0xBC, 0x7C, 0xB4, 0x74, 0x75, 0xB5,
89  0x77, 0xB7, 0xB6, 0x76, 0x72, 0xB2, 0xB3, 0x73, 0xB1, 0x71,
90  0x70, 0xB0, 0x50, 0x90, 0x91, 0x51, 0x93, 0x53, 0x52, 0x92,
91  0x96, 0x56, 0x57, 0x97, 0x55, 0x95, 0x94, 0x54, 0x9C, 0x5C,
92  0x5D, 0x9D, 0x5F, 0x9F, 0x9E, 0x5E, 0x5A, 0x9A, 0x9B, 0x5B,
93  0x99, 0x59, 0x58, 0x98, 0x88, 0x48, 0x49, 0x89, 0x4B, 0x8B,
94  0x8A, 0x4A, 0x4E, 0x8E, 0x8F, 0x4F, 0x8D, 0x4D, 0x4C, 0x8C,
95  0x44, 0x84, 0x85, 0x45, 0x87, 0x47, 0x46, 0x86, 0x82, 0x42,
96  0x43, 0x83, 0x41, 0x81, 0x80, 0x40
97 };
98 
99 /* Define the slave ID of the remote device to talk in master mode or set the
100  * internal slave ID in slave mode */
101 static int _modbus_set_slave(modbus_t *ctx, int slave)
102 {
103  /* Broadcast address is 0 (MODBUS_BROADCAST_ADDRESS) */
104  if (slave >= 0 && slave <= 247) {
105  ctx->slave = slave;
106  } else {
107  errno = EINVAL;
108  return -1;
109  }
110 
111  return 0;
112 }
113 
114 /* Builds a RTU request header */
115 static int _modbus_rtu_build_request_basis(modbus_t *ctx, int function,
116  int addr, int nb,
117  uint8_t *req)
118 {
119  assert(ctx->slave != -1);
120  req[0] = ctx->slave;
121  req[1] = function;
122  req[2] = addr >> 8;
123  req[3] = addr & 0x00ff;
124  req[4] = nb >> 8;
125  req[5] = nb & 0x00ff;
126 
128 }
129 
130 /* Builds a RTU response header */
131 static int _modbus_rtu_build_response_basis(sft_t *sft, uint8_t *rsp)
132 {
133  /* In this case, the slave is certainly valid because a check is already
134  * done in _modbus_rtu_listen */
135  rsp[0] = sft->slave;
136  rsp[1] = sft->function;
137 
139 }
140 
141 static uint16_t crc16(uint8_t *buffer, uint16_t buffer_length)
142 {
143  uint8_t crc_hi = 0xFF; /* high CRC byte initialized */
144  uint8_t crc_lo = 0xFF; /* low CRC byte initialized */
145  unsigned int i; /* will index into CRC lookup */
146 
147  /* pass through message buffer */
148  while (buffer_length--) {
149  i = crc_hi ^ *buffer++; /* calculate the CRC */
150  crc_hi = crc_lo ^ table_crc_hi[i];
151  crc_lo = table_crc_lo[i];
152  }
153 
154  return (crc_hi << 8 | crc_lo);
155 }
156 
157 int _modbus_rtu_prepare_response_tid(const uint8_t *req, int *req_length)
158 {
159  (*req_length) -= _MODBUS_RTU_CHECKSUM_LENGTH;
160  /* No TID */
161  return 0;
162 }
163 
164 int _modbus_rtu_send_msg_pre(uint8_t *req, int req_length)
165 {
166  uint16_t crc = crc16(req, req_length);
167  req[req_length++] = crc >> 8;
168  req[req_length++] = crc & 0x00FF;
169 
170  return req_length;
171 }
172 
173 #if defined(_WIN32)
174 
175 /* This simple implementation is sort of a substitute of the select() call,
176  * working this way: the win32_ser_select() call tries to read some data from
177  * the serial port, setting the timeout as the select() call would. Data read is
178  * stored into the receive buffer, that is then consumed by the win32_ser_read()
179  * call. So win32_ser_select() does both the event waiting and the reading,
180  * while win32_ser_read() only consumes the receive buffer.
181  */
182 
183 static void win32_ser_init(struct win32_ser *ws) {
184  /* Clear everything */
185  memset(ws, 0x00, sizeof(struct win32_ser));
186 
187  /* Set file handle to invalid */
188  ws->fd = INVALID_HANDLE_VALUE;
189 }
190 
191 /* FIXME Try to remove length_to_read -> max_len argument, only used by win32 */
192 static int win32_ser_select(struct win32_ser *ws, int max_len,
193  struct timeval *tv) {
194  COMMTIMEOUTS comm_to;
195  unsigned int msec = 0;
196 
197  /* Check if some data still in the buffer to be consumed */
198  if (ws->n_bytes > 0) {
199  return 1;
200  }
201 
202  /* Setup timeouts like select() would do.
203  FIXME Please someone on Windows can look at this?
204  Does it possible to use WaitCommEvent?
205  When tv is NULL, MAXDWORD isn't infinite!
206  */
207  if (tv == NULL) {
208  msec = MAXDWORD;
209  } else {
210  msec = tv->tv_sec * 1000 + tv->tv_usec / 1000;
211  if (msec < 1)
212  msec = 1;
213  }
214 
215  comm_to.ReadIntervalTimeout = msec;
216  comm_to.ReadTotalTimeoutMultiplier = 0;
217  comm_to.ReadTotalTimeoutConstant = msec;
218  comm_to.WriteTotalTimeoutMultiplier = 0;
219  comm_to.WriteTotalTimeoutConstant = 1000;
220  SetCommTimeouts(ws->fd, &comm_to);
221 
222  /* Read some bytes */
223  if ((max_len > PY_BUF_SIZE) || (max_len < 0)) {
224  max_len = PY_BUF_SIZE;
225  }
226 
227  if (ReadFile(ws->fd, &ws->buf, max_len, &ws->n_bytes, NULL)) {
228  /* Check if some bytes available */
229  if (ws->n_bytes > 0) {
230  /* Some bytes read */
231  return 1;
232  } else {
233  /* Just timed out */
234  return 0;
235  }
236  } else {
237  /* Some kind of error */
238  return -1;
239  }
240 }
241 
242 static int win32_ser_read(struct win32_ser *ws, uint8_t *p_msg,
243  unsigned int max_len) {
244  unsigned int n = ws->n_bytes;
245 
246  if (max_len < n) {
247  n = max_len;
248  }
249 
250  if (n > 0) {
251  memcpy(p_msg, ws->buf, n);
252  }
253 
254  ws->n_bytes -= n;
255 
256  return n;
257 }
258 #endif
259 
260 ssize_t _modbus_rtu_send(modbus_t *ctx, const uint8_t *req, int req_length)
261 {
262 #if defined(_WIN32)
263  modbus_rtu_t *ctx_rtu = ctx->backend_data;
264  DWORD n_bytes = 0;
265  return (WriteFile(ctx_rtu->w_ser.fd, req, req_length, &n_bytes, NULL)) ? n_bytes : -1;
266 #else
267  return write(ctx->s, req, req_length);
268 #endif
269 }
270 
271 ssize_t _modbus_rtu_recv(modbus_t *ctx, uint8_t *rsp, int rsp_length)
272 {
273 #if defined(_WIN32)
274  return win32_ser_read(&((modbus_rtu_t *)ctx->backend_data)->w_ser, rsp, rsp_length);
275 #else
276  return read(ctx->s, rsp, rsp_length);
277 #endif
278 }
279 
281 
282 /* The check_crc16 function shall return the message length if the CRC is
283  valid. Otherwise it shall return -1 and set errno to EMBADCRC. */
285  const int msg_length)
286 {
287  uint16_t crc_calculated;
288  uint16_t crc_received;
289 
290  crc_calculated = crc16(msg, msg_length - 2);
291  crc_received = (msg[msg_length - 2] << 8) | msg[msg_length - 1];
292 
293  /* Check CRC of msg */
294  if (crc_calculated == crc_received) {
295  return msg_length;
296  } else {
297  if (ctx->debug) {
298  fprintf(stderr, "ERROR CRC received %0X != CRC calculated %0X\n",
299  crc_received, crc_calculated);
300  }
302  _modbus_rtu_flush(ctx);
303  }
304  errno = EMBBADCRC;
305  return -1;
306  }
307 }
308 
309 /* Sets up a serial port for RTU communications */
311 {
312 #if defined(_WIN32)
313  DCB dcb;
314 #else
315  struct termios tios;
316  speed_t speed;
317 #endif
318  modbus_rtu_t *ctx_rtu = ctx->backend_data;
319 
320  if (ctx->debug) {
321  printf("Opening %s at %d bauds (%c, %d, %d)\n",
322  ctx_rtu->device, ctx_rtu->baud, ctx_rtu->parity,
323  ctx_rtu->data_bit, ctx_rtu->stop_bit);
324  }
325 
326 #if defined(_WIN32)
327  /* Some references here:
328  * http://msdn.microsoft.com/en-us/library/aa450602.aspx
329  */
330  win32_ser_init(&ctx_rtu->w_ser);
331 
332  /* ctx_rtu->device should contain a string like "COMxx:" xx being a decimal
333  * number */
334  ctx_rtu->w_ser.fd = CreateFileA(ctx_rtu->device,
335  GENERIC_READ | GENERIC_WRITE,
336  0,
337  NULL,
338  OPEN_EXISTING,
339  0,
340  NULL);
341 
342  /* Error checking */
343  if (ctx_rtu->w_ser.fd == INVALID_HANDLE_VALUE) {
344  fprintf(stderr, "ERROR Can't open the device %s (%s)\n",
345  ctx_rtu->device, strerror(errno));
346  return -1;
347  }
348 
349  /* Save params */
350  ctx_rtu->old_dcb.DCBlength = sizeof(DCB);
351  if (!GetCommState(ctx_rtu->w_ser.fd, &ctx_rtu->old_dcb)) {
352  fprintf(stderr, "ERROR Error getting configuration (LastError %d)\n",
353  (int)GetLastError());
354  CloseHandle(ctx_rtu->w_ser.fd);
355  ctx_rtu->w_ser.fd = INVALID_HANDLE_VALUE;
356  return -1;
357  }
358 
359  /* Build new configuration (starting from current settings) */
360  dcb = ctx_rtu->old_dcb;
361 
362  /* Speed setting */
363  switch (ctx_rtu->baud) {
364  case 110:
365  dcb.BaudRate = CBR_110;
366  break;
367  case 300:
368  dcb.BaudRate = CBR_300;
369  break;
370  case 600:
371  dcb.BaudRate = CBR_600;
372  break;
373  case 1200:
374  dcb.BaudRate = CBR_1200;
375  break;
376  case 2400:
377  dcb.BaudRate = CBR_2400;
378  break;
379  case 4800:
380  dcb.BaudRate = CBR_4800;
381  break;
382  case 9600:
383  dcb.BaudRate = CBR_9600;
384  break;
385  case 19200:
386  dcb.BaudRate = CBR_19200;
387  break;
388  case 38400:
389  dcb.BaudRate = CBR_38400;
390  break;
391  case 57600:
392  dcb.BaudRate = CBR_57600;
393  break;
394  case 115200:
395  dcb.BaudRate = CBR_115200;
396  break;
397  case 1152000:
398  dcb.BaudRate = CBR_1152000;
399  break;
400  case 1250000:
401  dcb.BaudRate = CBR_1250000;
402  break;
403  default:
404  dcb.BaudRate = CBR_9600;
405  printf("WARNING Unknown baud rate %d for %s (B9600 used)\n",
406  ctx_rtu->baud, ctx_rtu->device);
407  }
408 
409  /* Data bits */
410  switch (ctx_rtu->data_bit) {
411  case 5:
412  dcb.ByteSize = 5;
413  break;
414  case 6:
415  dcb.ByteSize = 6;
416  break;
417  case 7:
418  dcb.ByteSize = 7;
419  break;
420  case 8:
421  default:
422  dcb.ByteSize = 8;
423  break;
424  }
425 
426  /* Stop bits */
427  if (ctx_rtu->stop_bit == 1)
428  dcb.StopBits = ONESTOPBIT;
429  else /* 2 */
430  dcb.StopBits = TWOSTOPBITS;
431 
432  /* Parity */
433  if (ctx_rtu->parity == 'N') {
434  dcb.Parity = NOPARITY;
435  dcb.fParity = FALSE;
436  } else if (ctx_rtu->parity == 'E') {
437  dcb.Parity = EVENPARITY;
438  dcb.fParity = TRUE;
439  } else {
440  /* odd */
441  dcb.Parity = ODDPARITY;
442  dcb.fParity = TRUE;
443  }
444 
445  /* Hardware handshaking left as default settings retrieved */
446 
447  /* No software handshaking */
448  dcb.fTXContinueOnXoff = TRUE;
449  dcb.fOutX = FALSE;
450  dcb.fInX = FALSE;
451 
452  /* Binary mode (it's the only supported on Windows anyway) */
453  dcb.fBinary = TRUE;
454 
455  /* Don't want errors to be blocking */
456  dcb.fAbortOnError = FALSE;
457 
458  /* TODO: any other flags!? */
459 
460  /* Setup port */
461  if (!SetCommState(ctx_rtu->w_ser.fd, &dcb)) {
462  fprintf(stderr, "ERROR Error setting new configuration (LastError %d)\n",
463  (int)GetLastError());
464  CloseHandle(ctx_rtu->w_ser.fd);
465  ctx_rtu->w_ser.fd = INVALID_HANDLE_VALUE;
466  return -1;
467  }
468 #else
469  /* The O_NOCTTY flag tells UNIX that this program doesn't want
470  to be the "controlling terminal" for that port. If you
471  don't specify this then any input (such as keyboard abort
472  signals and so forth) will affect your process
473 
474  Timeouts are ignored in canonical input mode or when the
475  NDELAY option is set on the file via open or fcntl */
476  ctx->s = open(ctx_rtu->device, O_RDWR | O_NOCTTY | O_NDELAY | O_EXCL);
477  if (ctx->s == -1) {
478  fprintf(stderr, "ERROR Can't open the device %s (%s)\n",
479  ctx_rtu->device, strerror(errno));
480  return -1;
481  }
482 
483  /* Save */
484  tcgetattr(ctx->s, &(ctx_rtu->old_tios));
485 
486  memset(&tios, 0, sizeof(struct termios));
487 
488  /* C_ISPEED Input baud (new interface)
489  C_OSPEED Output baud (new interface)
490  */
491  struct serial_struct ss;
492  switch (ctx_rtu->baud) {
493  case 110:
494  speed = B110;
495  break;
496  case 300:
497  speed = B300;
498  break;
499  case 600:
500  speed = B600;
501  break;
502  case 1200:
503  speed = B1200;
504  break;
505  case 2400:
506  speed = B2400;
507  break;
508  case 4800:
509  speed = B4800;
510  break;
511  case 9600:
512  speed = B9600;
513  break;
514  case 19200:
515  speed = B19200;
516  break;
517  case 38400:
518  speed = B38400;
519  break;
520  case 57600:
521  speed = B57600;
522  break;
523  case 115200:
524  speed = B115200;
525  break;
526  case 1152000:
527  speed = B1152000;
528  break;
529  case 1250000:
530  ioctl(ctx->s, TIOCGSERIAL, &ss);
531  ss.flags = (ss.flags & ~ASYNC_SPD_MASK) | ASYNC_SPD_CUST;
532  ss.custom_divisor = (ss.baud_base + (ctx_rtu->baud / 2)) / ctx_rtu->baud;
533  int closestSpeed = ss.baud_base / ss.custom_divisor;
534 
535  if (closestSpeed < ctx_rtu->baud * 98 / 100 || closestSpeed > ctx_rtu->baud * 102 / 100) {
536  fprintf(stderr, "Cannot set serial port speed to. Closest possible is %i\n", closestSpeed);
537  }
538 
539  ioctl(ctx->s, TIOCSSERIAL, &ss);
540  speed = B38400;
541  cfsetispeed(&tios, B38400);
542  cfsetospeed(&tios, B38400);
543  break;
544  default:
545  speed = B9600;
546  if (ctx->debug) {
547  fprintf(stderr,
548  "WARNING Unknown baud rate %d for %s (B9600 used)\n",
549  ctx_rtu->baud, ctx_rtu->device);
550  }
551  }
552  fprintf(stderr, "Setting speed to: %i \n", speed);
553  /* Set the baud rate */
554  if ((cfsetispeed(&tios, speed) < 0) ||
555  (cfsetospeed(&tios, speed) < 0)) {
556  close(ctx->s);
557  ctx->s = -1;
558  return -1;
559  }
560 
561  /* C_CFLAG Control options
562  CLOCAL Local line - do not change "owner" of port
563  CREAD Enable receiver
564  */
565  tios.c_cflag |= (CREAD | CLOCAL);
566  /* CSIZE, HUPCL, CRTSCTS (hardware flow control) */
567 
568  /* Set data bits (5, 6, 7, 8 bits)
569  CSIZE Bit mask for data bits
570  */
571  tios.c_cflag &= ~CSIZE;
572  switch (ctx_rtu->data_bit) {
573  case 5:
574  tios.c_cflag |= CS5;
575  break;
576  case 6:
577  tios.c_cflag |= CS6;
578  break;
579  case 7:
580  tios.c_cflag |= CS7;
581  break;
582  case 8:
583  default:
584  tios.c_cflag |= CS8;
585  break;
586  }
587 
588  /* Stop bit (1 or 2) */
589  if (ctx_rtu->stop_bit == 1)
590  tios.c_cflag &=~ CSTOPB;
591  else /* 2 */
592  tios.c_cflag |= CSTOPB;
593 
594  /* PARENB Enable parity bit
595  PARODD Use odd parity instead of even */
596  if (ctx_rtu->parity == 'N') {
597  /* None */
598  tios.c_cflag &=~ PARENB;
599  } else if (ctx_rtu->parity == 'E') {
600  /* Even */
601  tios.c_cflag |= PARENB;
602  tios.c_cflag &=~ PARODD;
603  } else {
604  /* Odd */
605  tios.c_cflag |= PARENB;
606  tios.c_cflag |= PARODD;
607  }
608 
609  /* Read the man page of termios if you need more information. */
610 
611  /* This field isn't used on POSIX systems
612  tios.c_line = 0;
613  */
614 
615  /* C_LFLAG Line options
616 
617  ISIG Enable SIGINTR, SIGSUSP, SIGDSUSP, and SIGQUIT signals
618  ICANON Enable canonical input (else raw)
619  XCASE Map uppercase \lowercase (obsolete)
620  ECHO Enable echoing of input characters
621  ECHOE Echo erase character as BS-SP-BS
622  ECHOK Echo NL after kill character
623  ECHONL Echo NL
624  NOFLSH Disable flushing of input buffers after
625  interrupt or quit characters
626  IEXTEN Enable extended functions
627  ECHOCTL Echo control characters as ^char and delete as ~?
628  ECHOPRT Echo erased character as character erased
629  ECHOKE BS-SP-BS entire line on line kill
630  FLUSHO Output being flushed
631  PENDIN Retype pending input at next read or input char
632  TOSTOP Send SIGTTOU for background output
633 
634  Canonical input is line-oriented. Input characters are put
635  into a buffer which can be edited interactively by the user
636  until a CR (carriage return) or LF (line feed) character is
637  received.
638 
639  Raw input is unprocessed. Input characters are passed
640  through exactly as they are received, when they are
641  received. Generally you'll deselect the ICANON, ECHO,
642  ECHOE, and ISIG options when using raw input
643  */
644 
645  /* Raw input */
646  tios.c_lflag &= ~(ICANON | ECHO | ECHOE | ISIG);
647 
648  /* C_IFLAG Input options
649 
650  Constant Description
651  INPCK Enable parity check
652  IGNPAR Ignore parity errors
653  PARMRK Mark parity errors
654  ISTRIP Strip parity bits
655  IXON Enable software flow control (outgoing)
656  IXOFF Enable software flow control (incoming)
657  IXANY Allow any character to start flow again
658  IGNBRK Ignore break condition
659  BRKINT Send a SIGINT when a break condition is detected
660  INLCR Map NL to CR
661  IGNCR Ignore CR
662  ICRNL Map CR to NL
663  IUCLC Map uppercase to lowercase
664  IMAXBEL Echo BEL on input line too long
665  */
666  if (ctx_rtu->parity == 'N') {
667  /* None */
668  tios.c_iflag &= ~INPCK;
669  } else {
670  tios.c_iflag |= INPCK;
671  }
672 
673  /* Software flow control is disabled */
674  tios.c_iflag &= ~(IXON | IXOFF | IXANY);
675 
676  /* C_OFLAG Output options
677  OPOST Postprocess output (not set = raw output)
678  ONLCR Map NL to CR-NL
679 
680  ONCLR ant others needs OPOST to be enabled
681  */
682 
683  /* Raw ouput */
684  tios.c_oflag &=~ OPOST;
685 
686  /* C_CC Control characters
687  VMIN Minimum number of characters to read
688  VTIME Time to wait for data (tenths of seconds)
689 
690  UNIX serial interface drivers provide the ability to
691  specify character and packet timeouts. Two elements of the
692  c_cc array are used for timeouts: VMIN and VTIME. Timeouts
693  are ignored in canonical input mode or when the NDELAY
694  option is set on the file via open or fcntl.
695 
696  VMIN specifies the minimum number of characters to read. If
697  it is set to 0, then the VTIME value specifies the time to
698  wait for every character read. Note that this does not mean
699  that a read call for N bytes will wait for N characters to
700  come in. Rather, the timeout will apply to the first
701  character and the read call will return the number of
702  characters immediately available (up to the number you
703  request).
704 
705  If VMIN is non-zero, VTIME specifies the time to wait for
706  the first character read. If a character is read within the
707  time given, any read will block (wait) until all VMIN
708  characters are read. That is, once the first character is
709  read, the serial interface driver expects to receive an
710  entire packet of characters (VMIN bytes total). If no
711  character is read within the time allowed, then the call to
712  read returns 0. This method allows you to tell the serial
713  driver you need exactly N bytes and any read call will
714  return 0 or N bytes. However, the timeout only applies to
715  the first character read, so if for some reason the driver
716  misses one character inside the N byte packet then the read
717  call could block forever waiting for additional input
718  characters.
719 
720  VTIME specifies the amount of time to wait for incoming
721  characters in tenths of seconds. If VTIME is set to 0 (the
722  default), reads will block (wait) indefinitely unless the
723  NDELAY option is set on the port with open or fcntl.
724  */
725  /* Unused because we use open with the NDELAY option */
726  tios.c_cc[VMIN] = 0;
727  tios.c_cc[VTIME] = 0;
728 
729  if (tcsetattr(ctx->s, TCSANOW, &tios) < 0) {
730  close(ctx->s);
731  ctx->s = -1;
732  return -1;
733  }
734 #endif
735 
736 #if HAVE_DECL_TIOCSRS485
737  fprintf(stderr, "HAVE_DECL_TIOCSRS485\n");
738  /* The RS232 mode has been set by default */
739  ctx_rtu->serial_mode = MODBUS_RTU_RS232;
740 #endif
741 
742  return 0;
743 }
744 
746 {
747  if (ctx == NULL) {
748  errno = EINVAL;
749  return -1;
750  }
751 
753 #if HAVE_DECL_TIOCSRS485
754  modbus_rtu_t *ctx_rtu = ctx->backend_data;
755  struct serial_rs485 rs485conf;
756  if (mode == MODBUS_RTU_RS485) {
757  // Get
758  if (ioctl(ctx->s, TIOCGRS485, &rs485conf) < 0) {
759  fprintf(stderr, "Getting serial mode failed\n");
760  return -1;
761  }
762  // Set
763  rs485conf.flags |= SER_RS485_ENABLED;
764  if (ioctl(ctx->s, TIOCSRS485, &rs485conf) < 0) {
765  fprintf(stderr, "Setting serial mode to rs485 failed\n");
766  return -1;
767  }
768 
769  ctx_rtu->serial_mode = MODBUS_RTU_RS485;
770  return 0;
771  } else if (mode == MODBUS_RTU_RS232) {
772  if (ioctl(ctx->s, TIOCSRS485, &rs485conf) < 0) {
773  return -1;
774  }
775  fprintf(stderr, "Setting to serial mode RTU RS232\n");
776  ctx_rtu->serial_mode = MODBUS_RTU_RS232;
777  return 0;
778  }
779 #else
780  if (ctx->debug) {
781  fprintf(stderr, "This function isn't supported on your platform\n");
782  }
783  errno = ENOTSUP;
784  return -1;
785 #endif
786  }
787  fprintf(stderr, "wrong backed\n");
788  /* Wrong backend and invalid mode specified */
789  errno = EINVAL;
790  return -1;
791 }
792 
795 #if HAVE_DECL_TIOCSRS485
796  modbus_rtu_t *ctx_rtu = ctx->backend_data;
797  return ctx_rtu->serial_mode;
798 #else
799  if (ctx->debug) {
800  fprintf(stderr, "This function isn't supported on your platform\n");
801  }
802  errno = ENOTSUP;
803  return -1;
804 #endif
805  } else {
806  errno = EINVAL;
807  return -1;
808  }
809 }
810 
812 {
813  /* Closes the file descriptor in RTU mode */
814  modbus_rtu_t *ctx_rtu = ctx->backend_data;
815 
816 #if defined(_WIN32)
817  /* Revert settings */
818  if (!SetCommState(ctx_rtu->w_ser.fd, &ctx_rtu->old_dcb))
819  fprintf(stderr, "ERROR Couldn't revert to configuration (LastError %d)\n",
820  (int)GetLastError());
821 
822  if (!CloseHandle(ctx_rtu->w_ser.fd))
823  fprintf(stderr, "ERROR Error while closing handle (LastError %d)\n",
824  (int)GetLastError());
825 #else
826  tcsetattr(ctx->s, TCSANOW, &(ctx_rtu->old_tios));
827  close(ctx->s);
828 #endif
829 }
830 
832 {
833 #if defined(_WIN32)
834  modbus_rtu_t *ctx_rtu = ctx->backend_data;
835  ctx_rtu->w_ser.n_bytes = 0;
836  return (FlushFileBuffers(ctx_rtu->w_ser.fd) == FALSE);
837 #else
838  return tcflush(ctx->s, TCIOFLUSH);
839 #endif
840 }
841 
842 int _modbus_rtu_select(modbus_t *ctx, fd_set *rfds,
843  struct timeval *tv, int length_to_read)
844 {
845  int s_rc;
846 #if defined(_WIN32)
847  s_rc = win32_ser_select(&(((modbus_rtu_t*)ctx->backend_data)->w_ser),
848  length_to_read, tv);
849  if (s_rc == 0) {
850  errno = ETIMEDOUT;
851  return -1;
852  }
853 
854  if (s_rc < 0) {
855  return -1;
856  }
857 #else
858  while ((s_rc = select(ctx->s+1, rfds, NULL, NULL, tv)) == -1) {
859  if (errno == EINTR) {
860  if (ctx->debug) {
861  fprintf(stderr, "A non blocked signal was caught\n");
862  }
863  /* Necessary after an error */
864  FD_ZERO(rfds);
865  FD_SET(ctx->s, rfds);
866  } else {
867  return -1;
868  }
869  }
870 
871  if (s_rc == 0) {
872  /* Timeout */
873  errno = ETIMEDOUT;
874  return -1;
875  }
876 #endif
877 
878  return s_rc;
879 }
880 
882 {
883  /* Filter on the Modbus unit identifier (slave) in RTU mode */
884  if (slave != ctx->slave && slave != MODBUS_BROADCAST_ADDRESS) {
885  /* Ignores the request (not for me) */
886  if (ctx->debug) {
887  printf("Request for slave %d ignored (not %d)\n",
888  slave, ctx->slave);
889  }
890  return 1;
891  } else {
892  return 0;
893  }
894 }
895 
909  NULL,
915 };
916 
917 modbus_t* modbus_new_rtu(const char *device,
918  int baud, char parity, int data_bit,
919  int stop_bit)
920 {
921  modbus_t *ctx;
922  modbus_rtu_t *ctx_rtu;
923  size_t dest_size;
924  size_t ret_size;
925 
926  ctx = (modbus_t *) malloc(sizeof(modbus_t));
927  _modbus_init_common(ctx);
928 
930  ctx->backend_data = (modbus_rtu_t *) malloc(sizeof(modbus_rtu_t));
931  ctx_rtu = (modbus_rtu_t *)ctx->backend_data;
932 
933  dest_size = sizeof(ctx_rtu->device);
934  ret_size = strlcpy(ctx_rtu->device, device, dest_size);
935  if (ret_size == 0) {
936  fprintf(stderr, "The device string is empty\n");
937  modbus_free(ctx);
938  errno = EINVAL;
939  return NULL;
940  }
941 
942  if (ret_size >= dest_size) {
943  fprintf(stderr, "The device string has been truncated\n");
944  modbus_free(ctx);
945  errno = EINVAL;
946  return NULL;
947  }
948 
949  ctx_rtu->baud = baud;
950  if (parity == 'N' || parity == 'E' || parity == 'O') {
951  ctx_rtu->parity = parity;
952  } else {
953  modbus_free(ctx);
954  errno = EINVAL;
955  return NULL;
956  }
957  ctx_rtu->data_bit = data_bit;
958  ctx_rtu->stop_bit = stop_bit;
959 
960  return ctx;
961 }
static int _modbus_rtu_build_response_basis(sft_t *sft, uint8_t *rsp)
Definition: modbus-rtu.c:131
#define _MODBUS_RTU_HEADER_LENGTH
static int _modbus_set_slave(modbus_t *ctx, int slave)
Definition: modbus-rtu.c:101
#define FALSE
Definition: modbus.h:48
size_t strlcpy(char *dest, const char *src, size_t dest_size)
Definition: modbus.c:1651
#define MODBUS_RTU_MAX_ADU_LENGTH
Definition: modbus-rtu.h:29
int _modbus_rtu_send_msg_pre(uint8_t *req, int req_length)
Definition: modbus-rtu.c:164
static const uint8_t table_crc_hi[]
Definition: modbus-rtu.c:40
ssize_t _modbus_rtu_recv(modbus_t *ctx, uint8_t *rsp, int rsp_length)
Definition: modbus-rtu.c:271
int _modbus_rtu_filter_request(modbus_t *ctx, int slave)
Definition: modbus-rtu.c:881
void modbus_free(modbus_t *ctx)
Definition: modbus.c:1528
const modbus_backend_t * backend
#define _MODBUS_RTU_CHECKSUM_LENGTH
int _modbus_rtu_check_integrity(modbus_t *ctx, uint8_t *msg, const int msg_length)
Definition: modbus-rtu.c:284
static int _modbus_rtu_build_request_basis(modbus_t *ctx, int function, int addr, int nb, uint8_t *req)
Definition: modbus-rtu.c:115
void * backend_data
ssize_t _modbus_rtu_send(modbus_t *ctx, const uint8_t *req, int req_length)
Definition: modbus-rtu.c:260
struct termios old_tios
#define _MODBUS_RTU_PRESET_RSP_LENGTH
#define MODBUS_BROADCAST_ADDRESS
Definition: modbus.h:63
int slave
#define MODBUS_RTU_RS485
Definition: modbus-rtu.h:35
#define _MODBUS_RTU_PRESET_REQ_LENGTH
static const uint8_t table_crc_lo[]
Definition: modbus-rtu.c:70
void _modbus_init_common(modbus_t *ctx)
Definition: modbus.c:1448
int error_recovery
int _modbus_rtu_prepare_response_tid(const uint8_t *req, int *req_length)
Definition: modbus-rtu.c:157
int function
int _modbus_rtu_flush(modbus_t *)
Definition: modbus-rtu.c:831
modbus_t * ctx
#define MODBUS_RTU_RS232
Definition: modbus-rtu.h:34
void _modbus_rtu_close(modbus_t *ctx)
Definition: modbus-rtu.c:811
int modbus_rtu_get_serial_mode(modbus_t *ctx)
Definition: modbus-rtu.c:793
#define TRUE
Definition: modbus.h:52
int _modbus_rtu_select(modbus_t *ctx, fd_set *rfds, struct timeval *tv, int length_to_read)
Definition: modbus-rtu.c:842
#define EMBBADCRC
Definition: modbus.h:115
int modbus_rtu_set_serial_mode(modbus_t *ctx, int mode)
Definition: modbus-rtu.c:745
static int _modbus_rtu_connect(modbus_t *ctx)
Definition: modbus-rtu.c:310
unsigned int backend_type
const modbus_backend_t _modbus_rtu_backend
Definition: modbus-rtu.c:896
static uint16_t crc16(uint8_t *buffer, uint16_t buffer_length)
Definition: modbus-rtu.c:141
modbus_t * modbus_new_rtu(const char *device, int baud, char parity, int data_bit, int stop_bit)
Definition: modbus-rtu.c:917


libmodbus
Author(s):
autogenerated on Sat Nov 21 2020 03:17:32