Added attempts at minimizing firmware. Added MATLAB code generation setup with MODBUS TCP

This commit is contained in:
judsonupchurch 2025-06-14 14:31:17 -05:00
parent 8f7fb5602c
commit bd9bc76e88
524 changed files with 137618 additions and 0 deletions

Binary file not shown.

View File

@ -0,0 +1,5 @@
{
"files.associations": {
"iosfwd": "c"
}
}

View File

@ -0,0 +1,43 @@
## This cmakelist.txt file was generated from
## the UAV Toolbox Support Package for PX4 Autopilots
set(MAVLINK_LIBRARY_DIR "${CMAKE_BINARY_DIR}/mavlink")
set(MAVLINK_DIALECT_UAVIONIX "uAvionix")
add_definitions(
-DMODEL=MODBUS_TCP_Test -DNUMST=1 -DNCSTATES=0 -DHAVESTDIO -DMODEL_HAS_DYNAMICALLY_LOADED_SFCNS=0 -DCLASSIC_INTERFACE=0 -DALLOCATIONFCN=0 -DTID01EQ=0 -DTERMFCN=1 -DONESTEPFCN=1 -DMAT_FILE=0 -DMULTI_INSTANCE_CODE=0 -DINTEGER_CODE=0 -DMT=0 -DPX4 -DFMUv6x -DNULL=0 -DMW_PX4_NUTTX_BUILD -DEXTMODE_DISABLETESTING -DEXTMODE_DISABLEPRINTF -DEXTMODE_DISABLE_ARGS_PROCESSING=1 -D__linux__ -DXCP_PLATFORM_LINUX_NO_PIE_SUPPORT -DSTACK_SIZE=64 -D__MW_TARGET_USE_HARDWARE_RESOURCES_H__ -DRT )
px4_add_module(
MODULE modules__px4_simulink_app
MAIN px4_simulink_app
STACK_MAIN 2000
SRCS
ert_main.cpp
MODBUS_TCP_Test.cpp
modbus_tcp_client.cpp
MW_PX4_TaskControl.cpp
nuttxinitialize.cpp
COMPILE_FLAGS
-fpermissive
-Wno-narrowing
-Wno-address-of-packed-member
-Wno-cast-align
INCLUDES
${PX4_SOURCE_DIR}/src/modules/mavlink
${MAVLINK_LIBRARY_DIR}
${MAVLINK_LIBRARY_DIR}/${CONFIG_MAVLINK_DIALECT}
${MAVLINK_LIBRARY_DIR}/${MAVLINK_DIALECT_UAVIONIX}
/home/judson/Desktop/Pixhawk/MATLAB/MODBUS_TCP_Test
/home/judson/Desktop/Pixhawk/MATLAB/MODBUS_TCP_Test/MODBUS_TCP_Test_ert_rtw
/usr/local/MATLAB/R2024a/extern/include
/usr/local/MATLAB/R2024a/simulink/include
/usr/local/MATLAB/R2024a/rtw/c/src
/usr/local/MATLAB/R2024a/rtw/c/src/ext_mode/common
/usr/local/MATLAB/R2024a/rtw/c/ert
/root/Documents/MATLAB/SupportPackages/R2024a/toolbox/target/supportpackages/px4/include
)
get_target_property(PX4_SL_APP_COMPILE_FLAGS modules__px4_simulink_app COMPILE_OPTIONS)
list(REMOVE_ITEM PX4_SL_APP_COMPILE_FLAGS -Werror)
set_target_properties(modules__px4_simulink_app PROPERTIES COMPILE_OPTIONS "${PX4_SL_APP_COMPILE_FLAGS}")

View File

@ -0,0 +1,63 @@
//
// Academic License - for use in teaching, academic research, and meeting
// course requirements at degree granting institutions only. Not for
// government, commercial, or other organizational use.
//
// File: MODBUS_TCP_Test.cpp
//
// Code generated for Simulink model 'MODBUS_TCP_Test'.
//
// Model version : 1.4
// Simulink Coder version : 24.1 (R2024a) 19-Nov-2023
// C/C++ source code generated on : Fri Mar 7 20:25:14 2025
//
// Target selection: ert.tlc
// Embedded hardware selection: ARM Compatible->ARM Cortex
// Code generation objectives: Unspecified
// Validation result: Not run
//
#include "MODBUS_TCP_Test.h"
// Real-time model
RT_MODEL_MODBUS_TCP_Test_T MODBUS_TCP_Test_M_{ };
RT_MODEL_MODBUS_TCP_Test_T *const MODBUS_TCP_Test_M{ &MODBUS_TCP_Test_M_ };
// Model step function
void MODBUS_TCP_Test_step(void)
{
// CFunction: '<Root>/C Function3'
{
static ModbusTCPClient modbus("192.168.0.129", 5020, 10, 10, 10, 10);
if (!modbus.isConnected()) { // Only connect if not already connected
modbus.setTimeout(1000);
if (!modbus.connectServer()) {
printf("Failed to connect to MODBUS server!\n");
return 1;
}
}
// Read fresh MODBUS values
modbus.readAll();
uint16_t new_value = modbus.getHoldingRegister(0);
printf("After readAll: Holding Register: %u\n", new_value);
}
}
// Model initialize function
void MODBUS_TCP_Test_initialize(void)
{
// (no initialization code required)
}
// Model terminate function
void MODBUS_TCP_Test_terminate(void)
{
// (no terminate code required)
}
//
// File trailer for generated code.
//
// [EOF]
//

View File

@ -0,0 +1,114 @@
//
// Academic License - for use in teaching, academic research, and meeting
// course requirements at degree granting institutions only. Not for
// government, commercial, or other organizational use.
//
// File: MODBUS_TCP_Test.h
//
// Code generated for Simulink model 'MODBUS_TCP_Test'.
//
// Model version : 1.4
// Simulink Coder version : 24.1 (R2024a) 19-Nov-2023
// C/C++ source code generated on : Fri Mar 7 20:25:14 2025
//
// Target selection: ert.tlc
// Embedded hardware selection: ARM Compatible->ARM Cortex
// Code generation objectives: Unspecified
// Validation result: Not run
//
#ifndef MODBUS_TCP_Test_h_
#define MODBUS_TCP_Test_h_
#include "rtwtypes.h"
#include "MODBUS_TCP_Test_types.h"
#include "modbus_tcp_client.h"
// Macros for accessing real-time model data structure
#ifndef rtmGetErrorStatus
#define rtmGetErrorStatus(rtm) ((rtm)->errorStatus)
#endif
#ifndef rtmSetErrorStatus
#define rtmSetErrorStatus(rtm, val) ((rtm)->errorStatus = (val))
#endif
// user code (top of header file)
#include <netinet/in.h>
#include <sys/types.h>
#include <sys/socket.h>
#include <arpa/inet.h>
#include <errno.h>
#include <stdio.h>
#include <string.h>
#include <unistd.h>
#include "modbus_tcp_client.h"
// Real-time Model Data Structure
struct tag_RTM_MODBUS_TCP_Test_T {
const char_T * volatile errorStatus;
};
#ifdef __cplusplus
extern "C"
{
#endif
// Model entry point functions
extern void MODBUS_TCP_Test_initialize(void);
extern void MODBUS_TCP_Test_step(void);
extern void MODBUS_TCP_Test_terminate(void);
#ifdef __cplusplus
}
#endif
// Real-time Model object
#ifdef __cplusplus
extern "C"
{
#endif
extern RT_MODEL_MODBUS_TCP_Test_T *const MODBUS_TCP_Test_M;
#ifdef __cplusplus
}
#endif
extern volatile boolean_T stopRequested;
extern volatile boolean_T runModel;
//-
// The generated code includes comments that allow you to trace directly
// back to the appropriate location in the model. The basic format
// is <system>/block_name, where system is the system number (uniquely
// assigned by Simulink) and block_name is the name of the block.
//
// Use the MATLAB hilite_system command to trace the generated code back
// to the model. For example,
//
// hilite_system('<S3>') - opens system 3
// hilite_system('<S3>/Kp') - opens and selects block Kp which resides in S3
//
// Here is the system hierarchy for this model
//
// '<Root>' : 'MODBUS_TCP_Test'
//-
// Requirements for '<Root>': MODBUS_TCP_Test
#endif // MODBUS_TCP_Test_h_
//
// File trailer for generated code.
//
// [EOF]
//

View File

@ -0,0 +1,29 @@
//
// Academic License - for use in teaching, academic research, and meeting
// course requirements at degree granting institutions only. Not for
// government, commercial, or other organizational use.
//
// File: MODBUS_TCP_Test_private.h
//
// Code generated for Simulink model 'MODBUS_TCP_Test'.
//
// Model version : 1.4
// Simulink Coder version : 24.1 (R2024a) 19-Nov-2023
// C/C++ source code generated on : Fri Mar 7 20:25:14 2025
//
// Target selection: ert.tlc
// Embedded hardware selection: ARM Compatible->ARM Cortex
// Code generation objectives: Unspecified
// Validation result: Not run
//
#ifndef MODBUS_TCP_Test_private_h_
#define MODBUS_TCP_Test_private_h_
#include "rtwtypes.h"
#include "MODBUS_TCP_Test_types.h"
#endif // MODBUS_TCP_Test_private_h_
//
// File trailer for generated code.
//
// [EOF]
//

View File

@ -0,0 +1,31 @@
//
// Academic License - for use in teaching, academic research, and meeting
// course requirements at degree granting institutions only. Not for
// government, commercial, or other organizational use.
//
// File: MODBUS_TCP_Test_types.h
//
// Code generated for Simulink model 'MODBUS_TCP_Test'.
//
// Model version : 1.4
// Simulink Coder version : 24.1 (R2024a) 19-Nov-2023
// C/C++ source code generated on : Fri Mar 7 20:25:14 2025
//
// Target selection: ert.tlc
// Embedded hardware selection: ARM Compatible->ARM Cortex
// Code generation objectives: Unspecified
// Validation result: Not run
//
#ifndef MODBUS_TCP_Test_types_h_
#define MODBUS_TCP_Test_types_h_
// Forward declaration for rtModel
typedef struct tag_RTM_MODBUS_TCP_Test_T RT_MODEL_MODBUS_TCP_Test_T;
#endif // MODBUS_TCP_Test_types_h_
//
// File trailer for generated code.
//
// [EOF]
//

View File

@ -0,0 +1,25 @@
#ifndef _MW_CUSTOM_RTOS_HEADER_H_
#define _MW_CUSTOM_RTOS_HEADER_H_
#define MW_BASERATE_PRIORITY 250
#define MW_BASERATE_PERIOD 10.0
#define MW_NUMBER_SUBRATES 0
#define MW_NUMBER_APERIODIC_TASKS 0
#define MW_IS_CONCURRENT 0
#define MW_NUMBER_TIMER_DRIVEN_TASKS 0
extern void exitFcn(int sig);
extern void *terminateTask(void *arg);
extern void *baseRateTask(void *arg);
extern void *subrateTask(void *arg);
extern pthread_t schedulerThread;
extern pthread_t baseRateThread;
extern pthread_t subRateThread[];
extern px4_sem_t stopSem;
extern px4_sem_t baserateTaskSem;
extern px4_sem_t subrateTaskSem[];
extern int taskId[];
extern int subratePriority[];
#endif
#define MW_MAX_TASKNAME 16

View File

@ -0,0 +1,102 @@
#ifndef PORTABLE_WORDSIZES
#ifdef __MW_TARGET_USE_HARDWARE_RESOURCES_H__
#ifndef __MW_TARGET_HARDWARE_RESOURCES_H__
#define __MW_TARGET_HARDWARE_RESOURCES_H__
#define MW_MULTI_TASKING_MODE 1
#include "MW_PX4_TaskControl.h"
#define MW_USECODERTARGET 1
#define MW_TARGETHARDWARE PX4 Pixhawk 6x
#define MW_EXTMODEPROTOCOLINFO_XCPONSERIAL_HOSTINTERFACE Simulink
#define MW_EXTMODEPROTOCOLINFO_XCPONSERIAL_LOGGINGBUFFERAUTO 1
#define MW_EXTMODEPROTOCOLINFO_XCPONSERIAL_LOGGINGBUFFERSIZE 1024
#define MW_EXTMODEPROTOCOLINFO_XCPONSERIAL_LOGGINGBUFFERNUM 3
#define MW_EXTMODEPROTOCOLINFO_XCPONSERIAL_MAXCONTIGSAMPLES 10
#define MW_CONNECTIONINFO_XCPONSERIAL_BAUDRATE codertarget.pixhawk.internal.getExternalModeBaudrate(hCS);
#define MW_CONNECTIONINFO_XCPONSERIAL_COMPORT codertarget.pixhawk.internal.getExternalSerialPortName(hCS);
#define MW_CONNECTIONINFO_XCPONSERIAL_VERBOSE 1
#define MW_EXTMODE_CONFIGURATION XCP on Serial
#define MW_RTOS NuttX
#define MW_RTOSBASERATETASKPRIORITY 250
#define MW_SCHEDULER_INTERRUPT_SOURCE 0
#define MW_RUNTIME_BUILDACTION 0
#define MW_CMAKECONFIG px4_fmu-v6x_fixedwing
#define MW_CHANGECMAKECONFIG 48
#define MW_AUTOMATIC_SERIAL_SCAN 1
#define MW_COM_UPLOAD_STORAGE
#define MW_NUTTX_SERIAL_PORT
#define MW_ENABLE_HITL 0
#define MW_SIMULATOR 0
#define MW_CONNECTEDIOSERIALPORT /dev/ttyACM0
#define MW_CONNECTEDIOSERIALPORT_CHECKBOX 1
#define MW_CONNECTEDIOHOSTCOMPORT
#define MW_SIMULINKIO_MODELTRANSPORTDATAFCN px4.internal.ConnectedIO.getConfigsetInfo
#define MW_SIMULINKIO_SERVERDEPLOYFCN px4.internal.ConnectedIO.buildAndDeployPX4IOServer
#define MW_CLOCKING_CPUCLOCKRATEMHZ 480
#define MW_EXTSERIALPORT 0
#define MW_EXTMODESERIALPORT_CHECKBOX 1
#define MW_EXTMODEHOSTCOMPORT
#define MW_PILSERIALPORT /dev/ttyACM0
#define MW_PILSERIALPORT_CHECKBOX 1
#define MW_PILHOSTCOMPORT COM6
#define MW_I2C_BUS1SPEEDKHZ_INDEX 0
#define MW_I2C_BUS2SPEEDKHZ_INDEX 0
#define MW_I2C_BUS3SPEEDKHZ_INDEX 0
#define MW_I2C_BUS1SPEEDKHZ 100
#define MW_I2C_BUS2SPEEDKHZ 100
#define MW_I2C_BUS3SPEEDKHZ 100
#define MW_CAN_PORTINDEX 0
#define MW_CAN_BAUDRATE_INDEX 2
#define MW_CAN_BAUDRATE 500000
#define MW_CAN_TESTMODE 0
#define MW_ENABLEMAVLINKCHECKBOX 1
#define MW_TTYACM0_BAUDRATE 27
#define MW_TTYACM0_PARITY 0
#define MW_TTYACM0_STOPBIT 0
#define MW_TTYACM0_PORTMAP 48
#define MW_TTYS0_BAUDRATE 27
#define MW_TTYS0_PARITY 0
#define MW_TTYS0_STOPBIT 0
#define MW_TTYS0_PORTMAP 48
#define MW_TTYS1_BAUDRATE 27
#define MW_TTYS1_PARITY 0
#define MW_TTYS1_STOPBIT 0
#define MW_TTYS1_PORTMAP 48
#define MW_TTYS1HWFLOWCONTROL_CHECKBOX 0
#define MW_TTYS2_BAUDRATE 27
#define MW_TTYS2_PARITY 0
#define MW_TTYS2_STOPBIT 0
#define MW_TTYS2_PORTMAP 48
#define MW_TTYS2HWFLOWCONTROL_CHECKBOX 0
#define MW_TTYS3_BAUDRATE 27
#define MW_TTYS3_PARITY 0
#define MW_TTYS3_STOPBIT 0
#define MW_TTYS3_PORTMAP 48
#define MW_TTYS3HWFLOWCONTROL_CHECKBOX 0
#define MW_TTYS4_BAUDRATE 27
#define MW_TTYS4_PARITY 0
#define MW_TTYS4_STOPBIT 0
#define MW_TTYS4_PORTMAP 48
#define MW_TTYS5_BAUDRATE 27
#define MW_TTYS5_PARITY 0
#define MW_TTYS5_STOPBIT 0
#define MW_TTYS5_PORTMAP 48
#define MW_TTYS6_BAUDRATE 27
#define MW_TTYS6_PARITY 0
#define MW_TTYS6_STOPBIT 0
#define MW_TTYS6_PORTMAP 48
#define MW_TTYS7_BAUDRATE 27
#define MW_TTYS7_PARITY 0
#define MW_TTYS7_STOPBIT 0
#define MW_TTYS7_PORTMAP 48
#define MW_HRT_CONSTRAINT 0
#define MW_SEM_WATERMARK 20
#define MW_IOBLOCKSMODE deployed
#define MW_DATAVERSION 2016.02
#endif /* __MW_TARGET_HARDWARE_RESOURCES_H__ */
#endif
#endif

View File

@ -0,0 +1,6 @@
#ifndef _MW_UORB_BUSSTRUCT_CONVERSION_H_
#define _MW_UORB_BUSSTRUCT_CONVERSION_H_
#endif

View File

@ -0,0 +1,116 @@
//
// Academic License - for use in teaching, academic research, and meeting
// course requirements at degree granting institutions only. Not for
// government, commercial, or other organizational use.
//
// File: ert_main.cpp
//
// Code generated for Simulink model 'MODBUS_TCP_Test'.
//
// Model version : 1.4
// Simulink Coder version : 24.1 (R2024a) 19-Nov-2023
// C/C++ source code generated on : Fri Mar 7 20:25:14 2025
//
// Target selection: ert.tlc
// Embedded hardware selection: ARM Compatible->ARM Cortex
// Code generation objectives: Unspecified
// Validation result: Not run
//
#include <stdio.h>
#include <stdlib.h>
#include "MODBUS_TCP_Test.h"
#include "MODBUS_TCP_Test_private.h"
#include "rtwtypes.h"
#include "limits.h"
#include "MW_PX4_TaskControl.h"
#include "nuttxinitialize.h"
#define UNUSED(x) x = x
#define NAMELEN 16
// Function prototype declaration
void exitFcn(int sig);
void *terminateTask(void *arg);
void *baseRateTask(void *arg);
void *subrateTask(void *arg);
volatile boolean_T stopRequested = false;
volatile boolean_T runModel = true;
px4_sem_t stopSem;
px4_sem_t baserateTaskSem;
pthread_t schedulerThread;
pthread_t baseRateThread;
void *threadJoinStatus;
int terminatingmodel = 0;
void *baseRateTask(void *arg)
{
runModel = (rtmGetErrorStatus(MODBUS_TCP_Test_M) == (nullptr));
while (runModel) {
px4_sem_wait(&baserateTaskSem);
MODBUS_TCP_Test_step();
// Get model outputs here
stopRequested = !((rtmGetErrorStatus(MODBUS_TCP_Test_M) == (nullptr)));
}
runModel = 0;
terminateTask(arg);
pthread_exit((void *)0);
return NULL;
}
void exitFcn(int sig)
{
UNUSED(sig);
rtmSetErrorStatus(MODBUS_TCP_Test_M, "stopping the model");
runModel = 0;
}
void *terminateTask(void *arg)
{
UNUSED(arg);
terminatingmodel = 1;
{
runModel = 0;
}
MW_PX4_Terminate();
// Terminate model
MODBUS_TCP_Test_terminate();
px4_sem_post(&stopSem);
return NULL;
}
int px4_simulink_app_task_main (int argc, char *argv[])
{
px4_simulink_app_control_MAVLink();
rtmSetErrorStatus(MODBUS_TCP_Test_M, 0);
// Initialize model
MODBUS_TCP_Test_initialize();
// Call RTOS Initialization function
nuttxRTOSInit(10.0, 0);
// Wait for stop semaphore
px4_sem_wait(&stopSem);
#if (MW_NUMBER_TIMER_DRIVEN_TASKS > 0)
{
int i;
for (i=0; i < MW_NUMBER_TIMER_DRIVEN_TASKS; i++) {
CHECK_STATUS(px4_sem_destroy(&timerTaskSem[i]), 0, "px4_sem_destroy");
}
}
#endif
return 0;
}
//
// File trailer for generated code.
//
// [EOF]
//

View File

@ -0,0 +1,33 @@
//
// Academic License - for use in teaching, academic research, and meeting
// course requirements at degree granting institutions only. Not for
// government, commercial, or other organizational use.
//
// File: rtmodel.h
//
// Code generated for Simulink model 'MODBUS_TCP_Test'.
//
// Model version : 1.4
// Simulink Coder version : 24.1 (R2024a) 19-Nov-2023
// C/C++ source code generated on : Fri Mar 7 20:25:14 2025
//
// Target selection: ert.tlc
// Embedded hardware selection: ARM Compatible->ARM Cortex
// Code generation objectives: Unspecified
// Validation result: Not run
//
#ifndef rtmodel_h_
#define rtmodel_h_
#include "MODBUS_TCP_Test.h"
// Macros generated for backwards compatibility
#ifndef rtmGetStopRequested
#define rtmGetStopRequested(rtm) ((void*) 0)
#endif
#endif // rtmodel_h_
//
// File trailer for generated code.
//
// [EOF]
//

View File

@ -0,0 +1,4 @@
Simulink Coder project for MODBUS_TCP_Test using . MATLAB root = /usr/local/MATLAB/R2024a. SimStruct date: 12-Jan-2024 04:16:21
This file is generated by Simulink Coder for use by the make utility
to determine when to rebuild objects when the name of the current Simulink Coder project changes.
The rtwinfomat located at: ../slprj/ert/MODBUS_TCP_Test/tmwinternal/binfo.mat

View File

@ -0,0 +1,180 @@
//
// Academic License - for use in teaching, academic research, and meeting
// course requirements at degree granting institutions only. Not for
// government, commercial, or other organizational use.
//
// File: rtwtypes.h
//
// Code generated for Simulink model 'MODBUS_TCP_Test'.
//
// Model version : 1.4
// Simulink Coder version : 24.1 (R2024a) 19-Nov-2023
// C/C++ source code generated on : Fri Mar 7 20:25:14 2025
//
// Target selection: ert.tlc
// Embedded hardware selection: ARM Compatible->ARM Cortex
// Code generation objectives: Unspecified
// Validation result: Not run
//
#ifndef RTWTYPES_H
#define RTWTYPES_H
// Logical type definitions
#if (!defined(__cplusplus))
#ifndef false
#define false (0U)
#endif
#ifndef true
#define true (1U)
#endif
#endif
//=======================================================================*
// Target hardware information
// Device type: ARM Compatible->ARM Cortex
// Number of bits: char: 8 short: 16 int: 32
// long: 32 long long: 64
// native word size: 32
// Byte ordering: LittleEndian
// Signed integer division rounds to: Zero
// Shift right on a signed integer as arithmetic shift: on
// =======================================================================
//=======================================================================*
// Fixed width word size data types: *
// int8_T, int16_T, int32_T - signed 8, 16, or 32 bit integers *
// uint8_T, uint16_T, uint32_T - unsigned 8, 16, or 32 bit integers *
// real32_T, real64_T - 32 and 64 bit floating point numbers *
// =======================================================================
typedef signed char int8_T;
typedef unsigned char uint8_T;
typedef short int16_T;
typedef unsigned short uint16_T;
typedef int int32_T;
typedef unsigned int uint32_T;
typedef long long int64_T;
typedef unsigned long long uint64_T;
typedef float real32_T;
typedef double real64_T;
//===========================================================================*
// Generic type definitions: boolean_T, char_T, byte_T, int_T, uint_T, *
// real_T, time_T, ulong_T, ulonglong_T. *
// ===========================================================================
typedef double real_T;
typedef double time_T;
typedef unsigned char boolean_T;
typedef int int_T;
typedef unsigned int uint_T;
typedef unsigned long ulong_T;
typedef unsigned long long ulonglong_T;
typedef char char_T;
typedef unsigned char uchar_T;
typedef char_T byte_T;
//===========================================================================*
// Complex number type definitions *
// ===========================================================================
#define CREAL_T
typedef struct {
real32_T re;
real32_T im;
} creal32_T;
typedef struct {
real64_T re;
real64_T im;
} creal64_T;
typedef struct {
real_T re;
real_T im;
} creal_T;
#define CINT8_T
typedef struct {
int8_T re;
int8_T im;
} cint8_T;
#define CUINT8_T
typedef struct {
uint8_T re;
uint8_T im;
} cuint8_T;
#define CINT16_T
typedef struct {
int16_T re;
int16_T im;
} cint16_T;
#define CUINT16_T
typedef struct {
uint16_T re;
uint16_T im;
} cuint16_T;
#define CINT32_T
typedef struct {
int32_T re;
int32_T im;
} cint32_T;
#define CUINT32_T
typedef struct {
uint32_T re;
uint32_T im;
} cuint32_T;
#define CINT64_T
typedef struct {
int64_T re;
int64_T im;
} cint64_T;
#define CUINT64_T
typedef struct {
uint64_T re;
uint64_T im;
} cuint64_T;
//=======================================================================*
// Min and Max: *
// int8_T, int16_T, int32_T - signed 8, 16, or 32 bit integers *
// uint8_T, uint16_T, uint32_T - unsigned 8, 16, or 32 bit integers *
// =======================================================================
#define MAX_int8_T ((int8_T)(127))
#define MIN_int8_T ((int8_T)(-128))
#define MAX_uint8_T ((uint8_T)(255U))
#define MAX_int16_T ((int16_T)(32767))
#define MIN_int16_T ((int16_T)(-32768))
#define MAX_uint16_T ((uint16_T)(65535U))
#define MAX_int32_T ((int32_T)(2147483647))
#define MIN_int32_T ((int32_T)(-2147483647-1))
#define MAX_uint32_T ((uint32_T)(0xFFFFFFFFU))
#define MAX_int64_T ((int64_T)(9223372036854775807LL))
#define MIN_int64_T ((int64_T)(-9223372036854775807LL-1LL))
#define MAX_uint64_T ((uint64_T)(0xFFFFFFFFFFFFFFFFULL))
// Block D-Work pointer type
typedef void * pointer_T;
#endif // RTWTYPES_H
//
// File trailer for generated code.
//
// [EOF]
//

View File

@ -0,0 +1,6 @@
<?xml version="1.0" encoding="UTF-8"?>
<MF0 version="1.1" packageUris="http://schema.mathworks.com/mf0/SlCache/19700101">
<slcache.FileAttributes type="slcache.FileAttributes" uuid="6db6c3e0-4022-4dc9-b1d6-6ee8c34c34fe">
<checksum>H37imuDFiD02KFOsjdkGOrCHQGiIDB2xYv3P0axwbr/H63quSJ8DDg6D3hgdg1Xf5KAv2ihuFLCiDjrA0GzUVw==</checksum>
</slcache.FileAttributes>
</MF0>

View File

@ -0,0 +1,618 @@
#include "modbus_tcp_client.h"
#include <sys/select.h> // For select() timeout
ModbusTCPClient::ModbusTCPClient(const char* ip, int port)
: serverIP(ip), serverPort(port), socketFD(-1), transactionID(1) {}
ModbusTCPClient::~ModbusTCPClient() {
disconnectServer();
}
bool ModbusTCPClient::connectServer() {
// Step 1: If socket is already open, verify it's still connected
if (socketFD != -1) {
struct timeval timeout;
timeout.tv_sec = 0;
timeout.tv_usec = 100000; // 100ms timeout for connection check
fd_set read_fds;
FD_ZERO(&read_fds);
FD_SET(socketFD, &read_fds);
int result = select(socketFD + 1, &read_fds, NULL, NULL, &timeout);
if (result == 0) {
// No error in select, socket is still connected
printf("MODBUS_TCP_CLIENT: Already connected to MODBUS server\n");
return true;
} else {
// Connection is broken, close and reset
printf("MODBUS_TCP_CLIENT: Warning: Connection lost, reconnecting...\n");
disconnectServer();
}
}
// Step 2: Create a new socket
for (int attempts = 0; attempts < 5; attempts++) { // Retry up to 5 times
socketFD = socket(AF_INET, SOCK_STREAM, 0);
if (socketFD < 0) {
printf("MODBUS_TCP_CLIENT: Error: Could not create socket\n");
return false;
}
struct sockaddr_in serverAddr;
serverAddr.sin_family = AF_INET;
serverAddr.sin_port = htons(serverPort);
inet_pton(AF_INET, serverIP, &serverAddr.sin_addr);
// Step 3: Attempt to connect
printf("MODBUS_TCP_CLIENT: Attempting to connect to MODBUS server (Try %d)...\n", attempts + 1);
if (connect(socketFD, (struct sockaddr*)&serverAddr, sizeof(serverAddr)) == 0) {
printf("MODBUS_TCP_CLIENT: Connected to MODBUS server at %s:%d\n", serverIP, serverPort);
return true;
}
printf("MODBUS_TCP_CLIENT: Connection failed, retrying...\n");
disconnectServer(); // Close socket before retrying
usleep(100000); // Wait 100ms before retrying
}
}
void ModbusTCPClient::disconnectServer() {
if (socketFD != -1) {
close(socketFD);
socketFD = -1;
printf("MODBUS_TCP_CLIENT: Disconnected from MODBUS server\n");
}
}
void ModbusTCPClient::setTimeout(int milliseconds) {
timeoutMilliseconds = milliseconds;
printf("MODBUS_TCP_CLIENT: Timeout set to %d ms\n", timeoutMilliseconds);
}
bool ModbusTCPClient::isConnected() const {
return socketFD != -1;
}
bool ModbusTCPClient::reconnectServer() {
printf("MODBUS_TCP_CLIENT: Attempting manual reconnection...\n");
disconnectServer();
return connectServer();
}
bool ModbusTCPClient::sendRequest(uint8_t* request, int requestSize) {
// Ensure we're connected before sending
if (socketFD == -1) {
printf("MODBUS_TCP_CLIENT: Connection lost. Attempting to reconnect...\n");
if (!connectServer()) {
printf("MODBUS_TCP_CLIENT: Reconnection failed. Cannot send request.\n");
return false;
}
}
int bytesSent = write(socketFD, request, requestSize);
if (bytesSent <= 0) { // Detect broken connection during write
printf("MODBUS_TCP_CLIENT: Write failed, connection lost. Disconnecting...\n");
disconnectServer();
return false;
}
return bytesSent == requestSize;
return bytesSent == requestSize;
}
bool ModbusTCPClient::receiveResponse(uint8_t* response, int expectedSize) {
int totalBytesReceived = 0;
while (totalBytesReceived < expectedSize) {
struct timeval timeout;
timeout.tv_sec = timeoutMilliseconds / 1000; // Convert ms to seconds
timeout.tv_usec = (timeoutMilliseconds % 1000) * 1000; // Convert remaining ms to µs
fd_set read_fds;
FD_ZERO(&read_fds);
FD_SET(socketFD, &read_fds);
// Use select() to wait for data before reading
int ready = select(socketFD + 1, &read_fds, NULL, NULL, &timeout);
if (ready == 0) { // Timeout case
printf("MODBUS_TCP_CLIENT: Error: Timeout waiting for MODBUS response. Disconnecting...\n");
disconnectServer(); // Close socket and reset socketFD
return false;
} else if (ready < 0) { // Select failed
printf("MODBUS_TCP_CLIENT: Error: Select failed. Disconnecting...\n");
disconnectServer(); // Close socket and reset socketFD
return false;
}
// Read available data
int bytesReceived = read(socketFD, response + totalBytesReceived, expectedSize - totalBytesReceived);
if (bytesReceived <= 0) { // Connection lost or no data received
printf("MODBUS_TCP_CLIENT: Error: Connection lost. Disconnecting...\n");
disconnectServer(); // Close socket and reset socketFD
return false;
}
totalBytesReceived += bytesReceived;
}
return true;
}
void ModbusTCPClient::buildReadRequest(uint8_t* buffer, ModbusFunction functionCode, uint16_t startAddr, uint16_t quantity) {
transactionID++;
// Transaction ID
buffer[0] = transactionID >> 8;
buffer[1] = transactionID & 0xFF;
// Protocol ID, always 00 00
buffer[2] = 0x00;
buffer[3] = 0x00;
// Length (remaining bytes after Unit ID)
buffer[4] = 0x00;
buffer[5] = 0x06;
// Unit ID (Slave Address)
buffer[6] = 0x01;
// Function code
buffer[7] = static_cast<uint8_t>(functionCode);
// Start Address
buffer[8] = startAddr >> 8;
buffer[9] = startAddr & 0xFF;
// Quantity (How many coils to read)
buffer[10] = quantity >> 8;
buffer[11] = quantity & 0xFF;
}
void ModbusTCPClient::buildWriteSingleRequest(uint8_t* buffer, ModbusFunction functionCode, uint16_t address, uint16_t value) {
transactionID++;
buffer[0] = transactionID >> 8;
buffer[1] = transactionID & 0xFF;
buffer[2] = 0x00;
buffer[3] = 0x00;
buffer[4] = 0x00;
buffer[5] = 0x06;
buffer[6] = 0x01;
buffer[7] = static_cast<uint8_t>(functionCode);
buffer[8] = address >> 8;
buffer[9] = address & 0xFF;
buffer[10] = value >> 8;
buffer[11] = value & 0xFF;
}
void ModbusTCPClient::buildWriteMultipleRequest(uint8_t* buffer, ModbusFunction functionCode, uint16_t address, uint16_t count, const void* values, uint8_t byteCount) {
transactionID++;
// MODBUS TCP Header
buffer[0] = transactionID >> 8;
buffer[1] = transactionID & 0xFF;
buffer[2] = 0x00; // Protocol ID (always 0x0000)
buffer[3] = 0x00;
buffer[4] = 0x00; // Length (remaining bytes after Unit ID)
buffer[5] = 7 + byteCount;
buffer[6] = 0x01; // Unit ID
buffer[7] = static_cast<uint8_t>(functionCode); // Function Code (0x0F for coils, 0x10 for registers)
buffer[8] = address >> 8; // Start address high byte
buffer[9] = address & 0xFF; // Start address low byte
buffer[10] = count >> 8; // Quantity high byte
buffer[11] = count & 0xFF; // Quantity low byte
buffer[12] = byteCount; // Byte count
// Copy data payload manually (instead of memcpy)
const uint8_t* data = (const uint8_t*)values;
for (uint8_t i = 0; i < byteCount; i++) {
buffer[13 + i] = data[i];
}
}
ModbusError ModbusTCPClient::readCoil(int address, bool &coilState) {
uint8_t request[12];
buildReadRequest(request, ModbusFunction::READ_COIL, address, 1);
sendRequest(request, 12);
uint8_t response[10]; // Expecting 10 bytes
if (!receiveResponse(response, 10)) {
return ModbusError::TIMEOUT;
}
// Handle MODBUS exception responses (0x80 + function code)
if (response[7] & 0x80) {
printf("MODBUS_TCP_CLIENT: Error: MODBUS Exception Code %02X\n", response[8]);
return ModbusError::EXCEPTION_RESPONSE;
}
// Ensure function code matches the request (allowing for server behavior)
if (response[7] != static_cast<uint8_t>(ModbusFunction::READ_COIL)) {
printf("MODBUS_TCP_CLIENT: Warning: Unexpected function code (Expected: %02X, Got: %02X)\n",
static_cast<uint8_t>(ModbusFunction::READ_COIL), response[7]);
return ModbusError::INVALID_RESPONSE;
}
// Extract coil state (only first bit is used)
coilState = (response[9] & 0x01) != 0; // Adjusted index based on 10-byte response
return ModbusError::NONE;
}
ModbusError ModbusTCPClient::readMultipleCoils(int address, int count, bool coilStates[]) {
if (count < 1 || count > 2000) {
printf("MODBUS_TCP_CLIENT: Error: Invalid coil count (1-2000 allowed)\n");
return ModbusError::INVALID_RESPONSE;
}
uint8_t request[12];
buildReadRequest(request, ModbusFunction::READ_COIL, address, count);
sendRequest(request, 12);
// Expected response size: Fixed header (9) + variable byte count
int byteCount = (count + 7) / 8; // 1 byte per 8 coils
int expectedSize = 9 + byteCount;
uint8_t response[256]; // Ensure buffer is large enough
if (!receiveResponse(response, expectedSize)) {
return ModbusError::TIMEOUT;
}
// Handle MODBUS exception responses (0x80 + function code)
if (response[7] & 0x80) {
printf("MODBUS_TCP_CLIENT: Error: MODBUS Exception Code %02X\n", response[8]);
return ModbusError::EXCEPTION_RESPONSE;
}
// Ensure the function code matches
if (response[7] != static_cast<uint8_t>(ModbusFunction::READ_COIL)) {
printf("MODBUS_TCP_CLIENT: Warning: Unexpected function code (Expected: %02X, Got: %02X)\n",
static_cast<uint8_t>(ModbusFunction::READ_COIL), response[7]);
return ModbusError::INVALID_RESPONSE;
}
// Read coil values
for (int i = 0; i < count; i++) {
int byteIndex = 9 + (i / 8); // Data starts at index 9
int bitIndex = i % 8;
coilStates[i] = (response[byteIndex] >> bitIndex) & 0x01;
}
return ModbusError::NONE;
}
ModbusError ModbusTCPClient::readDiscreteInput(int address, bool &discreteInput) {
uint8_t request[12];
buildReadRequest(request, ModbusFunction::READ_DISCRETE_INPUT, address, 1);
sendRequest(request, 12);
uint8_t response[10]; // Expected response size
if (!receiveResponse(response, 10)) {
return ModbusError::TIMEOUT;
}
// Handle MODBUS exception responses (0x80 + function code)
if (response[7] & 0x80) {
printf("MODBUS_TCP_CLIENT: Error: MODBUS Exception Code %02X\n", response[8]);
return ModbusError::EXCEPTION_RESPONSE;
}
// Ensure function code matches the request
if (response[7] != static_cast<uint8_t>(ModbusFunction::READ_DISCRETE_INPUT)) {
printf("MODBUS_TCP_CLIENT: Warning: Unexpected function code (Expected: %02X, Got: %02X)\n",
static_cast<uint8_t>(ModbusFunction::READ_DISCRETE_INPUT), response[7]);
return ModbusError::INVALID_RESPONSE;
}
// Extract single discrete input state
discreteInput = (response[9] & 0x01) != 0;
return ModbusError::NONE; // Success
}
ModbusError ModbusTCPClient::readMultipleDiscreteInputs(int address, int count, bool discreteInputs[]) {
if (count < 1 || count > 2000) {
printf("MODBUS_TCP_CLIENT: Error: Invalid discrete input count (1-2000 allowed)\n");
return ModbusError::INVALID_RESPONSE;
}
uint8_t request[12];
buildReadRequest(request, ModbusFunction::READ_DISCRETE_INPUT, address, count);
sendRequest(request, 12);
// Expected response size: Fixed header (9) + variable byte count
int byteCount = (count + 7) / 8; // 1 byte per 8 inputs
int expectedSize = 9 + byteCount;
uint8_t response[256]; // Ensure buffer is large enough
if (!receiveResponse(response, expectedSize)) {
return ModbusError::TIMEOUT;
}
// Handle MODBUS exception responses (0x80 + function code)
if (response[7] & 0x80) {
printf("MODBUS_TCP_CLIENT: Error: MODBUS Exception Code %02X\n", response[8]);
return ModbusError::EXCEPTION_RESPONSE;
}
// Ensure the function code matches
if (response[7] != static_cast<uint8_t>(ModbusFunction::READ_DISCRETE_INPUT)) {
printf("MODBUS_TCP_CLIENT: Warning: Unexpected function code (Expected: %02X, Got: %02X)\n",
static_cast<uint8_t>(ModbusFunction::READ_DISCRETE_INPUT), response[7]);
return ModbusError::INVALID_RESPONSE;
}
// Read discrete input values
for (int i = 0; i < count; i++) {
int byteIndex = 9 + (i / 8); // Data starts at index 9
int bitIndex = i % 8;
discreteInputs[i] = (response[byteIndex] >> bitIndex) & 0x01;
}
return ModbusError::NONE;
}
ModbusError ModbusTCPClient::readHoldingRegister(int address, uint16_t &holdingRegister) {
uint8_t request[12];
buildReadRequest(request, ModbusFunction::READ_HOLDING_REGISTER, address, 1);
sendRequest(request, 12);
uint8_t response[11]; // Expected response size for reading 1 register
if (!receiveResponse(response, 11)) {
return ModbusError::TIMEOUT;
}
// Handle MODBUS exception responses (0x80 + function code)
if (response[7] & 0x80) {
printf("MODBUS_TCP_CLIENT: Error: MODBUS Exception Code %02X\n", response[8]);
return ModbusError::EXCEPTION_RESPONSE;
}
// Ensure function code matches the request
if (response[7] != static_cast<uint8_t>(ModbusFunction::READ_HOLDING_REGISTER)) {
printf("MODBUS_TCP_CLIENT: Warning: Unexpected function code (Expected: %02X, Got: %02X)\n",
static_cast<uint8_t>(ModbusFunction::READ_HOLDING_REGISTER), response[7]);
return ModbusError::INVALID_RESPONSE;
}
// Extract holding register value (Big-endian format)
holdingRegister = (response[9] << 8) | response[10];
return ModbusError::NONE; // Success
}
ModbusError ModbusTCPClient::readMultipleHoldingRegisters(int address, int count, uint16_t holdingRegisters[]) {
if (count < 1 || count > 125) { // MODBUS limits reading up to 125 registers per request
printf("MODBUS_TCP_CLIENT: Error: Invalid holding register count (1-125 allowed)\n");
return ModbusError::INVALID_RESPONSE;
}
uint8_t request[12];
buildReadRequest(request, ModbusFunction::READ_HOLDING_REGISTER, address, count);
sendRequest(request, 12);
// Expected response size: 9-byte header + 2 * count registers
int expectedSize = 9 + (count * 2);
uint8_t response[256]; // Ensure buffer is large enough
if (!receiveResponse(response, expectedSize)) {
return ModbusError::TIMEOUT;
}
// Handle MODBUS exception responses (0x80 + function code)
if (response[7] & 0x80) {
printf("MODBUS_TCP_CLIENT: Error: MODBUS Exception Code %02X\n", response[8]);
return ModbusError::EXCEPTION_RESPONSE;
}
// Ensure function code matches the request
if (response[7] != static_cast<uint8_t>(ModbusFunction::READ_HOLDING_REGISTER)) {
printf("MODBUS_TCP_CLIENT: Warning: Unexpected function code (Expected: %02X, Got: %02X)\n",
static_cast<uint8_t>(ModbusFunction::READ_HOLDING_REGISTER), response[7]);
return ModbusError::INVALID_RESPONSE;
}
// Extract register values (each register is 2 bytes, big-endian)
for (int i = 0; i < count; i++) {
holdingRegisters[i] = (response[9 + (i * 2)] << 8) | response[10 + (i * 2)];
}
return ModbusError::NONE;
}
ModbusError ModbusTCPClient::readInputRegister(int address, uint16_t &inputRegister) {
uint8_t request[12];
buildReadRequest(request, ModbusFunction::READ_INPUT_REGISTER, address, 1);
sendRequest(request, 12);
uint8_t response[11]; // Expected response size for reading 1 register
if (!receiveResponse(response, 11)) {
return ModbusError::TIMEOUT;
}
// Handle MODBUS exception responses (0x80 + function code)
if (response[7] & 0x80) {
printf("MODBUS_TCP_CLIENT: Error: MODBUS Exception Code %02X\n", response[8]);
return ModbusError::EXCEPTION_RESPONSE;
}
// Ensure function code matches the request
if (response[7] != static_cast<uint8_t>(ModbusFunction::READ_INPUT_REGISTER)) {
printf("MODBUS_TCP_CLIENT: Warning: Unexpected function code (Expected: %02X, Got: %02X)\n",
static_cast<uint8_t>(ModbusFunction::READ_INPUT_REGISTER), response[7]);
return ModbusError::INVALID_RESPONSE;
}
// Extract input register value (Big-endian format)
inputRegister = (response[9] << 8) | response[10];
return ModbusError::NONE; // Success
}
ModbusError ModbusTCPClient::readMultipleInputRegisters(int address, int count, uint16_t inputRegisters[]) {
if (count < 1 || count > 125) { // MODBUS limits reading up to 125 registers per request
printf("MODBUS_TCP_CLIENT: Error: Invalid input register count (1-125 allowed)\n");
return ModbusError::INVALID_RESPONSE;
}
uint8_t request[12];
buildReadRequest(request, ModbusFunction::READ_INPUT_REGISTER, address, count);
sendRequest(request, 12);
// Expected response size: 9-byte header + 2 * count registers
int expectedSize = 9 + (count * 2);
uint8_t response[256]; // Ensure buffer is large enough
if (!receiveResponse(response, expectedSize)) {
return ModbusError::TIMEOUT;
}
// Handle MODBUS exception responses (0x80 + function code)
if (response[7] & 0x80) {
printf("MODBUS_TCP_CLIENT: Error: MODBUS Exception Code %02X\n", response[8]);
return ModbusError::EXCEPTION_RESPONSE;
}
// Ensure function code matches the request
if (response[7] != static_cast<uint8_t>(ModbusFunction::READ_INPUT_REGISTER)) {
printf("MODBUS_TCP_CLIENT: Warning: Unexpected function code (Expected: %02X, Got: %02X)\n",
static_cast<uint8_t>(ModbusFunction::READ_INPUT_REGISTER), response[7]);
return ModbusError::INVALID_RESPONSE;
}
// Extract register values (each register is 2 bytes, big-endian)
for (int i = 0; i < count; i++) {
inputRegisters[i] = (response[9 + (i * 2)] << 8) | response[10 + (i * 2)];
}
return ModbusError::NONE;
}
ModbusError ModbusTCPClient::writeCoil(int address, bool value) {
uint8_t request[12];
buildWriteSingleRequest(request, ModbusFunction::WRITE_SINGLE_COIL, address, value ? 0xFF00 : 0x0000);
sendRequest(request, 12);
// Receive response
uint8_t response[12];
if (!receiveResponse(response, 12)) {
return ModbusError::TIMEOUT; // No response received
}
// Check if response matches request (MODBUS TCP should echo back the same request)
for (int i = 0; i < 12; i++) {
if (request[i] != response[i]) {
printf("MODBUS_TCP_CLIENT: Error: Response does not match request!\n");
return ModbusError::INVALID_RESPONSE;
}
}
return ModbusError::NONE; // Success
}
ModbusError ModbusTCPClient::writeMultipleCoils(int address, int count, const bool values[]) {
if (count < 1 || count > 1968) { // MODBUS limit: max 1968 coils per request
printf("MODBUS_TCP_CLIENT: Error: Invalid coil count (1-1968 allowed)\n");
return ModbusError::INVALID_RESPONSE;
}
int byteCount = (count + 7) / 8; // Each byte holds 8 coils
uint8_t coilData[byteCount];
// Initialize to 0 (since we may not use all bits)
for (int i = 0; i < byteCount; i++) {
coilData[i] = 0;
}
// Pack coil data into bytes
for (int i = 0; i < count; i++) {
if (values[i]) {
coilData[i / 8] |= (1 << (i % 8));
}
}
uint8_t request[13 + byteCount];
buildWriteMultipleRequest(request, ModbusFunction::WRITE_MULTIPLE_COILS, address, count, coilData, byteCount);
sendRequest(request, 13 + byteCount);
// The expected response is always **12 bytes**
uint8_t response[12];
if (!receiveResponse(response, 12)) {
return ModbusError::TIMEOUT;
}
// Ensure the response matches the **first 10 bytes**, except for byte 5 (message length byte)
for (int i = 0; i < 10; i++) {
if (i == 5) continue; // Skip byte 5 (message length field)
if (request[i] != response[i]) {
printf("MODBUS_TCP_CLIENT: Error: Response does not match request!\n");
return ModbusError::INVALID_RESPONSE;
}
}
return ModbusError::NONE; // Success
}
ModbusError ModbusTCPClient::writeHoldingRegister(int address, uint16_t value) {
uint8_t request[12];
buildWriteSingleRequest(request, ModbusFunction::WRITE_SINGLE_HOLDING_REGISTER, address, value);
sendRequest(request, 12);
// Expected response size = 12 bytes (full echo of the request)
uint8_t response[12];
if (!receiveResponse(response, 12)) {
return ModbusError::TIMEOUT;
}
// Ensure response matches request exactly (full 12 bytes)
for (int i = 0; i < 12; i++) {
if (request[i] != response[i]) {
printf("MODBUS_TCP_CLIENT: Error: Response does not match request!\n");
return ModbusError::INVALID_RESPONSE;
}
}
return ModbusError::NONE; // Success
}
ModbusError ModbusTCPClient::writeMultipleHoldingRegisters(int address, int count, const uint16_t values[]) {
if (count < 1 || count > 123) { // MODBUS limit: max 123 registers per request
printf("MODBUS_TCP_CLIENT: Error: Invalid register count (1-123 allowed)\n");
return ModbusError::INVALID_RESPONSE;
}
int byteCount = count * 2; // Each register is 2 bytes
uint8_t registerData[byteCount];
// Convert register values to byte array (big-endian format)
for (int i = 0; i < count; i++) {
registerData[i * 2] = values[i] >> 8; // High byte
registerData[i * 2 + 1] = values[i] & 0xFF; // Low byte
}
uint8_t request[13 + byteCount];
buildWriteMultipleRequest(request, ModbusFunction::WRITE_MULTIPLE_HOLDING_REGISTERS, address, count, registerData, byteCount);
sendRequest(request, 13 + byteCount);
// Expected response size = 12 bytes (first 10 bytes + 2 bytes for number of registers written)
uint8_t response[12];
if (!receiveResponse(response, 12)) {
return ModbusError::TIMEOUT;
}
// Ensure response matches request (except for byte 5)
for (int i = 0; i < 10; i++) {
if (i == 5) continue; // Skip byte 5 (message length field)
if (request[i] != response[i]) {
printf("MODBUS_TCP_CLIENT: Error: Response does not match request!\n");
return ModbusError::INVALID_RESPONSE;
}
}
return ModbusError::NONE; // Success
}

View File

@ -0,0 +1,80 @@
#ifndef MODBUS_TCP_CLIENT_H
#define MODBUS_TCP_CLIENT_H
#include <stdint.h>
#include <stdio.h>
#include <unistd.h>
#include <arpa/inet.h>
#include <sys/socket.h>
// Enum class for MODBUS function codes
enum class ModbusFunction : uint8_t {
READ_COIL = 0x01,
READ_DISCRETE_INPUT = 0x02,
READ_HOLDING_REGISTER = 0x03,
READ_INPUT_REGISTER = 0x04,
WRITE_SINGLE_COIL = 0x05,
WRITE_SINGLE_HOLDING_REGISTER = 0x06,
WRITE_MULTIPLE_COILS = 0x0F,
WRITE_MULTIPLE_HOLDING_REGISTERS = 0x10
};
enum class ModbusError {
NONE = 0, // No error
TIMEOUT, // No response from server
INVALID_RESPONSE, // Response does not match request
CONNECTION_LOST, // Connection issue
EXCEPTION_RESPONSE // MODBUS Exception response (error code)
};
class ModbusTCPClient {
public:
ModbusTCPClient(const char* ip, int port);
~ModbusTCPClient();
bool connectServer();
void disconnectServer();
// Manually disconnectServer and return reconnectServer()
bool reconnectServer();
// Set the timeout for receiving responses
void setTimeout(int milliseconds);
bool isConnected() const;
ModbusError readCoil(int address, bool &coilState);
ModbusError readMultipleCoils(int address, int count, bool coilStates[]);
ModbusError readDiscreteInput(int address, bool &discreteInput);
ModbusError readMultipleDiscreteInputs(int address, int count, bool discreteInputs[]);
ModbusError readHoldingRegister(int address, uint16_t &holdingRegister);
ModbusError readMultipleHoldingRegisters(int address, int count, uint16_t holdingRegisters[]);
ModbusError readInputRegister(int address, uint16_t &inputRegister);
ModbusError readMultipleInputRegisters(int address, int count, uint16_t inputRegisters[]);
ModbusError writeCoil(int address, bool value);
ModbusError writeMultipleCoils(int address, int count, const bool values[]);
ModbusError writeHoldingRegister(int address, uint16_t value);
ModbusError writeMultipleHoldingRegisters(int address, int count, const uint16_t values[]);
private:
const char* serverIP;
int serverPort;
int socketFD;
uint16_t transactionID;
int timeoutMilliseconds = 2000; // Default 2 second timeout on receiving responses
bool sendRequest(uint8_t* request, int requestSize);
bool receiveResponse(uint8_t* response, int expectedSize);
void buildReadRequest(uint8_t* buffer, ModbusFunction functionCode, uint16_t startAddr, uint16_t quantity);
void buildWriteSingleRequest(uint8_t* buffer, ModbusFunction functionCode, uint16_t address, uint16_t value);
void buildWriteMultipleRequest(uint8_t* buffer, ModbusFunction functionCode, uint16_t address, uint16_t count, const void* values, uint8_t byteCount);
};
#endif // MODBUS_TCP_CLIENT_H

View File

@ -0,0 +1,757 @@
#include "modbus_tcp_client.h"
#include <sys/select.h> // For select() timeout
ModbusTCPClient::ModbusTCPClient(const char* ip, int port, int numCoils, int numDI, int numIR, int numHR,
int startCoils, int startDI, int startIR, int startHR)
: serverIP(ip), serverPort(port), socketFD(-1), transactionID(1),
numCoils(numCoils), numDiscreteInputs(numDI), numInputRegisters(numIR), numHoldingRegisters(numHR),
startCoils(startCoils), startDiscreteInputs(startDI), startInputRegisters(startIR), startHoldingRegisters(startHR) {
// Allocate memory dynamically based on provided sizes
coilsRead = new bool[numCoils]();
coilsWrite = new bool[numCoils]();
discreteInputs = new bool[numDiscreteInputs]();
inputRegisters = new uint16_t[numInputRegisters]();
holdingRegistersRead = new uint16_t[numHoldingRegisters]();
holdingRegistersWrite = new uint16_t[numHoldingRegisters]();
}
ModbusTCPClient::ModbusTCPClient(const char* ip, int port)
: serverIP(ip), serverPort(port), socketFD(-1) {
/*
This constructor is if the user manually wants to call MODBUS TCP functions and not
use readAll() and writeAll() and the setters/getters
*/
// Set everything to nullptr so that readAll() and writeAll() won't work
coilsRead = nullptr;
coilsWrite = nullptr;
discreteInputs = nullptr;
inputRegisters = nullptr;
holdingRegistersRead = nullptr;
holdingRegistersWrite = nullptr;
}
ModbusTCPClient::~ModbusTCPClient() {
delete[] coilsRead;
delete[] coilsWrite;
delete[] discreteInputs;
delete[] inputRegisters;
delete[] holdingRegistersRead;
delete[] holdingRegistersWrite;
}
void ModbusTCPClient::setStartAddresses(int startCoils, int startDI, int startIR, int startHR) {
this->startCoils = startCoils;
this->startDiscreteInputs = startDI;
this->startInputRegisters = startIR;
this->startHoldingRegisters = startHR;
}
bool ModbusTCPClient::connectServer() {
// Step 1: If socket is already open, verify it's still connected
if (socketFD != -1) {
struct timeval timeout;
timeout.tv_sec = 0;
timeout.tv_usec = 100000; // 100ms timeout for connection check
fd_set read_fds;
FD_ZERO(&read_fds);
FD_SET(socketFD, &read_fds);
int result = select(socketFD + 1, &read_fds, NULL, NULL, &timeout);
if (result == 0) {
// No error in select, socket is still connected
printf("MODBUS_TCP_CLIENT: Already connected to MODBUS server\n");
return true;
} else {
// Connection is broken, close and reset
printf("MODBUS_TCP_CLIENT: Warning: Connection lost, reconnecting...\n");
disconnectServer();
}
}
// Step 2: Create a new socket
for (int attempts = 0; attempts < 5; attempts++) { // Retry up to 5 times
socketFD = socket(AF_INET, SOCK_STREAM, 0);
if (socketFD < 0) {
printf("MODBUS_TCP_CLIENT: Could not create socket\n");
return false;
}
struct sockaddr_in serverAddr;
serverAddr.sin_family = AF_INET;
serverAddr.sin_port = htons(serverPort);
inet_pton(AF_INET, serverIP, &serverAddr.sin_addr);
// Step 3: Attempt to connect
printf("MODBUS_TCP_CLIENT: Attempting to connect to MODBUS server (Try %d)...\n", attempts + 1);
if (connect(socketFD, (struct sockaddr*)&serverAddr, sizeof(serverAddr)) == 0) {
printf("MODBUS_TCP_CLIENT: Connected to MODBUS server at %s:%d\n", serverIP, serverPort);
return true;
}
printf("MODBUS_TCP_CLIENT: Connection failed, retrying...\n");
disconnectServer(); // Close socket before retrying
usleep(100000); // Wait 100ms before retrying
}
}
void ModbusTCPClient::disconnectServer() {
if (socketFD != -1) {
close(socketFD);
socketFD = -1;
printf("MODBUS_TCP_CLIENT: Disconnected from MODBUS server\n");
}
}
void ModbusTCPClient::setTimeout(int milliseconds) {
timeoutMilliseconds = milliseconds;
printf("MODBUS_TCP_CLIENT: Timeout set to %d ms\n", timeoutMilliseconds);
}
bool ModbusTCPClient::isConnected() const {
return socketFD != -1;
}
bool ModbusTCPClient::reconnectServer() {
printf("MODBUS_TCP_CLIENT: Attempting manual reconnection...\n");
disconnectServer();
return connectServer();
}
bool ModbusTCPClient::sendRequest(uint8_t* request, int requestSize) {
// Ensure we're connected before sending
if (socketFD == -1) {
printf("MODBUS_TCP_CLIENT: Connection lost. Attempting to reconnect...\n");
if (!connectServer()) {
printf("MODBUS_TCP_CLIENT: Reconnection failed. Cannot send request.\n");
return false;
}
}
int bytesSent = write(socketFD, request, requestSize);
if (bytesSent <= 0) { // Detect broken connection during write
printf("MODBUS_TCP_CLIENT: Write failed, connection lost. Disconnecting...\n");
disconnectServer();
return false;
}
return bytesSent == requestSize;
return bytesSent == requestSize;
}
bool ModbusTCPClient::receiveResponse(uint8_t* response, int expectedSize) {
int totalBytesReceived = 0;
while (totalBytesReceived < expectedSize) {
struct timeval timeout;
timeout.tv_sec = timeoutMilliseconds / 1000; // Convert ms to seconds
timeout.tv_usec = (timeoutMilliseconds % 1000) * 1000; // Convert remaining ms to µs
fd_set read_fds;
FD_ZERO(&read_fds);
FD_SET(socketFD, &read_fds);
// Use select() to wait for data before reading
int ready = select(socketFD + 1, &read_fds, NULL, NULL, &timeout);
if (ready == 0) { // Timeout case
printf("MODBUS_TCP_CLIENT: Timeout waiting for MODBUS response. Disconnecting...\n");
disconnectServer(); // Close socket and reset socketFD
return false;
} else if (ready < 0) { // Select failed
printf("MODBUS_TCP_CLIENT: Select failed. Disconnecting...\n");
disconnectServer(); // Close socket and reset socketFD
return false;
}
// Read available data
int bytesReceived = read(socketFD, response + totalBytesReceived, expectedSize - totalBytesReceived);
if (bytesReceived <= 0) { // Connection lost or no data received
printf("MODBUS_TCP_CLIENT: Connection lost. Disconnecting...\n");
disconnectServer(); // Close socket and reset socketFD
return false;
}
totalBytesReceived += bytesReceived;
}
return true;
}
void ModbusTCPClient::buildReadRequest(uint8_t* buffer, ModbusFunction functionCode, uint16_t startAddr, uint16_t quantity) {
transactionID++;
// Transaction ID
buffer[0] = transactionID >> 8;
buffer[1] = transactionID & 0xFF;
// Protocol ID, always 00 00
buffer[2] = 0x00;
buffer[3] = 0x00;
// Length (remaining bytes after Unit ID)
buffer[4] = 0x00;
buffer[5] = 0x06;
// Unit ID (Slave Address)
buffer[6] = 0x01;
// Function code
buffer[7] = static_cast<uint8_t>(functionCode);
// Start Address
buffer[8] = startAddr >> 8;
buffer[9] = startAddr & 0xFF;
// Quantity (How many coils to read)
buffer[10] = quantity >> 8;
buffer[11] = quantity & 0xFF;
}
void ModbusTCPClient::buildWriteSingleRequest(uint8_t* buffer, ModbusFunction functionCode, uint16_t address, uint16_t value) {
transactionID++;
buffer[0] = transactionID >> 8;
buffer[1] = transactionID & 0xFF;
buffer[2] = 0x00;
buffer[3] = 0x00;
buffer[4] = 0x00;
buffer[5] = 0x06;
buffer[6] = 0x01;
buffer[7] = static_cast<uint8_t>(functionCode);
buffer[8] = address >> 8;
buffer[9] = address & 0xFF;
buffer[10] = value >> 8;
buffer[11] = value & 0xFF;
}
void ModbusTCPClient::buildWriteMultipleRequest(uint8_t* buffer, ModbusFunction functionCode, uint16_t address, uint16_t count, const void* values, uint8_t byteCount) {
transactionID++;
// MODBUS TCP Header
buffer[0] = transactionID >> 8;
buffer[1] = transactionID & 0xFF;
buffer[2] = 0x00; // Protocol ID (always 0x0000)
buffer[3] = 0x00;
buffer[4] = 0x00; // Length (remaining bytes after Unit ID)
buffer[5] = 7 + byteCount;
buffer[6] = 0x01; // Unit ID
buffer[7] = static_cast<uint8_t>(functionCode); // Function Code (0x0F for coils, 0x10 for registers)
buffer[8] = address >> 8; // Start address high byte
buffer[9] = address & 0xFF; // Start address low byte
buffer[10] = count >> 8; // Quantity high byte
buffer[11] = count & 0xFF; // Quantity low byte
buffer[12] = byteCount; // Byte count
// Copy data payload manually (instead of memcpy)
const uint8_t* data = (const uint8_t*)values;
for (uint8_t i = 0; i < byteCount; i++) {
buffer[13 + i] = data[i];
}
}
ModbusError ModbusTCPClient::readCoil(int address, bool &coilState) {
uint8_t request[12];
buildReadRequest(request, ModbusFunction::READ_COIL, address, 1);
sendRequest(request, 12);
uint8_t response[10]; // Expecting 10 bytes
if (!receiveResponse(response, 10)) {
return ModbusError::TIMEOUT;
}
// Handle MODBUS exception responses (0x80 + function code)
if (response[7] & 0x80) {
printf("MODBUS_TCP_CLIENT: MODBUS Exception Code %02X\n", response[8]);
return ModbusError::EXCEPTION_RESPONSE;
}
// Ensure function code matches the request (allowing for server behavior)
if (response[7] != static_cast<uint8_t>(ModbusFunction::READ_COIL)) {
printf("MODBUS_TCP_CLIENT: Warning: Unexpected function code (Expected: %02X, Got: %02X)\n",
static_cast<uint8_t>(ModbusFunction::READ_COIL), response[7]);
return ModbusError::INVALID_RESPONSE;
}
// Extract coil state (only first bit is used)
coilState = (response[9] & 0x01) != 0; // Adjusted index based on 10-byte response
return ModbusError::NONE;
}
ModbusError ModbusTCPClient::readMultipleCoils(int address, int count, bool coilStates[]) {
if (count < 1 || count > 2000) {
printf("MODBUS_TCP_CLIENT: Invalid coil count (1-2000 allowed)\n");
return ModbusError::INVALID_RESPONSE;
}
uint8_t request[12];
buildReadRequest(request, ModbusFunction::READ_COIL, address, count);
sendRequest(request, 12);
// Expected response size: Fixed header (9) + variable byte count
int byteCount = (count + 7) / 8; // 1 byte per 8 coils
int expectedSize = 9 + byteCount;
uint8_t response[256]; // Ensure buffer is large enough
if (!receiveResponse(response, expectedSize)) {
return ModbusError::TIMEOUT;
}
// Handle MODBUS exception responses (0x80 + function code)
if (response[7] & 0x80) {
printf("MODBUS_TCP_CLIENT: MODBUS Exception Code %02X\n", response[8]);
return ModbusError::EXCEPTION_RESPONSE;
}
// Ensure the function code matches
if (response[7] != static_cast<uint8_t>(ModbusFunction::READ_COIL)) {
printf("MODBUS_TCP_CLIENT: Warning: Unexpected function code (Expected: %02X, Got: %02X)\n",
static_cast<uint8_t>(ModbusFunction::READ_COIL), response[7]);
return ModbusError::INVALID_RESPONSE;
}
// Read coil values
for (int i = 0; i < count; i++) {
int byteIndex = 9 + (i / 8); // Data starts at index 9
int bitIndex = i % 8;
coilStates[i] = (response[byteIndex] >> bitIndex) & 0x01;
}
return ModbusError::NONE;
}
ModbusError ModbusTCPClient::readDiscreteInput(int address, bool &discreteInput) {
uint8_t request[12];
buildReadRequest(request, ModbusFunction::READ_DISCRETE_INPUT, address, 1);
sendRequest(request, 12);
uint8_t response[10]; // Expected response size
if (!receiveResponse(response, 10)) {
return ModbusError::TIMEOUT;
}
// Handle MODBUS exception responses (0x80 + function code)
if (response[7] & 0x80) {
printf("MODBUS_TCP_CLIENT: MODBUS Exception Code %02X\n", response[8]);
return ModbusError::EXCEPTION_RESPONSE;
}
// Ensure function code matches the request
if (response[7] != static_cast<uint8_t>(ModbusFunction::READ_DISCRETE_INPUT)) {
printf("MODBUS_TCP_CLIENT: Warning: Unexpected function code (Expected: %02X, Got: %02X)\n",
static_cast<uint8_t>(ModbusFunction::READ_DISCRETE_INPUT), response[7]);
return ModbusError::INVALID_RESPONSE;
}
// Extract single discrete input state
discreteInput = (response[9] & 0x01) != 0;
return ModbusError::NONE; // Success
}
ModbusError ModbusTCPClient::readMultipleDiscreteInputs(int address, int count, bool discreteInputs[]) {
if (count < 1 || count > 2000) {
printf("MODBUS_TCP_CLIENT: Invalid discrete input count (1-2000 allowed)\n");
return ModbusError::INVALID_RESPONSE;
}
uint8_t request[12];
buildReadRequest(request, ModbusFunction::READ_DISCRETE_INPUT, address, count);
sendRequest(request, 12);
// Expected response size: Fixed header (9) + variable byte count
int byteCount = (count + 7) / 8; // 1 byte per 8 inputs
int expectedSize = 9 + byteCount;
uint8_t response[256]; // Ensure buffer is large enough
if (!receiveResponse(response, expectedSize)) {
return ModbusError::TIMEOUT;
}
// Handle MODBUS exception responses (0x80 + function code)
if (response[7] & 0x80) {
printf("MODBUS_TCP_CLIENT: MODBUS Exception Code %02X\n", response[8]);
return ModbusError::EXCEPTION_RESPONSE;
}
// Ensure the function code matches
if (response[7] != static_cast<uint8_t>(ModbusFunction::READ_DISCRETE_INPUT)) {
printf("MODBUS_TCP_CLIENT: Warning: Unexpected function code (Expected: %02X, Got: %02X)\n",
static_cast<uint8_t>(ModbusFunction::READ_DISCRETE_INPUT), response[7]);
return ModbusError::INVALID_RESPONSE;
}
// Read discrete input values
for (int i = 0; i < count; i++) {
int byteIndex = 9 + (i / 8); // Data starts at index 9
int bitIndex = i % 8;
discreteInputs[i] = (response[byteIndex] >> bitIndex) & 0x01;
}
return ModbusError::NONE;
}
ModbusError ModbusTCPClient::readHoldingRegister(int address, uint16_t &holdingRegister) {
uint8_t request[12];
buildReadRequest(request, ModbusFunction::READ_HOLDING_REGISTER, address, 1);
sendRequest(request, 12);
uint8_t response[11]; // Expected response size for reading 1 register
if (!receiveResponse(response, 11)) {
return ModbusError::TIMEOUT;
}
// Handle MODBUS exception responses (0x80 + function code)
if (response[7] & 0x80) {
printf("MODBUS_TCP_CLIENT: MODBUS Exception Code %02X\n", response[8]);
return ModbusError::EXCEPTION_RESPONSE;
}
// Ensure function code matches the request
if (response[7] != static_cast<uint8_t>(ModbusFunction::READ_HOLDING_REGISTER)) {
printf("MODBUS_TCP_CLIENT: Warning: Unexpected function code (Expected: %02X, Got: %02X)\n",
static_cast<uint8_t>(ModbusFunction::READ_HOLDING_REGISTER), response[7]);
return ModbusError::INVALID_RESPONSE;
}
// Extract holding register value (Big-endian format)
holdingRegister = (response[9] << 8) | response[10];
return ModbusError::NONE; // Success
}
ModbusError ModbusTCPClient::readMultipleHoldingRegisters(int address, int count, uint16_t holdingRegisters[]) {
if (count < 1 || count > 125) { // MODBUS limits reading up to 125 registers per request
printf("MODBUS_TCP_CLIENT: Invalid holding register count (1-125 allowed)\n");
return ModbusError::INVALID_RESPONSE;
}
uint8_t request[12];
buildReadRequest(request, ModbusFunction::READ_HOLDING_REGISTER, address, count);
sendRequest(request, 12);
// Expected response size: 9-byte header + 2 * count registers
int expectedSize = 9 + (count * 2);
uint8_t response[256]; // Ensure buffer is large enough
if (!receiveResponse(response, expectedSize)) {
return ModbusError::TIMEOUT;
}
// Handle MODBUS exception responses (0x80 + function code)
if (response[7] & 0x80) {
printf("MODBUS_TCP_CLIENT: MODBUS Exception Code %02X\n", response[8]);
return ModbusError::EXCEPTION_RESPONSE;
}
// Ensure function code matches the request
if (response[7] != static_cast<uint8_t>(ModbusFunction::READ_HOLDING_REGISTER)) {
printf("MODBUS_TCP_CLIENT: Warning: Unexpected function code (Expected: %02X, Got: %02X)\n",
static_cast<uint8_t>(ModbusFunction::READ_HOLDING_REGISTER), response[7]);
return ModbusError::INVALID_RESPONSE;
}
// Extract register values (each register is 2 bytes, big-endian)
for (int i = 0; i < count; i++) {
holdingRegisters[i] = (response[9 + (i * 2)] << 8) | response[10 + (i * 2)];
}
return ModbusError::NONE;
}
ModbusError ModbusTCPClient::readInputRegister(int address, uint16_t &inputRegister) {
uint8_t request[12];
buildReadRequest(request, ModbusFunction::READ_INPUT_REGISTER, address, 1);
sendRequest(request, 12);
uint8_t response[11]; // Expected response size for reading 1 register
if (!receiveResponse(response, 11)) {
return ModbusError::TIMEOUT;
}
// Handle MODBUS exception responses (0x80 + function code)
if (response[7] & 0x80) {
printf("MODBUS_TCP_CLIENT: MODBUS Exception Code %02X\n", response[8]);
return ModbusError::EXCEPTION_RESPONSE;
}
// Ensure function code matches the request
if (response[7] != static_cast<uint8_t>(ModbusFunction::READ_INPUT_REGISTER)) {
printf("MODBUS_TCP_CLIENT: Warning: Unexpected function code (Expected: %02X, Got: %02X)\n",
static_cast<uint8_t>(ModbusFunction::READ_INPUT_REGISTER), response[7]);
return ModbusError::INVALID_RESPONSE;
}
// Extract input register value (Big-endian format)
inputRegister = (response[9] << 8) | response[10];
return ModbusError::NONE; // Success
}
ModbusError ModbusTCPClient::readMultipleInputRegisters(int address, int count, uint16_t inputRegisters[]) {
if (count < 1 || count > 125) { // MODBUS limits reading up to 125 registers per request
printf("MODBUS_TCP_CLIENT: Invalid input register count (1-125 allowed)\n");
return ModbusError::INVALID_RESPONSE;
}
uint8_t request[12];
buildReadRequest(request, ModbusFunction::READ_INPUT_REGISTER, address, count);
sendRequest(request, 12);
// Expected response size: 9-byte header + 2 * count registers
int expectedSize = 9 + (count * 2);
uint8_t response[256]; // Ensure buffer is large enough
if (!receiveResponse(response, expectedSize)) {
return ModbusError::TIMEOUT;
}
// Handle MODBUS exception responses (0x80 + function code)
if (response[7] & 0x80) {
printf("MODBUS_TCP_CLIENT: MODBUS Exception Code %02X\n", response[8]);
return ModbusError::EXCEPTION_RESPONSE;
}
// Ensure function code matches the request
if (response[7] != static_cast<uint8_t>(ModbusFunction::READ_INPUT_REGISTER)) {
printf("MODBUS_TCP_CLIENT: Warning: Unexpected function code (Expected: %02X, Got: %02X)\n",
static_cast<uint8_t>(ModbusFunction::READ_INPUT_REGISTER), response[7]);
return ModbusError::INVALID_RESPONSE;
}
// Extract register values (each register is 2 bytes, big-endian)
for (int i = 0; i < count; i++) {
inputRegisters[i] = (response[9 + (i * 2)] << 8) | response[10 + (i * 2)];
}
return ModbusError::NONE;
}
ModbusError ModbusTCPClient::writeCoil(int address, bool value) {
uint8_t request[12];
buildWriteSingleRequest(request, ModbusFunction::WRITE_SINGLE_COIL, address, value ? 0xFF00 : 0x0000);
sendRequest(request, 12);
// Receive response
uint8_t response[12];
if (!receiveResponse(response, 12)) {
return ModbusError::TIMEOUT; // No response received
}
// Check if response matches request (MODBUS TCP should echo back the same request)
for (int i = 0; i < 12; i++) {
if (request[i] != response[i]) {
printf("MODBUS_TCP_CLIENT: Response does not match request!\n");
return ModbusError::INVALID_RESPONSE;
}
}
return ModbusError::NONE; // Success
}
ModbusError ModbusTCPClient::writeMultipleCoils(int address, int count, const bool values[]) {
if (count < 1 || count > 1968) { // MODBUS limit: max 1968 coils per request
printf("MODBUS_TCP_CLIENT: Invalid coil count (1-1968 allowed)\n");
return ModbusError::INVALID_RESPONSE;
}
int byteCount = (count + 7) / 8; // Each byte holds 8 coils
uint8_t coilData[byteCount];
// Initialize to 0 (since we may not use all bits)
for (int i = 0; i < byteCount; i++) {
coilData[i] = 0;
}
// Pack coil data into bytes
for (int i = 0; i < count; i++) {
if (values[i]) {
coilData[i / 8] |= (1 << (i % 8));
}
}
uint8_t request[13 + byteCount];
buildWriteMultipleRequest(request, ModbusFunction::WRITE_MULTIPLE_COILS, address, count, coilData, byteCount);
sendRequest(request, 13 + byteCount);
// The expected response is always **12 bytes**
uint8_t response[12];
if (!receiveResponse(response, 12)) {
return ModbusError::TIMEOUT;
}
// Ensure the response matches the **first 10 bytes**, except for byte 5 (message length byte)
for (int i = 0; i < 10; i++) {
if (i == 5) continue; // Skip byte 5 (message length field)
if (request[i] != response[i]) {
printf("MODBUS_TCP_CLIENT: Response does not match request!\n");
return ModbusError::INVALID_RESPONSE;
}
}
return ModbusError::NONE; // Success
}
ModbusError ModbusTCPClient::writeHoldingRegister(int address, uint16_t value) {
uint8_t request[12];
buildWriteSingleRequest(request, ModbusFunction::WRITE_SINGLE_HOLDING_REGISTER, address, value);
sendRequest(request, 12);
// Expected response size = 12 bytes (full echo of the request)
uint8_t response[12];
if (!receiveResponse(response, 12)) {
return ModbusError::TIMEOUT;
}
// Ensure response matches request exactly (full 12 bytes)
for (int i = 0; i < 12; i++) {
if (request[i] != response[i]) {
printf("MODBUS_TCP_CLIENT: Response does not match request!\n");
return ModbusError::INVALID_RESPONSE;
}
}
return ModbusError::NONE; // Success
}
ModbusError ModbusTCPClient::writeMultipleHoldingRegisters(int address, int count, const uint16_t values[]) {
if (count < 1 || count > 123) { // MODBUS limit: max 123 registers per request
printf("MODBUS_TCP_CLIENT: Invalid register count (1-123 allowed)\n");
return ModbusError::INVALID_RESPONSE;
}
int byteCount = count * 2; // Each register is 2 bytes
uint8_t registerData[byteCount];
// Convert register values to byte array (big-endian format)
for (int i = 0; i < count; i++) {
registerData[i * 2] = values[i] >> 8; // High byte
registerData[i * 2 + 1] = values[i] & 0xFF; // Low byte
}
uint8_t request[13 + byteCount];
buildWriteMultipleRequest(request, ModbusFunction::WRITE_MULTIPLE_HOLDING_REGISTERS, address, count, registerData, byteCount);
sendRequest(request, 13 + byteCount);
// Expected response size = 12 bytes (first 10 bytes + 2 bytes for number of registers written)
uint8_t response[12];
if (!receiveResponse(response, 12)) {
return ModbusError::TIMEOUT;
}
// Ensure response matches request (except for byte 5)
for (int i = 0; i < 10; i++) {
if (i == 5) continue; // Skip byte 5 (message length field)
if (request[i] != response[i]) {
printf("MODBUS_TCP_CLIENT: Response does not match request!\n");
return ModbusError::INVALID_RESPONSE;
}
}
return ModbusError::NONE; // Success
}
ModbusError ModbusTCPClient::readAll() {
/*
Reads every coil, discrete input, input register, and holding register
assuming that they start at address 0
*/
if (coilsRead == nullptr && discreteInputs == nullptr &&
inputRegisters == nullptr && holdingRegistersRead == nullptr) {
printf("MODBUS_TCP_CLIENT: readAll() called, but wrong constructor was used.\n");
return ModbusError::INVALID_REQUEST;
}
ModbusError error = ModbusError::NONE;
if (coilsRead != nullptr) {
error = readMultipleCoils(startCoils, numCoils, coilsRead);
if (error != ModbusError::NONE) return error;
}
if (discreteInputs != nullptr) {
error = readMultipleDiscreteInputs(startDiscreteInputs, numDiscreteInputs, discreteInputs);
if (error != ModbusError::NONE) return error;
}
if (inputRegisters != nullptr) {
error = readMultipleInputRegisters(startInputRegisters, numInputRegisters, inputRegisters);
if (error != ModbusError::NONE) return error;
}
if (holdingRegistersRead != nullptr) {
error = readMultipleHoldingRegisters(startHoldingRegisters, numHoldingRegisters, holdingRegistersRead);
}
return error;
}
ModbusError ModbusTCPClient::writeAll() {
/*
Reads every coil and holding register assuming that they start at address 0
*/
if (coilsWrite == nullptr && holdingRegistersWrite) {
printf("MODBUS_TCP_CLIENT: writeAll() called, but wrong constructor was used.\n");
return ModbusError::INVALID_REQUEST;
}
ModbusError error = ModbusError::NONE;
if (coilsWrite != nullptr) {
error = writeMultipleCoils(startCoils, numCoils, coilsWrite);
if (error != ModbusError::NONE) return error;
}
if (holdingRegistersWrite != nullptr) {
error = writeMultipleHoldingRegisters(startHoldingRegisters, numHoldingRegisters, holdingRegistersWrite);
}
return error;
}
// Setters for writing values (preferred to be used)
void ModbusTCPClient::setCoil(int address, bool value) {
if (address >= 0 && address < numCoils) {
coilsWrite[address] = value;
}
}
void ModbusTCPClient::setHoldingRegister(int address, uint16_t value) {
if (address >= 0 && address < numHoldingRegisters) {
holdingRegistersWrite[address] = value;
}
}
// Getters (preferred to be used as long as readAll is being called)
bool ModbusTCPClient::getCoil(int address) const {
return (address >= 0 && address < numCoils) ? coilsRead[address] : false;
}
bool ModbusTCPClient::getDesiredCoil(int address) const {
return (address >= 0 && address < numCoils) ? coilsWrite[address] : false;
}
bool ModbusTCPClient::getDiscreteInput(int address) const {
return (address >= 0 && address < numDiscreteInputs) ? discreteInputs[address] : false;
}
uint16_t ModbusTCPClient::getHoldingRegister(int address) const {
return (address >= 0 && address < numHoldingRegisters) ? holdingRegistersRead[address] : 0;
}
uint16_t ModbusTCPClient::getDesiredHoldingRegister(int address) const {
return (address >= 0 && address < numHoldingRegisters) ? holdingRegistersWrite[address] : 0;
}
uint16_t ModbusTCPClient::getInputRegister(int address) const {
return (address >= 0 && address < numInputRegisters) ? inputRegisters[address] : 0;
}

View File

@ -0,0 +1,115 @@
#ifndef MODBUS_TCP_CLIENT_H
#define MODBUS_TCP_CLIENT_H
#include <stdint.h>
#include <stdio.h>
#include <unistd.h>
#include <arpa/inet.h>
#include <sys/socket.h>
// Enum class for MODBUS function codes
enum class ModbusFunction : uint8_t {
READ_COIL = 0x01,
READ_DISCRETE_INPUT = 0x02,
READ_HOLDING_REGISTER = 0x03,
READ_INPUT_REGISTER = 0x04,
WRITE_SINGLE_COIL = 0x05,
WRITE_SINGLE_HOLDING_REGISTER = 0x06,
WRITE_MULTIPLE_COILS = 0x0F,
WRITE_MULTIPLE_HOLDING_REGISTERS = 0x10
};
enum class ModbusError {
NONE = 0, // No error
TIMEOUT, // No response from server
INVALID_RESPONSE, // Response does not match request
CONNECTION_LOST, // Connection issue
EXCEPTION_RESPONSE, // MODBUS Exception response (error code)
INVALID_REQUEST, // User tries doing something they shouldn't
};
class ModbusTCPClient {
public:
ModbusTCPClient(const char* ip, int port); // Extra constructor that does CANNOT use readAll() or writeAll()
ModbusTCPClient(const char* ip, int port, int numCoils, int numDI, int numIR, int numHR,
int startCoils = 0, int startDI = 0, int startIR = 0, int startHR = 0);
~ModbusTCPClient();
// Set the start address of each type. Either use this after creating the object or put them in the constructor
void setStartAddresses(int startCoils, int startDI, int startIR, int startHR);
bool connectServer();
void disconnectServer();
bool isConnected() const;
// Manually disconnectServer and return reconnectServer()
bool reconnectServer();
// Set the timeout for receiving responses
void setTimeout(int milliseconds);
// Setters (preferred to be used when calling writeAll())
void setCoil(int address, bool value);
void setHoldingRegister(int address, uint16_t value);
// Getters (preferred to be used when calling readAll())
bool getCoil(int address) const;
bool getDesiredCoil(int address) const; // Retrieves the "to be written" value
bool getDiscreteInput(int address) const;
uint16_t getHoldingRegister(int address) const;
uint16_t getDesiredHoldingRegister(int address) const; // Retrieves the "to be written" value
uint16_t getInputRegister(int address) const;
ModbusError readAll(); // Reads every coil, DI, IR, and HR
ModbusError writeAll(); // Writes every coil and HR
// Manual MODBUS TCP actions (not preferred to be called by user)
ModbusError readCoil(int address, bool &coilState);
ModbusError readMultipleCoils(int address, int count, bool coilStates[]);
ModbusError readDiscreteInput(int address, bool &discreteInput);
ModbusError readMultipleDiscreteInputs(int address, int count, bool discreteInputs[]);
ModbusError readHoldingRegister(int address, uint16_t &holdingRegister);
ModbusError readMultipleHoldingRegisters(int address, int count, uint16_t holdingRegisters[]);
ModbusError readInputRegister(int address, uint16_t &inputRegister);
ModbusError readMultipleInputRegisters(int address, int count, uint16_t inputRegisters[]);
ModbusError writeCoil(int address, bool value);
ModbusError writeMultipleCoils(int address, int count, const bool values[]);
ModbusError writeHoldingRegister(int address, uint16_t value);
ModbusError writeMultipleHoldingRegisters(int address, int count, const uint16_t values[]);
private:
// TCP settings
const char* serverIP;
int serverPort;
int socketFD;
uint16_t transactionID;
int timeoutMilliseconds = 2000; // Default 2 second timeout on receiving responses
// Storing MODBUS register information
int numCoils, numDiscreteInputs, numInputRegisters, numHoldingRegisters;
int startCoils, startDiscreteInputs, startInputRegisters, startHoldingRegisters; // The start address of each type of register
bool* coilsRead; // Stores the actual state of coils on the MODBUS server
bool* coilsWrite; // Stores the desired state of coils to be written
bool* discreteInputs; // Only read from the MODBUS server (no writes)
uint16_t* inputRegisters; // Only read from the MODBUS server
uint16_t* holdingRegistersRead; // Stores actual values from the MODBUS server
uint16_t* holdingRegistersWrite; // Stores desired values to write
bool sendRequest(uint8_t* request, int requestSize);
bool receiveResponse(uint8_t* response, int expectedSize);
void buildReadRequest(uint8_t* buffer, ModbusFunction functionCode, uint16_t startAddr, uint16_t quantity);
void buildWriteSingleRequest(uint8_t* buffer, ModbusFunction functionCode, uint16_t address, uint16_t value);
void buildWriteMultipleRequest(uint8_t* buffer, ModbusFunction functionCode, uint16_t address, uint16_t count, const void* values, uint8_t byteCount);
};
#endif // MODBUS_TCP_CLIENT_H

View File

@ -0,0 +1,66 @@
function makeInfo=rtwmakecfg()
%RTWMAKECFG.m adds include and source directories to rtw make files.
% makeInfo=RTWMAKECFG returns a structured array containing
% following field:
% makeInfo.includePath - cell array containing additional include
% directories. Those directories will be
% expanded into include instructions of Simulink
% Coder generated make files.
%
% makeInfo.sourcePath - cell array containing additional source
% directories. Those directories will be
% expanded into rules of Simulink Coder generated
% make files.
makeInfo.includePath = {};
makeInfo.sourcePath = {};
makeInfo.linkLibsObjs = {};
%<Generated by S-Function Builder 3.0. DO NOT REMOVE>
sfBuilderBlocksByMaskType = find_system(bdroot,'FollowLinks','on','LookUnderMasks','on','MaskType','S-Function Builder');
sfBuilderBlocksByCallback = find_system(bdroot,'OpenFcn','sfunctionwizard(gcbh)');
sfBuilderBlocksDeployed = find_system(bdroot,'BlockType','S-Function','SFunctionDeploymentMode','on');
sfBuilderBlocks = {sfBuilderBlocksByMaskType{:} sfBuilderBlocksByCallback{:} sfBuilderBlocksDeployed{:}};
sfBuilderBlocks = unique(sfBuilderBlocks);
if isempty(sfBuilderBlocks)
return;
end
sfBuilderBlockNameMATFile = cell(1, length(sfBuilderBlocks));
for idx = 1:length(sfBuilderBlocks)
sfBuilderBlockNameMATFile{idx} = get_param(sfBuilderBlocks{idx},'FunctionName');
sfBuilderBlockNameMATFile{idx} = ['.' filesep 'SFB__' char(sfBuilderBlockNameMATFile{idx}) '__SFB.mat'];
end
sfBuilderBlockNameMATFile = unique(sfBuilderBlockNameMATFile);
for idx = 1:length(sfBuilderBlockNameMATFile)
if exist(sfBuilderBlockNameMATFile{idx}, 'file')
loadedData = load(sfBuilderBlockNameMATFile{idx});
if isfield(loadedData,'SFBInfoStruct')
makeInfo = UpdateMakeInfo(makeInfo,loadedData.SFBInfoStruct);
clear loadedData;
end
end
end
function updatedMakeInfo = UpdateMakeInfo(makeInfo,SFBInfoStruct)
updatedMakeInfo = {};
if isfield(makeInfo,'includePath')
if isfield(SFBInfoStruct,'includePath')
updatedMakeInfo.includePath = {makeInfo.includePath{:} SFBInfoStruct.includePath{:}};
else
updatedMakeInfo.includePath = {makeInfo.includePath{:}};
end
end
if isfield(makeInfo,'sourcePath')
if isfield(SFBInfoStruct,'sourcePath')
updatedMakeInfo.sourcePath = {makeInfo.sourcePath{:} SFBInfoStruct.sourcePath{:}};
else
updatedMakeInfo.sourcePath = {makeInfo.sourcePath{:}};
end
end
if isfield(makeInfo,'linkLibsObjs')
if isfield(SFBInfoStruct,'additionalLibraries')
updatedMakeInfo.linkLibsObjs = {makeInfo.linkLibsObjs{:} SFBInfoStruct.additionalLibraries{:}};
else
updatedMakeInfo.linkLibsObjs = {makeInfo.linkLibsObjs{:}};
end
end

View File

@ -0,0 +1,46 @@
#ifndef __customcode_4eMPcfDEceM6BJ1iG0CtoD_h__
#define __customcode_4eMPcfDEceM6BJ1iG0CtoD_h__
/* Include files */
#include "mex.h"
#include <string.h>
#include <stdlib.h>
#include <math.h>
#include "tmwtypes.h"
/* Helper definitions for DLL support */
#if defined _WIN32
#define DLL_EXPORT_CC __declspec(dllexport)
#else
#if __GNUC__ >= 4
#define DLL_EXPORT_CC __attribute__ ((visibility ("default")))
#else
#define DLL_EXPORT_CC
#endif
#endif
/* Custom Code from Simulation Target dialog */
#include <netinet/in.h>
#include <sys/types.h>
#include <sys/socket.h>
#include <arpa/inet.h>
#include <errno.h>
#include <stdio.h>
#include <string.h>
#include <unistd.h>
#include <modbus.h>
/* Function Declarations */
#ifdef __cplusplus
extern "C" {
#endif
#define customcode_4eMPcfDEceM6BJ1iG0CtoD_initializer()
#define customcode_4eMPcfDEceM6BJ1iG0CtoD_terminator()
#ifdef __cplusplus
}
#endif
#endif

View File

@ -0,0 +1,283 @@
#ifndef MULTIWORD_TYPES_H
#define MULTIWORD_TYPES_H
#include "rtwtypes.h"
/*
* MultiWord supporting definitions
*/
typedef long long longlong_T;
/*
* MultiWord types
*/
typedef struct {
uint64_T chunks[2];
} int128m_T;
typedef struct {
int128m_T re;
int128m_T im;
} cint128m_T;
typedef struct {
uint64_T chunks[2];
} uint128m_T;
typedef struct {
uint128m_T re;
uint128m_T im;
} cuint128m_T;
typedef struct {
uint64_T chunks[3];
} int192m_T;
typedef struct {
int192m_T re;
int192m_T im;
} cint192m_T;
typedef struct {
uint64_T chunks[3];
} uint192m_T;
typedef struct {
uint192m_T re;
uint192m_T im;
} cuint192m_T;
typedef struct {
uint64_T chunks[4];
} int256m_T;
typedef struct {
int256m_T re;
int256m_T im;
} cint256m_T;
typedef struct {
uint64_T chunks[4];
} uint256m_T;
typedef struct {
uint256m_T re;
uint256m_T im;
} cuint256m_T;
typedef struct {
uint64_T chunks[5];
} int320m_T;
typedef struct {
int320m_T re;
int320m_T im;
} cint320m_T;
typedef struct {
uint64_T chunks[5];
} uint320m_T;
typedef struct {
uint320m_T re;
uint320m_T im;
} cuint320m_T;
typedef struct {
uint64_T chunks[6];
} int384m_T;
typedef struct {
int384m_T re;
int384m_T im;
} cint384m_T;
typedef struct {
uint64_T chunks[6];
} uint384m_T;
typedef struct {
uint384m_T re;
uint384m_T im;
} cuint384m_T;
typedef struct {
uint64_T chunks[7];
} int448m_T;
typedef struct {
int448m_T re;
int448m_T im;
} cint448m_T;
typedef struct {
uint64_T chunks[7];
} uint448m_T;
typedef struct {
uint448m_T re;
uint448m_T im;
} cuint448m_T;
typedef struct {
uint64_T chunks[8];
} int512m_T;
typedef struct {
int512m_T re;
int512m_T im;
} cint512m_T;
typedef struct {
uint64_T chunks[8];
} uint512m_T;
typedef struct {
uint512m_T re;
uint512m_T im;
} cuint512m_T;
typedef struct {
uint64_T chunks[9];
} int576m_T;
typedef struct {
int576m_T re;
int576m_T im;
} cint576m_T;
typedef struct {
uint64_T chunks[9];
} uint576m_T;
typedef struct {
uint576m_T re;
uint576m_T im;
} cuint576m_T;
typedef struct {
uint64_T chunks[10];
} int640m_T;
typedef struct {
int640m_T re;
int640m_T im;
} cint640m_T;
typedef struct {
uint64_T chunks[10];
} uint640m_T;
typedef struct {
uint640m_T re;
uint640m_T im;
} cuint640m_T;
typedef struct {
uint64_T chunks[11];
} int704m_T;
typedef struct {
int704m_T re;
int704m_T im;
} cint704m_T;
typedef struct {
uint64_T chunks[11];
} uint704m_T;
typedef struct {
uint704m_T re;
uint704m_T im;
} cuint704m_T;
typedef struct {
uint64_T chunks[12];
} int768m_T;
typedef struct {
int768m_T re;
int768m_T im;
} cint768m_T;
typedef struct {
uint64_T chunks[12];
} uint768m_T;
typedef struct {
uint768m_T re;
uint768m_T im;
} cuint768m_T;
typedef struct {
uint64_T chunks[13];
} int832m_T;
typedef struct {
int832m_T re;
int832m_T im;
} cint832m_T;
typedef struct {
uint64_T chunks[13];
} uint832m_T;
typedef struct {
uint832m_T re;
uint832m_T im;
} cuint832m_T;
typedef struct {
uint64_T chunks[14];
} int896m_T;
typedef struct {
int896m_T re;
int896m_T im;
} cint896m_T;
typedef struct {
uint64_T chunks[14];
} uint896m_T;
typedef struct {
uint896m_T re;
uint896m_T im;
} cuint896m_T;
typedef struct {
uint64_T chunks[15];
} int960m_T;
typedef struct {
int960m_T re;
int960m_T im;
} cint960m_T;
typedef struct {
uint64_T chunks[15];
} uint960m_T;
typedef struct {
uint960m_T re;
uint960m_T im;
} cuint960m_T;
typedef struct {
uint64_T chunks[16];
} int1024m_T;
typedef struct {
int1024m_T re;
int1024m_T im;
} cint1024m_T;
typedef struct {
uint64_T chunks[16];
} uint1024m_T;
typedef struct {
uint1024m_T re;
uint1024m_T im;
} cuint1024m_T;
#endif /* MULTIWORD_TYPES_H */

View File

@ -0,0 +1,61 @@
#ifndef RTWTYPES_H
#define RTWTYPES_H
#include "tmwtypes.h"
#ifndef POINTER_T
#define POINTER_T
typedef void * pointer_T;
#endif
/* Logical type definitions */
#if (!defined(__cplusplus))
#ifndef false
#define false (0U)
#endif
#ifndef true
#define true (1U)
#endif
#endif
#ifndef INT64_T
#define INT64_T
typedef long int64_T;
#define MAX_int64_T ((int64_T)(9223372036854775807L))
#define MIN_int64_T ((int64_T)(-9223372036854775807L-1L))
#endif
#ifndef UINT64_T
#define UINT64_T
typedef unsigned long uint64_T;
#define MAX_uint64_T ((uint64_T)(0xFFFFFFFFFFFFFFFFUL))
#endif
/*===========================================================================*
* Additional complex number type definitions *
*===========================================================================*/
#ifndef CINT64_T
#define CINT64_T
typedef struct {
int64_T re;
int64_T im;
} cint64_T;
#endif
#ifndef CUINT64_T
#define CUINT64_T
typedef struct {
uint64_T re;
uint64_T im;
} cuint64_T;
#endif
#endif /* RTWTYPES_H */

View File

@ -0,0 +1,38 @@
#include "customcode_4eMPcfDEceM6BJ1iG0CtoD.h"
#ifdef __cplusplus
extern "C" {
#endif
/* Type Definitions */
/* Named Constants */
/* Variable Declarations */
/* Variable Definitions */
/* Function Declarations */
DLL_EXPORT_CC extern const char_T *get_dll_checksum_4eMPcfDEceM6BJ1iG0CtoD();
DLL_EXPORT_CC extern void delete_modbus_D2x0zjof16u4aQ2mZ3NmZH_4eMPcfDEceM6BJ1iG0CtoD(void *classObj);
DLL_EXPORT_CC extern boolean_T modbus_modbus_connect_0WRDGl0sr2kL9Y9B9cYVDG_4eMPcfDEceM6BJ1iG0CtoD(void *classObj);
DLL_EXPORT_CC extern void modbus_modbus_close_rgkVO4hEl6zx8dFMSwlgxG_4eMPcfDEceM6BJ1iG0CtoD(void *classObj);
DLL_EXPORT_CC extern boolean_T modbus_is_connected_mrpACTntQJx1ozpT90ZZbF_4eMPcfDEceM6BJ1iG0CtoD(void *classObj);
DLL_EXPORT_CC extern void modbus_modbus_set_slave_id_iRLrromcI6Zf3XO6MaVAuG_4eMPcfDEceM6BJ1iG0CtoD(void *classObj, int32_T id);
DLL_EXPORT_CC extern int32_T modbus_modbus_read_coils_j2i6vGmatENgGhETRxd5k_4eMPcfDEceM6BJ1iG0CtoD(void *classObj, uint16_T address, uint16_T amount, boolean_T *buffer);
DLL_EXPORT_CC extern int32_T modbus_modbus_read_input_bits_0C7liNjeTVW5yVJal4vONF_4eMPcfDEceM6BJ1iG0CtoD(void *classObj, uint16_T address, uint16_T amount, boolean_T *buffer);
DLL_EXPORT_CC extern int32_T modbus_modbus_read_holding_registers_rjSoRF4I4FeDEliIHOmF8F_4eMPcfDEceM6BJ1iG0CtoD(void *classObj, uint16_T address, uint16_T amount, uint16_T *buffer);
DLL_EXPORT_CC extern int32_T modbus_modbus_read_input_registers_E8dlNtIy1NQr9Bv8qqFBdG_4eMPcfDEceM6BJ1iG0CtoD(void *classObj, uint16_T address, uint16_T amount, uint16_T *buffer);
DLL_EXPORT_CC extern int32_T modbus_modbus_write_coil_lnN8aQeA1YelV2trcV2SeD_4eMPcfDEceM6BJ1iG0CtoD(void *classObj, uint16_T address, const boolean_T *to_write);
DLL_EXPORT_CC extern int32_T modbus_modbus_write_register_OzpI09pzrU7CeyfMgk0MdB_4eMPcfDEceM6BJ1iG0CtoD(void *classObj, uint16_T address, const uint16_T *value);
DLL_EXPORT_CC extern int32_T modbus_modbus_write_coils_KrDRFga7PmTEFeoeaBWxPB_4eMPcfDEceM6BJ1iG0CtoD(void *classObj, uint16_T address, uint16_T amount, const boolean_T *value);
DLL_EXPORT_CC extern int32_T modbus_modbus_write_registers_Kne2GozSKYknwjXWJ8KlxC_4eMPcfDEceM6BJ1iG0CtoD(void *classObj, uint16_T address, uint16_T amount, const uint16_T *value);
DLL_EXPORT_CC extern boolean_T *get_err_modbus_D2x0zjof16u4aQ2mZ3NmZH_4eMPcfDEceM6BJ1iG0CtoD(void *classObj);
DLL_EXPORT_CC extern int32_T *get_err_no_modbus_D2x0zjof16u4aQ2mZ3NmZH_4eMPcfDEceM6BJ1iG0CtoD(void *classObj);
/* Function Definitions */
DLL_EXPORT_CC const uint8_T *get_checksum_source_info(int32_T *size);
#ifdef __cplusplus
}
#endif

View File

@ -0,0 +1,46 @@
#ifndef __customcode_CAa3eEWrwl5pAuWimVVCqH_h__
#define __customcode_CAa3eEWrwl5pAuWimVVCqH_h__
/* Include files */
#include "mex.h"
#include <string.h>
#include <stdlib.h>
#include <math.h>
#include "tmwtypes.h"
/* Helper definitions for DLL support */
#if defined _WIN32
#define DLL_EXPORT_CC __declspec(dllexport)
#else
#if __GNUC__ >= 4
#define DLL_EXPORT_CC __attribute__ ((visibility ("default")))
#else
#define DLL_EXPORT_CC
#endif
#endif
/* Custom Code from Simulation Target dialog */
#include <netinet/in.h>
#include <sys/types.h>
#include <sys/socket.h>
#include <arpa/inet.h>
#include <errno.h>
#include <stdio.h>
#include <string.h>
#include <unistd.h>
#include <nanomodbus.h>
#include <platform.h>
/* Function Declarations */
#ifdef __cplusplus
extern "C" {
#endif
#define customcode_CAa3eEWrwl5pAuWimVVCqH_initializer()
#define customcode_CAa3eEWrwl5pAuWimVVCqH_terminator()
#ifdef __cplusplus
}
#endif
#endif

View File

@ -0,0 +1,283 @@
#ifndef MULTIWORD_TYPES_H
#define MULTIWORD_TYPES_H
#include "rtwtypes.h"
/*
* MultiWord supporting definitions
*/
typedef long long longlong_T;
/*
* MultiWord types
*/
typedef struct {
uint64_T chunks[2];
} int128m_T;
typedef struct {
int128m_T re;
int128m_T im;
} cint128m_T;
typedef struct {
uint64_T chunks[2];
} uint128m_T;
typedef struct {
uint128m_T re;
uint128m_T im;
} cuint128m_T;
typedef struct {
uint64_T chunks[3];
} int192m_T;
typedef struct {
int192m_T re;
int192m_T im;
} cint192m_T;
typedef struct {
uint64_T chunks[3];
} uint192m_T;
typedef struct {
uint192m_T re;
uint192m_T im;
} cuint192m_T;
typedef struct {
uint64_T chunks[4];
} int256m_T;
typedef struct {
int256m_T re;
int256m_T im;
} cint256m_T;
typedef struct {
uint64_T chunks[4];
} uint256m_T;
typedef struct {
uint256m_T re;
uint256m_T im;
} cuint256m_T;
typedef struct {
uint64_T chunks[5];
} int320m_T;
typedef struct {
int320m_T re;
int320m_T im;
} cint320m_T;
typedef struct {
uint64_T chunks[5];
} uint320m_T;
typedef struct {
uint320m_T re;
uint320m_T im;
} cuint320m_T;
typedef struct {
uint64_T chunks[6];
} int384m_T;
typedef struct {
int384m_T re;
int384m_T im;
} cint384m_T;
typedef struct {
uint64_T chunks[6];
} uint384m_T;
typedef struct {
uint384m_T re;
uint384m_T im;
} cuint384m_T;
typedef struct {
uint64_T chunks[7];
} int448m_T;
typedef struct {
int448m_T re;
int448m_T im;
} cint448m_T;
typedef struct {
uint64_T chunks[7];
} uint448m_T;
typedef struct {
uint448m_T re;
uint448m_T im;
} cuint448m_T;
typedef struct {
uint64_T chunks[8];
} int512m_T;
typedef struct {
int512m_T re;
int512m_T im;
} cint512m_T;
typedef struct {
uint64_T chunks[8];
} uint512m_T;
typedef struct {
uint512m_T re;
uint512m_T im;
} cuint512m_T;
typedef struct {
uint64_T chunks[9];
} int576m_T;
typedef struct {
int576m_T re;
int576m_T im;
} cint576m_T;
typedef struct {
uint64_T chunks[9];
} uint576m_T;
typedef struct {
uint576m_T re;
uint576m_T im;
} cuint576m_T;
typedef struct {
uint64_T chunks[10];
} int640m_T;
typedef struct {
int640m_T re;
int640m_T im;
} cint640m_T;
typedef struct {
uint64_T chunks[10];
} uint640m_T;
typedef struct {
uint640m_T re;
uint640m_T im;
} cuint640m_T;
typedef struct {
uint64_T chunks[11];
} int704m_T;
typedef struct {
int704m_T re;
int704m_T im;
} cint704m_T;
typedef struct {
uint64_T chunks[11];
} uint704m_T;
typedef struct {
uint704m_T re;
uint704m_T im;
} cuint704m_T;
typedef struct {
uint64_T chunks[12];
} int768m_T;
typedef struct {
int768m_T re;
int768m_T im;
} cint768m_T;
typedef struct {
uint64_T chunks[12];
} uint768m_T;
typedef struct {
uint768m_T re;
uint768m_T im;
} cuint768m_T;
typedef struct {
uint64_T chunks[13];
} int832m_T;
typedef struct {
int832m_T re;
int832m_T im;
} cint832m_T;
typedef struct {
uint64_T chunks[13];
} uint832m_T;
typedef struct {
uint832m_T re;
uint832m_T im;
} cuint832m_T;
typedef struct {
uint64_T chunks[14];
} int896m_T;
typedef struct {
int896m_T re;
int896m_T im;
} cint896m_T;
typedef struct {
uint64_T chunks[14];
} uint896m_T;
typedef struct {
uint896m_T re;
uint896m_T im;
} cuint896m_T;
typedef struct {
uint64_T chunks[15];
} int960m_T;
typedef struct {
int960m_T re;
int960m_T im;
} cint960m_T;
typedef struct {
uint64_T chunks[15];
} uint960m_T;
typedef struct {
uint960m_T re;
uint960m_T im;
} cuint960m_T;
typedef struct {
uint64_T chunks[16];
} int1024m_T;
typedef struct {
int1024m_T re;
int1024m_T im;
} cint1024m_T;
typedef struct {
uint64_T chunks[16];
} uint1024m_T;
typedef struct {
uint1024m_T re;
uint1024m_T im;
} cuint1024m_T;
#endif /* MULTIWORD_TYPES_H */

View File

@ -0,0 +1,61 @@
#ifndef RTWTYPES_H
#define RTWTYPES_H
#include "tmwtypes.h"
#ifndef POINTER_T
#define POINTER_T
typedef void * pointer_T;
#endif
/* Logical type definitions */
#if (!defined(__cplusplus))
#ifndef false
#define false (0U)
#endif
#ifndef true
#define true (1U)
#endif
#endif
#ifndef INT64_T
#define INT64_T
typedef long int64_T;
#define MAX_int64_T ((int64_T)(9223372036854775807L))
#define MIN_int64_T ((int64_T)(-9223372036854775807L-1L))
#endif
#ifndef UINT64_T
#define UINT64_T
typedef unsigned long uint64_T;
#define MAX_uint64_T ((uint64_T)(0xFFFFFFFFFFFFFFFFUL))
#endif
/*===========================================================================*
* Additional complex number type definitions *
*===========================================================================*/
#ifndef CINT64_T
#define CINT64_T
typedef struct {
int64_T re;
int64_T im;
} cint64_T;
#endif
#ifndef CUINT64_T
#define CUINT64_T
typedef struct {
uint64_T re;
uint64_T im;
} cuint64_T;
#endif
#endif /* RTWTYPES_H */

View File

@ -0,0 +1,64 @@
#include "customcode_CAa3eEWrwl5pAuWimVVCqH.h"
#ifdef __cplusplus
extern "C" {
#endif
/* Type Definitions */
/* Named Constants */
/* Variable Declarations */
/* Variable Definitions */
/* Function Declarations */
DLL_EXPORT_CC extern void get_NMBS_BROADCAST_ADDRESS_addr_CAa3eEWrwl5pAuWimVVCqH(const uint8_T **varAddr);
DLL_EXPORT_CC extern void get_client_connection_modbus_addr_CAa3eEWrwl5pAuWimVVCqH(int32_T **varAddr);
DLL_EXPORT_CC extern void get_client_read_fd_addr_CAa3eEWrwl5pAuWimVVCqH(int32_T **varAddr);
DLL_EXPORT_CC extern void get_client_connections_modbus_addr_CAa3eEWrwl5pAuWimVVCqH(fd_set **varAddr);
DLL_EXPORT_CC extern void get_server_fd_addr_CAa3eEWrwl5pAuWimVVCqH(int32_T **varAddr);
DLL_EXPORT_CC extern const char_T *get_dll_checksum_CAa3eEWrwl5pAuWimVVCqH();
DLL_EXPORT_CC extern void nmbs_set_read_timeout_CAa3eEWrwl5pAuWimVVCqH(nmbs_t *nmbs, int32_T timeout_ms);
DLL_EXPORT_CC extern void nmbs_set_byte_timeout_CAa3eEWrwl5pAuWimVVCqH(nmbs_t *nmbs, int32_T timeout_ms);
DLL_EXPORT_CC extern void nmbs_platform_conf_create_CAa3eEWrwl5pAuWimVVCqH(nmbs_platform_conf *platform_conf);
DLL_EXPORT_CC extern void nmbs_set_platform_arg_CAa3eEWrwl5pAuWimVVCqH(nmbs_t *nmbs, void *arg);
DLL_EXPORT_CC extern void nmbs_callbacks_create_CAa3eEWrwl5pAuWimVVCqH(nmbs_callbacks *callbacks);
DLL_EXPORT_CC extern nmbs_error nmbs_server_create_CAa3eEWrwl5pAuWimVVCqH(nmbs_t *nmbs, uint8_T address_rtu, const nmbs_platform_conf *platform_conf, const nmbs_callbacks *callbacks);
DLL_EXPORT_CC extern nmbs_error nmbs_server_poll_CAa3eEWrwl5pAuWimVVCqH(nmbs_t *nmbs);
DLL_EXPORT_CC extern void nmbs_set_callbacks_arg_CAa3eEWrwl5pAuWimVVCqH(nmbs_t *nmbs, void *arg);
DLL_EXPORT_CC extern nmbs_error nmbs_client_create_CAa3eEWrwl5pAuWimVVCqH(nmbs_t *nmbs, const nmbs_platform_conf *platform_conf);
DLL_EXPORT_CC extern void nmbs_set_destination_rtu_address_CAa3eEWrwl5pAuWimVVCqH(nmbs_t *nmbs, uint8_T address);
DLL_EXPORT_CC extern nmbs_error nmbs_read_coils_CAa3eEWrwl5pAuWimVVCqH(nmbs_t *nmbs, uint16_T address, uint16_T quantity, uint8_T coils_out[250]);
DLL_EXPORT_CC extern nmbs_error nmbs_read_discrete_inputs_CAa3eEWrwl5pAuWimVVCqH(nmbs_t *nmbs, uint16_T address, uint16_T quantity, uint8_T inputs_out[250]);
DLL_EXPORT_CC extern nmbs_error nmbs_read_holding_registers_CAa3eEWrwl5pAuWimVVCqH(nmbs_t *nmbs, uint16_T address, uint16_T quantity, uint16_T *registers_out);
DLL_EXPORT_CC extern nmbs_error nmbs_read_input_registers_CAa3eEWrwl5pAuWimVVCqH(nmbs_t *nmbs, uint16_T address, uint16_T quantity, uint16_T *registers_out);
DLL_EXPORT_CC extern nmbs_error nmbs_write_single_coil_CAa3eEWrwl5pAuWimVVCqH(nmbs_t *nmbs, uint16_T address, boolean_T value);
DLL_EXPORT_CC extern nmbs_error nmbs_write_single_register_CAa3eEWrwl5pAuWimVVCqH(nmbs_t *nmbs, uint16_T address, uint16_T value);
DLL_EXPORT_CC extern nmbs_error nmbs_write_multiple_coils_CAa3eEWrwl5pAuWimVVCqH(nmbs_t *nmbs, uint16_T address, uint16_T quantity, const uint8_T coils[250]);
DLL_EXPORT_CC extern nmbs_error nmbs_write_multiple_registers_CAa3eEWrwl5pAuWimVVCqH(nmbs_t *nmbs, uint16_T address, uint16_T quantity, const uint16_T *registers);
DLL_EXPORT_CC extern nmbs_error nmbs_read_file_record_CAa3eEWrwl5pAuWimVVCqH(nmbs_t *nmbs, uint16_T file_number, uint16_T record_number, uint16_T *registers, uint16_T count);
DLL_EXPORT_CC extern nmbs_error nmbs_write_file_record_CAa3eEWrwl5pAuWimVVCqH(nmbs_t *nmbs, uint16_T file_number, uint16_T record_number, const uint16_T *registers, uint16_T count);
DLL_EXPORT_CC extern nmbs_error nmbs_read_write_registers_CAa3eEWrwl5pAuWimVVCqH(nmbs_t *nmbs, uint16_T read_address, uint16_T read_quantity, uint16_T *registers_out, uint16_T write_address, uint16_T write_quantity, const uint16_T *registers);
DLL_EXPORT_CC extern nmbs_error nmbs_read_device_identification_basic_CAa3eEWrwl5pAuWimVVCqH(nmbs_t *nmbs, char_T *vendor_name, char_T *product_code, char_T *major_minor_revision, uint8_T buffers_length);
DLL_EXPORT_CC extern nmbs_error nmbs_read_device_identification_regular_CAa3eEWrwl5pAuWimVVCqH(nmbs_t *nmbs, char_T *vendor_url, char_T *product_name, char_T *model_name, char_T *user_application_name, uint8_T buffers_length);
DLL_EXPORT_CC extern nmbs_error nmbs_read_device_identification_extended_CAa3eEWrwl5pAuWimVVCqH(nmbs_t *nmbs, uint8_T object_id_start, uint8_T *ids, char_T **buffers, uint8_T ids_length, uint8_T buffer_length, uint8_T *objects_count_out);
DLL_EXPORT_CC extern nmbs_error nmbs_read_device_identification_CAa3eEWrwl5pAuWimVVCqH(nmbs_t *nmbs, uint8_T object_id, char_T *buffer, uint8_T buffer_length);
DLL_EXPORT_CC extern nmbs_error nmbs_send_raw_pdu_CAa3eEWrwl5pAuWimVVCqH(nmbs_t *nmbs, uint8_T fc, const uint8_T *data, uint16_T data_len);
DLL_EXPORT_CC extern nmbs_error nmbs_receive_raw_pdu_response_CAa3eEWrwl5pAuWimVVCqH(nmbs_t *nmbs, uint8_T *data_out, uint8_T data_out_len);
DLL_EXPORT_CC extern uint16_T nmbs_crc_calc_CAa3eEWrwl5pAuWimVVCqH(const uint8_T *data, uint32_T length, void *arg);
DLL_EXPORT_CC extern const char_T *nmbs_strerror_CAa3eEWrwl5pAuWimVVCqH(nmbs_error error);
DLL_EXPORT_CC extern void *connect_tcp_CAa3eEWrwl5pAuWimVVCqH(const char_T *address, const char_T *port);
DLL_EXPORT_CC extern void close_tcp_server_CAa3eEWrwl5pAuWimVVCqH();
DLL_EXPORT_CC extern int32_T create_tcp_server_CAa3eEWrwl5pAuWimVVCqH(const char_T *address, const char_T *port);
DLL_EXPORT_CC extern void *server_poll_CAa3eEWrwl5pAuWimVVCqH();
DLL_EXPORT_CC extern void disconnect_CAa3eEWrwl5pAuWimVVCqH(void *conn);
DLL_EXPORT_CC extern int32_T read_fd_linux_modbus_CAa3eEWrwl5pAuWimVVCqH(uint8_T *buf, uint16_T count, int32_T timeout_ms, void *arg);
DLL_EXPORT_CC extern int32_T write_fd_linux_modbus_CAa3eEWrwl5pAuWimVVCqH(const uint8_T *buf, uint16_T count, int32_T timeout_ms, void *arg);
/* Function Definitions */
DLL_EXPORT_CC const uint8_T *get_checksum_source_info(int32_T *size);
#ifdef __cplusplus
}
#endif

View File

@ -0,0 +1,46 @@
#ifndef __customcode_Ej1daMrr4K63oI3eysQs8_h__
#define __customcode_Ej1daMrr4K63oI3eysQs8_h__
/* Include files */
#include "mex.h"
#include <string.h>
#include <stdlib.h>
#include <math.h>
#include "tmwtypes.h"
/* Helper definitions for DLL support */
#if defined _WIN32
#define DLL_EXPORT_CC __declspec(dllexport)
#else
#if __GNUC__ >= 4
#define DLL_EXPORT_CC __attribute__ ((visibility ("default")))
#else
#define DLL_EXPORT_CC
#endif
#endif
/* Custom Code from Simulation Target dialog */
#include <netinet/in.h>
#include <sys/types.h>
#include <sys/socket.h>
#include <arpa/inet.h>
#include <errno.h>
#include <stdio.h>
#include <string.h>
#include <unistd.h>
#include <modbus2.h>
/* Function Declarations */
#ifdef __cplusplus
extern "C" {
#endif
#define customcode_Ej1daMrr4K63oI3eysQs8_initializer()
#define customcode_Ej1daMrr4K63oI3eysQs8_terminator()
#ifdef __cplusplus
}
#endif
#endif

View File

@ -0,0 +1,283 @@
#ifndef MULTIWORD_TYPES_H
#define MULTIWORD_TYPES_H
#include "rtwtypes.h"
/*
* MultiWord supporting definitions
*/
typedef long long longlong_T;
/*
* MultiWord types
*/
typedef struct {
uint64_T chunks[2];
} int128m_T;
typedef struct {
int128m_T re;
int128m_T im;
} cint128m_T;
typedef struct {
uint64_T chunks[2];
} uint128m_T;
typedef struct {
uint128m_T re;
uint128m_T im;
} cuint128m_T;
typedef struct {
uint64_T chunks[3];
} int192m_T;
typedef struct {
int192m_T re;
int192m_T im;
} cint192m_T;
typedef struct {
uint64_T chunks[3];
} uint192m_T;
typedef struct {
uint192m_T re;
uint192m_T im;
} cuint192m_T;
typedef struct {
uint64_T chunks[4];
} int256m_T;
typedef struct {
int256m_T re;
int256m_T im;
} cint256m_T;
typedef struct {
uint64_T chunks[4];
} uint256m_T;
typedef struct {
uint256m_T re;
uint256m_T im;
} cuint256m_T;
typedef struct {
uint64_T chunks[5];
} int320m_T;
typedef struct {
int320m_T re;
int320m_T im;
} cint320m_T;
typedef struct {
uint64_T chunks[5];
} uint320m_T;
typedef struct {
uint320m_T re;
uint320m_T im;
} cuint320m_T;
typedef struct {
uint64_T chunks[6];
} int384m_T;
typedef struct {
int384m_T re;
int384m_T im;
} cint384m_T;
typedef struct {
uint64_T chunks[6];
} uint384m_T;
typedef struct {
uint384m_T re;
uint384m_T im;
} cuint384m_T;
typedef struct {
uint64_T chunks[7];
} int448m_T;
typedef struct {
int448m_T re;
int448m_T im;
} cint448m_T;
typedef struct {
uint64_T chunks[7];
} uint448m_T;
typedef struct {
uint448m_T re;
uint448m_T im;
} cuint448m_T;
typedef struct {
uint64_T chunks[8];
} int512m_T;
typedef struct {
int512m_T re;
int512m_T im;
} cint512m_T;
typedef struct {
uint64_T chunks[8];
} uint512m_T;
typedef struct {
uint512m_T re;
uint512m_T im;
} cuint512m_T;
typedef struct {
uint64_T chunks[9];
} int576m_T;
typedef struct {
int576m_T re;
int576m_T im;
} cint576m_T;
typedef struct {
uint64_T chunks[9];
} uint576m_T;
typedef struct {
uint576m_T re;
uint576m_T im;
} cuint576m_T;
typedef struct {
uint64_T chunks[10];
} int640m_T;
typedef struct {
int640m_T re;
int640m_T im;
} cint640m_T;
typedef struct {
uint64_T chunks[10];
} uint640m_T;
typedef struct {
uint640m_T re;
uint640m_T im;
} cuint640m_T;
typedef struct {
uint64_T chunks[11];
} int704m_T;
typedef struct {
int704m_T re;
int704m_T im;
} cint704m_T;
typedef struct {
uint64_T chunks[11];
} uint704m_T;
typedef struct {
uint704m_T re;
uint704m_T im;
} cuint704m_T;
typedef struct {
uint64_T chunks[12];
} int768m_T;
typedef struct {
int768m_T re;
int768m_T im;
} cint768m_T;
typedef struct {
uint64_T chunks[12];
} uint768m_T;
typedef struct {
uint768m_T re;
uint768m_T im;
} cuint768m_T;
typedef struct {
uint64_T chunks[13];
} int832m_T;
typedef struct {
int832m_T re;
int832m_T im;
} cint832m_T;
typedef struct {
uint64_T chunks[13];
} uint832m_T;
typedef struct {
uint832m_T re;
uint832m_T im;
} cuint832m_T;
typedef struct {
uint64_T chunks[14];
} int896m_T;
typedef struct {
int896m_T re;
int896m_T im;
} cint896m_T;
typedef struct {
uint64_T chunks[14];
} uint896m_T;
typedef struct {
uint896m_T re;
uint896m_T im;
} cuint896m_T;
typedef struct {
uint64_T chunks[15];
} int960m_T;
typedef struct {
int960m_T re;
int960m_T im;
} cint960m_T;
typedef struct {
uint64_T chunks[15];
} uint960m_T;
typedef struct {
uint960m_T re;
uint960m_T im;
} cuint960m_T;
typedef struct {
uint64_T chunks[16];
} int1024m_T;
typedef struct {
int1024m_T re;
int1024m_T im;
} cint1024m_T;
typedef struct {
uint64_T chunks[16];
} uint1024m_T;
typedef struct {
uint1024m_T re;
uint1024m_T im;
} cuint1024m_T;
#endif /* MULTIWORD_TYPES_H */

View File

@ -0,0 +1,61 @@
#ifndef RTWTYPES_H
#define RTWTYPES_H
#include "tmwtypes.h"
#ifndef POINTER_T
#define POINTER_T
typedef void * pointer_T;
#endif
/* Logical type definitions */
#if (!defined(__cplusplus))
#ifndef false
#define false (0U)
#endif
#ifndef true
#define true (1U)
#endif
#endif
#ifndef INT64_T
#define INT64_T
typedef long int64_T;
#define MAX_int64_T ((int64_T)(9223372036854775807L))
#define MIN_int64_T ((int64_T)(-9223372036854775807L-1L))
#endif
#ifndef UINT64_T
#define UINT64_T
typedef unsigned long uint64_T;
#define MAX_uint64_T ((uint64_T)(0xFFFFFFFFFFFFFFFFUL))
#endif
/*===========================================================================*
* Additional complex number type definitions *
*===========================================================================*/
#ifndef CINT64_T
#define CINT64_T
typedef struct {
int64_T re;
int64_T im;
} cint64_T;
#endif
#ifndef CUINT64_T
#define CUINT64_T
typedef struct {
uint64_T re;
uint64_T im;
} cuint64_T;
#endif
#endif /* RTWTYPES_H */

View File

@ -0,0 +1,38 @@
#include "customcode_Ej1daMrr4K63oI3eysQs8.h"
#ifdef __cplusplus
extern "C" {
#endif
/* Type Definitions */
/* Named Constants */
/* Variable Declarations */
/* Variable Definitions */
/* Function Declarations */
DLL_EXPORT_CC extern const char_T *get_dll_checksum_Ej1daMrr4K63oI3eysQs8();
DLL_EXPORT_CC extern void delete_modbus_D2x0zjof16u4aQ2mZ3NmZH_Ej1daMrr4K63oI3eysQs8(void *classObj);
DLL_EXPORT_CC extern boolean_T modbus_modbus_connect_0WRDGl0sr2kL9Y9B9cYVDG_Ej1daMrr4K63oI3eysQs8(void *classObj);
DLL_EXPORT_CC extern void modbus_modbus_close_rgkVO4hEl6zx8dFMSwlgxG_Ej1daMrr4K63oI3eysQs8(void *classObj);
DLL_EXPORT_CC extern boolean_T modbus_is_connected_mrpACTntQJx1ozpT90ZZbF_Ej1daMrr4K63oI3eysQs8(void *classObj);
DLL_EXPORT_CC extern void modbus_modbus_set_slave_id_iRLrromcI6Zf3XO6MaVAuG_Ej1daMrr4K63oI3eysQs8(void *classObj, int32_T id);
DLL_EXPORT_CC extern int32_T modbus_modbus_read_coils_j2i6vGmatENgGhETRxd5k_Ej1daMrr4K63oI3eysQs8(void *classObj, uint16_T address, uint16_T amount, boolean_T *buffer);
DLL_EXPORT_CC extern int32_T modbus_modbus_read_input_bits_0C7liNjeTVW5yVJal4vONF_Ej1daMrr4K63oI3eysQs8(void *classObj, uint16_T address, uint16_T amount, boolean_T *buffer);
DLL_EXPORT_CC extern int32_T modbus_modbus_read_holding_registers_rjSoRF4I4FeDEliIHOmF8F_Ej1daMrr4K63oI3eysQs8(void *classObj, uint16_T address, uint16_T amount, uint16_T *buffer);
DLL_EXPORT_CC extern int32_T modbus_modbus_read_input_registers_E8dlNtIy1NQr9Bv8qqFBdG_Ej1daMrr4K63oI3eysQs8(void *classObj, uint16_T address, uint16_T amount, uint16_T *buffer);
DLL_EXPORT_CC extern int32_T modbus_modbus_write_coil_lnN8aQeA1YelV2trcV2SeD_Ej1daMrr4K63oI3eysQs8(void *classObj, uint16_T address, const boolean_T *to_write);
DLL_EXPORT_CC extern int32_T modbus_modbus_write_register_OzpI09pzrU7CeyfMgk0MdB_Ej1daMrr4K63oI3eysQs8(void *classObj, uint16_T address, const uint16_T *value);
DLL_EXPORT_CC extern int32_T modbus_modbus_write_coils_KrDRFga7PmTEFeoeaBWxPB_Ej1daMrr4K63oI3eysQs8(void *classObj, uint16_T address, uint16_T amount, const boolean_T *value);
DLL_EXPORT_CC extern int32_T modbus_modbus_write_registers_Kne2GozSKYknwjXWJ8KlxC_Ej1daMrr4K63oI3eysQs8(void *classObj, uint16_T address, uint16_T amount, const uint16_T *value);
DLL_EXPORT_CC extern boolean_T *get_err_modbus_D2x0zjof16u4aQ2mZ3NmZH_Ej1daMrr4K63oI3eysQs8(void *classObj);
DLL_EXPORT_CC extern int32_T *get_err_no_modbus_D2x0zjof16u4aQ2mZ3NmZH_Ej1daMrr4K63oI3eysQs8(void *classObj);
/* Function Definitions */
DLL_EXPORT_CC const uint8_T *get_checksum_source_info(int32_T *size);
#ifdef __cplusplus
}
#endif

View File

@ -0,0 +1,45 @@
#ifndef __customcode_MeBsjfmGFfz26w2PPf29rD_h__
#define __customcode_MeBsjfmGFfz26w2PPf29rD_h__
/* Include files */
#include "mex.h"
#include <string.h>
#include <stdlib.h>
#include <math.h>
#include "tmwtypes.h"
/* Helper definitions for DLL support */
#if defined _WIN32
#define DLL_EXPORT_CC __declspec(dllexport)
#else
#if __GNUC__ >= 4
#define DLL_EXPORT_CC __attribute__ ((visibility ("default")))
#else
#define DLL_EXPORT_CC
#endif
#endif
/* Custom Code from Simulation Target dialog */
#include <netinet/in.h>
#include <sys/types.h>
#include <sys/socket.h>
#include <arpa/inet.h>
#include <errno.h>
#include <stdio.h>
#include <string.h>
#include <unistd.h>
#include <nanomodbus.h>
/* Function Declarations */
#ifdef __cplusplus
extern "C" {
#endif
#define customcode_MeBsjfmGFfz26w2PPf29rD_initializer()
#define customcode_MeBsjfmGFfz26w2PPf29rD_terminator()
#ifdef __cplusplus
}
#endif
#endif

View File

@ -0,0 +1,283 @@
#ifndef MULTIWORD_TYPES_H
#define MULTIWORD_TYPES_H
#include "rtwtypes.h"
/*
* MultiWord supporting definitions
*/
typedef long long longlong_T;
/*
* MultiWord types
*/
typedef struct {
uint64_T chunks[2];
} int128m_T;
typedef struct {
int128m_T re;
int128m_T im;
} cint128m_T;
typedef struct {
uint64_T chunks[2];
} uint128m_T;
typedef struct {
uint128m_T re;
uint128m_T im;
} cuint128m_T;
typedef struct {
uint64_T chunks[3];
} int192m_T;
typedef struct {
int192m_T re;
int192m_T im;
} cint192m_T;
typedef struct {
uint64_T chunks[3];
} uint192m_T;
typedef struct {
uint192m_T re;
uint192m_T im;
} cuint192m_T;
typedef struct {
uint64_T chunks[4];
} int256m_T;
typedef struct {
int256m_T re;
int256m_T im;
} cint256m_T;
typedef struct {
uint64_T chunks[4];
} uint256m_T;
typedef struct {
uint256m_T re;
uint256m_T im;
} cuint256m_T;
typedef struct {
uint64_T chunks[5];
} int320m_T;
typedef struct {
int320m_T re;
int320m_T im;
} cint320m_T;
typedef struct {
uint64_T chunks[5];
} uint320m_T;
typedef struct {
uint320m_T re;
uint320m_T im;
} cuint320m_T;
typedef struct {
uint64_T chunks[6];
} int384m_T;
typedef struct {
int384m_T re;
int384m_T im;
} cint384m_T;
typedef struct {
uint64_T chunks[6];
} uint384m_T;
typedef struct {
uint384m_T re;
uint384m_T im;
} cuint384m_T;
typedef struct {
uint64_T chunks[7];
} int448m_T;
typedef struct {
int448m_T re;
int448m_T im;
} cint448m_T;
typedef struct {
uint64_T chunks[7];
} uint448m_T;
typedef struct {
uint448m_T re;
uint448m_T im;
} cuint448m_T;
typedef struct {
uint64_T chunks[8];
} int512m_T;
typedef struct {
int512m_T re;
int512m_T im;
} cint512m_T;
typedef struct {
uint64_T chunks[8];
} uint512m_T;
typedef struct {
uint512m_T re;
uint512m_T im;
} cuint512m_T;
typedef struct {
uint64_T chunks[9];
} int576m_T;
typedef struct {
int576m_T re;
int576m_T im;
} cint576m_T;
typedef struct {
uint64_T chunks[9];
} uint576m_T;
typedef struct {
uint576m_T re;
uint576m_T im;
} cuint576m_T;
typedef struct {
uint64_T chunks[10];
} int640m_T;
typedef struct {
int640m_T re;
int640m_T im;
} cint640m_T;
typedef struct {
uint64_T chunks[10];
} uint640m_T;
typedef struct {
uint640m_T re;
uint640m_T im;
} cuint640m_T;
typedef struct {
uint64_T chunks[11];
} int704m_T;
typedef struct {
int704m_T re;
int704m_T im;
} cint704m_T;
typedef struct {
uint64_T chunks[11];
} uint704m_T;
typedef struct {
uint704m_T re;
uint704m_T im;
} cuint704m_T;
typedef struct {
uint64_T chunks[12];
} int768m_T;
typedef struct {
int768m_T re;
int768m_T im;
} cint768m_T;
typedef struct {
uint64_T chunks[12];
} uint768m_T;
typedef struct {
uint768m_T re;
uint768m_T im;
} cuint768m_T;
typedef struct {
uint64_T chunks[13];
} int832m_T;
typedef struct {
int832m_T re;
int832m_T im;
} cint832m_T;
typedef struct {
uint64_T chunks[13];
} uint832m_T;
typedef struct {
uint832m_T re;
uint832m_T im;
} cuint832m_T;
typedef struct {
uint64_T chunks[14];
} int896m_T;
typedef struct {
int896m_T re;
int896m_T im;
} cint896m_T;
typedef struct {
uint64_T chunks[14];
} uint896m_T;
typedef struct {
uint896m_T re;
uint896m_T im;
} cuint896m_T;
typedef struct {
uint64_T chunks[15];
} int960m_T;
typedef struct {
int960m_T re;
int960m_T im;
} cint960m_T;
typedef struct {
uint64_T chunks[15];
} uint960m_T;
typedef struct {
uint960m_T re;
uint960m_T im;
} cuint960m_T;
typedef struct {
uint64_T chunks[16];
} int1024m_T;
typedef struct {
int1024m_T re;
int1024m_T im;
} cint1024m_T;
typedef struct {
uint64_T chunks[16];
} uint1024m_T;
typedef struct {
uint1024m_T re;
uint1024m_T im;
} cuint1024m_T;
#endif /* MULTIWORD_TYPES_H */

View File

@ -0,0 +1,61 @@
#ifndef RTWTYPES_H
#define RTWTYPES_H
#include "tmwtypes.h"
#ifndef POINTER_T
#define POINTER_T
typedef void * pointer_T;
#endif
/* Logical type definitions */
#if (!defined(__cplusplus))
#ifndef false
#define false (0U)
#endif
#ifndef true
#define true (1U)
#endif
#endif
#ifndef INT64_T
#define INT64_T
typedef long int64_T;
#define MAX_int64_T ((int64_T)(9223372036854775807L))
#define MIN_int64_T ((int64_T)(-9223372036854775807L-1L))
#endif
#ifndef UINT64_T
#define UINT64_T
typedef unsigned long uint64_T;
#define MAX_uint64_T ((uint64_T)(0xFFFFFFFFFFFFFFFFUL))
#endif
/*===========================================================================*
* Additional complex number type definitions *
*===========================================================================*/
#ifndef CINT64_T
#define CINT64_T
typedef struct {
int64_T re;
int64_T im;
} cint64_T;
#endif
#ifndef CUINT64_T
#define CUINT64_T
typedef struct {
uint64_T re;
uint64_T im;
} cuint64_T;
#endif
#endif /* RTWTYPES_H */

View File

@ -0,0 +1,53 @@
#include "customcode_MeBsjfmGFfz26w2PPf29rD.h"
#ifdef __cplusplus
extern "C" {
#endif
/* Type Definitions */
/* Named Constants */
/* Variable Declarations */
/* Variable Definitions */
/* Function Declarations */
DLL_EXPORT_CC extern void get_NMBS_BROADCAST_ADDRESS_addr_MeBsjfmGFfz26w2PPf29rD(const uint8_T **varAddr);
DLL_EXPORT_CC extern const char_T *get_dll_checksum_MeBsjfmGFfz26w2PPf29rD();
DLL_EXPORT_CC extern void nmbs_set_read_timeout_MeBsjfmGFfz26w2PPf29rD(nmbs_t *nmbs, int32_T timeout_ms);
DLL_EXPORT_CC extern void nmbs_set_byte_timeout_MeBsjfmGFfz26w2PPf29rD(nmbs_t *nmbs, int32_T timeout_ms);
DLL_EXPORT_CC extern void nmbs_platform_conf_create_MeBsjfmGFfz26w2PPf29rD(nmbs_platform_conf *platform_conf);
DLL_EXPORT_CC extern void nmbs_set_platform_arg_MeBsjfmGFfz26w2PPf29rD(nmbs_t *nmbs, void *arg);
DLL_EXPORT_CC extern void nmbs_callbacks_create_MeBsjfmGFfz26w2PPf29rD(nmbs_callbacks *callbacks);
DLL_EXPORT_CC extern nmbs_error nmbs_server_create_MeBsjfmGFfz26w2PPf29rD(nmbs_t *nmbs, uint8_T address_rtu, const nmbs_platform_conf *platform_conf, const nmbs_callbacks *callbacks);
DLL_EXPORT_CC extern nmbs_error nmbs_server_poll_MeBsjfmGFfz26w2PPf29rD(nmbs_t *nmbs);
DLL_EXPORT_CC extern void nmbs_set_callbacks_arg_MeBsjfmGFfz26w2PPf29rD(nmbs_t *nmbs, void *arg);
DLL_EXPORT_CC extern nmbs_error nmbs_client_create_MeBsjfmGFfz26w2PPf29rD(nmbs_t *nmbs, const nmbs_platform_conf *platform_conf);
DLL_EXPORT_CC extern void nmbs_set_destination_rtu_address_MeBsjfmGFfz26w2PPf29rD(nmbs_t *nmbs, uint8_T address);
DLL_EXPORT_CC extern nmbs_error nmbs_read_coils_MeBsjfmGFfz26w2PPf29rD(nmbs_t *nmbs, uint16_T address, uint16_T quantity, uint8_T coils_out[250]);
DLL_EXPORT_CC extern nmbs_error nmbs_read_discrete_inputs_MeBsjfmGFfz26w2PPf29rD(nmbs_t *nmbs, uint16_T address, uint16_T quantity, uint8_T inputs_out[250]);
DLL_EXPORT_CC extern nmbs_error nmbs_read_holding_registers_MeBsjfmGFfz26w2PPf29rD(nmbs_t *nmbs, uint16_T address, uint16_T quantity, uint16_T *registers_out);
DLL_EXPORT_CC extern nmbs_error nmbs_read_input_registers_MeBsjfmGFfz26w2PPf29rD(nmbs_t *nmbs, uint16_T address, uint16_T quantity, uint16_T *registers_out);
DLL_EXPORT_CC extern nmbs_error nmbs_write_single_coil_MeBsjfmGFfz26w2PPf29rD(nmbs_t *nmbs, uint16_T address, boolean_T value);
DLL_EXPORT_CC extern nmbs_error nmbs_write_single_register_MeBsjfmGFfz26w2PPf29rD(nmbs_t *nmbs, uint16_T address, uint16_T value);
DLL_EXPORT_CC extern nmbs_error nmbs_write_multiple_coils_MeBsjfmGFfz26w2PPf29rD(nmbs_t *nmbs, uint16_T address, uint16_T quantity, const uint8_T coils[250]);
DLL_EXPORT_CC extern nmbs_error nmbs_write_multiple_registers_MeBsjfmGFfz26w2PPf29rD(nmbs_t *nmbs, uint16_T address, uint16_T quantity, const uint16_T *registers);
DLL_EXPORT_CC extern nmbs_error nmbs_read_file_record_MeBsjfmGFfz26w2PPf29rD(nmbs_t *nmbs, uint16_T file_number, uint16_T record_number, uint16_T *registers, uint16_T count);
DLL_EXPORT_CC extern nmbs_error nmbs_write_file_record_MeBsjfmGFfz26w2PPf29rD(nmbs_t *nmbs, uint16_T file_number, uint16_T record_number, const uint16_T *registers, uint16_T count);
DLL_EXPORT_CC extern nmbs_error nmbs_read_write_registers_MeBsjfmGFfz26w2PPf29rD(nmbs_t *nmbs, uint16_T read_address, uint16_T read_quantity, uint16_T *registers_out, uint16_T write_address, uint16_T write_quantity, const uint16_T *registers);
DLL_EXPORT_CC extern nmbs_error nmbs_read_device_identification_basic_MeBsjfmGFfz26w2PPf29rD(nmbs_t *nmbs, char_T *vendor_name, char_T *product_code, char_T *major_minor_revision, uint8_T buffers_length);
DLL_EXPORT_CC extern nmbs_error nmbs_read_device_identification_regular_MeBsjfmGFfz26w2PPf29rD(nmbs_t *nmbs, char_T *vendor_url, char_T *product_name, char_T *model_name, char_T *user_application_name, uint8_T buffers_length);
DLL_EXPORT_CC extern nmbs_error nmbs_read_device_identification_extended_MeBsjfmGFfz26w2PPf29rD(nmbs_t *nmbs, uint8_T object_id_start, uint8_T *ids, char_T **buffers, uint8_T ids_length, uint8_T buffer_length, uint8_T *objects_count_out);
DLL_EXPORT_CC extern nmbs_error nmbs_read_device_identification_MeBsjfmGFfz26w2PPf29rD(nmbs_t *nmbs, uint8_T object_id, char_T *buffer, uint8_T buffer_length);
DLL_EXPORT_CC extern nmbs_error nmbs_send_raw_pdu_MeBsjfmGFfz26w2PPf29rD(nmbs_t *nmbs, uint8_T fc, const uint8_T *data, uint16_T data_len);
DLL_EXPORT_CC extern nmbs_error nmbs_receive_raw_pdu_response_MeBsjfmGFfz26w2PPf29rD(nmbs_t *nmbs, uint8_T *data_out, uint8_T data_out_len);
DLL_EXPORT_CC extern uint16_T nmbs_crc_calc_MeBsjfmGFfz26w2PPf29rD(const uint8_T *data, uint32_T length, void *arg);
DLL_EXPORT_CC extern const char_T *nmbs_strerror_MeBsjfmGFfz26w2PPf29rD(nmbs_error error);
/* Function Definitions */
DLL_EXPORT_CC const uint8_T *get_checksum_source_info(int32_T *size);
#ifdef __cplusplus
}
#endif

View File

@ -0,0 +1,45 @@
#ifndef __customcode_NrUqZ7JIZtB1SCgcPvEdbB_h__
#define __customcode_NrUqZ7JIZtB1SCgcPvEdbB_h__
/* Include files */
#include "mex.h"
#include <string.h>
#include <stdlib.h>
#include <math.h>
#include "tmwtypes.h"
/* Helper definitions for DLL support */
#if defined _WIN32
#define DLL_EXPORT_CC __declspec(dllexport)
#else
#if __GNUC__ >= 4
#define DLL_EXPORT_CC __attribute__ ((visibility ("default")))
#else
#define DLL_EXPORT_CC
#endif
#endif
/* Custom Code from Simulation Target dialog */
#include <netinet/in.h>
#include <sys/types.h>
#include <sys/socket.h>
#include <arpa/inet.h>
#include <errno.h>
#include <stdio.h>
#include <string.h>
#include <unistd.h>
#include "nanomodbus.h"
/* Function Declarations */
#ifdef __cplusplus
extern "C" {
#endif
#define customcode_NrUqZ7JIZtB1SCgcPvEdbB_initializer()
#define customcode_NrUqZ7JIZtB1SCgcPvEdbB_terminator()
#ifdef __cplusplus
}
#endif
#endif

View File

@ -0,0 +1,283 @@
#ifndef MULTIWORD_TYPES_H
#define MULTIWORD_TYPES_H
#include "rtwtypes.h"
/*
* MultiWord supporting definitions
*/
typedef long long longlong_T;
/*
* MultiWord types
*/
typedef struct {
uint64_T chunks[2];
} int128m_T;
typedef struct {
int128m_T re;
int128m_T im;
} cint128m_T;
typedef struct {
uint64_T chunks[2];
} uint128m_T;
typedef struct {
uint128m_T re;
uint128m_T im;
} cuint128m_T;
typedef struct {
uint64_T chunks[3];
} int192m_T;
typedef struct {
int192m_T re;
int192m_T im;
} cint192m_T;
typedef struct {
uint64_T chunks[3];
} uint192m_T;
typedef struct {
uint192m_T re;
uint192m_T im;
} cuint192m_T;
typedef struct {
uint64_T chunks[4];
} int256m_T;
typedef struct {
int256m_T re;
int256m_T im;
} cint256m_T;
typedef struct {
uint64_T chunks[4];
} uint256m_T;
typedef struct {
uint256m_T re;
uint256m_T im;
} cuint256m_T;
typedef struct {
uint64_T chunks[5];
} int320m_T;
typedef struct {
int320m_T re;
int320m_T im;
} cint320m_T;
typedef struct {
uint64_T chunks[5];
} uint320m_T;
typedef struct {
uint320m_T re;
uint320m_T im;
} cuint320m_T;
typedef struct {
uint64_T chunks[6];
} int384m_T;
typedef struct {
int384m_T re;
int384m_T im;
} cint384m_T;
typedef struct {
uint64_T chunks[6];
} uint384m_T;
typedef struct {
uint384m_T re;
uint384m_T im;
} cuint384m_T;
typedef struct {
uint64_T chunks[7];
} int448m_T;
typedef struct {
int448m_T re;
int448m_T im;
} cint448m_T;
typedef struct {
uint64_T chunks[7];
} uint448m_T;
typedef struct {
uint448m_T re;
uint448m_T im;
} cuint448m_T;
typedef struct {
uint64_T chunks[8];
} int512m_T;
typedef struct {
int512m_T re;
int512m_T im;
} cint512m_T;
typedef struct {
uint64_T chunks[8];
} uint512m_T;
typedef struct {
uint512m_T re;
uint512m_T im;
} cuint512m_T;
typedef struct {
uint64_T chunks[9];
} int576m_T;
typedef struct {
int576m_T re;
int576m_T im;
} cint576m_T;
typedef struct {
uint64_T chunks[9];
} uint576m_T;
typedef struct {
uint576m_T re;
uint576m_T im;
} cuint576m_T;
typedef struct {
uint64_T chunks[10];
} int640m_T;
typedef struct {
int640m_T re;
int640m_T im;
} cint640m_T;
typedef struct {
uint64_T chunks[10];
} uint640m_T;
typedef struct {
uint640m_T re;
uint640m_T im;
} cuint640m_T;
typedef struct {
uint64_T chunks[11];
} int704m_T;
typedef struct {
int704m_T re;
int704m_T im;
} cint704m_T;
typedef struct {
uint64_T chunks[11];
} uint704m_T;
typedef struct {
uint704m_T re;
uint704m_T im;
} cuint704m_T;
typedef struct {
uint64_T chunks[12];
} int768m_T;
typedef struct {
int768m_T re;
int768m_T im;
} cint768m_T;
typedef struct {
uint64_T chunks[12];
} uint768m_T;
typedef struct {
uint768m_T re;
uint768m_T im;
} cuint768m_T;
typedef struct {
uint64_T chunks[13];
} int832m_T;
typedef struct {
int832m_T re;
int832m_T im;
} cint832m_T;
typedef struct {
uint64_T chunks[13];
} uint832m_T;
typedef struct {
uint832m_T re;
uint832m_T im;
} cuint832m_T;
typedef struct {
uint64_T chunks[14];
} int896m_T;
typedef struct {
int896m_T re;
int896m_T im;
} cint896m_T;
typedef struct {
uint64_T chunks[14];
} uint896m_T;
typedef struct {
uint896m_T re;
uint896m_T im;
} cuint896m_T;
typedef struct {
uint64_T chunks[15];
} int960m_T;
typedef struct {
int960m_T re;
int960m_T im;
} cint960m_T;
typedef struct {
uint64_T chunks[15];
} uint960m_T;
typedef struct {
uint960m_T re;
uint960m_T im;
} cuint960m_T;
typedef struct {
uint64_T chunks[16];
} int1024m_T;
typedef struct {
int1024m_T re;
int1024m_T im;
} cint1024m_T;
typedef struct {
uint64_T chunks[16];
} uint1024m_T;
typedef struct {
uint1024m_T re;
uint1024m_T im;
} cuint1024m_T;
#endif /* MULTIWORD_TYPES_H */

View File

@ -0,0 +1,61 @@
#ifndef RTWTYPES_H
#define RTWTYPES_H
#include "tmwtypes.h"
#ifndef POINTER_T
#define POINTER_T
typedef void * pointer_T;
#endif
/* Logical type definitions */
#if (!defined(__cplusplus))
#ifndef false
#define false (0U)
#endif
#ifndef true
#define true (1U)
#endif
#endif
#ifndef INT64_T
#define INT64_T
typedef long int64_T;
#define MAX_int64_T ((int64_T)(9223372036854775807L))
#define MIN_int64_T ((int64_T)(-9223372036854775807L-1L))
#endif
#ifndef UINT64_T
#define UINT64_T
typedef unsigned long uint64_T;
#define MAX_uint64_T ((uint64_T)(0xFFFFFFFFFFFFFFFFUL))
#endif
/*===========================================================================*
* Additional complex number type definitions *
*===========================================================================*/
#ifndef CINT64_T
#define CINT64_T
typedef struct {
int64_T re;
int64_T im;
} cint64_T;
#endif
#ifndef CUINT64_T
#define CUINT64_T
typedef struct {
uint64_T re;
uint64_T im;
} cuint64_T;
#endif
#endif /* RTWTYPES_H */

View File

@ -0,0 +1,53 @@
#include "customcode_NrUqZ7JIZtB1SCgcPvEdbB.h"
#ifdef __cplusplus
extern "C" {
#endif
/* Type Definitions */
/* Named Constants */
/* Variable Declarations */
/* Variable Definitions */
/* Function Declarations */
DLL_EXPORT_CC extern void get_NMBS_BROADCAST_ADDRESS_addr_NrUqZ7JIZtB1SCgcPvEdbB(const uint8_T **varAddr);
DLL_EXPORT_CC extern const char_T *get_dll_checksum_NrUqZ7JIZtB1SCgcPvEdbB();
DLL_EXPORT_CC extern void nmbs_set_read_timeout_NrUqZ7JIZtB1SCgcPvEdbB(nmbs_t *nmbs, int32_T timeout_ms);
DLL_EXPORT_CC extern void nmbs_set_byte_timeout_NrUqZ7JIZtB1SCgcPvEdbB(nmbs_t *nmbs, int32_T timeout_ms);
DLL_EXPORT_CC extern void nmbs_platform_conf_create_NrUqZ7JIZtB1SCgcPvEdbB(nmbs_platform_conf *platform_conf);
DLL_EXPORT_CC extern void nmbs_set_platform_arg_NrUqZ7JIZtB1SCgcPvEdbB(nmbs_t *nmbs, void *arg);
DLL_EXPORT_CC extern void nmbs_callbacks_create_NrUqZ7JIZtB1SCgcPvEdbB(nmbs_callbacks *callbacks);
DLL_EXPORT_CC extern nmbs_error nmbs_server_create_NrUqZ7JIZtB1SCgcPvEdbB(nmbs_t *nmbs, uint8_T address_rtu, const nmbs_platform_conf *platform_conf, const nmbs_callbacks *callbacks);
DLL_EXPORT_CC extern nmbs_error nmbs_server_poll_NrUqZ7JIZtB1SCgcPvEdbB(nmbs_t *nmbs);
DLL_EXPORT_CC extern void nmbs_set_callbacks_arg_NrUqZ7JIZtB1SCgcPvEdbB(nmbs_t *nmbs, void *arg);
DLL_EXPORT_CC extern nmbs_error nmbs_client_create_NrUqZ7JIZtB1SCgcPvEdbB(nmbs_t *nmbs, const nmbs_platform_conf *platform_conf);
DLL_EXPORT_CC extern void nmbs_set_destination_rtu_address_NrUqZ7JIZtB1SCgcPvEdbB(nmbs_t *nmbs, uint8_T address);
DLL_EXPORT_CC extern nmbs_error nmbs_read_coils_NrUqZ7JIZtB1SCgcPvEdbB(nmbs_t *nmbs, uint16_T address, uint16_T quantity, uint8_T coils_out[250]);
DLL_EXPORT_CC extern nmbs_error nmbs_read_discrete_inputs_NrUqZ7JIZtB1SCgcPvEdbB(nmbs_t *nmbs, uint16_T address, uint16_T quantity, uint8_T inputs_out[250]);
DLL_EXPORT_CC extern nmbs_error nmbs_read_holding_registers_NrUqZ7JIZtB1SCgcPvEdbB(nmbs_t *nmbs, uint16_T address, uint16_T quantity, uint16_T *registers_out);
DLL_EXPORT_CC extern nmbs_error nmbs_read_input_registers_NrUqZ7JIZtB1SCgcPvEdbB(nmbs_t *nmbs, uint16_T address, uint16_T quantity, uint16_T *registers_out);
DLL_EXPORT_CC extern nmbs_error nmbs_write_single_coil_NrUqZ7JIZtB1SCgcPvEdbB(nmbs_t *nmbs, uint16_T address, boolean_T value);
DLL_EXPORT_CC extern nmbs_error nmbs_write_single_register_NrUqZ7JIZtB1SCgcPvEdbB(nmbs_t *nmbs, uint16_T address, uint16_T value);
DLL_EXPORT_CC extern nmbs_error nmbs_write_multiple_coils_NrUqZ7JIZtB1SCgcPvEdbB(nmbs_t *nmbs, uint16_T address, uint16_T quantity, const uint8_T coils[250]);
DLL_EXPORT_CC extern nmbs_error nmbs_write_multiple_registers_NrUqZ7JIZtB1SCgcPvEdbB(nmbs_t *nmbs, uint16_T address, uint16_T quantity, const uint16_T *registers);
DLL_EXPORT_CC extern nmbs_error nmbs_read_file_record_NrUqZ7JIZtB1SCgcPvEdbB(nmbs_t *nmbs, uint16_T file_number, uint16_T record_number, uint16_T *registers, uint16_T count);
DLL_EXPORT_CC extern nmbs_error nmbs_write_file_record_NrUqZ7JIZtB1SCgcPvEdbB(nmbs_t *nmbs, uint16_T file_number, uint16_T record_number, const uint16_T *registers, uint16_T count);
DLL_EXPORT_CC extern nmbs_error nmbs_read_write_registers_NrUqZ7JIZtB1SCgcPvEdbB(nmbs_t *nmbs, uint16_T read_address, uint16_T read_quantity, uint16_T *registers_out, uint16_T write_address, uint16_T write_quantity, const uint16_T *registers);
DLL_EXPORT_CC extern nmbs_error nmbs_read_device_identification_basic_NrUqZ7JIZtB1SCgcPvEdbB(nmbs_t *nmbs, char_T *vendor_name, char_T *product_code, char_T *major_minor_revision, uint8_T buffers_length);
DLL_EXPORT_CC extern nmbs_error nmbs_read_device_identification_regular_NrUqZ7JIZtB1SCgcPvEdbB(nmbs_t *nmbs, char_T *vendor_url, char_T *product_name, char_T *model_name, char_T *user_application_name, uint8_T buffers_length);
DLL_EXPORT_CC extern nmbs_error nmbs_read_device_identification_extended_NrUqZ7JIZtB1SCgcPvEdbB(nmbs_t *nmbs, uint8_T object_id_start, uint8_T *ids, char_T **buffers, uint8_T ids_length, uint8_T buffer_length, uint8_T *objects_count_out);
DLL_EXPORT_CC extern nmbs_error nmbs_read_device_identification_NrUqZ7JIZtB1SCgcPvEdbB(nmbs_t *nmbs, uint8_T object_id, char_T *buffer, uint8_T buffer_length);
DLL_EXPORT_CC extern nmbs_error nmbs_send_raw_pdu_NrUqZ7JIZtB1SCgcPvEdbB(nmbs_t *nmbs, uint8_T fc, const uint8_T *data, uint16_T data_len);
DLL_EXPORT_CC extern nmbs_error nmbs_receive_raw_pdu_response_NrUqZ7JIZtB1SCgcPvEdbB(nmbs_t *nmbs, uint8_T *data_out, uint8_T data_out_len);
DLL_EXPORT_CC extern uint16_T nmbs_crc_calc_NrUqZ7JIZtB1SCgcPvEdbB(const uint8_T *data, uint32_T length, void *arg);
DLL_EXPORT_CC extern const char_T *nmbs_strerror_NrUqZ7JIZtB1SCgcPvEdbB(nmbs_error error);
/* Function Definitions */
DLL_EXPORT_CC const uint8_T *get_checksum_source_info(int32_T *size);
#ifdef __cplusplus
}
#endif

View File

@ -0,0 +1,46 @@
#ifndef __customcode_WOZg8SrZCI3YH7YaIklGiE_h__
#define __customcode_WOZg8SrZCI3YH7YaIklGiE_h__
/* Include files */
#include "mex.h"
#include <string.h>
#include <stdlib.h>
#include <math.h>
#include "tmwtypes.h"
/* Helper definitions for DLL support */
#if defined _WIN32
#define DLL_EXPORT_CC __declspec(dllexport)
#else
#if __GNUC__ >= 4
#define DLL_EXPORT_CC __attribute__ ((visibility ("default")))
#else
#define DLL_EXPORT_CC
#endif
#endif
/* Custom Code from Simulation Target dialog */
#include <netinet/in.h>
#include <sys/types.h>
#include <sys/socket.h>
#include <arpa/inet.h>
#include <errno.h>
#include <stdio.h>
#include <string.h>
#include <unistd.h>
#include "modbus_tcp_client.h"
/* Function Declarations */
#ifdef __cplusplus
extern "C" {
#endif
#define customcode_WOZg8SrZCI3YH7YaIklGiE_initializer()
#define customcode_WOZg8SrZCI3YH7YaIklGiE_terminator()
#ifdef __cplusplus
}
#endif
#endif

View File

@ -0,0 +1,283 @@
#ifndef MULTIWORD_TYPES_H
#define MULTIWORD_TYPES_H
#include "rtwtypes.h"
/*
* MultiWord supporting definitions
*/
typedef long long longlong_T;
/*
* MultiWord types
*/
typedef struct {
uint64_T chunks[2];
} int128m_T;
typedef struct {
int128m_T re;
int128m_T im;
} cint128m_T;
typedef struct {
uint64_T chunks[2];
} uint128m_T;
typedef struct {
uint128m_T re;
uint128m_T im;
} cuint128m_T;
typedef struct {
uint64_T chunks[3];
} int192m_T;
typedef struct {
int192m_T re;
int192m_T im;
} cint192m_T;
typedef struct {
uint64_T chunks[3];
} uint192m_T;
typedef struct {
uint192m_T re;
uint192m_T im;
} cuint192m_T;
typedef struct {
uint64_T chunks[4];
} int256m_T;
typedef struct {
int256m_T re;
int256m_T im;
} cint256m_T;
typedef struct {
uint64_T chunks[4];
} uint256m_T;
typedef struct {
uint256m_T re;
uint256m_T im;
} cuint256m_T;
typedef struct {
uint64_T chunks[5];
} int320m_T;
typedef struct {
int320m_T re;
int320m_T im;
} cint320m_T;
typedef struct {
uint64_T chunks[5];
} uint320m_T;
typedef struct {
uint320m_T re;
uint320m_T im;
} cuint320m_T;
typedef struct {
uint64_T chunks[6];
} int384m_T;
typedef struct {
int384m_T re;
int384m_T im;
} cint384m_T;
typedef struct {
uint64_T chunks[6];
} uint384m_T;
typedef struct {
uint384m_T re;
uint384m_T im;
} cuint384m_T;
typedef struct {
uint64_T chunks[7];
} int448m_T;
typedef struct {
int448m_T re;
int448m_T im;
} cint448m_T;
typedef struct {
uint64_T chunks[7];
} uint448m_T;
typedef struct {
uint448m_T re;
uint448m_T im;
} cuint448m_T;
typedef struct {
uint64_T chunks[8];
} int512m_T;
typedef struct {
int512m_T re;
int512m_T im;
} cint512m_T;
typedef struct {
uint64_T chunks[8];
} uint512m_T;
typedef struct {
uint512m_T re;
uint512m_T im;
} cuint512m_T;
typedef struct {
uint64_T chunks[9];
} int576m_T;
typedef struct {
int576m_T re;
int576m_T im;
} cint576m_T;
typedef struct {
uint64_T chunks[9];
} uint576m_T;
typedef struct {
uint576m_T re;
uint576m_T im;
} cuint576m_T;
typedef struct {
uint64_T chunks[10];
} int640m_T;
typedef struct {
int640m_T re;
int640m_T im;
} cint640m_T;
typedef struct {
uint64_T chunks[10];
} uint640m_T;
typedef struct {
uint640m_T re;
uint640m_T im;
} cuint640m_T;
typedef struct {
uint64_T chunks[11];
} int704m_T;
typedef struct {
int704m_T re;
int704m_T im;
} cint704m_T;
typedef struct {
uint64_T chunks[11];
} uint704m_T;
typedef struct {
uint704m_T re;
uint704m_T im;
} cuint704m_T;
typedef struct {
uint64_T chunks[12];
} int768m_T;
typedef struct {
int768m_T re;
int768m_T im;
} cint768m_T;
typedef struct {
uint64_T chunks[12];
} uint768m_T;
typedef struct {
uint768m_T re;
uint768m_T im;
} cuint768m_T;
typedef struct {
uint64_T chunks[13];
} int832m_T;
typedef struct {
int832m_T re;
int832m_T im;
} cint832m_T;
typedef struct {
uint64_T chunks[13];
} uint832m_T;
typedef struct {
uint832m_T re;
uint832m_T im;
} cuint832m_T;
typedef struct {
uint64_T chunks[14];
} int896m_T;
typedef struct {
int896m_T re;
int896m_T im;
} cint896m_T;
typedef struct {
uint64_T chunks[14];
} uint896m_T;
typedef struct {
uint896m_T re;
uint896m_T im;
} cuint896m_T;
typedef struct {
uint64_T chunks[15];
} int960m_T;
typedef struct {
int960m_T re;
int960m_T im;
} cint960m_T;
typedef struct {
uint64_T chunks[15];
} uint960m_T;
typedef struct {
uint960m_T re;
uint960m_T im;
} cuint960m_T;
typedef struct {
uint64_T chunks[16];
} int1024m_T;
typedef struct {
int1024m_T re;
int1024m_T im;
} cint1024m_T;
typedef struct {
uint64_T chunks[16];
} uint1024m_T;
typedef struct {
uint1024m_T re;
uint1024m_T im;
} cuint1024m_T;
#endif /* MULTIWORD_TYPES_H */

View File

@ -0,0 +1,61 @@
#ifndef RTWTYPES_H
#define RTWTYPES_H
#include "tmwtypes.h"
#ifndef POINTER_T
#define POINTER_T
typedef void * pointer_T;
#endif
/* Logical type definitions */
#if (!defined(__cplusplus))
#ifndef false
#define false (0U)
#endif
#ifndef true
#define true (1U)
#endif
#endif
#ifndef INT64_T
#define INT64_T
typedef long int64_T;
#define MAX_int64_T ((int64_T)(9223372036854775807L))
#define MIN_int64_T ((int64_T)(-9223372036854775807L-1L))
#endif
#ifndef UINT64_T
#define UINT64_T
typedef unsigned long uint64_T;
#define MAX_uint64_T ((uint64_T)(0xFFFFFFFFFFFFFFFFUL))
#endif
/*===========================================================================*
* Additional complex number type definitions *
*===========================================================================*/
#ifndef CINT64_T
#define CINT64_T
typedef struct {
int64_T re;
int64_T im;
} cint64_T;
#endif
#ifndef CUINT64_T
#define CUINT64_T
typedef struct {
uint64_T re;
uint64_T im;
} cuint64_T;
#endif
#endif /* RTWTYPES_H */

View File

@ -0,0 +1,36 @@
#include "customcode_WOZg8SrZCI3YH7YaIklGiE.h"
#ifdef __cplusplus
extern "C" {
#endif
/* Type Definitions */
/* Named Constants */
/* Variable Declarations */
/* Variable Definitions */
/* Function Declarations */
DLL_EXPORT_CC extern const char_T *get_dll_checksum_WOZg8SrZCI3YH7YaIklGiE();
DLL_EXPORT_CC extern void *create_ModbusTCPClient_m6DHLsRJatb7jFhPa9sibF_WOZg8SrZCI3YH7YaIklGiE(const char_T *ip, int32_T port);
DLL_EXPORT_CC extern void delete_ModbusTCPClient_IUI8Q2S0ulkAvLxLsx7k7_WOZg8SrZCI3YH7YaIklGiE(void *classObj);
DLL_EXPORT_CC extern boolean_T ModbusTCPClient_connectServer_QWoAn8DsWluHwos1RJjgIB_WOZg8SrZCI3YH7YaIklGiE(void *classObj);
DLL_EXPORT_CC extern void ModbusTCPClient_disconnectServer_8RQB4Kyl2X5kNVGUlAlOgF_WOZg8SrZCI3YH7YaIklGiE(void *classObj);
DLL_EXPORT_CC extern boolean_T ModbusTCPClient_readCoil_I0fzDOaax3ByUlCPekapKG_WOZg8SrZCI3YH7YaIklGiE(void *classObj, int32_T address);
DLL_EXPORT_CC extern void ModbusTCPClient_writeCoil_QoP3Zii3RZpABaPcesHRiB_WOZg8SrZCI3YH7YaIklGiE(void *classObj, int32_T address, boolean_T value);
DLL_EXPORT_CC extern uint16_T ModbusTCPClient_readHoldingRegister_g900vXiXPbOtZqtApt9hNC_WOZg8SrZCI3YH7YaIklGiE(void *classObj, int32_T address);
DLL_EXPORT_CC extern void ModbusTCPClient_writeHoldingRegister_mGVMywqtoVY5ZLnrtEy19G_WOZg8SrZCI3YH7YaIklGiE(void *classObj, int32_T address, uint16_T value);
DLL_EXPORT_CC extern void ModbusTCPClient_readAll_0LzP2HH0Zq4XkTmFCbG4o_WOZg8SrZCI3YH7YaIklGiE(void *classObj);
DLL_EXPORT_CC extern boolean_T (*get_coils_ModbusTCPClient_IUI8Q2S0ulkAvLxLsx7k7_WOZg8SrZCI3YH7YaIklGiE(void *classObj))[16];
DLL_EXPORT_CC extern boolean_T (*get_discreteInputs_ModbusTCPClient_IUI8Q2S0ulkAvLxLsx7k7_WOZg8SrZCI3YH7YaIklGiE(void *classObj))[16];
DLL_EXPORT_CC extern uint16_T (*get_inputRegisters_ModbusTCPClient_IUI8Q2S0ulkAvLxLsx7k7_WOZg8SrZCI3YH7YaIklGiE(void *classObj))[16];
DLL_EXPORT_CC extern uint16_T (*get_holdingRegisters_ModbusTCPClient_IUI8Q2S0ulkAvLxLsx7k7_WOZg8SrZCI3YH7YaIklGiE(void *classObj))[16];
/* Function Definitions */
DLL_EXPORT_CC const uint8_T *get_checksum_source_info(int32_T *size);
#ifdef __cplusplus
}
#endif

View File

@ -0,0 +1,46 @@
#ifndef __customcode_ajRnfzdOQXfvhDl5S08NkG_h__
#define __customcode_ajRnfzdOQXfvhDl5S08NkG_h__
/* Include files */
#include "mex.h"
#include <string.h>
#include <stdlib.h>
#include <math.h>
#include "tmwtypes.h"
/* Helper definitions for DLL support */
#if defined _WIN32
#define DLL_EXPORT_CC __declspec(dllexport)
#else
#if __GNUC__ >= 4
#define DLL_EXPORT_CC __attribute__ ((visibility ("default")))
#else
#define DLL_EXPORT_CC
#endif
#endif
/* Custom Code from Simulation Target dialog */
#include <netinet/in.h>
#include <sys/types.h>
#include <sys/socket.h>
#include <arpa/inet.h>
#include <errno.h>
#include <stdio.h>
#include <string.h>
#include <unistd.h>
#include "modbus_tcp_client.h"
/* Function Declarations */
#ifdef __cplusplus
extern "C" {
#endif
#define customcode_ajRnfzdOQXfvhDl5S08NkG_initializer()
#define customcode_ajRnfzdOQXfvhDl5S08NkG_terminator()
#ifdef __cplusplus
}
#endif
#endif

View File

@ -0,0 +1,283 @@
#ifndef MULTIWORD_TYPES_H
#define MULTIWORD_TYPES_H
#include "rtwtypes.h"
/*
* MultiWord supporting definitions
*/
typedef long long longlong_T;
/*
* MultiWord types
*/
typedef struct {
uint64_T chunks[2];
} int128m_T;
typedef struct {
int128m_T re;
int128m_T im;
} cint128m_T;
typedef struct {
uint64_T chunks[2];
} uint128m_T;
typedef struct {
uint128m_T re;
uint128m_T im;
} cuint128m_T;
typedef struct {
uint64_T chunks[3];
} int192m_T;
typedef struct {
int192m_T re;
int192m_T im;
} cint192m_T;
typedef struct {
uint64_T chunks[3];
} uint192m_T;
typedef struct {
uint192m_T re;
uint192m_T im;
} cuint192m_T;
typedef struct {
uint64_T chunks[4];
} int256m_T;
typedef struct {
int256m_T re;
int256m_T im;
} cint256m_T;
typedef struct {
uint64_T chunks[4];
} uint256m_T;
typedef struct {
uint256m_T re;
uint256m_T im;
} cuint256m_T;
typedef struct {
uint64_T chunks[5];
} int320m_T;
typedef struct {
int320m_T re;
int320m_T im;
} cint320m_T;
typedef struct {
uint64_T chunks[5];
} uint320m_T;
typedef struct {
uint320m_T re;
uint320m_T im;
} cuint320m_T;
typedef struct {
uint64_T chunks[6];
} int384m_T;
typedef struct {
int384m_T re;
int384m_T im;
} cint384m_T;
typedef struct {
uint64_T chunks[6];
} uint384m_T;
typedef struct {
uint384m_T re;
uint384m_T im;
} cuint384m_T;
typedef struct {
uint64_T chunks[7];
} int448m_T;
typedef struct {
int448m_T re;
int448m_T im;
} cint448m_T;
typedef struct {
uint64_T chunks[7];
} uint448m_T;
typedef struct {
uint448m_T re;
uint448m_T im;
} cuint448m_T;
typedef struct {
uint64_T chunks[8];
} int512m_T;
typedef struct {
int512m_T re;
int512m_T im;
} cint512m_T;
typedef struct {
uint64_T chunks[8];
} uint512m_T;
typedef struct {
uint512m_T re;
uint512m_T im;
} cuint512m_T;
typedef struct {
uint64_T chunks[9];
} int576m_T;
typedef struct {
int576m_T re;
int576m_T im;
} cint576m_T;
typedef struct {
uint64_T chunks[9];
} uint576m_T;
typedef struct {
uint576m_T re;
uint576m_T im;
} cuint576m_T;
typedef struct {
uint64_T chunks[10];
} int640m_T;
typedef struct {
int640m_T re;
int640m_T im;
} cint640m_T;
typedef struct {
uint64_T chunks[10];
} uint640m_T;
typedef struct {
uint640m_T re;
uint640m_T im;
} cuint640m_T;
typedef struct {
uint64_T chunks[11];
} int704m_T;
typedef struct {
int704m_T re;
int704m_T im;
} cint704m_T;
typedef struct {
uint64_T chunks[11];
} uint704m_T;
typedef struct {
uint704m_T re;
uint704m_T im;
} cuint704m_T;
typedef struct {
uint64_T chunks[12];
} int768m_T;
typedef struct {
int768m_T re;
int768m_T im;
} cint768m_T;
typedef struct {
uint64_T chunks[12];
} uint768m_T;
typedef struct {
uint768m_T re;
uint768m_T im;
} cuint768m_T;
typedef struct {
uint64_T chunks[13];
} int832m_T;
typedef struct {
int832m_T re;
int832m_T im;
} cint832m_T;
typedef struct {
uint64_T chunks[13];
} uint832m_T;
typedef struct {
uint832m_T re;
uint832m_T im;
} cuint832m_T;
typedef struct {
uint64_T chunks[14];
} int896m_T;
typedef struct {
int896m_T re;
int896m_T im;
} cint896m_T;
typedef struct {
uint64_T chunks[14];
} uint896m_T;
typedef struct {
uint896m_T re;
uint896m_T im;
} cuint896m_T;
typedef struct {
uint64_T chunks[15];
} int960m_T;
typedef struct {
int960m_T re;
int960m_T im;
} cint960m_T;
typedef struct {
uint64_T chunks[15];
} uint960m_T;
typedef struct {
uint960m_T re;
uint960m_T im;
} cuint960m_T;
typedef struct {
uint64_T chunks[16];
} int1024m_T;
typedef struct {
int1024m_T re;
int1024m_T im;
} cint1024m_T;
typedef struct {
uint64_T chunks[16];
} uint1024m_T;
typedef struct {
uint1024m_T re;
uint1024m_T im;
} cuint1024m_T;
#endif /* MULTIWORD_TYPES_H */

View File

@ -0,0 +1,61 @@
#ifndef RTWTYPES_H
#define RTWTYPES_H
#include "tmwtypes.h"
#ifndef POINTER_T
#define POINTER_T
typedef void * pointer_T;
#endif
/* Logical type definitions */
#if (!defined(__cplusplus))
#ifndef false
#define false (0U)
#endif
#ifndef true
#define true (1U)
#endif
#endif
#ifndef INT64_T
#define INT64_T
typedef long int64_T;
#define MAX_int64_T ((int64_T)(9223372036854775807L))
#define MIN_int64_T ((int64_T)(-9223372036854775807L-1L))
#endif
#ifndef UINT64_T
#define UINT64_T
typedef unsigned long uint64_T;
#define MAX_uint64_T ((uint64_T)(0xFFFFFFFFFFFFFFFFUL))
#endif
/*===========================================================================*
* Additional complex number type definitions *
*===========================================================================*/
#ifndef CINT64_T
#define CINT64_T
typedef struct {
int64_T re;
int64_T im;
} cint64_T;
#endif
#ifndef CUINT64_T
#define CUINT64_T
typedef struct {
uint64_T re;
uint64_T im;
} cuint64_T;
#endif
#endif /* RTWTYPES_H */

View File

@ -0,0 +1,54 @@
#include "customcode_ajRnfzdOQXfvhDl5S08NkG.h"
#ifdef __cplusplus
extern "C" {
#endif
/* Type Definitions */
/* Named Constants */
/* Variable Declarations */
/* Variable Definitions */
/* Function Declarations */
DLL_EXPORT_CC extern const char_T *get_dll_checksum_ajRnfzdOQXfvhDl5S08NkG();
DLL_EXPORT_CC extern void *create_ModbusTCPClient_m6DHLsRJatb7jFhPa9sibF_ajRnfzdOQXfvhDl5S08NkG(const char_T *ip, int32_T port);
DLL_EXPORT_CC extern void *create_ModbusTCPClient_DTOtnS5jzeCt7wI4BrWszE_ajRnfzdOQXfvhDl5S08NkG(const char_T *ip, int32_T port, int32_T numCoils, int32_T numDI, int32_T numIR, int32_T numHR, int32_T startCoils, int32_T startDI, int32_T startIR, int32_T startHR);
DLL_EXPORT_CC extern void delete_ModbusTCPClient_IUI8Q2S0ulkAvLxLsx7k7_ajRnfzdOQXfvhDl5S08NkG(void *classObj);
DLL_EXPORT_CC extern void ModbusTCPClient_setStartAddresses_WBPKyX5chtvoJpkQQz9yaE_ajRnfzdOQXfvhDl5S08NkG(void *classObj, int32_T startCoils, int32_T startDI, int32_T startIR, int32_T startHR);
DLL_EXPORT_CC extern boolean_T ModbusTCPClient_connectServer_QWoAn8DsWluHwos1RJjgIB_ajRnfzdOQXfvhDl5S08NkG(void *classObj);
DLL_EXPORT_CC extern void ModbusTCPClient_disconnectServer_8RQB4Kyl2X5kNVGUlAlOgF_ajRnfzdOQXfvhDl5S08NkG(void *classObj);
DLL_EXPORT_CC extern boolean_T ModbusTCPClient_isConnected_6gPjpu9NwavTxFjRzBfnHH_ajRnfzdOQXfvhDl5S08NkG(void *classObj);
DLL_EXPORT_CC extern boolean_T ModbusTCPClient_reconnectServer_tmHQpYOBqsG4QOWlcN1JCG_ajRnfzdOQXfvhDl5S08NkG(void *classObj);
DLL_EXPORT_CC extern void ModbusTCPClient_setTimeout_pKk7C4CiK7cGunjmXsoo9G_ajRnfzdOQXfvhDl5S08NkG(void *classObj, int32_T milliseconds);
DLL_EXPORT_CC extern void ModbusTCPClient_setCoil_uKV63H2F6Bk5GhMpqdzPnH_ajRnfzdOQXfvhDl5S08NkG(void *classObj, int32_T address, boolean_T value);
DLL_EXPORT_CC extern void ModbusTCPClient_setHoldingRegister_4XFxsavHXRTDHK2Ce0yJN_ajRnfzdOQXfvhDl5S08NkG(void *classObj, int32_T address, uint16_T value);
DLL_EXPORT_CC extern boolean_T ModbusTCPClient_getCoil_koLGZb1i8WN62u3e1PZwYH_ajRnfzdOQXfvhDl5S08NkG(void *classObj, int32_T address);
DLL_EXPORT_CC extern boolean_T ModbusTCPClient_getDesiredCoil_4MZCcH6ezDGZg0uObXZUCC_ajRnfzdOQXfvhDl5S08NkG(void *classObj, int32_T address);
DLL_EXPORT_CC extern boolean_T ModbusTCPClient_getDiscreteInput_ae9HPljrPWD4BuZzmFBLEH_ajRnfzdOQXfvhDl5S08NkG(void *classObj, int32_T address);
DLL_EXPORT_CC extern uint16_T ModbusTCPClient_getHoldingRegister_mYLPn0wppPgH4bOhTiVvvF_ajRnfzdOQXfvhDl5S08NkG(void *classObj, int32_T address);
DLL_EXPORT_CC extern uint16_T ModbusTCPClient_getDesiredHoldingRegister_15FbNf22xvcBTZOmdfDtkC_ajRnfzdOQXfvhDl5S08NkG(void *classObj, int32_T address);
DLL_EXPORT_CC extern uint16_T ModbusTCPClient_getInputRegister_ULtxwrYKJbrRxoQjkBCEs_ajRnfzdOQXfvhDl5S08NkG(void *classObj, int32_T address);
DLL_EXPORT_CC extern ModbusError ModbusTCPClient_readAll_0LzP2HH0Zq4XkTmFCbG4o_ajRnfzdOQXfvhDl5S08NkG(void *classObj);
DLL_EXPORT_CC extern ModbusError ModbusTCPClient_writeAll_zaImFzR1o00mWpc4RczmN_ajRnfzdOQXfvhDl5S08NkG(void *classObj);
DLL_EXPORT_CC extern ModbusError ModbusTCPClient_readCoil_zMFMzEaWMy4AM0fCGw6vkB_ajRnfzdOQXfvhDl5S08NkG(void *classObj, int32_T address, boolean_T *coilState);
DLL_EXPORT_CC extern ModbusError ModbusTCPClient_readMultipleCoils_FsHZsYjrSrPY8P2Ay58lEB_ajRnfzdOQXfvhDl5S08NkG(void *classObj, int32_T address, int32_T count, boolean_T *coilStates);
DLL_EXPORT_CC extern ModbusError ModbusTCPClient_readDiscreteInput_hw3i2qSdn19YvGoOIzPSQF_ajRnfzdOQXfvhDl5S08NkG(void *classObj, int32_T address, boolean_T *discreteInput);
DLL_EXPORT_CC extern ModbusError ModbusTCPClient_readMultipleDiscreteInputs_ejm6F8zFfmummwJiWr5WWE_ajRnfzdOQXfvhDl5S08NkG(void *classObj, int32_T address, int32_T count, boolean_T *discreteInputs);
DLL_EXPORT_CC extern ModbusError ModbusTCPClient_readHoldingRegister_6gyuCNdZQDr6LxODE49ARC_ajRnfzdOQXfvhDl5S08NkG(void *classObj, int32_T address, uint16_T *holdingRegister);
DLL_EXPORT_CC extern ModbusError ModbusTCPClient_readMultipleHoldingRegisters_Nsd2PmYkYCsTdyTlOKb0KB_ajRnfzdOQXfvhDl5S08NkG(void *classObj, int32_T address, int32_T count, uint16_T *holdingRegisters);
DLL_EXPORT_CC extern ModbusError ModbusTCPClient_readInputRegister_LiIzv9TV0ONDt8VfLmy35G_ajRnfzdOQXfvhDl5S08NkG(void *classObj, int32_T address, uint16_T *inputRegister);
DLL_EXPORT_CC extern ModbusError ModbusTCPClient_readMultipleInputRegisters_two67DgbwFGoO6KyFi3I5B_ajRnfzdOQXfvhDl5S08NkG(void *classObj, int32_T address, int32_T count, uint16_T *inputRegisters);
DLL_EXPORT_CC extern ModbusError ModbusTCPClient_writeCoil_QoP3Zii3RZpABaPcesHRiB_ajRnfzdOQXfvhDl5S08NkG(void *classObj, int32_T address, boolean_T value);
DLL_EXPORT_CC extern ModbusError ModbusTCPClient_writeMultipleCoils_p5zcgcGPFH7wlbBhce5JYG_ajRnfzdOQXfvhDl5S08NkG(void *classObj, int32_T address, int32_T count, const boolean_T *values);
DLL_EXPORT_CC extern ModbusError ModbusTCPClient_writeHoldingRegister_mGVMywqtoVY5ZLnrtEy19G_ajRnfzdOQXfvhDl5S08NkG(void *classObj, int32_T address, uint16_T value);
DLL_EXPORT_CC extern ModbusError ModbusTCPClient_writeMultipleHoldingRegisters_ga2jca071NX41GYGjHLKzB_ajRnfzdOQXfvhDl5S08NkG(void *classObj, int32_T address, int32_T count, const uint16_T *values);
/* Function Definitions */
DLL_EXPORT_CC const uint8_T *get_checksum_source_info(int32_T *size);
#ifdef __cplusplus
}
#endif

Some files were not shown because too many files have changed in this diff Show More