modbus.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  * This library implements the Modbus protocol.
20  * http://libmodbus.org/
21  */
22 
23 #include <stdio.h>
24 #include <string.h>
25 #include <stdlib.h>
26 #include <errno.h>
27 #include <limits.h>
28 #include <time.h>
29 
30 #include <libmodbus/config.h>
31 
32 #include "libmodbus/modbus.h"
34 
35 /* Internal use */
36 #define MSG_LENGTH_UNDEFINED -1
37 
38 /* Exported version */
42 
43 /* Max between RTU and TCP max adu length (so TCP) */
44 #define MAX_MESSAGE_LENGTH 260
45 
46 /* 3 steps are used to parse the query */
47 typedef enum {
51 } _step_t;
52 
53 const char *modbus_strerror(int errnum) {
54  switch (errnum) {
55  case EMBXILFUN:
56  return "Illegal function";
57  case EMBXILADD:
58  return "Illegal data address";
59  case EMBXILVAL:
60  return "Illegal data value";
61  case EMBXSFAIL:
62  return "Slave device or server failure";
63  case EMBXACK:
64  return "Acknowledge";
65  case EMBXSBUSY:
66  return "Slave device or server is busy";
67  case EMBXNACK:
68  return "Negative acknowledge";
69  case EMBXMEMPAR:
70  return "Memory parity error";
71  case EMBXGPATH:
72  return "Gateway path unavailable";
73  case EMBXGTAR:
74  return "Target device failed to respond";
75  case EMBBADCRC:
76  return "Invalid CRC";
77  case EMBBADDATA:
78  return "Invalid data";
79  case EMBBADEXC:
80  return "Invalid exception code";
81  case EMBMDATA:
82  return "Too many data";
83  default:
84  return strerror(errnum);
85  }
86 }
87 
88 void _error_print(modbus_t *ctx, const char *context)
89 {
90  if (ctx->debug) {
91  fprintf(stderr, "ERROR %s", modbus_strerror(errno));
92  if (context != NULL) {
93  fprintf(stderr, ": %s\n", context);
94  } else {
95  fprintf(stderr, "\n");
96  }
97  }
98 }
99 
101 {
102 #ifdef _WIN32
103  /* usleep doesn't exist on Windows */
104  Sleep((ctx->response_timeout.tv_sec * 1000) +
105  (ctx->response_timeout.tv_usec / 1000));
106 #else
107  /* usleep source code */
108  struct timespec request, remaining;
109  request.tv_sec = ctx->response_timeout.tv_sec;
110  request.tv_nsec = ((long int)ctx->response_timeout.tv_usec % 1000000)
111  * 1000;
112  while (nanosleep(&request, &remaining) == -1 && errno == EINTR)
113  request = remaining;
114 #endif
115  return modbus_flush(ctx);
116 }
117 
119 {
120  int rc = ctx->backend->flush(ctx);
121  if (rc != -1 && ctx->debug) {
122  printf("%d bytes flushed\n", rc);
123  }
124  return rc;
125 }
126 
127 /* Computes the length of the expected response */
128 static unsigned int compute_response_length_from_request(modbus_t *ctx, uint8_t *req)
129 {
130  int length;
131  const int offset = ctx->backend->header_length;
132 
133  switch (req[offset]) {
134  case _FC_READ_COILS:
136  /* Header + nb values (code from write_bits) */
137  int nb = (req[offset + 3] << 8) | req[offset + 4];
138  length = 2 + (nb / 8) + ((nb % 8) ? 1 : 0);
139  }
140  break;
144  /* Header + 2 * nb values */
145  length = 2 + 2 * (req[offset + 3] << 8 | req[offset + 4]);
146  break;
148  length = 3;
149  break;
150  case _FC_REPORT_SLAVE_ID:
151  /* The response is device specific (the header provides the
152  length) */
153  return MSG_LENGTH_UNDEFINED;
154  default:
155  length = 5;
156  }
157 
158  return offset + length + ctx->backend->checksum_length;
159 }
160 
161 /* Sends a request/response */
162 static int send_msg(modbus_t *ctx, uint8_t *msg, int msg_length)
163 {
164  int rc;
165  int i;
166 
167  msg_length = ctx->backend->send_msg_pre(msg, msg_length);
168 
169  if (ctx->debug) {
170  for (i = 0; i < msg_length; i++)
171  printf("[%.2X]", msg[i]);
172  printf("\n");
173  }
174 
175  /* In recovery mode, the write command will be issued until to be
176  successful! Disabled by default. */
177  do {
178  rc = ctx->backend->send(ctx, msg, msg_length);
179  if (rc == -1) {
180  _error_print(ctx, NULL);
182  int saved_errno = errno;
183 
184  if ((errno == EBADF || errno == ECONNRESET || errno == EPIPE)) {
185  modbus_close(ctx);
186  modbus_connect(ctx);
187  } else {
188  _sleep_and_flush(ctx);
189  }
190  errno = saved_errno;
191  }
192  }
193  } while ((ctx->error_recovery & MODBUS_ERROR_RECOVERY_LINK) &&
194  rc == -1);
195 
196  if (rc > 0 && rc != msg_length) {
197  errno = EMBBADDATA;
198  return -1;
199  }
200 
201  return rc;
202 }
203 
204 int modbus_send_raw_request(modbus_t *ctx, uint8_t *raw_req, int raw_req_length)
205 {
206  sft_t sft;
207  uint8_t req[MAX_MESSAGE_LENGTH];
208  int req_length;
209 
210  if (raw_req_length < 2) {
211  /* The raw request must contain function and slave at least */
212  errno = EINVAL;
213  return -1;
214  }
215 
216  sft.slave = raw_req[0];
217  sft.function = raw_req[1];
218  /* The t_id is left to zero */
219  sft.t_id = 0;
220  /* This response function only set the header so it's convenient here */
221  req_length = ctx->backend->build_response_basis(&sft, req);
222 
223  if (raw_req_length > 2) {
224  /* Copy data after function code */
225  memcpy(req + req_length, raw_req + 2, raw_req_length - 2);
226  req_length += raw_req_length - 2;
227  }
228 
229  return send_msg(ctx, req, req_length);
230 }
231 
232 /*
233  ---------- Request Indication ----------
234  | Client | ---------------------->| Server |
235  ---------- Confirmation Response ----------
236 */
237 
238 typedef enum {
239  /* Request message on the server side */
241  /* Request message on the client side */
243 } msg_type_t;
244 
245 /* Computes the length to read after the function received */
246 static uint8_t compute_meta_length_after_function(int function,
247  msg_type_t msg_type)
248 {
249  int length;
250 
251  if (msg_type == MSG_INDICATION) {
252  if (function <= _FC_WRITE_SINGLE_REGISTER) {
253  length = 4;
254  } else if (function == _FC_WRITE_MULTIPLE_COILS ||
255  function == _FC_WRITE_MULTIPLE_REGISTERS) {
256  length = 5;
257  } else if (function == _FC_WRITE_AND_READ_REGISTERS) {
258  length = 9;
259  } else {
260  /* _FC_READ_EXCEPTION_STATUS, _FC_REPORT_SLAVE_ID */
261  length = 0;
262  }
263  } else {
264  /* MSG_CONFIRMATION */
265  switch (function) {
270  length = 4;
271  break;
272  default:
273  length = 1;
274  }
275  }
276 
277  return length;
278 }
279 
280 /* Computes the length to read after the meta information (address, count, etc) */
281 static int compute_data_length_after_meta(modbus_t *ctx, uint8_t *msg,
282  msg_type_t msg_type)
283 {
284  int function = msg[ctx->backend->header_length];
285  int length;
286 
287  if (msg_type == MSG_INDICATION) {
288  switch (function) {
291  length = msg[ctx->backend->header_length + 5];
292  break;
294  length = msg[ctx->backend->header_length + 9];
295  break;
296  default:
297  length = 0;
298  }
299  } else {
300  /* MSG_CONFIRMATION */
301  if (function <= _FC_READ_INPUT_REGISTERS ||
302  function == _FC_REPORT_SLAVE_ID ||
303  function == _FC_WRITE_AND_READ_REGISTERS) {
304  length = msg[ctx->backend->header_length + 1];
305  } else {
306  length = 0;
307  }
308  }
309 
310  length += ctx->backend->checksum_length;
311 
312  return length;
313 }
314 
315 
316 /* Waits a response from a modbus server or a request from a modbus client.
317  This function blocks if there is no replies (3 timeouts).
318 
319  The function shall return the number of received characters and the received
320  message in an array of uint8_t if successful. Otherwise it shall return -1
321  and errno is set to one of the values defined below:
322  - ECONNRESET
323  - EMBBADDATA
324  - EMBUNKEXC
325  - ETIMEDOUT
326  - read() or recv() error codes
327 */
328 
329 static int receive_msg(modbus_t *ctx, uint8_t *msg, msg_type_t msg_type)
330 {
331  int rc;
332  fd_set rfds;
333  struct timeval tv;
334  struct timeval *p_tv;
335  int length_to_read;
336  int msg_length = 0;
337  _step_t step;
338 
339  if (ctx->debug) {
340  if (msg_type == MSG_INDICATION) {
341  printf("Waiting for a indication...\n");
342  } else {
343  printf("Waiting for a confirmation...\n");
344  }
345  }
346 
347  /* Add a file descriptor to the set */
348  FD_ZERO(&rfds);
349  FD_SET(ctx->s, &rfds);
350 
351  /* We need to analyse the message step by step. At the first step, we want
352  * to reach the function code because all packets contain this
353  * information. */
354  step = _STEP_FUNCTION;
355  length_to_read = ctx->backend->header_length + 1;
356 
357  if (msg_type == MSG_INDICATION) {
358  /* Wait for a message, we don't know when the message will be
359  * received */
360  p_tv = NULL;
361  } else {
362  tv.tv_sec = ctx->response_timeout.tv_sec;
363  tv.tv_usec = ctx->response_timeout.tv_usec;
364  p_tv = &tv;
365  }
366 
367  while (length_to_read != 0) {
368  rc = ctx->backend->select(ctx, &rfds, p_tv, length_to_read);
369  if (rc == -1) {
370  _error_print(ctx, "select");
372  int saved_errno = errno;
373 
374  if (errno == ETIMEDOUT) {
375  _sleep_and_flush(ctx);
376  } else if (errno == EBADF) {
377  modbus_close(ctx);
378  modbus_connect(ctx);
379  }
380  errno = saved_errno;
381  }
382  return -1;
383  }
384 
385  rc = ctx->backend->recv(ctx, msg + msg_length, length_to_read);
386  if (rc == 0) {
387  errno = ECONNRESET;
388  rc = -1;
389  }
390 
391  if (rc == -1) {
392  _error_print(ctx, "read");
394  (errno == ECONNRESET || errno == ECONNREFUSED ||
395  errno == EBADF)) {
396  int saved_errno = errno;
397  modbus_close(ctx);
398  modbus_connect(ctx);
399  /* Could be removed by previous calls */
400  errno = saved_errno;
401  }
402  return -1;
403  }
404 
405  /* Display the hex code of each character received */
406  if (ctx->debug) {
407  int i;
408  for (i=0; i < rc; i++)
409  printf("<%.2X>", msg[msg_length + i]);
410  }
411 
412  /* Sums bytes received */
413  msg_length += rc;
414  /* Computes remaining bytes */
415  length_to_read -= rc;
416 
417  if (length_to_read == 0) {
418  switch (step) {
419  case _STEP_FUNCTION:
420  /* Function code position */
421  length_to_read = compute_meta_length_after_function(
422  msg[ctx->backend->header_length],
423  msg_type);
424  if (length_to_read != 0) {
425  step = _STEP_META;
426  break;
427  } /* else switches straight to the next step */
428  case _STEP_META:
429  length_to_read = compute_data_length_after_meta(
430  ctx, msg, msg_type);
431  if ((msg_length + length_to_read) > ctx->backend->max_adu_length) {
432  errno = EMBBADDATA;
433  _error_print(ctx, "too many data");
434  return -1;
435  }
436  step = _STEP_DATA;
437  break;
438  default:
439  break;
440  }
441  }
442 
443  if (length_to_read > 0 && ctx->byte_timeout.tv_sec != -1) {
444  /* If there is no character in the buffer, the allowed timeout
445  interval between two consecutive bytes is defined by
446  byte_timeout */
447  tv.tv_sec = ctx->byte_timeout.tv_sec;
448  tv.tv_usec = ctx->byte_timeout.tv_usec;
449  p_tv = &tv;
450  }
451  }
452 
453  if (ctx->debug)
454  printf("\n");
455 
456  return ctx->backend->check_integrity(ctx, msg, msg_length);
457 }
458 
459 /* Receive the request from a modbus master */
460 int modbus_receive(modbus_t *ctx, uint8_t *req)
461 {
462  return receive_msg(ctx, req, MSG_INDICATION);
463 }
464 
465 /* Receives the confirmation.
466 
467  The function shall store the read response in rsp and return the number of
468  values (bits or words). Otherwise, its shall return -1 and errno is set.
469 
470  The function doesn't check the confirmation is the expected response to the
471  initial request.
472 */
474 {
475  return receive_msg(ctx, rsp, MSG_CONFIRMATION);
476 }
477 
478 static int check_confirmation(modbus_t *ctx, uint8_t *req,
479  uint8_t *rsp, int rsp_length)
480 {
481  int rc;
482  int rsp_length_computed;
483  const int offset = ctx->backend->header_length;
484 
485  if (ctx->backend->pre_check_confirmation) {
486  rc = ctx->backend->pre_check_confirmation(ctx, req, rsp, rsp_length);
487  if (rc == -1) {
489  _sleep_and_flush(ctx);
490  }
491  return -1;
492  }
493  }
494 
495  rsp_length_computed = compute_response_length_from_request(ctx, req);
496 
497  /* Check length */
498  if (rsp_length == rsp_length_computed ||
499  rsp_length_computed == MSG_LENGTH_UNDEFINED) {
500  int req_nb_value;
501  int rsp_nb_value;
502  const int function = rsp[offset];
503 
504  /* Check function code */
505  if (function != req[offset]) {
506  if (ctx->debug) {
507  fprintf(stderr,
508  "Received function not corresponding to the request (%d != %d)\n",
509  function, req[offset]);
510  }
512  _sleep_and_flush(ctx);
513  }
514  errno = EMBBADDATA;
515  return -1;
516  }
517 
518  /* Check the number of values is corresponding to the request */
519  switch (function) {
520  case _FC_READ_COILS:
522  /* Read functions, 8 values in a byte (nb
523  * of values in the request and byte count in
524  * the response. */
525  req_nb_value = (req[offset + 3] << 8) + req[offset + 4];
526  req_nb_value = (req_nb_value / 8) + ((req_nb_value % 8) ? 1 : 0);
527  rsp_nb_value = rsp[offset + 1];
528  break;
532  /* Read functions 1 value = 2 bytes */
533  req_nb_value = (req[offset + 3] << 8) + req[offset + 4];
534  rsp_nb_value = (rsp[offset + 1] / 2);
535  break;
538  /* N Write functions */
539  req_nb_value = (req[offset + 3] << 8) + req[offset + 4];
540  rsp_nb_value = (rsp[offset + 3] << 8) | rsp[offset + 4];
541  break;
542  case _FC_REPORT_SLAVE_ID:
543  /* Report slave ID (bytes received) */
544  req_nb_value = rsp_nb_value = rsp[offset + 1];
545  break;
546  default:
547  /* 1 Write functions & others */
548  req_nb_value = rsp_nb_value = 1;
549  }
550 
551  if (req_nb_value == rsp_nb_value) {
552  rc = rsp_nb_value;
553  } else {
554  if (ctx->debug) {
555  fprintf(stderr,
556  "Quantity not corresponding to the request (%d != %d)\n",
557  rsp_nb_value, req_nb_value);
558  }
559 
561  _sleep_and_flush(ctx);
562  }
563 
564  errno = EMBBADDATA;
565  rc = -1;
566  }
567  } else if (rsp_length == (offset + 2 + ctx->backend->checksum_length) &&
568  req[offset] == (rsp[offset] - 0x80)) {
569  /* EXCEPTION CODE RECEIVED */
570 
571  int exception_code = rsp[offset + 1];
572  if (exception_code < MODBUS_EXCEPTION_MAX) {
573  errno = MODBUS_ENOBASE + exception_code;
574  } else {
575  errno = EMBBADEXC;
576  }
577  _error_print(ctx, NULL);
578  rc = -1;
579  } else {
580  if (ctx->debug) {
581  fprintf(stderr,
582  "Message length not corresponding to the computed length (%d != %d)\n",
583  rsp_length, rsp_length_computed);
584  }
586  _sleep_and_flush(ctx);
587  }
588  errno = EMBBADDATA;
589  rc = -1;
590  }
591 
592  return rc;
593 }
594 
595 static int response_io_status(int address, int nb,
596  uint8_t *tab_io_status,
597  uint8_t *rsp, int offset)
598 {
599  int shift = 0;
600  int byte = 0;
601  int i;
602 
603  for (i = address; i < address+nb; i++) {
604  byte |= tab_io_status[i] << shift;
605  if (shift == 7) {
606  /* Byte is full */
607  rsp[offset++] = byte;
608  byte = shift = 0;
609  } else {
610  shift++;
611  }
612  }
613 
614  if (shift != 0)
615  rsp[offset++] = byte;
616 
617  return offset;
618 }
619 
620 /* Build the exception response */
622  int exception_code, uint8_t *rsp)
623 {
624  int rsp_length;
625 
626  sft->function = sft->function + 0x80;
627  rsp_length = ctx->backend->build_response_basis(sft, rsp);
628 
629  /* Positive exception code */
630  rsp[rsp_length++] = exception_code;
631 
632  return rsp_length;
633 }
634 
635 /* Send a response to the received request.
636  Analyses the request and constructs a response.
637 
638  If an error occurs, this function construct the response
639  accordingly.
640 */
641 int modbus_reply(modbus_t *ctx, const uint8_t *req,
642  int req_length, modbus_mapping_t *mb_mapping)
643 {
644  int offset = ctx->backend->header_length;
645  int slave = req[offset - 1];
646  int function = req[offset];
647  uint16_t address = (req[offset + 1] << 8) + req[offset + 2];
648  uint8_t rsp[MAX_MESSAGE_LENGTH];
649  int rsp_length = 0;
650  sft_t sft;
651 
652  if (ctx->backend->filter_request(ctx, slave) == 1) {
653  /* Filtered */
654  return 0;
655  }
656 
657  sft.slave = slave;
658  sft.function = function;
659  sft.t_id = ctx->backend->prepare_response_tid(req, &req_length);
660 
661  switch (function) {
662  case _FC_READ_COILS: {
663  int nb = (req[offset + 3] << 8) + req[offset + 4];
664 
665  if (nb < 1 || MODBUS_MAX_READ_BITS < nb) {
666  if (ctx->debug) {
667  fprintf(stderr,
668  "Illegal nb of values %d in read_bits (max %d)\n",
670  }
671  rsp_length = response_exception(
672  ctx, &sft,
674  } else if ((address + nb) > mb_mapping->nb_bits) {
675  if (ctx->debug) {
676  fprintf(stderr, "Illegal data address %0X in read_bits\n",
677  address + nb);
678  }
679  rsp_length = response_exception(
680  ctx, &sft,
682  } else {
683  rsp_length = ctx->backend->build_response_basis(&sft, rsp);
684  rsp[rsp_length++] = (nb / 8) + ((nb % 8) ? 1 : 0);
685  rsp_length = response_io_status(address, nb,
686  mb_mapping->tab_bits,
687  rsp, rsp_length);
688  }
689  }
690  break;
692  /* Similar to coil status (but too many arguments to use a
693  * function) */
694  int nb = (req[offset + 3] << 8) + req[offset + 4];
695 
696  if (nb < 1 || MODBUS_MAX_READ_BITS < nb) {
697  if (ctx->debug) {
698  fprintf(stderr,
699  "Illegal nb of values %d in read_input_bits (max %d)\n",
701  }
702  rsp_length = response_exception(
703  ctx, &sft,
705  } else if ((address + nb) > mb_mapping->nb_input_bits) {
706  if (ctx->debug) {
707  fprintf(stderr, "Illegal data address %0X in read_input_bits\n",
708  address + nb);
709  }
710  rsp_length = response_exception(
711  ctx, &sft,
713  } else {
714  rsp_length = ctx->backend->build_response_basis(&sft, rsp);
715  rsp[rsp_length++] = (nb / 8) + ((nb % 8) ? 1 : 0);
716  rsp_length = response_io_status(address, nb,
717  mb_mapping->tab_input_bits,
718  rsp, rsp_length);
719  }
720  }
721  break;
723  int nb = (req[offset + 3] << 8) + req[offset + 4];
724 
725  if (nb < 1 || MODBUS_MAX_READ_REGISTERS < nb) {
726  if (ctx->debug) {
727  fprintf(stderr,
728  "Illegal nb of values %d in read_holding_registers (max %d)\n",
730  }
731  rsp_length = response_exception(
732  ctx, &sft,
734  } else if ((address + nb) > mb_mapping->nb_registers) {
735  if (ctx->debug) {
736  fprintf(stderr, "Illegal data address %0X in read_registers\n",
737  address + nb);
738  }
739  rsp_length = response_exception(
740  ctx, &sft,
742  } else {
743  int i;
744 
745  rsp_length = ctx->backend->build_response_basis(&sft, rsp);
746  rsp[rsp_length++] = nb << 1;
747  for (i = address; i < address + nb; i++) {
748  rsp[rsp_length++] = mb_mapping->tab_registers[i] >> 8;
749  rsp[rsp_length++] = mb_mapping->tab_registers[i] & 0xFF;
750  }
751  }
752  }
753  break;
755  /* Similar to holding registers (but too many arguments to use a
756  * function) */
757  int nb = (req[offset + 3] << 8) + req[offset + 4];
758 
759  if (nb < 1 || MODBUS_MAX_READ_REGISTERS < nb) {
760  if (ctx->debug) {
761  fprintf(stderr,
762  "Illegal number of values %d in read_input_registers (max %d)\n",
764  }
765  rsp_length = response_exception(
766  ctx, &sft,
768  } else if ((address + nb) > mb_mapping->nb_input_registers) {
769  if (ctx->debug) {
770  fprintf(stderr, "Illegal data address %0X in read_input_registers\n",
771  address + nb);
772  }
773  rsp_length = response_exception(
774  ctx, &sft,
776  } else {
777  int i;
778 
779  rsp_length = ctx->backend->build_response_basis(&sft, rsp);
780  rsp[rsp_length++] = nb << 1;
781  for (i = address; i < address + nb; i++) {
782  rsp[rsp_length++] = mb_mapping->tab_input_registers[i] >> 8;
783  rsp[rsp_length++] = mb_mapping->tab_input_registers[i] & 0xFF;
784  }
785  }
786  }
787  break;
789  if (address >= mb_mapping->nb_bits) {
790  if (ctx->debug) {
791  fprintf(stderr, "Illegal data address %0X in write_bit\n",
792  address);
793  }
794  rsp_length = response_exception(
795  ctx, &sft,
797  } else {
798  int data = (req[offset + 3] << 8) + req[offset + 4];
799 
800  if (data == 0xFF00 || data == 0x0) {
801  mb_mapping->tab_bits[address] = (data) ? ON : OFF;
802  memcpy(rsp, req, req_length);
803  rsp_length = req_length;
804  } else {
805  if (ctx->debug) {
806  fprintf(stderr,
807  "Illegal data value %0X in write_bit request at address %0X\n",
808  data, address);
809  }
810  rsp_length = response_exception(
811  ctx, &sft,
813  }
814  }
815  break;
817  if (address >= mb_mapping->nb_registers) {
818  if (ctx->debug) {
819  fprintf(stderr, "Illegal data address %0X in write_register\n",
820  address);
821  }
822  rsp_length = response_exception(
823  ctx, &sft,
825  } else {
826  int data = (req[offset + 3] << 8) + req[offset + 4];
827 
828  mb_mapping->tab_registers[address] = data;
829  memcpy(rsp, req, req_length);
830  rsp_length = req_length;
831  }
832  break;
834  int nb = (req[offset + 3] << 8) + req[offset + 4];
835 
836  if (nb < 1 || MODBUS_MAX_WRITE_BITS < nb) {
837  if (ctx->debug) {
838  fprintf(stderr,
839  "Illegal number of values %d in write_bits (max %d)\n",
841  }
842  rsp_length = response_exception(
843  ctx, &sft,
845  } else if ((address + nb) > mb_mapping->nb_bits) {
846  if (ctx->debug) {
847  fprintf(stderr, "Illegal data address %0X in write_bits\n",
848  address + nb);
849  }
850  rsp_length = response_exception(
851  ctx, &sft,
853  } else {
854  /* 6 = byte count */
855  modbus_set_bits_from_bytes(mb_mapping->tab_bits, address, nb, &req[offset + 6]);
856 
857  rsp_length = ctx->backend->build_response_basis(&sft, rsp);
858  /* 4 to copy the bit address (2) and the quantity of bits */
859  memcpy(rsp + rsp_length, req + rsp_length, 4);
860  rsp_length += 4;
861  }
862  }
863  break;
865  int nb = (req[offset + 3] << 8) + req[offset + 4];
866 
867  if (nb < 1 || MODBUS_MAX_WRITE_REGISTERS < nb) {
868  if (ctx->debug) {
869  fprintf(stderr,
870  "Illegal number of values %d in write_registers (max %d)\n",
872  }
873  rsp_length = response_exception(
874  ctx, &sft,
876  } else if ((address + nb) > mb_mapping->nb_registers) {
877  if (ctx->debug) {
878  fprintf(stderr, "Illegal data address %0X in write_registers\n",
879  address + nb);
880  }
881  rsp_length = response_exception(
882  ctx, &sft,
884  } else {
885  int i, j;
886  for (i = address, j = 6; i < address + nb; i++, j += 2) {
887  /* 6 and 7 = first value */
888  mb_mapping->tab_registers[i] =
889  (req[offset + j] << 8) + req[offset + j + 1];
890  }
891 
892  rsp_length = ctx->backend->build_response_basis(&sft, rsp);
893  /* 4 to copy the address (2) and the no. of registers */
894  memcpy(rsp + rsp_length, req + rsp_length, 4);
895  rsp_length += 4;
896  }
897  }
898  break;
899  case _FC_REPORT_SLAVE_ID: {
900  int str_len;
901  int byte_count_pos;
902 
903  rsp_length = ctx->backend->build_response_basis(&sft, rsp);
904  /* Skip byte count for now */
905  byte_count_pos = rsp_length++;
906  rsp[rsp_length++] = _REPORT_SLAVE_ID;
907  /* Run indicator status to ON */
908  rsp[rsp_length++] = 0xFF;
909  /* LMB + length of LIBMODBUS_VERSION_STRING */
910  str_len = 3 + strlen(LIBMODBUS_VERSION_STRING);
911  memcpy(rsp + rsp_length, "LMB" LIBMODBUS_VERSION_STRING, str_len);
912  rsp_length += str_len;
913  rsp[byte_count_pos] = rsp_length - byte_count_pos - 1;
914  }
915  break;
917  if (ctx->debug) {
918  fprintf(stderr, "FIXME Not implemented\n");
919  }
920  errno = ENOPROTOOPT;
921  return -1;
922  break;
923 
925  int nb = (req[offset + 3] << 8) + req[offset + 4];
926  uint16_t address_write = (req[offset + 5] << 8) + req[offset + 6];
927  int nb_write = (req[offset + 7] << 8) + req[offset + 8];
928  int nb_write_bytes = req[offset + 9];
929 
930  if (nb_write < 1 || MODBUS_MAX_RW_WRITE_REGISTERS < nb_write ||
931  nb < 1 || MODBUS_MAX_READ_REGISTERS < nb ||
932  nb_write_bytes != nb_write * 2) {
933  if (ctx->debug) {
934  fprintf(stderr,
935  "Illegal nb of values (W%d, R%d) in write_and_read_registers (max W%d, R%d)\n",
936  nb_write, nb,
938  }
939  rsp_length = response_exception(
940  ctx, &sft,
942  } else if ((address + nb) > mb_mapping->nb_registers ||
943  (address_write + nb_write) > mb_mapping->nb_registers) {
944  if (ctx->debug) {
945  fprintf(stderr,
946  "Illegal data read address %0X or write address %0X write_and_read_registers\n",
947  address + nb, address_write + nb_write);
948  }
949  rsp_length = response_exception(ctx, &sft,
951  } else {
952  int i, j;
953  rsp_length = ctx->backend->build_response_basis(&sft, rsp);
954  rsp[rsp_length++] = nb << 1;
955 
956  /* Write first.
957  10 and 11 are the offset of the first values to write */
958  for (i = address_write, j = 10; i < address_write + nb_write; i++, j += 2) {
959  mb_mapping->tab_registers[i] =
960  (req[offset + j] << 8) + req[offset + j + 1];
961  }
962 
963  /* and read the data for the response */
964  for (i = address; i < address + nb; i++) {
965  rsp[rsp_length++] = mb_mapping->tab_registers[i] >> 8;
966  rsp[rsp_length++] = mb_mapping->tab_registers[i] & 0xFF;
967  }
968  }
969  }
970  break;
971 
972  default:
973  rsp_length = response_exception(ctx, &sft,
975  rsp);
976  break;
977  }
978 
979  return send_msg(ctx, rsp, rsp_length);
980 }
981 
982 int modbus_reply_exception(modbus_t *ctx, const uint8_t *req,
983  unsigned int exception_code)
984 {
985  int offset = ctx->backend->header_length;
986  int slave = req[offset - 1];
987  int function = req[offset];
988  uint8_t rsp[MAX_MESSAGE_LENGTH];
989  int rsp_length;
990  int dummy_length = 99;
991  sft_t sft;
992 
993  if (ctx->backend->filter_request(ctx, slave) == 1) {
994  /* Filtered */
995  return 0;
996  }
997 
998  sft.slave = slave;
999  sft.function = function + 0x80;;
1000  sft.t_id = ctx->backend->prepare_response_tid(req, &dummy_length);
1001  rsp_length = ctx->backend->build_response_basis(&sft, rsp);
1002 
1003  /* Positive exception code */
1004  if (exception_code < MODBUS_EXCEPTION_MAX) {
1005  rsp[rsp_length++] = exception_code;
1006  return send_msg(ctx, rsp, rsp_length);
1007  } else {
1008  errno = EINVAL;
1009  return -1;
1010  }
1011 }
1012 
1013 /* Reads IO status */
1014 static int read_io_status(modbus_t *ctx, int function,
1015  int addr, int nb, uint8_t *dest)
1016 {
1017  int rc;
1018  int req_length;
1019 
1020  uint8_t req[_MIN_REQ_LENGTH];
1021  uint8_t rsp[MAX_MESSAGE_LENGTH];
1022 
1023  req_length = ctx->backend->build_request_basis(ctx, function, addr, nb, req);
1024 
1025  rc = send_msg(ctx, req, req_length);
1026  if (rc > 0) {
1027  int i, temp, bit;
1028  int pos = 0;
1029  int offset;
1030  int offset_end;
1031 
1032  rc = receive_msg(ctx, rsp, MSG_CONFIRMATION);
1033  if (rc == -1)
1034  return -1;
1035 
1036  rc = check_confirmation(ctx, req, rsp, rc);
1037  if (rc == -1)
1038  return -1;
1039 
1040  offset = ctx->backend->header_length + 2;
1041  offset_end = offset + rc;
1042  for (i = offset; i < offset_end; i++) {
1043  /* Shift reg hi_byte to temp */
1044  temp = rsp[i];
1045 
1046  for (bit = 0x01; (bit & 0xff) && (pos < nb);) {
1047  dest[pos++] = (temp & bit) ? TRUE : FALSE;
1048  bit = bit << 1;
1049  }
1050 
1051  }
1052  }
1053 
1054  return rc;
1055 }
1056 
1057 /* Reads the boolean status of bits and sets the array elements
1058  in the destination to TRUE or FALSE (single bits). */
1059 int modbus_read_bits(modbus_t *ctx, int addr, int nb, uint8_t *dest)
1060 {
1061  int rc;
1062 
1063  if (nb > MODBUS_MAX_READ_BITS) {
1064  if (ctx->debug) {
1065  fprintf(stderr,
1066  "ERROR Too many bits requested (%d > %d)\n",
1067  nb, MODBUS_MAX_READ_BITS);
1068  }
1069  errno = EMBMDATA;
1070  return -1;
1071  }
1072 
1073  rc = read_io_status(ctx, _FC_READ_COILS, addr, nb, dest);
1074 
1075  if (rc == -1)
1076  return -1;
1077  else
1078  return nb;
1079 }
1080 
1081 
1082 /* Same as modbus_read_bits but reads the remote device input table */
1083 int modbus_read_input_bits(modbus_t *ctx, int addr, int nb, uint8_t *dest)
1084 {
1085  int rc;
1086 
1087  if (nb > MODBUS_MAX_READ_BITS) {
1088  if (ctx->debug) {
1089  fprintf(stderr,
1090  "ERROR Too many discrete inputs requested (%d > %d)\n",
1091  nb, MODBUS_MAX_READ_BITS);
1092  }
1093  errno = EMBMDATA;
1094  return -1;
1095  }
1096 
1097  rc = read_io_status(ctx, _FC_READ_DISCRETE_INPUTS, addr, nb, dest);
1098 
1099  if (rc == -1)
1100  return -1;
1101  else
1102  return nb;
1103 }
1104 
1105 /* Reads the data from a remove device and put that data into an array */
1106 static int read_registers(modbus_t *ctx, int function, int addr, int nb,
1107  uint16_t *dest)
1108 {
1109  int rc;
1110  int req_length;
1111  uint8_t req[_MIN_REQ_LENGTH];
1112  uint8_t rsp[MAX_MESSAGE_LENGTH];
1113 
1114  if (nb > MODBUS_MAX_READ_REGISTERS) {
1115  if (ctx->debug) {
1116  fprintf(stderr,
1117  "ERROR Too many registers requested (%d > %d)\n",
1119  }
1120  errno = EMBMDATA;
1121  return -1;
1122  }
1123 
1124  req_length = ctx->backend->build_request_basis(ctx, function, addr, nb, req);
1125 
1126  rc = send_msg(ctx, req, req_length);
1127  if (rc > 0) {
1128  int offset;
1129  int i;
1130 
1131  rc = receive_msg(ctx, rsp, MSG_CONFIRMATION);
1132  if (rc == -1)
1133  return -1;
1134 
1135  rc = check_confirmation(ctx, req, rsp, rc);
1136  if (rc == -1)
1137  return -1;
1138 
1139  offset = ctx->backend->header_length;
1140 
1141  for (i = 0; i < rc; i++) {
1142  /* shift reg hi_byte to temp OR with lo_byte */
1143  dest[i] = (rsp[offset + 2 + (i << 1)] << 8) |
1144  rsp[offset + 3 + (i << 1)];
1145  }
1146  }
1147 
1148  return rc;
1149 }
1150 
1151 /* Reads the holding registers of remote device and put the data into an
1152  array */
1153 int modbus_read_registers(modbus_t *ctx, int addr, int nb, uint16_t *dest)
1154 {
1155  int status;
1156 
1157  if (nb > MODBUS_MAX_READ_REGISTERS) {
1158  if (ctx->debug) {
1159  fprintf(stderr,
1160  "ERROR Too many registers requested (%d > %d)\n",
1162  }
1163  errno = EMBMDATA;
1164  return -1;
1165  }
1166 
1168  addr, nb, dest);
1169  return status;
1170 }
1171 
1172 /* Reads the input registers of remote device and put the data into an array */
1174  uint16_t *dest)
1175 {
1176  int status;
1177 
1178  if (nb > MODBUS_MAX_READ_REGISTERS) {
1179  fprintf(stderr,
1180  "ERROR Too many input registers requested (%d > %d)\n",
1182  errno = EMBMDATA;
1183  return -1;
1184  }
1185 
1187  addr, nb, dest);
1188 
1189  return status;
1190 }
1191 
1192 /* Write a value to the specified register of the remote device.
1193  Used by write_bit and write_register */
1194 static int write_single(modbus_t *ctx, int function, int addr, int value)
1195 {
1196  int rc;
1197  int req_length;
1198  uint8_t req[_MIN_REQ_LENGTH];
1199 
1200  req_length = ctx->backend->build_request_basis(ctx, function, addr, value, req);
1201 
1202  rc = send_msg(ctx, req, req_length);
1203  if (rc > 0) {
1204  /* Used by write_bit and write_register */
1205  uint8_t rsp[MAX_MESSAGE_LENGTH];
1206 
1207  rc = receive_msg(ctx, rsp, MSG_CONFIRMATION);
1208  if (rc == -1)
1209  return -1;
1210 
1211  rc = check_confirmation(ctx, req, rsp, rc);
1212  }
1213 
1214  return rc;
1215 }
1216 
1217 /* Turns ON or OFF a single bit of the remote device */
1218 int modbus_write_bit(modbus_t *ctx, int addr, int status)
1219 {
1220  return write_single(ctx, _FC_WRITE_SINGLE_COIL, addr,
1221  status ? 0xFF00 : 0);
1222 }
1223 
1224 /* Writes a value in one register of the remote device */
1225 int modbus_write_register(modbus_t *ctx, int addr, int value)
1226 {
1227  return write_single(ctx, _FC_WRITE_SINGLE_REGISTER, addr, value);
1228 }
1229 
1230 /* Write the bits of the array in the remote device */
1231 int modbus_write_bits(modbus_t *ctx, int addr, int nb, const uint8_t *src)
1232 {
1233  int rc;
1234  int i;
1235  int byte_count;
1236  int req_length;
1237  int bit_check = 0;
1238  int pos = 0;
1239 
1240  uint8_t req[MAX_MESSAGE_LENGTH];
1241 
1242  if (nb > MODBUS_MAX_WRITE_BITS) {
1243  if (ctx->debug) {
1244  fprintf(stderr, "ERROR Writing too many bits (%d > %d)\n",
1245  nb, MODBUS_MAX_WRITE_BITS);
1246  }
1247  errno = EMBMDATA;
1248  return -1;
1249  }
1250 
1251  req_length = ctx->backend->build_request_basis(ctx,
1253  addr, nb, req);
1254  byte_count = (nb / 8) + ((nb % 8) ? 1 : 0);
1255  req[req_length++] = byte_count;
1256 
1257  for (i = 0; i < byte_count; i++) {
1258  int bit;
1259 
1260  bit = 0x01;
1261  req[req_length] = 0;
1262 
1263  while ((bit & 0xFF) && (bit_check++ < nb)) {
1264  if (src[pos++])
1265  req[req_length] |= bit;
1266  else
1267  req[req_length] &=~ bit;
1268 
1269  bit = bit << 1;
1270  }
1271  req_length++;
1272  }
1273 
1274  rc = send_msg(ctx, req, req_length);
1275  if (rc > 0) {
1276  uint8_t rsp[MAX_MESSAGE_LENGTH];
1277 
1278  rc = receive_msg(ctx, rsp, MSG_CONFIRMATION);
1279  if (rc == -1)
1280  return -1;
1281 
1282  rc = check_confirmation(ctx, req, rsp, rc);
1283  }
1284 
1285 
1286  return rc;
1287 }
1288 
1289 /* Write the values from the array to the registers of the remote device */
1290 int modbus_write_registers(modbus_t *ctx, int addr, int nb, const uint16_t *src)
1291 {
1292  int rc;
1293  int i;
1294  int req_length;
1295  int byte_count;
1296 
1297  uint8_t req[MAX_MESSAGE_LENGTH];
1298 
1299  if (nb > MODBUS_MAX_WRITE_REGISTERS) {
1300  if (ctx->debug) {
1301  fprintf(stderr,
1302  "ERROR Trying to write to too many registers (%d > %d)\n",
1304  }
1305  errno = EMBMDATA;
1306  return -1;
1307  }
1308 
1309  req_length = ctx->backend->build_request_basis(ctx,
1311  addr, nb, req);
1312  byte_count = nb * 2;
1313  req[req_length++] = byte_count;
1314 
1315  for (i = 0; i < nb; i++) {
1316  req[req_length++] = src[i] >> 8;
1317  req[req_length++] = src[i] & 0x00FF;
1318  }
1319 
1320  rc = send_msg(ctx, req, req_length);
1321  if (rc > 0) {
1322  uint8_t rsp[MAX_MESSAGE_LENGTH];
1323 
1324  rc = receive_msg(ctx, rsp, MSG_CONFIRMATION);
1325  if (rc == -1)
1326  return -1;
1327 
1328  rc = check_confirmation(ctx, req, rsp, rc);
1329  }
1330 
1331  return rc;
1332 }
1333 
1334 /* Write multiple registers from src array to remote device and read multiple
1335  registers from remote device to dest array. */
1337  int write_addr, int write_nb, const uint16_t *src,
1338  int read_addr, int read_nb, uint16_t *dest)
1339 
1340 {
1341  int rc;
1342  int req_length;
1343  int i;
1344  int byte_count;
1345  uint8_t req[MAX_MESSAGE_LENGTH];
1346  uint8_t rsp[MAX_MESSAGE_LENGTH];
1347 
1348  if (write_nb > MODBUS_MAX_RW_WRITE_REGISTERS) {
1349  if (ctx->debug) {
1350  fprintf(stderr,
1351  "ERROR Too many registers to write (%d > %d)\n",
1352  write_nb, MODBUS_MAX_RW_WRITE_REGISTERS);
1353  }
1354  errno = EMBMDATA;
1355  return -1;
1356  }
1357 
1358  if (read_nb > MODBUS_MAX_READ_REGISTERS) {
1359  if (ctx->debug) {
1360  fprintf(stderr,
1361  "ERROR Too many registers requested (%d > %d)\n",
1362  read_nb, MODBUS_MAX_READ_REGISTERS);
1363  }
1364  errno = EMBMDATA;
1365  return -1;
1366  }
1367  req_length = ctx->backend->build_request_basis(ctx,
1369  read_addr, read_nb, req);
1370 
1371  req[req_length++] = write_addr >> 8;
1372  req[req_length++] = write_addr & 0x00ff;
1373  req[req_length++] = write_nb >> 8;
1374  req[req_length++] = write_nb & 0x00ff;
1375  byte_count = write_nb * 2;
1376  req[req_length++] = byte_count;
1377 
1378  for (i = 0; i < write_nb; i++) {
1379  req[req_length++] = src[i] >> 8;
1380  req[req_length++] = src[i] & 0x00FF;
1381  }
1382 
1383  rc = send_msg(ctx, req, req_length);
1384  if (rc > 0) {
1385  int offset;
1386 
1387  rc = receive_msg(ctx, rsp, MSG_CONFIRMATION);
1388  if (rc == -1)
1389  return -1;
1390 
1391  rc = check_confirmation(ctx, req, rsp, rc);
1392  if (rc == -1)
1393  return -1;
1394 
1395  offset = ctx->backend->header_length;
1396 
1397  /* If rc is negative, the loop is jumped ! */
1398  for (i = 0; i < rc; i++) {
1399  /* shift reg hi_byte to temp OR with lo_byte */
1400  dest[i] = (rsp[offset + 2 + (i << 1)] << 8) |
1401  rsp[offset + 3 + (i << 1)];
1402  }
1403  }
1404 
1405  return rc;
1406 }
1407 
1408 /* Send a request to get the slave ID of the device (only available in serial
1409  communication). */
1411 {
1412  int rc;
1413  int req_length;
1414  uint8_t req[_MIN_REQ_LENGTH];
1415 
1416  req_length = ctx->backend->build_request_basis(ctx, _FC_REPORT_SLAVE_ID,
1417  0, 0, req);
1418 
1419  /* HACKISH, addr and count are not used */
1420  req_length -= 4;
1421 
1422  rc = send_msg(ctx, req, req_length);
1423  if (rc > 0) {
1424  int i;
1425  int offset;
1426  uint8_t rsp[MAX_MESSAGE_LENGTH];
1427 
1428  rc = receive_msg(ctx, rsp, MSG_CONFIRMATION);
1429  if (rc == -1)
1430  return -1;
1431 
1432  rc = check_confirmation(ctx, req, rsp, rc);
1433  if (rc == -1)
1434  return -1;
1435 
1436  offset = ctx->backend->header_length + 2;
1437 
1438  /* Byte count, slave id, run indicator status,
1439  additional data */
1440  for (i=0; i < rc; i++) {
1441  dest[i] = rsp[offset + i];
1442  }
1443  }
1444 
1445  return rc;
1446 }
1447 
1449 {
1450  /* Slave and socket are initialized to -1 */
1451  ctx->slave = -1;
1452  ctx->s = -1;
1453 
1454  ctx->debug = FALSE;
1456 
1457  ctx->response_timeout.tv_sec = 0;
1458  ctx->response_timeout.tv_usec = _RESPONSE_TIMEOUT;
1459 
1460  ctx->byte_timeout.tv_sec = 0;
1461  ctx->byte_timeout.tv_usec = _BYTE_TIMEOUT;
1462 }
1463 
1464 /* Define the slave number */
1466 {
1467  return ctx->backend->set_slave(ctx, slave);
1468 }
1469 
1471  modbus_error_recovery_mode error_recovery)
1472 {
1473  /* The type of modbus_error_recovery_mode is unsigned enum */
1474  ctx->error_recovery = (uint8_t) error_recovery;
1475  return 0;
1476 }
1477 
1478 void modbus_set_socket(modbus_t *ctx, int socket)
1479 {
1480  ctx->s = socket;
1481 }
1482 
1484 {
1485  return ctx->s;
1486 }
1487 
1488 /* Get the timeout interval used to wait for a response */
1489 void modbus_get_response_timeout(modbus_t *ctx, struct timeval *timeout)
1490 {
1491  *timeout = ctx->response_timeout;
1492 }
1493 
1494 void modbus_set_response_timeout(modbus_t *ctx, const struct timeval *timeout)
1495 {
1496  ctx->response_timeout = *timeout;
1497 }
1498 
1499 /* Get the timeout interval between two consecutive bytes of a message */
1500 void modbus_get_byte_timeout(modbus_t *ctx, struct timeval *timeout)
1501 {
1502  *timeout = ctx->byte_timeout;
1503 }
1504 
1505 void modbus_set_byte_timeout(modbus_t *ctx, const struct timeval *timeout)
1506 {
1507  ctx->byte_timeout = *timeout;
1508 }
1509 
1511 {
1512  return ctx->backend->header_length;
1513 }
1514 
1516 {
1517  return ctx->backend->connect(ctx);
1518 }
1519 
1521 {
1522  if (ctx == NULL)
1523  return;
1524 
1525  ctx->backend->close(ctx);
1526 }
1527 
1529 {
1530  if (ctx == NULL)
1531  return;
1532 
1533  free(ctx->backend_data);
1534  free(ctx);
1535 }
1536 
1537 void modbus_set_debug(modbus_t *ctx, int boolean)
1538 {
1539  ctx->debug = boolean;
1540 }
1541 
1542 /* Allocates 4 arrays to store bits, input bits, registers and inputs
1543  registers. The pointers are stored in modbus_mapping structure.
1544 
1545  The modbus_mapping_new() function shall return the new allocated structure if
1546  successful. Otherwise it shall return NULL and set errno to ENOMEM. */
1547 modbus_mapping_t* modbus_mapping_new(int nb_bits, int nb_input_bits,
1548  int nb_registers, int nb_input_registers)
1549 {
1551 
1552  mb_mapping = (modbus_mapping_t *)malloc(sizeof(modbus_mapping_t));
1553  if (mb_mapping == NULL) {
1554  return NULL;
1555  }
1556 
1557  /* 0X */
1558  mb_mapping->nb_bits = nb_bits;
1559  if (nb_bits == 0) {
1560  mb_mapping->tab_bits = NULL;
1561  } else {
1562  /* Negative number raises a POSIX error */
1563  mb_mapping->tab_bits =
1564  (uint8_t *) malloc(nb_bits * sizeof(uint8_t));
1565  if (mb_mapping->tab_bits == NULL) {
1566  free(mb_mapping);
1567  return NULL;
1568  }
1569  memset(mb_mapping->tab_bits, 0, nb_bits * sizeof(uint8_t));
1570  }
1571 
1572  /* 1X */
1573  mb_mapping->nb_input_bits = nb_input_bits;
1574  if (nb_input_bits == 0) {
1575  mb_mapping->tab_input_bits = NULL;
1576  } else {
1577  mb_mapping->tab_input_bits =
1578  (uint8_t *) malloc(nb_input_bits * sizeof(uint8_t));
1579  if (mb_mapping->tab_input_bits == NULL) {
1580  free(mb_mapping->tab_bits);
1581  free(mb_mapping);
1582  return NULL;
1583  }
1584  memset(mb_mapping->tab_input_bits, 0, nb_input_bits * sizeof(uint8_t));
1585  }
1586 
1587  /* 4X */
1588  mb_mapping->nb_registers = nb_registers;
1589  if (nb_registers == 0) {
1590  mb_mapping->tab_registers = NULL;
1591  } else {
1592  mb_mapping->tab_registers =
1593  (uint16_t *) malloc(nb_registers * sizeof(uint16_t));
1594  if (mb_mapping->tab_registers == NULL) {
1595  free(mb_mapping->tab_input_bits);
1596  free(mb_mapping->tab_bits);
1597  free(mb_mapping);
1598  return NULL;
1599  }
1600  memset(mb_mapping->tab_registers, 0, nb_registers * sizeof(uint16_t));
1601  }
1602 
1603  /* 3X */
1604  mb_mapping->nb_input_registers = nb_input_registers;
1605  if (nb_input_registers == 0) {
1606  mb_mapping->tab_input_registers = NULL;
1607  } else {
1608  mb_mapping->tab_input_registers =
1609  (uint16_t *) malloc(nb_input_registers * sizeof(uint16_t));
1610  if (mb_mapping->tab_input_registers == NULL) {
1611  free(mb_mapping->tab_registers);
1612  free(mb_mapping->tab_input_bits);
1613  free(mb_mapping->tab_bits);
1614  free(mb_mapping);
1615  return NULL;
1616  }
1617  memset(mb_mapping->tab_input_registers, 0,
1618  nb_input_registers * sizeof(uint16_t));
1619  }
1620 
1621  return mb_mapping;
1622 }
1623 
1624 /* Frees the 4 arrays */
1626 {
1627  if (mb_mapping == NULL) {
1628  return;
1629  }
1630 
1631  free(mb_mapping->tab_input_registers);
1632  free(mb_mapping->tab_registers);
1633  free(mb_mapping->tab_input_bits);
1634  free(mb_mapping->tab_bits);
1635  free(mb_mapping);
1636 }
1637 
1638 #ifndef HAVE_STRLCPY
1639 /*
1640  * Function strlcpy was originally developed by
1641  * Todd C. Miller <Todd.Miller@courtesan.com> to simplify writing secure code.
1642  * See ftp://ftp.openbsd.org/pub/OpenBSD/src/lib/libc/string/strlcpy.3
1643  * for more information.
1644  *
1645  * Thank you Ulrich Drepper... not!
1646  *
1647  * Copy src to string dest of size dest_size. At most dest_size-1 characters
1648  * will be copied. Always NUL terminates (unless dest_size == 0). Returns
1649  * strlen(src); if retval >= dest_size, truncation occurred.
1650  */
1651 size_t strlcpy(char *dest, const char *src, size_t dest_size)
1652 {
1653  register char *d = dest;
1654  register const char *s = src;
1655  register size_t n = dest_size;
1656 
1657  /* Copy as many bytes as will fit */
1658  if (n != 0 && --n != 0) {
1659  do {
1660  if ((*d++ = *s++) == 0)
1661  break;
1662  } while (--n != 0);
1663  }
1664 
1665  /* Not enough room in dest, add NUL and traverse rest of src */
1666  if (n == 0) {
1667  if (dest_size != 0)
1668  *d = '\0'; /* NUL-terminate dest */
1669  while (*s++)
1670  ;
1671  }
1672 
1673  return (s - src - 1); /* count does not include NUL */
1674 }
1675 #endif
#define MODBUS_MAX_WRITE_REGISTERS
Definition: modbus.h:81
int modbus_reply_exception(modbus_t *ctx, const uint8_t *req, unsigned int exception_code)
Definition: modbus.c:982
unsigned int header_length
#define LIBMODBUS_VERSION_MICRO
void _modbus_init_common(modbus_t *ctx)
Definition: modbus.c:1448
#define _RESPONSE_TIMEOUT
#define EMBXSBUSY
Definition: modbus.h:108
int modbus_send_raw_request(modbus_t *ctx, uint8_t *raw_req, int raw_req_length)
Definition: modbus.c:204
#define _FC_READ_COILS
int nb_registers
Definition: modbus.h:131
void modbus_set_debug(modbus_t *ctx, int boolean)
Definition: modbus.c:1537
int(* filter_request)(modbus_t *ctx, int slave)
size_t strlcpy(char *dest, const char *src, size_t dest_size)
Definition: modbus.c:1651
#define EMBXSFAIL
Definition: modbus.h:106
int modbus_set_slave(modbus_t *ctx, int slave)
Definition: modbus.c:1465
static int write_single(modbus_t *ctx, int function, int addr, int value)
Definition: modbus.c:1194
int modbus_read_registers(modbus_t *ctx, int addr, int nb, uint16_t *dest)
Definition: modbus.c:1153
#define FALSE
Definition: modbus.h:48
#define MAX_MESSAGE_LENGTH
Definition: modbus.c:44
#define _FC_WRITE_AND_READ_REGISTERS
int(* send_msg_pre)(uint8_t *req, int req_length)
#define EMBMDATA
Definition: modbus.h:119
int modbus_write_registers(modbus_t *ctx, int addr, int nb, const uint16_t *src)
Definition: modbus.c:1290
static unsigned int compute_response_length_from_request(modbus_t *ctx, uint8_t *req)
Definition: modbus.c:128
int nb_input_bits
Definition: modbus.h:129
#define EMBXMEMPAR
Definition: modbus.h:110
void modbus_mapping_free(modbus_mapping_t *mb_mapping)
Definition: modbus.c:1625
static int compute_data_length_after_meta(modbus_t *ctx, uint8_t *msg, msg_type_t msg_type)
Definition: modbus.c:281
uint8_t * tab_input_bits
Definition: modbus.h:133
unsigned int max_adu_length
const modbus_backend_t * backend
int(* check_integrity)(modbus_t *ctx, uint8_t *msg, const int msg_length)
void modbus_set_byte_timeout(modbus_t *ctx, const struct timeval *timeout)
Definition: modbus.c:1505
int(* select)(modbus_t *ctx, fd_set *rfds, struct timeval *tv, int msg_length)
int modbus_get_socket(modbus_t *ctx)
Definition: modbus.c:1483
ssize_t(* send)(modbus_t *ctx, const uint8_t *req, int req_length)
void * backend_data
#define MODBUS_MAX_READ_REGISTERS
Definition: modbus.h:80
int modbus_flush(modbus_t *ctx)
Definition: modbus.c:118
const char * modbus_strerror(int errnum)
Definition: modbus.c:53
#define EMBBADEXC
Definition: modbus.h:117
modbus_mapping_t * modbus_mapping_new(int nb_bits, int nb_input_bits, int nb_registers, int nb_input_registers)
Definition: modbus.c:1547
#define _FC_READ_EXCEPTION_STATUS
int slave
static uint8_t compute_meta_length_after_function(int function, msg_type_t msg_type)
Definition: modbus.c:246
void modbus_get_byte_timeout(modbus_t *ctx, struct timeval *timeout)
Definition: modbus.c:1500
void(* close)(modbus_t *ctx)
static int check_confirmation(modbus_t *ctx, uint8_t *req, uint8_t *rsp, int rsp_length)
Definition: modbus.c:478
#define _FC_WRITE_MULTIPLE_REGISTERS
#define _FC_WRITE_SINGLE_REGISTER
int _sleep_and_flush(modbus_t *ctx)
Definition: modbus.c:100
#define EMBXACK
Definition: modbus.h:107
int modbus_read_input_bits(modbus_t *ctx, int addr, int nb, uint8_t *dest)
Definition: modbus.c:1083
#define _FC_REPORT_SLAVE_ID
void modbus_set_response_timeout(modbus_t *ctx, const struct timeval *timeout)
Definition: modbus.c:1494
int modbus_write_bit(modbus_t *ctx, int addr, int status)
Definition: modbus.c:1218
int modbus_write_and_read_registers(modbus_t *ctx, int write_addr, int write_nb, const uint16_t *src, int read_addr, int read_nb, uint16_t *dest)
Definition: modbus.c:1336
#define _FC_READ_HOLDING_REGISTERS
int modbus_set_error_recovery(modbus_t *ctx, modbus_error_recovery_mode error_recovery)
Definition: modbus.c:1470
int(* build_request_basis)(modbus_t *ctx, int function, int addr, int nb, uint8_t *req)
#define MODBUS_ENOBASE
Definition: modbus.h:85
int(* pre_check_confirmation)(modbus_t *ctx, const uint8_t *req, const uint8_t *rsp, int rsp_length)
unsigned int checksum_length
int(* connect)(modbus_t *ctx)
#define _REPORT_SLAVE_ID
#define _BYTE_TIMEOUT
int error_recovery
int modbus_write_bits(modbus_t *ctx, int addr, int nb, const uint8_t *src)
Definition: modbus.c:1231
int(* flush)(modbus_t *ctx)
int function
int modbus_get_header_length(modbus_t *ctx)
Definition: modbus.c:1510
void modbus_set_socket(modbus_t *ctx, int socket)
Definition: modbus.c:1478
const unsigned int libmodbus_version_major
Definition: modbus.c:39
#define _FC_READ_INPUT_REGISTERS
#define EMBXNACK
Definition: modbus.h:109
#define LIBMODBUS_VERSION_MAJOR
ssize_t(* recv)(modbus_t *ctx, uint8_t *rsp, int rsp_length)
#define EMBXILADD
Definition: modbus.h:104
#define EMBXGTAR
Definition: modbus.h:112
#define EMBXILVAL
Definition: modbus.h:105
#define MODBUS_MAX_WRITE_BITS
Definition: modbus.h:71
#define LIBMODBUS_VERSION_MINOR
static int response_io_status(int address, int nb, uint8_t *tab_io_status, uint8_t *rsp, int offset)
Definition: modbus.c:595
msg_type_t
Definition: modbus.c:238
uint16_t * tab_registers
Definition: modbus.h:135
modbus_t * ctx
const unsigned int libmodbus_version_minor
Definition: modbus.c:40
void modbus_set_bits_from_bytes(uint8_t *dest, int index, unsigned int nb_bits, const uint8_t *tab_byte)
Definition: modbus-data.c:41
#define MODBUS_MAX_RW_WRITE_REGISTERS
Definition: modbus.h:82
#define LIBMODBUS_VERSION_STRING
uint16_t * tab_input_registers
Definition: modbus.h:134
modbus_error_recovery_mode
Definition: modbus.h:138
void modbus_get_response_timeout(modbus_t *ctx, struct timeval *timeout)
Definition: modbus.c:1489
static int read_io_status(modbus_t *ctx, int function, int addr, int nb, uint8_t *dest)
Definition: modbus.c:1014
#define _MIN_REQ_LENGTH
#define MSG_LENGTH_UNDEFINED
Definition: modbus.c:36
int modbus_receive(modbus_t *ctx, uint8_t *req)
Definition: modbus.c:460
#define _FC_READ_DISCRETE_INPUTS
static int read_registers(modbus_t *ctx, int function, int addr, int nb, uint16_t *dest)
Definition: modbus.c:1106
int nb_input_registers
Definition: modbus.h:130
void _error_print(modbus_t *ctx, const char *context)
Definition: modbus.c:88
#define EMBBADDATA
Definition: modbus.h:116
#define TRUE
Definition: modbus.h:52
int(* build_response_basis)(sft_t *sft, uint8_t *rsp)
_step_t
Definition: modbus.c:47
#define EMBBADCRC
Definition: modbus.h:115
int modbus_read_bits(modbus_t *ctx, int addr, int nb, uint8_t *dest)
Definition: modbus.c:1059
#define ON
Definition: modbus.h:60
static int send_msg(modbus_t *ctx, uint8_t *msg, int msg_length)
Definition: modbus.c:162
int(* prepare_response_tid)(const uint8_t *req, int *req_length)
#define _FC_WRITE_MULTIPLE_COILS
#define _FC_WRITE_SINGLE_COIL
struct timeval byte_timeout
modbus_mapping_t * mb_mapping
const unsigned int libmodbus_version_micro
Definition: modbus.c:41
uint8_t * tab_bits
Definition: modbus.h:132
static int receive_msg(modbus_t *ctx, uint8_t *msg, msg_type_t msg_type)
Definition: modbus.c:329
int modbus_receive_confirmation(modbus_t *ctx, uint8_t *rsp)
Definition: modbus.c:473
#define MODBUS_MAX_READ_BITS
Definition: modbus.h:70
void modbus_close(modbus_t *ctx)
Definition: modbus.c:1520
static int response_exception(modbus_t *ctx, sft_t *sft, int exception_code, uint8_t *rsp)
Definition: modbus.c:621
#define EMBXGPATH
Definition: modbus.h:111
int modbus_reply(modbus_t *ctx, const uint8_t *req, int req_length, modbus_mapping_t *mb_mapping)
Definition: modbus.c:641
void modbus_free(modbus_t *ctx)
Definition: modbus.c:1528
#define OFF
Definition: modbus.h:56
int(* set_slave)(modbus_t *ctx, int slave)
int t_id
int modbus_report_slave_id(modbus_t *ctx, uint8_t *dest)
Definition: modbus.c:1410
int modbus_connect(modbus_t *ctx)
Definition: modbus.c:1515
int modbus_read_input_registers(modbus_t *ctx, int addr, int nb, uint16_t *dest)
Definition: modbus.c:1173
struct timeval response_timeout
#define EMBXILFUN
Definition: modbus.h:103
int modbus_write_register(modbus_t *ctx, int addr, int value)
Definition: modbus.c:1225


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