From d9714b556703561a0abcbe71970b1cd6922168a6 Mon Sep 17 00:00:00 2001 From: patacongo Date: Sat, 21 Jul 2012 21:23:18 +0000 Subject: Use NuttX types in FreeModBus port; Add FreeModBus demo at apps/examples/modbus; Add new termios APIs git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@4964 42af7a65-404d-4744-a932-0658087f49c3 --- apps/ChangeLog.txt | 8 +- apps/examples/Kconfig | 4 + apps/examples/Makefile | 10 +- apps/examples/README.txt | 15 + apps/examples/ftpd/ftpd_main.c | 0 apps/examples/modbus/.depend | 0 apps/examples/modbus/Kconfig | 13 + apps/examples/modbus/Makefile | 105 +++++++ apps/examples/modbus/modbus_main.c | 531 ++++++++++++++++++++++++++++++++++ apps/include/modbus/mb.h | 36 +-- apps/include/modbus/mbframe.h | 12 +- apps/include/modbus/mbfunc.h | 20 +- apps/include/modbus/mbport.h | 37 +-- apps/include/modbus/mbproto.h | 4 +- apps/include/modbus/mbutils.h | 12 +- apps/modbus/ascii/mbascii.c | 116 ++++---- apps/modbus/ascii/mbascii.h | 18 +- apps/modbus/functions/mbfunccoils.c | 54 ++-- apps/modbus/functions/mbfuncdisc.c | 22 +- apps/modbus/functions/mbfuncholding.c | 76 ++--- apps/modbus/functions/mbfuncinput.c | 18 +- apps/modbus/functions/mbfuncother.c | 14 +- apps/modbus/functions/mbutils.c | 56 ++-- apps/modbus/mb.c | 30 +- apps/modbus/nuttx/port.h | 24 +- apps/modbus/nuttx/portevent.c | 24 +- apps/modbus/nuttx/portother.c | 4 +- apps/modbus/nuttx/portserial.c | 88 +++--- apps/modbus/nuttx/porttimer.c | 16 +- apps/modbus/rtu/mbcrc.c | 16 +- apps/modbus/rtu/mbcrc.h | 2 +- apps/modbus/rtu/mbrtu.c | 68 ++--- apps/modbus/rtu/mbrtu.h | 14 +- apps/modbus/tcp/mbtcp.c | 22 +- apps/modbus/tcp/mbtcp.h | 10 +- 35 files changed, 1084 insertions(+), 415 deletions(-) mode change 100755 => 100644 apps/examples/ftpd/ftpd_main.c create mode 100644 apps/examples/modbus/.depend create mode 100644 apps/examples/modbus/Kconfig create mode 100644 apps/examples/modbus/Makefile create mode 100644 apps/examples/modbus/modbus_main.c (limited to 'apps') diff --git a/apps/ChangeLog.txt b/apps/ChangeLog.txt index d3a78a28f..d20abd343 100755 --- a/apps/ChangeLog.txt +++ b/apps/ChangeLog.txt @@ -251,5 +251,9 @@ 6.21 2012-xx-xx Gregory Nutt * apps/include/: Stylistic clean-up of all header files. - * apps/modbus and apps/include/modbus: The beginnings of a port of - freemodbus-v1.5.0. + * apps/modbus and apps/include/modbus: A port of freemodbus-v1.5.0 + has been added to the NuttX apps/ source tree. + * apps/examples/modbus: A port of the freemodbus-v1.5.0 "demo" + program that will be used to verify the FreeModBus port + + diff --git a/apps/examples/Kconfig b/apps/examples/Kconfig index fbbe6d583..a20f7c2e7 100644 --- a/apps/examples/Kconfig +++ b/apps/examples/Kconfig @@ -63,6 +63,10 @@ menu "File system mount example" source "$APPSDIR/examples/mount/Kconfig" endmenu +menu "FreeModBus example" +source "$APPSDIR/examples/modbus/Kconfig" +endmenu + menu "Network test example" source "$APPSDIR/examples/nettest/Kconfig" endmenu diff --git a/apps/examples/Makefile b/apps/examples/Makefile index 7ad8d82bc..ad5be6497 100644 --- a/apps/examples/Makefile +++ b/apps/examples/Makefile @@ -38,10 +38,10 @@ # Sub-directories SUBDIRS = adc buttons can cdcacm composite dhcpd ftpc ftpd hello helloxx \ - hidkbd igmp lcdrw mm mount nettest nsh null nx nxconsole nxffs nxflat \ - nxhello nximage nxlines nxtext ostest pashello pipe poll pwm qencoder \ - rgmp romfs serloop telnetd thttpd tiff touchscreen udp uip usbserial \ - sendmail usbstorage usbterm watchdog wget wlan + hidkbd igmp lcdrw mm modbus mount nettest nsh null nx nxconsole nxffs \ + nxflat nxhello nximage nxlines nxtext ostest pashello pipe poll pwm \ + qencoder rgmp romfs serloop telnetd thttpd tiff touchscreen udp uip \ + usbserial sendmail usbstorage usbterm watchdog wget wlan # Sub-directories that might need context setup. Directories may need # context setup for a variety of reasons, but the most common is because @@ -56,7 +56,7 @@ SUBDIRS = adc buttons can cdcacm composite dhcpd ftpc ftpd hello helloxx \ CNTXTDIRS = pwm ifeq ($(CONFIG_NSH_BUILTIN_APPS),y) -CNTXTDIRS += adc can cdcacm composite ftpd dhcpd nettest qencoder telnetd watchdog +CNTXTDIRS += adc can cdcacm composite ftpd dhcpd modbus nettest qencoder telnetd watchdog endif ifeq ($(CONFIG_EXAMPLES_HELLO_BUILTIN),y) diff --git a/apps/examples/README.txt b/apps/examples/README.txt index 4330224b0..29cdf1a76 100644 --- a/apps/examples/README.txt +++ b/apps/examples/README.txt @@ -483,6 +483,21 @@ examples/mm advantage that it runs in the actual NuttX tasking environment (the mm/mm_test.c only runs in a PC simulation environment). +examples/modbus +^^^^^^^^^^^^^^^ + + This is a port of the FreeModbus Linux demo. It derives from the + demos/LINUX directory of the FreeModBus version 1.5.0 (June 6, 2010) + that can be downloaded in its entirety from http://developer.berlios.de/project/showfiles.php?group_id=6120. + + CONFIG_EXAMPLES_MODBUS_REG_INPUT_START, Default 1000 + CONFIG_EXAMPLES_MODBUS_REG_INPUT_NREGS, Default 4 + CONFIG_EXAMPLES_MODBUS_REG_HOLDING_START, Default 2000 + CONFIG_EXAMPLES_MODBUS_REG_HOLDING_NREGS, Default 130 + + The FreeModBus library resides at apps/modbus. See apps/modbus/README.txt + for additional configuration information. + examples/mount ^^^^^^^^^^^^^^ diff --git a/apps/examples/ftpd/ftpd_main.c b/apps/examples/ftpd/ftpd_main.c old mode 100755 new mode 100644 diff --git a/apps/examples/modbus/.depend b/apps/examples/modbus/.depend new file mode 100644 index 000000000..e69de29bb diff --git a/apps/examples/modbus/Kconfig b/apps/examples/modbus/Kconfig new file mode 100644 index 000000000..4519ed2e3 --- /dev/null +++ b/apps/examples/modbus/Kconfig @@ -0,0 +1,13 @@ +# +# For a description of the syntax of this configuration file, +# see misc/tools/kconfig-language.txt. +# + +config EXAMPLES_MODBUS + bool "FreeModBus example" + default n + ---help--- + Enable the FreeModBus example + +if EXAMPLES_MODBUS +endif diff --git a/apps/examples/modbus/Makefile b/apps/examples/modbus/Makefile new file mode 100644 index 000000000..6dbc7e424 --- /dev/null +++ b/apps/examples/modbus/Makefile @@ -0,0 +1,105 @@ +############################################################################ +# apps/examples/modbus/Makefile +# +# Copyright (C) 2012 Gregory Nutt. All rights reserved. +# Author: Gregory Nutt +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# 3. Neither the name NuttX nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +############################################################################ + +-include $(TOPDIR)/.config +-include $(TOPDIR)/Make.defs +include $(APPDIR)/Make.defs + +# FreeModBus demo built-in application info + +APPNAME = modbus +PRIORITY = SCHED_PRIORITY_DEFAULT +STACKSIZE = 2048 + +# FreeModBus demo + +ASRCS = +CSRCS = modbus_main.c + +AOBJS = $(ASRCS:.S=$(OBJEXT)) +COBJS = $(CSRCS:.c=$(OBJEXT)) + +SRCS = $(ASRCS) $(CSRCS) +OBJS = $(AOBJS) $(COBJS) + +ifeq ($(WINTOOL),y) + BIN = "${shell cygpath -w $(APPDIR)/libapps$(LIBEXT)}" +else + BIN = "$(APPDIR)/libapps$(LIBEXT)" +endif + +ROOTDEPPATH = --dep-path . + +# Common build + +VPATH = + +all: .built +.PHONY: clean depend distclean + +$(AOBJS): %$(OBJEXT): %.S + $(call ASSEMBLE, $<, $@) + +$(COBJS): %$(OBJEXT): %.c + $(call COMPILE, $<, $@) + +.built: $(OBJS) + @( for obj in $(OBJS) ; do \ + $(call ARCHIVE, $(BIN), $${obj}); \ + done ; ) + @touch .built + +.context: +ifeq ($(CONFIG_NSH_BUILTIN_APPS),y) + $(call REGISTER,$(APPNAME),$(PRIORITY),$(STACKSIZE),$(APPNAME)_main) + @touch $@ +endif + +context: .context + +.depend: Makefile $(SRCS) + @$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep + @touch $@ + +depend: .depend + +clean: + @rm -f *.o *~ .*.swp .built + $(call CLEAN) + +distclean: clean + @rm -f Make.dep .depend + +-include Make.dep diff --git a/apps/examples/modbus/modbus_main.c b/apps/examples/modbus/modbus_main.c new file mode 100644 index 000000000..0f9dea4ac --- /dev/null +++ b/apps/examples/modbus/modbus_main.c @@ -0,0 +1,531 @@ +/**************************************************************************** + * examples/modbus/main.c + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + **************************************************************************** + * Leveraged from: + * + * FreeModbus Libary: Linux Demo Application + * Copyright (C) 2006 Christian Walter + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * This library is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with this library; if not, write to the Free Software + * Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include +#include +#include +#include +#include + +#include +#include + +/**************************************************************************** + * Definitions + ****************************************************************************/ +/* Configuration ************************************************************/ + +#ifndef CONFIG_EXAMPLES_MODBUS_REG_INPUT_START +# define CONFIG_EXAMPLES_MODBUS_REG_INPUT_START 1000 +#endif + +#ifndef CONFIG_EXAMPLES_MODBUS_REG_INPUT_NREGS +# define CONFIG_EXAMPLES_MODBUS_REG_INPUT_NREGS 4 +#endif + +#ifndef CONFIG_EXAMPLES_MODBUS_REG_HOLDING_START +# define CONFIG_EXAMPLES_MODBUS_REG_HOLDING_START 2000 +#endif + +#ifndef CONFIG_EXAMPLES_MODBUS_REG_HOLDING_NREGS +# define CONFIG_EXAMPLES_MODBUS_REG_HOLDING_NREGS 130 +#endif + +#ifdef CONFIG_NSH_BUILTIN_APPS +# define MAIN_NAME modbus_main +# define MAIN_NAME_STRING "modbus_main: " +#else +# define MAIN_NAME user_start +# define MAIN_NAME_STRING "user_start: " +#endif + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +enum modbus_threadstate_e +{ + STOPPED = 0, + RUNNING, + SHUTDOWN +}; + +struct modbus_state_s +{ + enum modbus_threadstate_e threadstate; + uint16_t reginput[CONFIG_EXAMPLES_MODBUS_REG_INPUT_NREGS]; + uint16_t regholding[CONFIG_EXAMPLES_MODBUS_REG_HOLDING_NREGS]; + pthread_t threadid; + pthread_mutex_t lock; + volatile bool quit; +}; + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +static inline int modbus_initialize(void); +static void *modbus_pollthread(void *pvarg); +static inline int modbus_create_pollthread(void); +static void modbus_showusage(FAR const char *progname, int exitcode); + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +static struct modbus_state_s g_modbus; +static const uint8_t g_slaveid[] = { 0xaa, 0xbb, 0xcc }; + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: modbus_initialize + * + * Description: + * Called from the ModBus polling thread in order to initialized the + * FreeModBus interface. + * + ****************************************************************************/ + +static inline int modbus_initialize(void) +{ + eMBErrorCode mberr; + int status; + + /* Verify that we are in the stopped state */ + + if (g_modbus.threadstate != STOPPED) + { + fprintf(stderr, MAIN_NAME_STRING + "ERROR: Bad state: %d\n", g_modbus.threadstate); + return EINVAL; + } + + /* Initialize the ModBus demo data structures */ + + status = pthread_mutex_init(&g_modbus.lock, NULL); + if (status != 0) + { + fprintf(stderr, MAIN_NAME_STRING + "ERROR: pthread_mutex_init failed: %d\n", status); + return status; + } + + status = ENODEV; + + /* Initialize the FreeModBus library */ + + mberr = eMBInit(MB_RTU, 0X0A, 0, 38400, MB_PAR_EVEN); + if (mberr != MB_ENOERR) + { + fprintf(stderr, MAIN_NAME_STRING + "ERROR: eMBInit failed: %d\n", mberr); + goto errout_with_mutex; + } + + /* Set the slave ID */ + + mberr = eMBSetSlaveID(0x34, TRUE, g_slaveid, 3); + if (mberr != MB_ENOERR) + { + fprintf(stderr, MAIN_NAME_STRING + "ERROR: eMBSetSlaveID failed: %d\n", mberr); + goto errout_with_modbus; + } + + /* Enable FreeModBus */ + + mberr = eMBEnable(); + if (mberr == MB_ENOERR) + { + fprintf(stderr, MAIN_NAME_STRING + "ERROR: eMBEnable failed: %d\n", mberr); + goto errout_with_modbus; + } + + /* Successfully initialized */ + + g_modbus.threadstate = RUNNING; + return OK; + +errout_with_modbus: + /* Release hardware resources. */ + + (void)eMBClose(); + +errout_with_mutex: + + /* Free/uninitialize data structures */ + + (void)pthread_mutex_destroy(&g_modbus.lock); + + g_modbus.threadstate = STOPPED; + return status; +} + +/**************************************************************************** + * Name: modbus_pollthread + * + * Description: + * This is the ModBus polling thread. + * + ****************************************************************************/ + +static void *modbus_pollthread(void *pvarg) +{ + eMBErrorCode mberr; + int ret; + + /* Initialize the modbus */ + + ret = modbus_initialize(); + if (ret != OK) + { + fprintf(stderr, MAIN_NAME_STRING + "ERROR: modbus_initialize failed: %d\n", ret); + return NULL; + } + + /* Then loop until we are commanded to shutdown */ + + do + { + /* Poll */ + + mberr = eMBPoll(); + if (mberr != MB_ENOERR) + { + break; + } + + /* Generate some random input */ + + g_modbus.reginput[0] = (uint16_t)rand(); + } + while (g_modbus.threadstate != SHUTDOWN); + + /* Disable */ + + (void)eMBDisable(); + + /* Release hardware resources. */ + + (void)eMBClose(); + + /* Free/uninitialize data structures */ + + (void)pthread_mutex_destroy(&g_modbus.lock); + g_modbus.threadstate = STOPPED; + return NULL; +} + +/**************************************************************************** + * Name: modbus_create_pollthread + * + * Description: + * Start the ModBus polling thread + * + ****************************************************************************/ + +static inline int modbus_create_pollthread(void) +{ + int ret; + + if (g_modbus.threadstate == STOPPED) + { + ret = pthread_create(&g_modbus.threadid, NULL, modbus_pollthread, NULL); + } + else + { + ret = EINVAL; + } + + return ret; +} + +/**************************************************************************** + * Name: modbus_showusage + * + * Description: + * Show usage of the demo program and exit + * + ****************************************************************************/ + +static void modbus_showusage(FAR const char *progname, int exitcode) +{ + printf("USAGE: %s [-d|e|s|q|h]\n\n", progname); + printf("Where:\n"); + printf(" -d : Disable protocol stack\n"); + printf(" -e : Enable the protocol stack\n"); + printf(" -s : Show current status\n"); + printf(" -q : Quit application\n"); + printf(" -h : Show this information\n"); + printf("\n"); + exit(exitcode); +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: user_start/modbus_main + * + * Description: + * This is the main entry point to the demo program + * + ****************************************************************************/ + +int MAIN_NAME(int argc, char *argv[]) +{ + int option; + int ret; + + /* Handle command line arguments */ + + g_modbus.quit = FALSE; + + while ((option = getopt(argc, argv, "desqh")) != ERROR) + { + switch (option) + { + case 'd': /* Disable protocol stack */ + (void)pthread_mutex_lock(&g_modbus.lock); + g_modbus.threadstate = SHUTDOWN; + (void)pthread_mutex_unlock(&g_modbus.lock); + break; + + case 'e': /* Enable the protocol stack */ + { + ret = modbus_create_pollthread(); + if (ret != OK) + { + fprintf(stderr, MAIN_NAME_STRING + "ERROR: modbus_create_pollthread failed: %d\n", ret); + exit(EXIT_FAILURE); + } + } + break; + + case 's': /* Show current status */ + switch (g_modbus.threadstate) + { + case RUNNING: + printf(MAIN_NAME_STRING "Protocol stack is running\n"); + break; + + case STOPPED: + printf(MAIN_NAME_STRING "Protocol stack is stopped\n"); + break; + + case SHUTDOWN: + printf(MAIN_NAME_STRING "Protocol stack is shutting down\n"); + break; + + default: + fprintf(stderr, MAIN_NAME_STRING + "ERROR: Invalid thread state: %d\n", + g_modbus.threadstate); + break; + } + break; + + case 'q': /* Quit application */ + g_modbus.quit = TRUE; + pthread_kill(g_modbus.threadid, 9); + break; + + case 'h': /* Show help info */ + modbus_showusage(argv[0], EXIT_SUCCESS); + break; + + default: + fprintf(stderr, MAIN_NAME_STRING + "ERROR: Unrecognized option: '%c'\n", option); + modbus_showusage(argv[0], EXIT_FAILURE); + break; + } + } + + return EXIT_SUCCESS; +} + +/**************************************************************************** + * Name: eMBRegInputCB + * + * Description: + * Required FreeModBus callback function + * + ****************************************************************************/ + +eMBErrorCode eMBRegInputCB(uint8_t *buffer, uint16_t address, uint16_t nregs) +{ + eMBErrorCode mberr = MB_ENOERR; + int index; + + if ((address >= CONFIG_EXAMPLES_MODBUS_REG_INPUT_START) && + (address + nregs <= + CONFIG_EXAMPLES_MODBUS_REG_INPUT_START + + CONFIG_EXAMPLES_MODBUS_REG_INPUT_NREGS)) + { + index = (int)(address - CONFIG_EXAMPLES_MODBUS_REG_INPUT_START); + while (nregs > 0) + { + *buffer++ = (uint8_t)(g_modbus.reginput[index] >> 8); + *buffer++ = (uint8_t)(g_modbus.reginput[index] & 0xff); + index++; + nregs--; + } + } + else + { + mberr = MB_ENOREG; + } + + return mberr; +} + +/**************************************************************************** + * Name: eMBRegHoldingCB + * + * Description: + * Required FreeModBus callback function + * + ****************************************************************************/ + +eMBErrorCode eMBRegHoldingCB(uint8_t *buffer, uint16_t address, uint16_t nregs, + eMBRegisterMode mode) +{ + eMBErrorCode mberr = MB_ENOERR; + int index; + + if ((address >= CONFIG_EXAMPLES_MODBUS_REG_HOLDING_START) && + (address + nregs <= + CONFIG_EXAMPLES_MODBUS_REG_HOLDING_START + + CONFIG_EXAMPLES_MODBUS_REG_HOLDING_NREGS)) + { + index = (int)(address - CONFIG_EXAMPLES_MODBUS_REG_HOLDING_START); + switch (mode) + { + /* Pass current register values to the protocol stack. */ + case MB_REG_READ: + while (nregs > 0) + { + *buffer++ = (uint8_t)(g_modbus.regholding[index] >> 8); + *buffer++ = (uint8_t)(g_modbus.regholding[index] & 0xff); + index++; + nregs--; + } + break; + + /* Update current register values with new values from the + * protocol stack. + */ + + case MB_REG_WRITE: + while (nregs > 0) + { + g_modbus.regholding[index] = *buffer++ << 8; + g_modbus.regholding[index] |= *buffer++; + index++; + nregs--; + } + break; + } + } + else + { + mberr = MB_ENOREG; + } + + return mberr; +} + +/**************************************************************************** + * Name: eMBRegCoilsCB + * + * Description: + * Required FreeModBus callback function + * + ****************************************************************************/ + +eMBErrorCode eMBRegCoilsCB(uint8_t *buffer, uint16_t address, uint16_t ncoils, + eMBRegisterMode mode) +{ + return MB_ENOREG; +} + +/**************************************************************************** + * Name: eMBRegDiscreteCB + * + * Description: + * Required FreeModBus callback function + * + ****************************************************************************/ + +eMBErrorCode eMBRegDiscreteCB(uint8_t *buffer, uint16_t address, uint16_t ndiscrete) +{ + return MB_ENOREG; +} diff --git a/apps/include/modbus/mb.h b/apps/include/modbus/mb.h index b534c178a..ed247d163 100644 --- a/apps/include/modbus/mb.h +++ b/apps/include/modbus/mb.h @@ -31,7 +31,8 @@ #ifndef _MB_H #define _MB_H -#include "port.h" +#include +#include #ifdef __cplusplus PR_BEGIN_EXTERN_C @@ -121,7 +122,6 @@ typedef enum MB_ETIMEDOUT /*!< timeout error occurred. */ } eMBErrorCode; - /* ----------------------- Function prototypes ------------------------------*/ /*! \ingroup modbus * \brief Initialize the Modbus protocol stack. @@ -148,8 +148,8 @@ typedef enum * slave addresses are in the range 1 - 247. * - eMBErrorCode::MB_EPORTERR IF the porting layer returned an error. */ -eMBErrorCode eMBInit( eMBMode eMode, UCHAR ucSlaveAddress, - UCHAR ucPort, ULONG ulBaudRate, eMBParity eParity ); +eMBErrorCode eMBInit( eMBMode eMode, uint8_t ucSlaveAddress, + uint8_t ucPort, uint32_t ulBaudRate, eMBParity eParity ); /*! \ingroup modbus * \brief Initialize the Modbus protocol stack for Modbus TCP. @@ -165,7 +165,7 @@ eMBErrorCode eMBInit( eMBMode eMode, UCHAR ucSlaveAddress, * slave addresses are in the range 1 - 247. * - eMBErrorCode::MB_EPORTERR IF the porting layer returned an error. */ -eMBErrorCode eMBTCPInit( USHORT usTCPPort ); +eMBErrorCode eMBTCPInit( uint16_t usTCPPort ); /*! \ingroup modbus * \brief Release resources used by the protocol stack. @@ -228,7 +228,7 @@ eMBErrorCode eMBPoll( void ); * * \param ucSlaveID Values is returned in the Slave ID byte of the * Report Slave ID response. - * \param xIsRunning If TRUE the Run Indicator Status byte is set to 0xFF. + * \param xIsRunning If true the Run Indicator Status byte is set to 0xFF. * otherwise the Run Indicator Status is 0x00. * \param pucAdditional Values which should be returned in the Additional * bytes of the Report Slave ID response. @@ -238,9 +238,9 @@ eMBErrorCode eMBPoll( void ); * is too small it returns eMBErrorCode::MB_ENORES. Otherwise * it returns eMBErrorCode::MB_ENOERR. */ -eMBErrorCode eMBSetSlaveID( UCHAR ucSlaveID, BOOL xIsRunning, - UCHAR const *pucAdditional, - USHORT usAdditionalLen ); +eMBErrorCode eMBSetSlaveID( uint8_t ucSlaveID, bool xIsRunning, + uint8_t const *pucAdditional, + uint16_t usAdditionalLen ); /*! \ingroup modbus * \brief Registers a callback handler for a given function code. @@ -262,7 +262,7 @@ eMBErrorCode eMBSetSlaveID( UCHAR ucSlaveID, BOOL xIsRunning, * case the values in config.h should be adjusted. If the argument was not * valid it returns eMBErrorCode::MB_EINVAL. */ -eMBErrorCode eMBRegisterCB( UCHAR ucFunctionCode, +eMBErrorCode eMBRegisterCB( uint8_t ucFunctionCode, pxMBFunctionHandler pxHandler ); /* ----------------------- Callback -----------------------------------------*/ @@ -309,8 +309,8 @@ eMBErrorCode eMBRegisterCB( UCHAR ucFunctionCode, * - eMBErrorCode::MB_EIO If an unrecoverable error occurred. In this case * a SLAVE DEVICE FAILURE exception is sent as a response. */ -eMBErrorCode eMBRegInputCB( UCHAR * pucRegBuffer, USHORT usAddress, - USHORT usNRegs ); +eMBErrorCode eMBRegInputCB( uint8_t * pucRegBuffer, uint16_t usAddress, + uint16_t usNRegs ); /*! \ingroup modbus_registers * \brief Callback function used if a Holding Register value is @@ -344,8 +344,8 @@ eMBErrorCode eMBRegInputCB( UCHAR * pucRegBuffer, USHORT usAddress, * - eMBErrorCode::MB_EIO If an unrecoverable error occurred. In this case * a SLAVE DEVICE FAILURE exception is sent as a response. */ -eMBErrorCode eMBRegHoldingCB( UCHAR * pucRegBuffer, USHORT usAddress, - USHORT usNRegs, eMBRegisterMode eMode ); +eMBErrorCode eMBRegHoldingCB( uint8_t * pucRegBuffer, uint16_t usAddress, + uint16_t usNRegs, eMBRegisterMode eMode ); /*! \ingroup modbus_registers * \brief Callback function used if a Coil Register value is @@ -379,8 +379,8 @@ eMBErrorCode eMBRegHoldingCB( UCHAR * pucRegBuffer, USHORT usAddress, * - eMBErrorCode::MB_EIO If an unrecoverable error occurred. In this case * a SLAVE DEVICE FAILURE exception is sent as a response. */ -eMBErrorCode eMBRegCoilsCB( UCHAR * pucRegBuffer, USHORT usAddress, - USHORT usNCoils, eMBRegisterMode eMode ); +eMBErrorCode eMBRegCoilsCB( uint8_t * pucRegBuffer, uint16_t usAddress, + uint16_t usNCoils, eMBRegisterMode eMode ); /*! \ingroup modbus_registers * \brief Callback function used if a Input Discrete Register value is @@ -408,8 +408,8 @@ eMBErrorCode eMBRegCoilsCB( UCHAR * pucRegBuffer, USHORT usAddress, * - eMBErrorCode::MB_EIO If an unrecoverable error occurred. In this case * a SLAVE DEVICE FAILURE exception is sent as a response. */ -eMBErrorCode eMBRegDiscreteCB( UCHAR * pucRegBuffer, USHORT usAddress, - USHORT usNDiscrete ); +eMBErrorCode eMBRegDiscreteCB( uint8_t * pucRegBuffer, uint16_t usAddress, + uint16_t usNDiscrete ); #ifdef __cplusplus PR_END_EXTERN_C diff --git a/apps/include/modbus/mbframe.h b/apps/include/modbus/mbframe.h index 99d59c613..0f701e6e5 100644 --- a/apps/include/modbus/mbframe.h +++ b/apps/include/modbus/mbframe.h @@ -71,13 +71,13 @@ typedef void ( *pvMBFrameStart ) ( void ); typedef void ( *pvMBFrameStop ) ( void ); -typedef eMBErrorCode( *peMBFrameReceive ) ( UCHAR * pucRcvAddress, - UCHAR ** pucFrame, - USHORT * pusLength ); +typedef eMBErrorCode( *peMBFrameReceive ) ( uint8_t * pucRcvAddress, + uint8_t ** pucFrame, + uint16_t * pusLength ); -typedef eMBErrorCode( *peMBFrameSend ) ( UCHAR slaveAddress, - const UCHAR * pucFrame, - USHORT usLength ); +typedef eMBErrorCode( *peMBFrameSend ) ( uint8_t slaveAddress, + const uint8_t * pucFrame, + uint16_t usLength ); typedef void( *pvMBFrameClose ) ( void ); diff --git a/apps/include/modbus/mbfunc.h b/apps/include/modbus/mbfunc.h index d948ec72b..68ccdb1d9 100644 --- a/apps/include/modbus/mbfunc.h +++ b/apps/include/modbus/mbfunc.h @@ -35,43 +35,43 @@ PR_BEGIN_EXTERN_C #endif #ifdef CONFIG_MB_FUNC_OTHER_REP_SLAVEID_BUF - eMBException eMBFuncReportSlaveID( UCHAR * pucFrame, USHORT * usLen ); + eMBException eMBFuncReportSlaveID( uint8_t * pucFrame, uint16_t * usLen ); #endif #ifdef CONFIG_MB_FUNC_READ_INPUT_ENABLED -eMBException eMBFuncReadInputRegister( UCHAR * pucFrame, USHORT * usLen ); +eMBException eMBFuncReadInputRegister( uint8_t * pucFrame, uint16_t * usLen ); #endif #ifdef CONFIG_MB_FUNC_READ_HOLDING_ENABLED -eMBException eMBFuncReadHoldingRegister( UCHAR * pucFrame, USHORT * usLen ); +eMBException eMBFuncReadHoldingRegister( uint8_t * pucFrame, uint16_t * usLen ); #endif #ifdef CONFIG_MB_FUNC_WRITE_HOLDING_ENABLED -eMBException eMBFuncWriteHoldingRegister( UCHAR * pucFrame, USHORT * usLen ); +eMBException eMBFuncWriteHoldingRegister( uint8_t * pucFrame, uint16_t * usLen ); #endif #ifdef CONFIG_MB_FUNC_WRITE_MULTIPLE_HOLDING_ENABLED -eMBException eMBFuncWriteMultipleHoldingRegister( UCHAR * pucFrame, USHORT * usLen ); +eMBException eMBFuncWriteMultipleHoldingRegister( uint8_t * pucFrame, uint16_t * usLen ); #endif #ifdef CONFIG_MB_FUNC_READ_COILS_ENABLED -eMBException eMBFuncReadCoils( UCHAR * pucFrame, USHORT * usLen ); +eMBException eMBFuncReadCoils( uint8_t * pucFrame, uint16_t * usLen ); #endif #ifdef CONFIG_MB_FUNC_WRITE_COIL_ENABLED -eMBException eMBFuncWriteCoil( UCHAR * pucFrame, USHORT * usLen ); +eMBException eMBFuncWriteCoil( uint8_t * pucFrame, uint16_t * usLen ); #endif #ifdef CONFIG_MB_FUNC_WRITE_MULTIPLE_COILS_ENABLED -eMBException eMBFuncWriteMultipleCoils( UCHAR * pucFrame, USHORT * usLen ); +eMBException eMBFuncWriteMultipleCoils( uint8_t * pucFrame, uint16_t * usLen ); #endif #ifdef CONFIG_MB_FUNC_READ_DISCRETE_INPUTS_ENABLED -eMBException eMBFuncReadDiscreteInputs( UCHAR * pucFrame, USHORT * usLen ); +eMBException eMBFuncReadDiscreteInputs( uint8_t * pucFrame, uint16_t * usLen ); #endif #ifdef CONFIG_MB_FUNC_READWRITE_HOLDING_ENABLED -eMBException eMBFuncReadWriteMultipleHoldingRegister( UCHAR * pucFrame, USHORT * usLen ); +eMBException eMBFuncReadWriteMultipleHoldingRegister( uint8_t * pucFrame, uint16_t * usLen ); #endif #ifdef __cplusplus diff --git a/apps/include/modbus/mbport.h b/apps/include/modbus/mbport.h index 4f25a9644..e011c15bd 100644 --- a/apps/include/modbus/mbport.h +++ b/apps/include/modbus/mbport.h @@ -31,6 +31,9 @@ #ifndef _MB_PORT_H #define _MB_PORT_H +#include +#include + #ifdef __cplusplus PR_BEGIN_EXTERN_C #endif @@ -60,29 +63,29 @@ typedef enum } eMBParity; /* ----------------------- Supporting functions -----------------------------*/ -BOOL xMBPortEventInit( void ); +bool xMBPortEventInit( void ); -BOOL xMBPortEventPost( eMBEventType eEvent ); +bool xMBPortEventPost( eMBEventType eEvent ); -BOOL xMBPortEventGet( /*@out@ */ eMBEventType * eEvent ); +bool xMBPortEventGet( /*@out@ */ eMBEventType * eEvent ); /* ----------------------- Serial port functions ----------------------------*/ -BOOL xMBPortSerialInit( UCHAR ucPort, ULONG ulBaudRate, - UCHAR ucDataBits, eMBParity eParity ); +bool xMBPortSerialInit( uint8_t ucPort, uint32_t ulBaudRate, + uint8_t ucDataBits, eMBParity eParity ); void vMBPortClose( void ); void xMBPortSerialClose( void ); -void vMBPortSerialEnable( BOOL xRxEnable, BOOL xTxEnable ); +void vMBPortSerialEnable( bool xRxEnable, bool xTxEnable ); -BOOL xMBPortSerialGetByte( CHAR * pucByte ); +bool xMBPortSerialGetByte( int8_t * pucByte ); -BOOL xMBPortSerialPutByte( CHAR ucByte ); +bool xMBPortSerialPutByte( int8_t ucByte ); /* ----------------------- Timers functions ---------------------------------*/ -BOOL xMBPortTimersInit( USHORT usTimeOut50us ); +bool xMBPortTimersInit( uint16_t usTimeOut50us ); void xMBPortTimersClose( void ); @@ -90,7 +93,7 @@ void vMBPortTimersEnable( void ); void vMBPortTimersDisable( void ); -void vMBPortTimersDelay( USHORT usTimeOutMS ); +void vMBPortTimersDelay( uint16_t usTimeOutMS ); /* ----------------------- Callback for the protocol stack ------------------*/ @@ -102,26 +105,26 @@ void vMBPortTimersDelay( USHORT usTimeOutMS ); * ASCII transmission layers. In any case a call to xMBPortSerialGetByte() * must immediately return a new character. * - * \return TRUE if a event was posted to the queue because + * \return true if a event was posted to the queue because * a new byte was received. The port implementation should wake up the * tasks which are currently blocked on the eventqueue. */ -extern BOOL( *pxMBFrameCBByteReceived ) ( void ); +extern bool( *pxMBFrameCBByteReceived ) ( void ); -extern BOOL( *pxMBFrameCBTransmitterEmpty ) ( void ); +extern bool( *pxMBFrameCBTransmitterEmpty ) ( void ); -extern BOOL( *pxMBPortCBTimerExpired ) ( void ); +extern bool( *pxMBPortCBTimerExpired ) ( void ); /* ----------------------- TCP port functions -------------------------------*/ -BOOL xMBTCPPortInit( USHORT usTCPPort ); +bool xMBTCPPortInit( uint16_t usTCPPort ); void vMBTCPPortClose( void ); void vMBTCPPortDisable( void ); -BOOL xMBTCPPortGetRequest( UCHAR **ppucMBTCPFrame, USHORT * usTCPLength ); +bool xMBTCPPortGetRequest( uint8_t **ppucMBTCPFrame, uint16_t * usTCPLength ); -BOOL xMBTCPPortSendResponse( const UCHAR *pucMBTCPFrame, USHORT usTCPLength ); +bool xMBTCPPortSendResponse( const uint8_t *pucMBTCPFrame, uint16_t usTCPLength ); #ifdef __cplusplus PR_END_EXTERN_C diff --git a/apps/include/modbus/mbproto.h b/apps/include/modbus/mbproto.h index 786aaf403..24b0c98e7 100644 --- a/apps/include/modbus/mbproto.h +++ b/apps/include/modbus/mbproto.h @@ -69,11 +69,11 @@ PR_BEGIN_EXTERN_C MB_EX_GATEWAY_TGT_FAILED = 0x0B } eMBException; -typedef eMBException( *pxMBFunctionHandler ) ( UCHAR * pucFrame, USHORT * pusLength ); +typedef eMBException( *pxMBFunctionHandler ) ( uint8_t * pucFrame, uint16_t * pusLength ); typedef struct { - UCHAR ucFunctionCode; + uint8_t ucFunctionCode; pxMBFunctionHandler pxHandler; } xMBFunctionHandler; diff --git a/apps/include/modbus/mbutils.h b/apps/include/modbus/mbutils.h index 61495751d..5f17376cc 100644 --- a/apps/include/modbus/mbutils.h +++ b/apps/include/modbus/mbutils.h @@ -75,8 +75,8 @@ PR_BEGIN_EXTERN_C * xMBUtilSetBits( ucBits, 8, 8, 0x5A); * \endcode */ -void xMBUtilSetBits( UCHAR * ucByteBuf, USHORT usBitOffset, - UCHAR ucNBits, UCHAR ucValues ); +void xMBUtilSetBits( uint8_t * ucByteBuf, uint16_t usBitOffset, + uint8_t ucNBits, uint8_t ucValues ); /*! \brief Function to read bits in a byte buffer. * @@ -90,15 +90,15 @@ void xMBUtilSetBits( UCHAR * ucByteBuf, USHORT usBitOffset, * than 8. * * \code - * UCHAR ucBits[2] = {0, 0}; - * UCHAR ucResult; + * uint8_t ucBits[2] = {0, 0}; + * uint8_t ucResult; * * // Extract the bits 3 - 10. * ucResult = xMBUtilGetBits( ucBits, 3, 8 ); * \endcode */ -UCHAR xMBUtilGetBits( UCHAR * ucByteBuf, USHORT usBitOffset, - UCHAR ucNBits ); +uint8_t xMBUtilGetBits( uint8_t * ucByteBuf, uint16_t usBitOffset, + uint8_t ucNBits ); /*! @} */ diff --git a/apps/modbus/ascii/mbascii.c b/apps/modbus/ascii/mbascii.c index 6b871601b..455e1a7cb 100644 --- a/apps/modbus/ascii/mbascii.c +++ b/apps/modbus/ascii/mbascii.c @@ -80,11 +80,11 @@ typedef enum } eMBBytePos; /* ----------------------- Static functions ---------------------------------*/ -static UCHAR prvucMBCHAR2BIN( UCHAR ucCharacter ); +static uint8_t prvucMBint8_t2BIN( uint8_t ucCharacter ); -static UCHAR prvucMBBIN2CHAR( UCHAR ucByte ); +static uint8_t prvucMBBIN2int8_t( uint8_t ucByte ); -static UCHAR prvucMBLRC( UCHAR * pucFrame, USHORT usLen ); +static uint8_t prvucMBLRC( uint8_t * pucFrame, uint16_t usLen ); /* ----------------------- Static variables ---------------------------------*/ static volatile eMBSndState eSndState; @@ -92,21 +92,21 @@ static volatile eMBRcvState eRcvState; /* We reuse the Modbus RTU buffer because only one buffer is needed and the * RTU buffer is bigger. */ -extern volatile UCHAR ucRTUBuf[]; -static volatile UCHAR *ucASCIIBuf = ucRTUBuf; +extern volatile uint8_t ucRTUBuf[]; +static volatile uint8_t *ucASCIIBuf = ucRTUBuf; -static volatile USHORT usRcvBufferPos; +static volatile uint16_t usRcvBufferPos; static volatile eMBBytePos eBytePos; -static volatile UCHAR *pucSndBufferCur; -static volatile USHORT usSndBufferCount; +static volatile uint8_t *pucSndBufferCur; +static volatile uint16_t usSndBufferCount; -static volatile UCHAR ucLRC; -static volatile UCHAR ucMBLFCharacter; +static volatile uint8_t ucLRC; +static volatile uint8_t ucMBLFCharacter; /* ----------------------- Start implementation -----------------------------*/ eMBErrorCode -eMBASCIIInit( UCHAR ucSlaveAddress, UCHAR ucPort, ULONG ulBaudRate, eMBParity eParity ) +eMBASCIIInit( uint8_t ucSlaveAddress, uint8_t ucPort, uint32_t ulBaudRate, eMBParity eParity ) { eMBErrorCode eStatus = MB_ENOERR; ( void )ucSlaveAddress; @@ -114,11 +114,11 @@ eMBASCIIInit( UCHAR ucSlaveAddress, UCHAR ucPort, ULONG ulBaudRate, eMBParity eP ENTER_CRITICAL_SECTION( ); ucMBLFCharacter = MB_ASCII_DEFAULT_LF; - if( xMBPortSerialInit( ucPort, ulBaudRate, 7, eParity ) != TRUE ) + if( xMBPortSerialInit( ucPort, ulBaudRate, 7, eParity ) != true ) { eStatus = MB_EPORTERR; } - else if( xMBPortTimersInit( CONFIG_MB_ASCII_TIMEOUT_SEC * 20000UL ) != TRUE ) + else if( xMBPortTimersInit( CONFIG_MB_ASCII_TIMEOUT_SEC * 20000UL ) != true ) { eStatus = MB_EPORTERR; } @@ -132,7 +132,7 @@ void eMBASCIIStart( void ) { ENTER_CRITICAL_SECTION( ); - vMBPortSerialEnable( TRUE, FALSE ); + vMBPortSerialEnable( true, false ); eRcvState = STATE_RX_IDLE; EXIT_CRITICAL_SECTION( ); @@ -144,13 +144,13 @@ void eMBASCIIStop( void ) { ENTER_CRITICAL_SECTION( ); - vMBPortSerialEnable( FALSE, FALSE ); + vMBPortSerialEnable( false, false ); vMBPortTimersDisable( ); EXIT_CRITICAL_SECTION( ); } eMBErrorCode -eMBASCIIReceive( UCHAR * pucRcvAddress, UCHAR ** pucFrame, USHORT * pusLength ) +eMBASCIIReceive( uint8_t * pucRcvAddress, uint8_t ** pucFrame, uint16_t * pusLength ) { eMBErrorCode eStatus = MB_ENOERR; @@ -159,7 +159,7 @@ eMBASCIIReceive( UCHAR * pucRcvAddress, UCHAR ** pucFrame, USHORT * pusLength ) /* Length and CRC check */ if( ( usRcvBufferPos >= MB_SER_PDU_SIZE_MIN ) - && ( prvucMBLRC( ( UCHAR * ) ucASCIIBuf, usRcvBufferPos ) == 0 ) ) + && ( prvucMBLRC( ( uint8_t * ) ucASCIIBuf, usRcvBufferPos ) == 0 ) ) { /* Save the address field. All frames are passed to the upper layed * and the decision if a frame is used is done there. @@ -169,10 +169,10 @@ eMBASCIIReceive( UCHAR * pucRcvAddress, UCHAR ** pucFrame, USHORT * pusLength ) /* Total length of Modbus-PDU is Modbus-Serial-Line-PDU minus * size of address field and CRC checksum. */ - *pusLength = ( USHORT )( usRcvBufferPos - MB_SER_PDU_PDU_OFF - MB_SER_PDU_SIZE_LRC ); + *pusLength = ( uint16_t )( usRcvBufferPos - MB_SER_PDU_PDU_OFF - MB_SER_PDU_SIZE_LRC ); /* Return the start of the Modbus PDU to the caller. */ - *pucFrame = ( UCHAR * ) & ucASCIIBuf[MB_SER_PDU_PDU_OFF]; + *pucFrame = ( uint8_t * ) & ucASCIIBuf[MB_SER_PDU_PDU_OFF]; } else { @@ -183,10 +183,10 @@ eMBASCIIReceive( UCHAR * pucRcvAddress, UCHAR ** pucFrame, USHORT * pusLength ) } eMBErrorCode -eMBASCIISend( UCHAR ucSlaveAddress, const UCHAR * pucFrame, USHORT usLength ) +eMBASCIISend( uint8_t ucSlaveAddress, const uint8_t * pucFrame, uint16_t usLength ) { eMBErrorCode eStatus = MB_ENOERR; - UCHAR usLRC; + uint8_t usLRC; ENTER_CRITICAL_SECTION( ); /* Check if the receiver is still in idle state. If not we where too @@ -196,7 +196,7 @@ eMBASCIISend( UCHAR ucSlaveAddress, const UCHAR * pucFrame, USHORT usLength ) if( eRcvState == STATE_RX_IDLE ) { /* First byte before the Modbus-PDU is the slave address. */ - pucSndBufferCur = ( UCHAR * ) pucFrame - 1; + pucSndBufferCur = ( uint8_t * ) pucFrame - 1; usSndBufferCount = 1; /* Now copy the Modbus-PDU into the Modbus-Serial-Line-PDU. */ @@ -204,12 +204,12 @@ eMBASCIISend( UCHAR ucSlaveAddress, const UCHAR * pucFrame, USHORT usLength ) usSndBufferCount += usLength; /* Calculate LRC checksum for Modbus-Serial-Line-PDU. */ - usLRC = prvucMBLRC( ( UCHAR * ) pucSndBufferCur, usSndBufferCount ); + usLRC = prvucMBLRC( ( uint8_t * ) pucSndBufferCur, usSndBufferCount ); ucASCIIBuf[usSndBufferCount++] = usLRC; /* Activate the transmitter. */ eSndState = STATE_TX_START; - vMBPortSerialEnable( FALSE, TRUE ); + vMBPortSerialEnable( false, true ); } else { @@ -219,16 +219,16 @@ eMBASCIISend( UCHAR ucSlaveAddress, const UCHAR * pucFrame, USHORT usLength ) return eStatus; } -BOOL +bool xMBASCIIReceiveFSM( void ) { - BOOL xNeedPoll = FALSE; - UCHAR ucByte; - UCHAR ucResult; + bool xNeedPoll = false; + uint8_t ucByte; + uint8_t ucResult; ASSERT( eSndState == STATE_TX_IDLE ); - ( void )xMBPortSerialGetByte( ( CHAR * ) & ucByte ); + ( void )xMBPortSerialGetByte( ( int8_t * ) & ucByte ); switch ( eRcvState ) { /* A new character is received. If the character is a ':' the input @@ -251,7 +251,7 @@ xMBASCIIReceiveFSM( void ) } else { - ucResult = prvucMBCHAR2BIN( ucByte ); + ucResult = prvucMBint8_t2BIN( ucByte ); switch ( eBytePos ) { /* High nibble of the byte comes first. We check for @@ -259,7 +259,7 @@ xMBASCIIReceiveFSM( void ) case BYTE_HIGH_NIBBLE: if( usRcvBufferPos < MB_SER_PDU_SIZE_MAX ) { - ucASCIIBuf[usRcvBufferPos] = ( UCHAR )( ucResult << 4 ); + ucASCIIBuf[usRcvBufferPos] = ( uint8_t )( ucResult << 4 ); eBytePos = BYTE_LOW_NIBBLE; break; } @@ -328,11 +328,11 @@ xMBASCIIReceiveFSM( void ) return xNeedPoll; } -BOOL +bool xMBASCIITransmitFSM( void ) { - BOOL xNeedPoll = FALSE; - UCHAR ucByte; + bool xNeedPoll = false; + uint8_t ucByte; ASSERT( eRcvState == STATE_RX_IDLE ); switch ( eSndState ) @@ -341,7 +341,7 @@ xMBASCIITransmitFSM( void ) * the character ':'. */ case STATE_TX_START: ucByte = ':'; - xMBPortSerialPutByte( ( CHAR )ucByte ); + xMBPortSerialPutByte( ( int8_t )ucByte ); eSndState = STATE_TX_DATA; eBytePos = BYTE_HIGH_NIBBLE; break; @@ -356,14 +356,14 @@ xMBASCIITransmitFSM( void ) switch ( eBytePos ) { case BYTE_HIGH_NIBBLE: - ucByte = prvucMBBIN2CHAR( ( UCHAR )( *pucSndBufferCur >> 4 ) ); - xMBPortSerialPutByte( ( CHAR ) ucByte ); + ucByte = prvucMBBIN2int8_t( ( uint8_t )( *pucSndBufferCur >> 4 ) ); + xMBPortSerialPutByte( ( int8_t ) ucByte ); eBytePos = BYTE_LOW_NIBBLE; break; case BYTE_LOW_NIBBLE: - ucByte = prvucMBBIN2CHAR( ( UCHAR )( *pucSndBufferCur & 0x0F ) ); - xMBPortSerialPutByte( ( CHAR )ucByte ); + ucByte = prvucMBBIN2int8_t( ( uint8_t )( *pucSndBufferCur & 0x0F ) ); + xMBPortSerialPutByte( ( int8_t )ucByte ); pucSndBufferCur++; eBytePos = BYTE_HIGH_NIBBLE; usSndBufferCount--; @@ -379,7 +379,7 @@ xMBASCIITransmitFSM( void ) /* Finish the frame by sending a LF character. */ case STATE_TX_END: - xMBPortSerialPutByte( ( CHAR )ucMBLFCharacter ); + xMBPortSerialPutByte( ( int8_t )ucMBLFCharacter ); /* We need another state to make sure that the CR character has * been sent. */ eSndState = STATE_TX_NOTIFY; @@ -393,7 +393,7 @@ xMBASCIITransmitFSM( void ) /* Disable transmitter. This prevents another transmit buffer * empty interrupt. */ - vMBPortSerialEnable( TRUE, FALSE ); + vMBPortSerialEnable( true, false ); eSndState = STATE_TX_IDLE; break; @@ -401,14 +401,14 @@ xMBASCIITransmitFSM( void ) * idle state. */ case STATE_TX_IDLE: /* enable receiver/disable transmitter. */ - vMBPortSerialEnable( TRUE, FALSE ); + vMBPortSerialEnable( true, false ); break; } return xNeedPoll; } -BOOL +bool xMBASCIITimerT1SExpired( void ) { switch ( eRcvState ) @@ -428,20 +428,20 @@ xMBASCIITimerT1SExpired( void ) vMBPortTimersDisable( ); /* no context switch required. */ - return FALSE; + return false; } -static UCHAR -prvucMBCHAR2BIN( UCHAR ucCharacter ) +static uint8_t +prvucMBint8_t2BIN( uint8_t ucCharacter ) { if( ( ucCharacter >= '0' ) && ( ucCharacter <= '9' ) ) { - return ( UCHAR )( ucCharacter - '0' ); + return ( uint8_t )( ucCharacter - '0' ); } else if( ( ucCharacter >= 'A' ) && ( ucCharacter <= 'F' ) ) { - return ( UCHAR )( ucCharacter - 'A' + 0x0A ); + return ( uint8_t )( ucCharacter - 'A' + 0x0A ); } else { @@ -449,16 +449,16 @@ prvucMBCHAR2BIN( UCHAR ucCharacter ) } } -static UCHAR -prvucMBBIN2CHAR( UCHAR ucByte ) +static uint8_t +prvucMBBIN2int8_t( uint8_t ucByte ) { if( ucByte <= 0x09 ) { - return ( UCHAR )( '0' + ucByte ); + return ( uint8_t )( '0' + ucByte ); } else if( ( ucByte >= 0x0A ) && ( ucByte <= 0x0F ) ) { - return ( UCHAR )( ucByte - 0x0A + 'A' ); + return ( uint8_t )( ucByte - 0x0A + 'A' ); } else { @@ -469,19 +469,19 @@ prvucMBBIN2CHAR( UCHAR ucByte ) } -static UCHAR -prvucMBLRC( UCHAR * pucFrame, USHORT usLen ) +static uint8_t +prvucMBLRC( uint8_t * pucFrame, uint16_t usLen ) { - UCHAR ucLRC = 0; /* LRC char initialized */ + uint8_t ucLocalLRC = 0; /* LRC char initialized */ while( usLen-- ) { - ucLRC += *pucFrame++; /* Add buffer byte without carry */ + ucLocalLRC += *pucFrame++; /* Add buffer byte without carry */ } /* Return twos complement */ - ucLRC = ( UCHAR ) ( -( ( CHAR ) ucLRC ) ); - return ucLRC; + ucLocalLRC = ( uint8_t ) ( -( ( int8_t ) ucLocalLRC ) ); + return ucLocalLRC; } #endif diff --git a/apps/modbus/ascii/mbascii.h b/apps/modbus/ascii/mbascii.h index 1191a1166..8ac0000e1 100644 --- a/apps/modbus/ascii/mbascii.h +++ b/apps/modbus/ascii/mbascii.h @@ -36,18 +36,18 @@ PR_BEGIN_EXTERN_C #endif #ifdef CONFIG_MB_ASCII_ENABLED -eMBErrorCode eMBASCIIInit( UCHAR slaveAddress, UCHAR ucPort, - ULONG ulBaudRate, eMBParity eParity ); +eMBErrorCode eMBASCIIInit( uint8_t slaveAddress, uint8_t ucPort, + uint32_t ulBaudRate, eMBParity eParity ); void eMBASCIIStart( void ); void eMBASCIIStop( void ); -eMBErrorCode eMBASCIIReceive( UCHAR * pucRcvAddress, UCHAR ** pucFrame, - USHORT * pusLength ); -eMBErrorCode eMBASCIISend( UCHAR slaveAddress, const UCHAR * pucFrame, - USHORT usLength ); -BOOL xMBASCIIReceiveFSM( void ); -BOOL xMBASCIITransmitFSM( void ); -BOOL xMBASCIITimerT1SExpired( void ); +eMBErrorCode eMBASCIIReceive( uint8_t * pucRcvAddress, uint8_t ** pucFrame, + uint16_t * pusLength ); +eMBErrorCode eMBASCIISend( uint8_t slaveAddress, const uint8_t * pucFrame, + uint16_t usLength ); +bool xMBASCIIReceiveFSM( void ); +bool xMBASCIITransmitFSM( void ); +bool xMBASCIITimerT1SExpired( void ); #endif #ifdef __cplusplus diff --git a/apps/modbus/functions/mbfunccoils.c b/apps/modbus/functions/mbfunccoils.c index e518dbc79..d5f23c855 100644 --- a/apps/modbus/functions/mbfunccoils.c +++ b/apps/modbus/functions/mbfunccoils.c @@ -66,24 +66,24 @@ eMBException prveMBError2Exception( eMBErrorCode eErrorCode ); #ifdef CONFIG_MB_FUNC_READ_COILS_ENABLED eMBException -eMBFuncReadCoils( UCHAR * pucFrame, USHORT * usLen ) +eMBFuncReadCoils( uint8_t * pucFrame, uint16_t * usLen ) { - USHORT usRegAddress; - USHORT usCoilCount; - UCHAR ucNBytes; - UCHAR *pucFrameCur; + uint16_t usRegAddress; + uint16_t usCoilCount; + uint8_t ucNBytes; + uint8_t *pucFrameCur; eMBException eStatus = MB_EX_NONE; eMBErrorCode eRegStatus; if( *usLen == ( MB_PDU_FUNC_READ_SIZE + MB_PDU_SIZE_MIN ) ) { - usRegAddress = ( USHORT )( pucFrame[MB_PDU_FUNC_READ_ADDR_OFF] << 8 ); - usRegAddress |= ( USHORT )( pucFrame[MB_PDU_FUNC_READ_ADDR_OFF + 1] ); + usRegAddress = ( uint16_t )( pucFrame[MB_PDU_FUNC_READ_ADDR_OFF] << 8 ); + usRegAddress |= ( uint16_t )( pucFrame[MB_PDU_FUNC_READ_ADDR_OFF + 1] ); usRegAddress++; - usCoilCount = ( USHORT )( pucFrame[MB_PDU_FUNC_READ_COILCNT_OFF] << 8 ); - usCoilCount |= ( USHORT )( pucFrame[MB_PDU_FUNC_READ_COILCNT_OFF + 1] ); + usCoilCount = ( uint16_t )( pucFrame[MB_PDU_FUNC_READ_COILCNT_OFF] << 8 ); + usCoilCount |= ( uint16_t )( pucFrame[MB_PDU_FUNC_READ_COILCNT_OFF + 1] ); /* Check if the number of registers to read is valid. If not * return Modbus illegal data value exception. @@ -103,11 +103,11 @@ eMBFuncReadCoils( UCHAR * pucFrame, USHORT * usLen ) * byte is only partially field with unused coils set to zero. */ if( ( usCoilCount & 0x0007 ) != 0 ) { - ucNBytes = ( UCHAR )( usCoilCount / 8 + 1 ); + ucNBytes = ( uint8_t )( usCoilCount / 8 + 1 ); } else { - ucNBytes = ( UCHAR )( usCoilCount / 8 ); + ucNBytes = ( uint8_t )( usCoilCount / 8 ); } *pucFrameCur++ = ucNBytes; *usLen += 1; @@ -145,18 +145,18 @@ eMBFuncReadCoils( UCHAR * pucFrame, USHORT * usLen ) #ifdef CONFIG_MB_FUNC_WRITE_COIL_ENABLED eMBException -eMBFuncWriteCoil( UCHAR * pucFrame, USHORT * usLen ) +eMBFuncWriteCoil( uint8_t * pucFrame, uint16_t * usLen ) { - USHORT usRegAddress; - UCHAR ucBuf[2]; + uint16_t usRegAddress; + uint8_t ucBuf[2]; eMBException eStatus = MB_EX_NONE; eMBErrorCode eRegStatus; if( *usLen == ( MB_PDU_FUNC_WRITE_SIZE + MB_PDU_SIZE_MIN ) ) { - usRegAddress = ( USHORT )( pucFrame[MB_PDU_FUNC_WRITE_ADDR_OFF] << 8 ); - usRegAddress |= ( USHORT )( pucFrame[MB_PDU_FUNC_WRITE_ADDR_OFF + 1] ); + usRegAddress = ( uint16_t )( pucFrame[MB_PDU_FUNC_WRITE_ADDR_OFF] << 8 ); + usRegAddress |= ( uint16_t )( pucFrame[MB_PDU_FUNC_WRITE_ADDR_OFF + 1] ); usRegAddress++; if( ( pucFrame[MB_PDU_FUNC_WRITE_VALUE_OFF + 1] == 0x00 ) && @@ -199,35 +199,35 @@ eMBFuncWriteCoil( UCHAR * pucFrame, USHORT * usLen ) #ifdef CONFIG_MB_FUNC_WRITE_MULTIPLE_COILS_ENABLED eMBException -eMBFuncWriteMultipleCoils( UCHAR * pucFrame, USHORT * usLen ) +eMBFuncWriteMultipleCoils( uint8_t * pucFrame, uint16_t * usLen ) { - USHORT usRegAddress; - USHORT usCoilCnt; - UCHAR ucByteCount; - UCHAR ucByteCountVerify; + uint16_t usRegAddress; + uint16_t usCoilCnt; + uint8_t ucByteCount; + uint8_t ucByteCountVerify; eMBException eStatus = MB_EX_NONE; eMBErrorCode eRegStatus; if( *usLen > ( MB_PDU_FUNC_WRITE_SIZE + MB_PDU_SIZE_MIN ) ) { - usRegAddress = ( USHORT )( pucFrame[MB_PDU_FUNC_WRITE_MUL_ADDR_OFF] << 8 ); - usRegAddress |= ( USHORT )( pucFrame[MB_PDU_FUNC_WRITE_MUL_ADDR_OFF + 1] ); + usRegAddress = ( uint16_t )( pucFrame[MB_PDU_FUNC_WRITE_MUL_ADDR_OFF] << 8 ); + usRegAddress |= ( uint16_t )( pucFrame[MB_PDU_FUNC_WRITE_MUL_ADDR_OFF + 1] ); usRegAddress++; - usCoilCnt = ( USHORT )( pucFrame[MB_PDU_FUNC_WRITE_MUL_COILCNT_OFF] << 8 ); - usCoilCnt |= ( USHORT )( pucFrame[MB_PDU_FUNC_WRITE_MUL_COILCNT_OFF + 1] ); + usCoilCnt = ( uint16_t )( pucFrame[MB_PDU_FUNC_WRITE_MUL_COILCNT_OFF] << 8 ); + usCoilCnt |= ( uint16_t )( pucFrame[MB_PDU_FUNC_WRITE_MUL_COILCNT_OFF + 1] ); ucByteCount = pucFrame[MB_PDU_FUNC_WRITE_MUL_BYTECNT_OFF]; /* Compute the number of expected bytes in the request. */ if( ( usCoilCnt & 0x0007 ) != 0 ) { - ucByteCountVerify = ( UCHAR )( usCoilCnt / 8 + 1 ); + ucByteCountVerify = ( uint8_t )( usCoilCnt / 8 + 1 ); } else { - ucByteCountVerify = ( UCHAR )( usCoilCnt / 8 ); + ucByteCountVerify = ( uint8_t )( usCoilCnt / 8 ); } if( ( usCoilCnt >= 1 ) && diff --git a/apps/modbus/functions/mbfuncdisc.c b/apps/modbus/functions/mbfuncdisc.c index 525fb037d..6f291bf2f 100644 --- a/apps/modbus/functions/mbfuncdisc.c +++ b/apps/modbus/functions/mbfuncdisc.c @@ -44,24 +44,24 @@ eMBException prveMBError2Exception( eMBErrorCode eErrorCode ); #ifdef CONFIG_MB_FUNC_READ_COILS_ENABLED eMBException -eMBFuncReadDiscreteInputs( UCHAR * pucFrame, USHORT * usLen ) +eMBFuncReadDiscreteInputs( uint8_t * pucFrame, uint16_t * usLen ) { - USHORT usRegAddress; - USHORT usDiscreteCnt; - UCHAR ucNBytes; - UCHAR *pucFrameCur; + uint16_t usRegAddress; + uint16_t usDiscreteCnt; + uint8_t ucNBytes; + uint8_t *pucFrameCur; eMBException eStatus = MB_EX_NONE; eMBErrorCode eRegStatus; if( *usLen == ( MB_PDU_FUNC_READ_SIZE + MB_PDU_SIZE_MIN ) ) { - usRegAddress = ( USHORT )( pucFrame[MB_PDU_FUNC_READ_ADDR_OFF] << 8 ); - usRegAddress |= ( USHORT )( pucFrame[MB_PDU_FUNC_READ_ADDR_OFF + 1] ); + usRegAddress = ( uint16_t )( pucFrame[MB_PDU_FUNC_READ_ADDR_OFF] << 8 ); + usRegAddress |= ( uint16_t )( pucFrame[MB_PDU_FUNC_READ_ADDR_OFF + 1] ); usRegAddress++; - usDiscreteCnt = ( USHORT )( pucFrame[MB_PDU_FUNC_READ_DISCCNT_OFF] << 8 ); - usDiscreteCnt |= ( USHORT )( pucFrame[MB_PDU_FUNC_READ_DISCCNT_OFF + 1] ); + usDiscreteCnt = ( uint16_t )( pucFrame[MB_PDU_FUNC_READ_DISCCNT_OFF] << 8 ); + usDiscreteCnt |= ( uint16_t )( pucFrame[MB_PDU_FUNC_READ_DISCCNT_OFF + 1] ); /* Check if the number of registers to read is valid. If not * return Modbus illegal data value exception. @@ -81,11 +81,11 @@ eMBFuncReadDiscreteInputs( UCHAR * pucFrame, USHORT * usLen ) * byte is only partially field with unused coils set to zero. */ if( ( usDiscreteCnt & 0x0007 ) != 0 ) { - ucNBytes = ( UCHAR ) ( usDiscreteCnt / 8 + 1 ); + ucNBytes = ( uint8_t ) ( usDiscreteCnt / 8 + 1 ); } else { - ucNBytes = ( UCHAR ) ( usDiscreteCnt / 8 ); + ucNBytes = ( uint8_t ) ( usDiscreteCnt / 8 ); } *pucFrameCur++ = ucNBytes; *usLen += 1; diff --git a/apps/modbus/functions/mbfuncholding.c b/apps/modbus/functions/mbfuncholding.c index 019699836..885ce34ca 100644 --- a/apps/modbus/functions/mbfuncholding.c +++ b/apps/modbus/functions/mbfuncholding.c @@ -74,16 +74,16 @@ eMBException prveMBError2Exception( eMBErrorCode eErrorCode ); #ifdef CONFIG_MB_FUNC_WRITE_HOLDING_ENABLED eMBException -eMBFuncWriteHoldingRegister( UCHAR * pucFrame, USHORT * usLen ) +eMBFuncWriteHoldingRegister( uint8_t * pucFrame, uint16_t * usLen ) { - USHORT usRegAddress; + uint16_t usRegAddress; eMBException eStatus = MB_EX_NONE; eMBErrorCode eRegStatus; if( *usLen == ( MB_PDU_FUNC_WRITE_SIZE + MB_PDU_SIZE_MIN ) ) { - usRegAddress = ( USHORT )( pucFrame[MB_PDU_FUNC_WRITE_ADDR_OFF] << 8 ); - usRegAddress |= ( USHORT )( pucFrame[MB_PDU_FUNC_WRITE_ADDR_OFF + 1] ); + usRegAddress = ( uint16_t )( pucFrame[MB_PDU_FUNC_WRITE_ADDR_OFF] << 8 ); + usRegAddress |= ( uint16_t )( pucFrame[MB_PDU_FUNC_WRITE_ADDR_OFF + 1] ); usRegAddress++; /* Make callback to update the value. */ @@ -107,29 +107,29 @@ eMBFuncWriteHoldingRegister( UCHAR * pucFrame, USHORT * usLen ) #ifdef CONFIG_MB_FUNC_WRITE_MULTIPLE_HOLDING_ENABLED eMBException -eMBFuncWriteMultipleHoldingRegister( UCHAR * pucFrame, USHORT * usLen ) +eMBFuncWriteMultipleHoldingRegister( uint8_t * pucFrame, uint16_t * usLen ) { - USHORT usRegAddress; - USHORT usRegCount; - UCHAR ucRegByteCount; + uint16_t usRegAddress; + uint16_t usRegCount; + uint8_t ucRegByteCount; eMBException eStatus = MB_EX_NONE; eMBErrorCode eRegStatus; if( *usLen >= ( MB_PDU_FUNC_WRITE_MUL_SIZE_MIN + MB_PDU_SIZE_MIN ) ) { - usRegAddress = ( USHORT )( pucFrame[MB_PDU_FUNC_WRITE_MUL_ADDR_OFF] << 8 ); - usRegAddress |= ( USHORT )( pucFrame[MB_PDU_FUNC_WRITE_MUL_ADDR_OFF + 1] ); + usRegAddress = ( uint16_t )( pucFrame[MB_PDU_FUNC_WRITE_MUL_ADDR_OFF] << 8 ); + usRegAddress |= ( uint16_t )( pucFrame[MB_PDU_FUNC_WRITE_MUL_ADDR_OFF + 1] ); usRegAddress++; - usRegCount = ( USHORT )( pucFrame[MB_PDU_FUNC_WRITE_MUL_REGCNT_OFF] << 8 ); - usRegCount |= ( USHORT )( pucFrame[MB_PDU_FUNC_WRITE_MUL_REGCNT_OFF + 1] ); + usRegCount = ( uint16_t )( pucFrame[MB_PDU_FUNC_WRITE_MUL_REGCNT_OFF] << 8 ); + usRegCount |= ( uint16_t )( pucFrame[MB_PDU_FUNC_WRITE_MUL_REGCNT_OFF + 1] ); ucRegByteCount = pucFrame[MB_PDU_FUNC_WRITE_MUL_BYTECNT_OFF]; if( ( usRegCount >= 1 ) && ( usRegCount <= MB_PDU_FUNC_WRITE_MUL_REGCNT_MAX ) && - ( ucRegByteCount == ( UCHAR ) ( 2 * usRegCount ) ) ) + ( ucRegByteCount == ( uint8_t ) ( 2 * usRegCount ) ) ) { /* Make callback to update the register values. */ eRegStatus = @@ -167,23 +167,23 @@ eMBFuncWriteMultipleHoldingRegister( UCHAR * pucFrame, USHORT * usLen ) #ifdef CONFIG_MB_FUNC_READ_HOLDING_ENABLED eMBException -eMBFuncReadHoldingRegister( UCHAR * pucFrame, USHORT * usLen ) +eMBFuncReadHoldingRegister( uint8_t * pucFrame, uint16_t * usLen ) { - USHORT usRegAddress; - USHORT usRegCount; - UCHAR *pucFrameCur; + uint16_t usRegAddress; + uint16_t usRegCount; + uint8_t *pucFrameCur; eMBException eStatus = MB_EX_NONE; eMBErrorCode eRegStatus; if( *usLen == ( MB_PDU_FUNC_READ_SIZE + MB_PDU_SIZE_MIN ) ) { - usRegAddress = ( USHORT )( pucFrame[MB_PDU_FUNC_READ_ADDR_OFF] << 8 ); - usRegAddress |= ( USHORT )( pucFrame[MB_PDU_FUNC_READ_ADDR_OFF + 1] ); + usRegAddress = ( uint16_t )( pucFrame[MB_PDU_FUNC_READ_ADDR_OFF] << 8 ); + usRegAddress |= ( uint16_t )( pucFrame[MB_PDU_FUNC_READ_ADDR_OFF + 1] ); usRegAddress++; - usRegCount = ( USHORT )( pucFrame[MB_PDU_FUNC_READ_REGCNT_OFF] << 8 ); - usRegCount = ( USHORT )( pucFrame[MB_PDU_FUNC_READ_REGCNT_OFF + 1] ); + usRegCount = ( uint16_t )( pucFrame[MB_PDU_FUNC_READ_REGCNT_OFF] << 8 ); + usRegCount = ( uint16_t )( pucFrame[MB_PDU_FUNC_READ_REGCNT_OFF + 1] ); /* Check if the number of registers to read is valid. If not * return Modbus illegal data value exception. @@ -199,7 +199,7 @@ eMBFuncReadHoldingRegister( UCHAR * pucFrame, USHORT * usLen ) *usLen += 1; /* Second byte in the response contain the number of bytes. */ - *pucFrameCur++ = ( UCHAR ) ( usRegCount * 2 ); + *pucFrameCur++ = ( uint8_t ) ( usRegCount * 2 ); *usLen += 1; /* Make callback to fill the buffer. */ @@ -232,33 +232,33 @@ eMBFuncReadHoldingRegister( UCHAR * pucFrame, USHORT * usLen ) #ifdef CONFIG_MB_FUNC_READWRITE_HOLDING_ENABLED eMBException -eMBFuncReadWriteMultipleHoldingRegister( UCHAR * pucFrame, USHORT * usLen ) +eMBFuncReadWriteMultipleHoldingRegister( uint8_t * pucFrame, uint16_t * usLen ) { - USHORT usRegReadAddress; - USHORT usRegReadCount; - USHORT usRegWriteAddress; - USHORT usRegWriteCount; - UCHAR ucRegWriteByteCount; - UCHAR *pucFrameCur; + uint16_t usRegReadAddress; + uint16_t usRegReadCount; + uint16_t usRegWriteAddress; + uint16_t usRegWriteCount; + uint8_t ucRegWriteByteCount; + uint8_t *pucFrameCur; eMBException eStatus = MB_EX_NONE; eMBErrorCode eRegStatus; if( *usLen >= ( MB_PDU_FUNC_READWRITE_SIZE_MIN + MB_PDU_SIZE_MIN ) ) { - usRegReadAddress = ( USHORT )( pucFrame[MB_PDU_FUNC_READWRITE_READ_ADDR_OFF] << 8U ); - usRegReadAddress |= ( USHORT )( pucFrame[MB_PDU_FUNC_READWRITE_READ_ADDR_OFF + 1] ); + usRegReadAddress = ( uint16_t )( pucFrame[MB_PDU_FUNC_READWRITE_READ_ADDR_OFF] << 8U ); + usRegReadAddress |= ( uint16_t )( pucFrame[MB_PDU_FUNC_READWRITE_READ_ADDR_OFF + 1] ); usRegReadAddress++; - usRegReadCount = ( USHORT )( pucFrame[MB_PDU_FUNC_READWRITE_READ_REGCNT_OFF] << 8U ); - usRegReadCount |= ( USHORT )( pucFrame[MB_PDU_FUNC_READWRITE_READ_REGCNT_OFF + 1] ); + usRegReadCount = ( uint16_t )( pucFrame[MB_PDU_FUNC_READWRITE_READ_REGCNT_OFF] << 8U ); + usRegReadCount |= ( uint16_t )( pucFrame[MB_PDU_FUNC_READWRITE_READ_REGCNT_OFF + 1] ); - usRegWriteAddress = ( USHORT )( pucFrame[MB_PDU_FUNC_READWRITE_WRITE_ADDR_OFF] << 8U ); - usRegWriteAddress |= ( USHORT )( pucFrame[MB_PDU_FUNC_READWRITE_WRITE_ADDR_OFF + 1] ); + usRegWriteAddress = ( uint16_t )( pucFrame[MB_PDU_FUNC_READWRITE_WRITE_ADDR_OFF] << 8U ); + usRegWriteAddress |= ( uint16_t )( pucFrame[MB_PDU_FUNC_READWRITE_WRITE_ADDR_OFF + 1] ); usRegWriteAddress++; - usRegWriteCount = ( USHORT )( pucFrame[MB_PDU_FUNC_READWRITE_WRITE_REGCNT_OFF] << 8U ); - usRegWriteCount |= ( USHORT )( pucFrame[MB_PDU_FUNC_READWRITE_WRITE_REGCNT_OFF + 1] ); + usRegWriteCount = ( uint16_t )( pucFrame[MB_PDU_FUNC_READWRITE_WRITE_REGCNT_OFF] << 8U ); + usRegWriteCount |= ( uint16_t )( pucFrame[MB_PDU_FUNC_READWRITE_WRITE_REGCNT_OFF + 1] ); ucRegWriteByteCount = pucFrame[MB_PDU_FUNC_READWRITE_BYTECNT_OFF]; @@ -281,7 +281,7 @@ eMBFuncReadWriteMultipleHoldingRegister( UCHAR * pucFrame, USHORT * usLen ) *usLen += 1; /* Second byte in the response contain the number of bytes. */ - *pucFrameCur++ = ( UCHAR ) ( usRegReadCount * 2 ); + *pucFrameCur++ = ( uint8_t ) ( usRegReadCount * 2 ); *usLen += 1; /* Make the read callback. */ diff --git a/apps/modbus/functions/mbfuncinput.c b/apps/modbus/functions/mbfuncinput.c index 3f66c6594..3061340f6 100644 --- a/apps/modbus/functions/mbfuncinput.c +++ b/apps/modbus/functions/mbfuncinput.c @@ -56,23 +56,23 @@ eMBException prveMBError2Exception( eMBErrorCode eErrorCode ); #ifdef CONFIG_MB_FUNC_READ_INPUT_ENABLED eMBException -eMBFuncReadInputRegister( UCHAR * pucFrame, USHORT * usLen ) +eMBFuncReadInputRegister( uint8_t * pucFrame, uint16_t * usLen ) { - USHORT usRegAddress; - USHORT usRegCount; - UCHAR *pucFrameCur; + uint16_t usRegAddress; + uint16_t usRegCount; + uint8_t *pucFrameCur; eMBException eStatus = MB_EX_NONE; eMBErrorCode eRegStatus; if( *usLen == ( MB_PDU_FUNC_READ_SIZE + MB_PDU_SIZE_MIN ) ) { - usRegAddress = ( USHORT )( pucFrame[MB_PDU_FUNC_READ_ADDR_OFF] << 8 ); - usRegAddress |= ( USHORT )( pucFrame[MB_PDU_FUNC_READ_ADDR_OFF + 1] ); + usRegAddress = ( uint16_t )( pucFrame[MB_PDU_FUNC_READ_ADDR_OFF] << 8 ); + usRegAddress |= ( uint16_t )( pucFrame[MB_PDU_FUNC_READ_ADDR_OFF + 1] ); usRegAddress++; - usRegCount = ( USHORT )( pucFrame[MB_PDU_FUNC_READ_REGCNT_OFF] << 8 ); - usRegCount |= ( USHORT )( pucFrame[MB_PDU_FUNC_READ_REGCNT_OFF + 1] ); + usRegCount = ( uint16_t )( pucFrame[MB_PDU_FUNC_READ_REGCNT_OFF] << 8 ); + usRegCount |= ( uint16_t )( pucFrame[MB_PDU_FUNC_READ_REGCNT_OFF + 1] ); /* Check if the number of registers to read is valid. If not * return Modbus illegal data value exception. @@ -89,7 +89,7 @@ eMBFuncReadInputRegister( UCHAR * pucFrame, USHORT * usLen ) *usLen += 1; /* Second byte in the response contain the number of bytes. */ - *pucFrameCur++ = ( UCHAR )( usRegCount * 2 ); + *pucFrameCur++ = ( uint8_t )( usRegCount * 2 ); *usLen += 1; eRegStatus = diff --git a/apps/modbus/functions/mbfuncother.c b/apps/modbus/functions/mbfuncother.c index f68097a4c..ea733e905 100644 --- a/apps/modbus/functions/mbfuncother.c +++ b/apps/modbus/functions/mbfuncother.c @@ -44,14 +44,14 @@ #ifdef CONFIG_MB_FUNC_OTHER_REP_SLAVEID_ENABLED /* ----------------------- Static variables ---------------------------------*/ -static UCHAR ucMBSlaveID[CONFIG_MB_FUNC_OTHER_REP_SLAVEID_BUF]; -static USHORT usMBSlaveIDLen; +static uint8_t ucMBSlaveID[CONFIG_MB_FUNC_OTHER_REP_SLAVEID_BUF]; +static uint16_t usMBSlaveIDLen; /* ----------------------- Start implementation -----------------------------*/ eMBErrorCode -eMBSetSlaveID( UCHAR ucSlaveID, BOOL xIsRunning, - UCHAR const *pucAdditional, USHORT usAdditionalLen ) +eMBSetSlaveID( uint8_t ucSlaveID, bool xIsRunning, + uint8_t const *pucAdditional, uint16_t usAdditionalLen ) { eMBErrorCode eStatus = MB_ENOERR; @@ -62,7 +62,7 @@ eMBSetSlaveID( UCHAR ucSlaveID, BOOL xIsRunning, { usMBSlaveIDLen = 0; ucMBSlaveID[usMBSlaveIDLen++] = ucSlaveID; - ucMBSlaveID[usMBSlaveIDLen++] = ( UCHAR )( xIsRunning ? 0xFF : 0x00 ); + ucMBSlaveID[usMBSlaveIDLen++] = ( uint8_t )( xIsRunning ? 0xFF : 0x00 ); if( usAdditionalLen > 0 ) { memcpy( &ucMBSlaveID[usMBSlaveIDLen], pucAdditional, @@ -78,10 +78,10 @@ eMBSetSlaveID( UCHAR ucSlaveID, BOOL xIsRunning, } eMBException -eMBFuncReportSlaveID( UCHAR * pucFrame, USHORT * usLen ) +eMBFuncReportSlaveID( uint8_t * pucFrame, uint16_t * usLen ) { memcpy( &pucFrame[MB_PDU_DATA_OFF], &ucMBSlaveID[0], ( size_t )usMBSlaveIDLen ); - *usLen = ( USHORT )( MB_PDU_DATA_OFF + usMBSlaveIDLen ); + *usLen = ( uint16_t )( MB_PDU_DATA_OFF + usMBSlaveIDLen ); return MB_EX_NONE; } diff --git a/apps/modbus/functions/mbutils.c b/apps/modbus/functions/mbutils.c index 992333565..cbe02872b 100644 --- a/apps/modbus/functions/mbutils.c +++ b/apps/modbus/functions/mbutils.c @@ -42,69 +42,69 @@ #include /* ----------------------- Defines ------------------------------------------*/ -#define BITS_UCHAR 8U +#define BITS_uint8_t 8U /* ----------------------- Start implementation -----------------------------*/ void -xMBUtilSetBits( UCHAR * ucByteBuf, USHORT usBitOffset, UCHAR ucNBits, - UCHAR ucValue ) +xMBUtilSetBits( uint8_t * ucByteBuf, uint16_t usBitOffset, uint8_t ucNBits, + uint8_t ucValue ) { - USHORT usWordBuf; - USHORT usMask; - USHORT usByteOffset; - USHORT usNPreBits; - USHORT usValue = ucValue; + uint16_t usWordBuf; + uint16_t usMask; + uint16_t usByteOffset; + uint16_t usNPreBits; + uint16_t usValue = ucValue; ASSERT( ucNBits <= 8 ); - ASSERT( ( size_t )BITS_UCHAR == sizeof( UCHAR ) * 8 ); + ASSERT( ( size_t )BITS_uint8_t == sizeof( uint8_t ) * 8 ); /* Calculate byte offset for first byte containing the bit values starting * at usBitOffset. */ - usByteOffset = ( USHORT )( ( usBitOffset ) / BITS_UCHAR ); + usByteOffset = ( uint16_t )( ( usBitOffset ) / BITS_uint8_t ); /* How many bits precede our bits to set. */ - usNPreBits = ( USHORT )( usBitOffset - usByteOffset * BITS_UCHAR ); + usNPreBits = ( uint16_t )( usBitOffset - usByteOffset * BITS_uint8_t ); /* Move bit field into position over bits to set */ usValue <<= usNPreBits; /* Prepare a mask for setting the new bits. */ - usMask = ( USHORT )( ( 1 << ( USHORT ) ucNBits ) - 1 ); - usMask <<= usBitOffset - usByteOffset * BITS_UCHAR; + usMask = ( uint16_t )( ( 1 << ( uint16_t ) ucNBits ) - 1 ); + usMask <<= usBitOffset - usByteOffset * BITS_uint8_t; /* copy bits into temporary storage. */ usWordBuf = ucByteBuf[usByteOffset]; - usWordBuf |= ucByteBuf[usByteOffset + 1] << BITS_UCHAR; + usWordBuf |= ucByteBuf[usByteOffset + 1] << BITS_uint8_t; /* Zero out bit field bits and then or value bits into them. */ - usWordBuf = ( USHORT )( ( usWordBuf & ( ~usMask ) ) | usValue ); + usWordBuf = ( uint16_t )( ( usWordBuf & ( ~usMask ) ) | usValue ); /* move bits back into storage */ - ucByteBuf[usByteOffset] = ( UCHAR )( usWordBuf & 0xFF ); - ucByteBuf[usByteOffset + 1] = ( UCHAR )( usWordBuf >> BITS_UCHAR ); + ucByteBuf[usByteOffset] = ( uint8_t )( usWordBuf & 0xFF ); + ucByteBuf[usByteOffset + 1] = ( uint8_t )( usWordBuf >> BITS_uint8_t ); } -UCHAR -xMBUtilGetBits( UCHAR * ucByteBuf, USHORT usBitOffset, UCHAR ucNBits ) +uint8_t +xMBUtilGetBits( uint8_t * ucByteBuf, uint16_t usBitOffset, uint8_t ucNBits ) { - USHORT usWordBuf; - USHORT usMask; - USHORT usByteOffset; - USHORT usNPreBits; + uint16_t usWordBuf; + uint16_t usMask; + uint16_t usByteOffset; + uint16_t usNPreBits; /* Calculate byte offset for first byte containing the bit values starting * at usBitOffset. */ - usByteOffset = ( USHORT )( ( usBitOffset ) / BITS_UCHAR ); + usByteOffset = ( uint16_t )( ( usBitOffset ) / BITS_uint8_t ); /* How many bits precede our bits to set. */ - usNPreBits = ( USHORT )( usBitOffset - usByteOffset * BITS_UCHAR ); + usNPreBits = ( uint16_t )( usBitOffset - usByteOffset * BITS_uint8_t ); /* Prepare a mask for setting the new bits. */ - usMask = ( USHORT )( ( 1 << ( USHORT ) ucNBits ) - 1 ); + usMask = ( uint16_t )( ( 1 << ( uint16_t ) ucNBits ) - 1 ); /* copy bits into temporary storage. */ usWordBuf = ucByteBuf[usByteOffset]; - usWordBuf |= ucByteBuf[usByteOffset + 1] << BITS_UCHAR; + usWordBuf |= ucByteBuf[usByteOffset + 1] << BITS_uint8_t; /* throw away unneeded bits. */ usWordBuf >>= usNPreBits; @@ -112,7 +112,7 @@ xMBUtilGetBits( UCHAR * ucByteBuf, USHORT usBitOffset, UCHAR ucNBits ) /* mask away bits above the requested bitfield. */ usWordBuf &= usMask; - return ( UCHAR ) usWordBuf; + return ( uint8_t ) usWordBuf; } eMBException diff --git a/apps/modbus/mb.c b/apps/modbus/mb.c index 421a25567..0e5c8a920 100644 --- a/apps/modbus/mb.c +++ b/apps/modbus/mb.c @@ -62,7 +62,7 @@ /* ----------------------- Static variables ---------------------------------*/ -static UCHAR ucMBAddress; +static uint8_t ucMBAddress; static eMBMode eMBCurrentMode; static enum @@ -85,12 +85,12 @@ static pvMBFrameClose pvMBFrameCloseCur; * an external event has happend which includes a timeout or the reception * or transmission of a character. */ -BOOL( *pxMBFrameCBByteReceived ) ( void ); -BOOL( *pxMBFrameCBTransmitterEmpty ) ( void ); -BOOL( *pxMBPortCBTimerExpired ) ( void ); +bool( *pxMBFrameCBByteReceived ) ( void ); +bool( *pxMBFrameCBTransmitterEmpty ) ( void ); +bool( *pxMBPortCBTimerExpired ) ( void ); -BOOL( *pxMBFrameCBReceiveFSMCur ) ( void ); -BOOL( *pxMBFrameCBTransmitFSMCur ) ( void ); +bool( *pxMBFrameCBReceiveFSMCur ) ( void ); +bool( *pxMBFrameCBTransmitFSMCur ) ( void ); /* An array of Modbus functions handlers which associates Modbus function * codes with implementing functions. @@ -130,7 +130,7 @@ static xMBFunctionHandler xFuncHandlers[CONFIG_MB_FUNC_HANDLERS_MAX] = { /* ----------------------- Start implementation -----------------------------*/ eMBErrorCode -eMBInit( eMBMode eMode, UCHAR ucSlaveAddress, UCHAR ucPort, ULONG ulBaudRate, eMBParity eParity ) +eMBInit( eMBMode eMode, uint8_t ucSlaveAddress, uint8_t ucPort, uint32_t ulBaudRate, eMBParity eParity ) { eMBErrorCode eStatus = MB_ENOERR; @@ -197,7 +197,7 @@ eMBInit( eMBMode eMode, UCHAR ucSlaveAddress, UCHAR ucPort, ULONG ulBaudRate, eM #ifdef CONFIG_MB_TCP_ENABLED eMBErrorCode -eMBTCPInit( USHORT ucTCPPort ) +eMBTCPInit( uint16_t ucTCPPort ) { eMBErrorCode eStatus = MB_ENOERR; @@ -226,7 +226,7 @@ eMBTCPInit( USHORT ucTCPPort ) #endif eMBErrorCode -eMBRegisterCB( UCHAR ucFunctionCode, pxMBFunctionHandler pxHandler ) +eMBRegisterCB( uint8_t ucFunctionCode, pxMBFunctionHandler pxHandler ) { int i; eMBErrorCode eStatus; @@ -334,10 +334,10 @@ eMBDisable( void ) eMBErrorCode eMBPoll( void ) { - static UCHAR *ucMBFrame; - static UCHAR ucRcvAddress; - static UCHAR ucFunctionCode; - static USHORT usLength; + static uint8_t *ucMBFrame; + static uint8_t ucRcvAddress; + static uint8_t ucFunctionCode; + static uint16_t usLength; static eMBException eException; int i; @@ -352,7 +352,7 @@ eMBPoll( void ) /* Check if there is a event available. If not return control to caller. * Otherwise we will handle the event. */ - if( xMBPortEventGet( &eEvent ) == TRUE ) + if( xMBPortEventGet( &eEvent ) == true ) { switch ( eEvent ) { @@ -396,7 +396,7 @@ eMBPoll( void ) { /* An exception occured. Build an error frame. */ usLength = 0; - ucMBFrame[usLength++] = ( UCHAR )( ucFunctionCode | MB_FUNC_ERROR ); + ucMBFrame[usLength++] = ( uint8_t )( ucFunctionCode | MB_FUNC_ERROR ); ucMBFrame[usLength++] = eException; } if( ( eMBCurrentMode == MB_ASCII ) && CONFIG_MB_ASCII_TIMEOUT_WAIT_BEFORE_SEND_MS ) diff --git a/apps/modbus/nuttx/port.h b/apps/modbus/nuttx/port.h index 6bb9ab1ba..d958791d9 100644 --- a/apps/modbus/nuttx/port.h +++ b/apps/modbus/nuttx/port.h @@ -43,12 +43,12 @@ PR_BEGIN_EXTERN_C #define MB_PORT_HAS_CLOSE 1 -#ifndef TRUE -# define TRUE true +#ifndef true +# define true true #endif -#ifndef FALSE -# define FALSE false +#ifndef false +# define false false #endif /* ----------------------- Type definitions ---------------------------------*/ @@ -61,23 +61,15 @@ typedef enum MB_LOG_DEBUG = 3 } eMBPortLogLevel; -typedef bool BOOL; -typedef uint8_t UCHAR; -typedef int8_t CHAR; -typedef uint16_t USHORT; -typedef int16_t SHORT; -typedef uint32_t ULONG; -typedef int32_t LONG; - /* ----------------------- Function prototypes ------------------------------*/ void vMBPortEnterCritical(void); void vMBPortExitCritical(void); -void vMBPortLog(eMBPortLogLevel eLevel, const CHAR * szModule, - const CHAR * szFmt, ...); +void vMBPortLog(eMBPortLogLevel eLevel, const char * szModule, + const char * szFmt, ...); void vMBPortTimerPoll(void); -BOOL xMBPortSerialPoll(void); -BOOL xMBPortSerialSetTimeout(ULONG dwTimeoutMs); +bool xMBPortSerialPoll(void); +bool xMBPortSerialSetTimeout(uint32_t dwTimeoutMs); #ifdef __cplusplus PR_END_EXTERN_C diff --git a/apps/modbus/nuttx/portevent.c b/apps/modbus/nuttx/portevent.c index e96eb3d73..72c02f8ed 100644 --- a/apps/modbus/nuttx/portevent.c +++ b/apps/modbus/nuttx/portevent.c @@ -25,36 +25,38 @@ #include #include +#include "port.h" + /* ----------------------- Variables ----------------------------------------*/ static eMBEventType eQueuedEvent; -static BOOL xEventInQueue; +static bool xEventInQueue; /* ----------------------- Start implementation -----------------------------*/ -BOOL +bool xMBPortEventInit( void ) { - xEventInQueue = FALSE; - return TRUE; + xEventInQueue = false; + return true; } -BOOL +bool xMBPortEventPost( eMBEventType eEvent ) { - xEventInQueue = TRUE; + xEventInQueue = true; eQueuedEvent = eEvent; - return TRUE; + return true; } -BOOL +bool xMBPortEventGet( eMBEventType * eEvent ) { - BOOL xEventHappened = FALSE; + bool xEventHappened = false; if( xEventInQueue ) { *eEvent = eQueuedEvent; - xEventInQueue = FALSE; - xEventHappened = TRUE; + xEventInQueue = false; + xEventHappened = true; } else { diff --git a/apps/modbus/nuttx/portother.c b/apps/modbus/nuttx/portother.c index d74d28de3..12f79defe 100644 --- a/apps/modbus/nuttx/portother.c +++ b/apps/modbus/nuttx/portother.c @@ -58,9 +58,9 @@ vMBPortLogFile( FILE * fNewLogFile ) } void -vMBPortLog( eMBPortLogLevel eLevel, const CHAR * szModule, const CHAR * szFmt, ... ) +vMBPortLog( eMBPortLogLevel eLevel, const char * szModule, const char * szFmt, ... ) { - CHAR szBuf[512]; + char szBuf[512]; int i; va_list args; FILE *fOutput = fLogFile == NULL ? stderr : fLogFile; diff --git a/apps/modbus/nuttx/portserial.c b/apps/modbus/nuttx/portserial.c index a30f7f4aa..f62166373 100644 --- a/apps/modbus/nuttx/portserial.c +++ b/apps/modbus/nuttx/portserial.c @@ -50,23 +50,23 @@ /* ----------------------- Static variables ---------------------------------*/ static int iSerialFd = -1; -static BOOL bRxEnabled; -static BOOL bTxEnabled; +static bool bRxEnabled; +static bool bTxEnabled; -static ULONG ulTimeoutMs; -static UCHAR ucBuffer[BUF_SIZE]; +static uint32_t ulTimeoutMs; +static uint8_t ucBuffer[BUF_SIZE]; static int uiRxBufferPos; static int uiTxBufferPos; static struct termios xOldTIO; /* ----------------------- Function prototypes ------------------------------*/ -static BOOL prvbMBPortSerialRead( UCHAR * pucBuffer, USHORT usNBytes, USHORT * usNBytesRead ); -static BOOL prvbMBPortSerialWrite( UCHAR * pucBuffer, USHORT usNBytes ); +static bool prvbMBPortSerialRead( uint8_t * pucBuffer, uint16_t usNBytes, uint16_t * usNBytesRead ); +static bool prvbMBPortSerialWrite( uint8_t * pucBuffer, uint16_t usNBytes ); /* ----------------------- Begin implementation -----------------------------*/ void -vMBPortSerialEnable( BOOL bEnableRx, BOOL bEnableTx ) +vMBPortSerialEnable( bool bEnableRx, bool bEnableTx ) { /* it is not allowed that both receiver and transmitter are enabled. */ ASSERT( !bEnableRx || !bEnableTx ); @@ -75,28 +75,28 @@ vMBPortSerialEnable( BOOL bEnableRx, BOOL bEnableTx ) { ( void )tcflush( iSerialFd, TCIFLUSH ); uiRxBufferPos = 0; - bRxEnabled = TRUE; + bRxEnabled = true; } else { - bRxEnabled = FALSE; + bRxEnabled = false; } if( bEnableTx ) { - bTxEnabled = TRUE; + bTxEnabled = true; uiTxBufferPos = 0; } else { - bTxEnabled = FALSE; + bTxEnabled = false; } } -BOOL -xMBPortSerialInit( UCHAR ucPort, ULONG ulBaudRate, UCHAR ucDataBits, eMBParity eParity ) +bool +xMBPortSerialInit( uint8_t ucPort, uint32_t ulBaudRate, uint8_t ucDataBits, eMBParity eParity ) { - CHAR szDevice[16]; - BOOL bStatus = TRUE; + char szDevice[16]; + bool bStatus = true; struct termios xNewTIO; speed_t xNewSpeed; @@ -130,7 +130,7 @@ xMBPortSerialInit( UCHAR ucPort, ULONG ulBaudRate, UCHAR ucDataBits, eMBParity e xNewTIO.c_cflag |= PARENB | PARODD; break; default: - bStatus = FALSE; + bStatus = false; } switch ( ucDataBits ) { @@ -141,7 +141,7 @@ xMBPortSerialInit( UCHAR ucPort, ULONG ulBaudRate, UCHAR ucDataBits, eMBParity e xNewTIO.c_cflag |= CS7; break; default: - bStatus = FALSE; + bStatus = false; } switch ( ulBaudRate ) { @@ -161,7 +161,7 @@ xMBPortSerialInit( UCHAR ucPort, ULONG ulBaudRate, UCHAR ucDataBits, eMBParity e xNewSpeed = B115200; break; default: - bStatus = FALSE; + bStatus = false; } if( bStatus ) { @@ -182,16 +182,16 @@ xMBPortSerialInit( UCHAR ucPort, ULONG ulBaudRate, UCHAR ucDataBits, eMBParity e } else { - vMBPortSerialEnable( FALSE, FALSE ); - bStatus = TRUE; + vMBPortSerialEnable( false, false ); + bStatus = true; } } } return bStatus; } -BOOL -xMBPortSerialSetTimeout( ULONG ulNewTimeoutMs ) +bool +xMBPortSerialSetTimeout( uint32_t ulNewTimeoutMs ) { if( ulNewTimeoutMs > 0 ) { @@ -201,7 +201,7 @@ xMBPortSerialSetTimeout( ULONG ulNewTimeoutMs ) { ulTimeoutMs = 1; } - return TRUE; + return true; } void @@ -215,10 +215,10 @@ vMBPortClose( void ) } } -BOOL -prvbMBPortSerialRead( UCHAR * pucBuffer, USHORT usNBytes, USHORT * usNBytesRead ) +bool +prvbMBPortSerialRead( uint8_t * pucBuffer, uint16_t usNBytes, uint16_t * usNBytesRead ) { - BOOL bResult = TRUE; + bool bResult = true; ssize_t res; fd_set rfds; struct timeval tv; @@ -236,18 +236,18 @@ prvbMBPortSerialRead( UCHAR * pucBuffer, USHORT usNBytes, USHORT * usNBytesRead { if( errno != EINTR ) { - bResult = FALSE; + bResult = false; } } else if( FD_ISSET( iSerialFd, &rfds ) ) { if( ( res = read( iSerialFd, pucBuffer, usNBytes ) ) == -1 ) { - bResult = FALSE; + bResult = false; } else { - *usNBytesRead = ( USHORT ) res; + *usNBytesRead = ( uint16_t ) res; break; } } @@ -257,12 +257,12 @@ prvbMBPortSerialRead( UCHAR * pucBuffer, USHORT usNBytes, USHORT * usNBytesRead break; } } - while( bResult == TRUE ); + while( bResult == true ); return bResult; } -BOOL -prvbMBPortSerialWrite( UCHAR * pucBuffer, USHORT usNBytes ) +bool +prvbMBPortSerialWrite( uint8_t * pucBuffer, uint16_t usNBytes ) { ssize_t res; size_t left = ( size_t ) usNBytes; @@ -282,14 +282,14 @@ prvbMBPortSerialWrite( UCHAR * pucBuffer, USHORT usNBytes ) done += res; left -= res; } - return left == 0 ? TRUE : FALSE; + return left == 0 ? true : false; } -BOOL +bool xMBPortSerialPoll( ) { - BOOL bStatus = TRUE; - USHORT usBytesRead; + bool bStatus = true; + uint16_t usBytesRead; int i; while( bRxEnabled ) @@ -315,7 +315,7 @@ xMBPortSerialPoll( ) { vMBPortLog( MB_LOG_ERROR, "SER-POLL", "read failed on serial device: %s\n", strerror( errno ) ); - bStatus = FALSE; + bStatus = false; } } if( bTxEnabled ) @@ -329,27 +329,27 @@ xMBPortSerialPoll( ) { vMBPortLog( MB_LOG_ERROR, "SER-POLL", "write failed on serial device: %s\n", strerror( errno ) ); - bStatus = FALSE; + bStatus = false; } } return bStatus; } -BOOL -xMBPortSerialPutByte( CHAR ucByte ) +bool +xMBPortSerialPutByte( int8_t ucByte ) { ASSERT( uiTxBufferPos < BUF_SIZE ); ucBuffer[uiTxBufferPos] = ucByte; uiTxBufferPos++; - return TRUE; + return true; } -BOOL -xMBPortSerialGetByte( CHAR * pucByte ) +bool +xMBPortSerialGetByte( int8_t * pucByte ) { ASSERT( uiRxBufferPos < BUF_SIZE ); *pucByte = ucBuffer[uiRxBufferPos]; uiRxBufferPos++; - return TRUE; + return true; } diff --git a/apps/modbus/nuttx/porttimer.c b/apps/modbus/nuttx/porttimer.c index 3ff2d78ae..d688c4f52 100644 --- a/apps/modbus/nuttx/porttimer.c +++ b/apps/modbus/nuttx/porttimer.c @@ -37,14 +37,14 @@ /* ----------------------- Defines ------------------------------------------*/ /* ----------------------- Static variables ---------------------------------*/ -ULONG ulTimeOut; -BOOL bTimeoutEnable; +uint32_t ulTimeOut; +bool bTimeoutEnable; static struct timeval xTimeLast; /* ----------------------- Start implementation -----------------------------*/ -BOOL -xMBPortTimersInit( USHORT usTim1Timerout50us ) +bool +xMBPortTimersInit( uint16_t usTim1Timerout50us ) { ulTimeOut = usTim1Timerout50us / 20U; if( ulTimeOut == 0 ) @@ -62,7 +62,7 @@ xMBPortTimersClose( ) void vMBPortTimerPoll( ) { - ULONG ulDeltaMS; + uint32_t ulDeltaMS; struct timeval xTimeCur; /* Timers are called from the serial layer because we have no high @@ -79,7 +79,7 @@ vMBPortTimerPoll( ) ( xTimeCur.tv_usec - xTimeLast.tv_usec ) * 1000L; if( ulDeltaMS > ulTimeOut ) { - bTimeoutEnable = FALSE; + bTimeoutEnable = false; ( void )pxMBPortCBTimerExpired( ); } } @@ -92,11 +92,11 @@ vMBPortTimersEnable( ) int res = gettimeofday( &xTimeLast, NULL ); ASSERT( res == 0 ); - bTimeoutEnable = TRUE; + bTimeoutEnable = true; } void vMBPortTimersDisable( ) { - bTimeoutEnable = FALSE; + bTimeoutEnable = false; } diff --git a/apps/modbus/rtu/mbcrc.c b/apps/modbus/rtu/mbcrc.c index 29b9ea765..82fe3c3fb 100644 --- a/apps/modbus/rtu/mbcrc.c +++ b/apps/modbus/rtu/mbcrc.c @@ -31,7 +31,7 @@ /* ----------------------- Platform includes --------------------------------*/ #include "port.h" -static const UCHAR aucCRCHi[] = { +static const uint8_t aucCRCHi[] = { 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41, @@ -56,7 +56,7 @@ static const UCHAR aucCRCHi[] = { 0x00, 0xC1, 0x81, 0x40 }; -static const UCHAR aucCRCLo[] = { +static const uint8_t aucCRCLo[] = { 0x00, 0xC0, 0xC1, 0x01, 0xC3, 0x03, 0x02, 0xC2, 0xC6, 0x06, 0x07, 0xC7, 0x05, 0xC5, 0xC4, 0x04, 0xCC, 0x0C, 0x0D, 0xCD, 0x0F, 0xCF, 0xCE, 0x0E, 0x0A, 0xCA, 0xCB, 0x0B, 0xC9, 0x09, 0x08, 0xC8, 0xD8, 0x18, 0x19, 0xD9, @@ -81,18 +81,18 @@ static const UCHAR aucCRCLo[] = { 0x41, 0x81, 0x80, 0x40 }; -USHORT -usMBCRC16( UCHAR * pucFrame, USHORT usLen ) +uint16_t +usMBCRC16( uint8_t * pucFrame, uint16_t usLen ) { - UCHAR ucCRCHi = 0xFF; - UCHAR ucCRCLo = 0xFF; + uint8_t ucCRCHi = 0xFF; + uint8_t ucCRCLo = 0xFF; int iIndex; while( usLen-- ) { iIndex = ucCRCLo ^ *( pucFrame++ ); - ucCRCLo = ( UCHAR )( ucCRCHi ^ aucCRCHi[iIndex] ); + ucCRCLo = ( uint8_t )( ucCRCHi ^ aucCRCHi[iIndex] ); ucCRCHi = aucCRCLo[iIndex]; } - return ( USHORT )( ucCRCHi << 8 | ucCRCLo ); + return ( uint16_t )( ucCRCHi << 8 | ucCRCLo ); } diff --git a/apps/modbus/rtu/mbcrc.h b/apps/modbus/rtu/mbcrc.h index db227763f..9ff06e25d 100644 --- a/apps/modbus/rtu/mbcrc.h +++ b/apps/modbus/rtu/mbcrc.h @@ -31,6 +31,6 @@ #ifndef _MB_CRC_H #define _MB_CRC_H -USHORT usMBCRC16( UCHAR * pucFrame, USHORT usLen ); +uint16_t usMBCRC16( uint8_t * pucFrame, uint16_t usLen ); #endif diff --git a/apps/modbus/rtu/mbrtu.c b/apps/modbus/rtu/mbrtu.c index 8959b66f7..1c2f02a8b 100644 --- a/apps/modbus/rtu/mbrtu.c +++ b/apps/modbus/rtu/mbrtu.c @@ -71,25 +71,25 @@ typedef enum static volatile eMBSndState eSndState; static volatile eMBRcvState eRcvState; -volatile UCHAR ucRTUBuf[MB_SER_PDU_SIZE_MAX]; +volatile uint8_t ucRTUBuf[MB_SER_PDU_SIZE_MAX]; -static volatile UCHAR *pucSndBufferCur; -static volatile USHORT usSndBufferCount; +static volatile uint8_t *pucSndBufferCur; +static volatile uint16_t usSndBufferCount; -static volatile USHORT usRcvBufferPos; +static volatile uint16_t usRcvBufferPos; /* ----------------------- Start implementation -----------------------------*/ eMBErrorCode -eMBRTUInit( UCHAR ucSlaveAddress, UCHAR ucPort, ULONG ulBaudRate, eMBParity eParity ) +eMBRTUInit( uint8_t ucSlaveAddress, uint8_t ucPort, uint32_t ulBaudRate, eMBParity eParity ) { eMBErrorCode eStatus = MB_ENOERR; - ULONG usTimerT35_50us; + uint32_t usTimerT35_50us; ( void )ucSlaveAddress; ENTER_CRITICAL_SECTION( ); /* Modbus RTU uses 8 Databits. */ - if( xMBPortSerialInit( ucPort, ulBaudRate, 8, eParity ) != TRUE ) + if( xMBPortSerialInit( ucPort, ulBaudRate, 8, eParity ) != true ) { eStatus = MB_EPORTERR; } @@ -114,7 +114,7 @@ eMBRTUInit( UCHAR ucSlaveAddress, UCHAR ucPort, ULONG ulBaudRate, eMBParity ePar */ usTimerT35_50us = ( 7UL * 220000UL ) / ( 2UL * ulBaudRate ); } - if( xMBPortTimersInit( ( USHORT ) usTimerT35_50us ) != TRUE ) + if( xMBPortTimersInit( ( uint16_t ) usTimerT35_50us ) != true ) { eStatus = MB_EPORTERR; } @@ -134,7 +134,7 @@ eMBRTUStart( void ) * modbus protocol stack until the bus is free. */ eRcvState = STATE_RX_INIT; - vMBPortSerialEnable( TRUE, FALSE ); + vMBPortSerialEnable( true, false ); vMBPortTimersEnable( ); EXIT_CRITICAL_SECTION( ); @@ -144,15 +144,15 @@ void eMBRTUStop( void ) { ENTER_CRITICAL_SECTION( ); - vMBPortSerialEnable( FALSE, FALSE ); + vMBPortSerialEnable( false, false ); vMBPortTimersDisable( ); EXIT_CRITICAL_SECTION( ); } eMBErrorCode -eMBRTUReceive( UCHAR * pucRcvAddress, UCHAR ** pucFrame, USHORT * pusLength ) +eMBRTUReceive( uint8_t * pucRcvAddress, uint8_t ** pucFrame, uint16_t * pusLength ) { - BOOL xFrameReceived = FALSE; + bool xFrameReceived = false; eMBErrorCode eStatus = MB_ENOERR; ENTER_CRITICAL_SECTION( ); @@ -160,7 +160,7 @@ eMBRTUReceive( UCHAR * pucRcvAddress, UCHAR ** pucFrame, USHORT * pusLength ) /* Length and CRC check */ if( ( usRcvBufferPos >= MB_SER_PDU_SIZE_MIN ) - && ( usMBCRC16( ( UCHAR * ) ucRTUBuf, usRcvBufferPos ) == 0 ) ) + && ( usMBCRC16( ( uint8_t * ) ucRTUBuf, usRcvBufferPos ) == 0 ) ) { /* Save the address field. All frames are passed to the upper layed * and the decision if a frame is used is done there. @@ -170,11 +170,11 @@ eMBRTUReceive( UCHAR * pucRcvAddress, UCHAR ** pucFrame, USHORT * pusLength ) /* Total length of Modbus-PDU is Modbus-Serial-Line-PDU minus * size of address field and CRC checksum. */ - *pusLength = ( USHORT )( usRcvBufferPos - MB_SER_PDU_PDU_OFF - MB_SER_PDU_SIZE_CRC ); + *pusLength = ( uint16_t )( usRcvBufferPos - MB_SER_PDU_PDU_OFF - MB_SER_PDU_SIZE_CRC ); /* Return the start of the Modbus PDU to the caller. */ - *pucFrame = ( UCHAR * ) & ucRTUBuf[MB_SER_PDU_PDU_OFF]; - xFrameReceived = TRUE; + *pucFrame = ( uint8_t * ) & ucRTUBuf[MB_SER_PDU_PDU_OFF]; + xFrameReceived = true; } else { @@ -186,10 +186,10 @@ eMBRTUReceive( UCHAR * pucRcvAddress, UCHAR ** pucFrame, USHORT * pusLength ) } eMBErrorCode -eMBRTUSend( UCHAR ucSlaveAddress, const UCHAR * pucFrame, USHORT usLength ) +eMBRTUSend( uint8_t ucSlaveAddress, const uint8_t * pucFrame, uint16_t usLength ) { eMBErrorCode eStatus = MB_ENOERR; - USHORT usCRC16; + uint16_t usCRC16; ENTER_CRITICAL_SECTION( ); @@ -200,7 +200,7 @@ eMBRTUSend( UCHAR ucSlaveAddress, const UCHAR * pucFrame, USHORT usLength ) if( eRcvState == STATE_RX_IDLE ) { /* First byte before the Modbus-PDU is the slave address. */ - pucSndBufferCur = ( UCHAR * ) pucFrame - 1; + pucSndBufferCur = ( uint8_t * ) pucFrame - 1; usSndBufferCount = 1; /* Now copy the Modbus-PDU into the Modbus-Serial-Line-PDU. */ @@ -208,13 +208,13 @@ eMBRTUSend( UCHAR ucSlaveAddress, const UCHAR * pucFrame, USHORT usLength ) usSndBufferCount += usLength; /* Calculate CRC16 checksum for Modbus-Serial-Line-PDU. */ - usCRC16 = usMBCRC16( ( UCHAR * ) pucSndBufferCur, usSndBufferCount ); - ucRTUBuf[usSndBufferCount++] = ( UCHAR )( usCRC16 & 0xFF ); - ucRTUBuf[usSndBufferCount++] = ( UCHAR )( usCRC16 >> 8 ); + usCRC16 = usMBCRC16( ( uint8_t * ) pucSndBufferCur, usSndBufferCount ); + ucRTUBuf[usSndBufferCount++] = ( uint8_t )( usCRC16 & 0xFF ); + ucRTUBuf[usSndBufferCount++] = ( uint8_t )( usCRC16 >> 8 ); /* Activate the transmitter. */ eSndState = STATE_TX_XMIT; - vMBPortSerialEnable( FALSE, TRUE ); + vMBPortSerialEnable( false, true ); } else { @@ -224,16 +224,16 @@ eMBRTUSend( UCHAR ucSlaveAddress, const UCHAR * pucFrame, USHORT usLength ) return eStatus; } -BOOL +bool xMBRTUReceiveFSM( void ) { - BOOL xTaskNeedSwitch = FALSE; - UCHAR ucByte; + bool xTaskNeedSwitch = false; + uint8_t ucByte; ASSERT( eSndState == STATE_TX_IDLE ); /* Always read the character. */ - ( void )xMBPortSerialGetByte( ( CHAR * ) & ucByte ); + ( void )xMBPortSerialGetByte( ( int8_t * ) & ucByte ); switch ( eRcvState ) { @@ -284,10 +284,10 @@ xMBRTUReceiveFSM( void ) return xTaskNeedSwitch; } -BOOL +bool xMBRTUTransmitFSM( void ) { - BOOL xNeedPoll = FALSE; + bool xNeedPoll = false; ASSERT( eRcvState == STATE_RX_IDLE ); @@ -297,14 +297,14 @@ xMBRTUTransmitFSM( void ) * idle state. */ case STATE_TX_IDLE: /* enable receiver/disable transmitter. */ - vMBPortSerialEnable( TRUE, FALSE ); + vMBPortSerialEnable( true, false ); break; case STATE_TX_XMIT: /* check if we are finished. */ if( usSndBufferCount != 0 ) { - xMBPortSerialPutByte( ( CHAR )*pucSndBufferCur ); + xMBPortSerialPutByte( ( int8_t )*pucSndBufferCur ); pucSndBufferCur++; /* next byte in sendbuffer. */ usSndBufferCount--; } @@ -313,7 +313,7 @@ xMBRTUTransmitFSM( void ) xNeedPoll = xMBPortEventPost( EV_FRAME_SENT ); /* Disable transmitter. This prevents another transmit buffer * empty interrupt. */ - vMBPortSerialEnable( TRUE, FALSE ); + vMBPortSerialEnable( true, false ); eSndState = STATE_TX_IDLE; } break; @@ -322,10 +322,10 @@ xMBRTUTransmitFSM( void ) return xNeedPoll; } -BOOL +bool xMBRTUTimerT35Expired( void ) { - BOOL xNeedPoll = FALSE; + bool xNeedPoll = false; switch ( eRcvState ) { diff --git a/apps/modbus/rtu/mbrtu.h b/apps/modbus/rtu/mbrtu.h index 8d8bd1f0a..6a14654f0 100644 --- a/apps/modbus/rtu/mbrtu.h +++ b/apps/modbus/rtu/mbrtu.h @@ -34,16 +34,16 @@ #ifdef __cplusplus PR_BEGIN_EXTERN_C #endif - eMBErrorCode eMBRTUInit( UCHAR slaveAddress, UCHAR ucPort, ULONG ulBaudRate, + eMBErrorCode eMBRTUInit( uint8_t slaveAddress, uint8_t ucPort, uint32_t ulBaudRate, eMBParity eParity ); void eMBRTUStart( void ); void eMBRTUStop( void ); -eMBErrorCode eMBRTUReceive( UCHAR * pucRcvAddress, UCHAR ** pucFrame, USHORT * pusLength ); -eMBErrorCode eMBRTUSend( UCHAR slaveAddress, const UCHAR * pucFrame, USHORT usLength ); -BOOL xMBRTUReceiveFSM( void ); -BOOL xMBRTUTransmitFSM( void ); -BOOL xMBRTUTimerT15Expired( void ); -BOOL xMBRTUTimerT35Expired( void ); +eMBErrorCode eMBRTUReceive( uint8_t * pucRcvAddress, uint8_t ** pucFrame, uint16_t * pusLength ); +eMBErrorCode eMBRTUSend( uint8_t slaveAddress, const uint8_t * pucFrame, uint16_t usLength ); +bool xMBRTUReceiveFSM( void ); +bool xMBRTUTransmitFSM( void ); +bool xMBRTUTimerT15Expired( void ); +bool xMBRTUTimerT35Expired( void ); #ifdef __cplusplus PR_END_EXTERN_C diff --git a/apps/modbus/tcp/mbtcp.c b/apps/modbus/tcp/mbtcp.c index 195a88fe9..b841f078a 100644 --- a/apps/modbus/tcp/mbtcp.c +++ b/apps/modbus/tcp/mbtcp.c @@ -79,11 +79,11 @@ /* ----------------------- Start implementation -----------------------------*/ eMBErrorCode -eMBTCPDoInit( USHORT ucTCPPort ) +eMBTCPDoInit( uint16_t ucTCPPort ) { eMBErrorCode eStatus = MB_ENOERR; - if( xMBTCPPortInit( ucTCPPort ) == FALSE ) + if( xMBTCPPortInit( ucTCPPort ) == false ) { eStatus = MB_EPORTERR; } @@ -103,14 +103,14 @@ eMBTCPStop( void ) } eMBErrorCode -eMBTCPReceive( UCHAR * pucRcvAddress, UCHAR ** ppucFrame, USHORT * pusLength ) +eMBTCPReceive( uint8_t * pucRcvAddress, uint8_t ** ppucFrame, uint16_t * pusLength ) { eMBErrorCode eStatus = MB_EIO; - UCHAR *pucMBTCPFrame; - USHORT usLength; - USHORT usPID; + uint8_t *pucMBTCPFrame; + uint16_t usLength; + uint16_t usPID; - if( xMBTCPPortGetRequest( &pucMBTCPFrame, &usLength ) != FALSE ) + if( xMBTCPPortGetRequest( &pucMBTCPFrame, &usLength ) != false ) { usPID = pucMBTCPFrame[MB_TCP_PID] << 8U; usPID |= pucMBTCPFrame[MB_TCP_PID + 1]; @@ -135,11 +135,11 @@ eMBTCPReceive( UCHAR * pucRcvAddress, UCHAR ** ppucFrame, USHORT * pusLength ) } eMBErrorCode -eMBTCPSend( UCHAR _unused, const UCHAR * pucFrame, USHORT usLength ) +eMBTCPSend( uint8_t _unused, const uint8_t * pucFrame, uint16_t usLength ) { eMBErrorCode eStatus = MB_ENOERR; - UCHAR *pucMBTCPFrame = ( UCHAR * ) pucFrame - MB_TCP_FUNC; - USHORT usTCPLength = usLength + MB_TCP_FUNC; + uint8_t *pucMBTCPFrame = ( uint8_t * ) pucFrame - MB_TCP_FUNC; + uint16_t usTCPLength = usLength + MB_TCP_FUNC; /* The MBAP header is already initialized because the caller calls this * function with the buffer returned by the previous call. Therefore we @@ -149,7 +149,7 @@ eMBTCPSend( UCHAR _unused, const UCHAR * pucFrame, USHORT usLength ) */ pucMBTCPFrame[MB_TCP_LEN] = ( usLength + 1 ) >> 8U; pucMBTCPFrame[MB_TCP_LEN + 1] = ( usLength + 1 ) & 0xFF; - if( xMBTCPPortSendResponse( pucMBTCPFrame, usTCPLength ) == FALSE ) + if( xMBTCPPortSendResponse( pucMBTCPFrame, usTCPLength ) == false ) { eStatus = MB_EIO; } diff --git a/apps/modbus/tcp/mbtcp.h b/apps/modbus/tcp/mbtcp.h index 905d113c5..1ded9c5d4 100644 --- a/apps/modbus/tcp/mbtcp.h +++ b/apps/modbus/tcp/mbtcp.h @@ -39,13 +39,13 @@ PR_BEGIN_EXTERN_C #define MB_TCP_PSEUDO_ADDRESS 255 /* ----------------------- Function prototypes ------------------------------*/ - eMBErrorCode eMBTCPDoInit( USHORT ucTCPPort ); + eMBErrorCode eMBTCPDoInit( uint16_t ucTCPPort ); void eMBTCPStart( void ); void eMBTCPStop( void ); -eMBErrorCode eMBTCPReceive( UCHAR * pucRcvAddress, UCHAR ** pucFrame, - USHORT * pusLength ); -eMBErrorCode eMBTCPSend( UCHAR _unused, const UCHAR * pucFrame, - USHORT usLength ); +eMBErrorCode eMBTCPReceive( uint8_t * pucRcvAddress, uint8_t ** pucFrame, + uint16_t * pusLength ); +eMBErrorCode eMBTCPSend( uint8_t _unused, const uint8_t * pucFrame, + uint16_t usLength ); #ifdef __cplusplus PR_END_EXTERN_C -- cgit v1.2.3