summaryrefslogtreecommitdiff
path: root/apps/include/modbus
diff options
context:
space:
mode:
Diffstat (limited to 'apps/include/modbus')
-rw-r--r--apps/include/modbus/mb.h435
-rw-r--r--apps/include/modbus/mbport.h135
2 files changed, 296 insertions, 274 deletions
diff --git a/apps/include/modbus/mb.h b/apps/include/modbus/mb.h
index e6f76b1d5..7f858b05f 100644
--- a/apps/include/modbus/mb.h
+++ b/apps/include/modbus/mb.h
@@ -1,4 +1,6 @@
-/*
+/****************************************************************************
+ * apps/include/modbus/mb.h
+ *
* FreeModbus Libary: A portable Modbus implementation for Modbus ASCII/RTU.
* Copyright (c) 2006 Christian Walter <wolti@sil.at>
* All rights reserved.
@@ -25,11 +27,14 @@
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF
* THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
- * File: $Id: mb.h,v 1.17 2006/12/07 22:10:34 wolti Exp $
- */
+ ****************************************************************************/
-#ifndef _MB_H
-#define _MB_H
+#ifndef __APPS_INCLUDE_MODBUS_MB_H
+#define __APPS_INCLUDE_MODBUS_MB_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
#include <stdint.h>
#include <stdbool.h>
@@ -42,10 +47,11 @@ PR_BEGIN_EXTERN_C
#include "mbport.h"
#include "mbproto.h"
-/*! \defgroup modbus Modbus
- * \code #include "mb.h" \endcode
- *
- * This module defines the interface for the application. It contains
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/* This module defines the interface for the application. It contains
* the basic functions and types required to use the Modbus protocol stack.
* A typical application will want to call eMBInit() first. If the device
* is ready to answer network requests it must then call eMBEnable() to activate
@@ -54,197 +60,207 @@ PR_BEGIN_EXTERN_C
* Modbus timeout. If an RTOS is available a separate task should be created
* and the task should always call the function eMBPoll().
*
- * \code
- * // Initialize protocol stack in RTU mode for a slave with address 10 = 0x0A
- * eMBInit( MB_RTU, 0x0A, 38400, MB_PAR_EVEN );
- * // Enable the Modbus Protocol Stack.
- * eMBEnable( );
- * for( ;; )
- * {
- * // Call the main polling loop of the Modbus protocol stack.
- * eMBPoll( );
- * ...
- * }
- * \endcode
+ * // Initialize protocol stack in RTU mode for a slave with address 10 = 0x0A
+ *
+ * eMBInit(MB_RTU, 0x0A, 38400, MB_PAR_EVEN);
+ *
+ * // Enable the Modbus Protocol Stack.
+ *
+ * eMBEnable();
+ * for(;;)
+ * {
+ * // Call the main polling loop of the Modbus protocol stack.
+ * eMBPoll();
+ * ...
+ * }
*/
-/* ----------------------- Defines ------------------------------------------*/
+/* Use the default Modbus TCP port (502) */
-/*! \ingroup modbus
- * \brief Use the default Modbus TCP port (502)
- */
#define MB_TCP_PORT_USE_DEFAULT 0
-/* ----------------------- Type definitions ---------------------------------*/
+/****************************************************************************
+ * Public Types
+ ****************************************************************************/
-/*! \ingroup modbus
- * \brief Modbus serial transmission modes (RTU/ASCII).
+/* Modbus serial transmission modes (RTU/ASCII).
*
* Modbus serial supports two transmission modes. Either ASCII or RTU. RTU
* is faster but has more hardware requirements and requires a network with
* a low jitter. ASCII is slower and more reliable on slower links (E.g. modems)
*/
- typedef enum
+
+typedef enum
{
- MB_RTU, /*!< RTU transmission mode. */
- MB_ASCII, /*!< ASCII transmission mode. */
- MB_TCP /*!< TCP mode. */
+ MB_RTU, /* RTU transmission mode. */
+ MB_ASCII, /* ASCII transmission mode. */
+ MB_TCP /* TCP mode. */
} eMBMode;
-/*! \ingroup modbus
- * \brief If register should be written or read.
+/* If register should be written or read.
*
* This value is passed to the callback functions which support either
* reading or writing register values. Writing means that the application
* registers should be updated and reading means that the modbus protocol
* stack needs to know the current register values.
*
- * \see eMBRegHoldingCB( ), eMBRegCoilsCB( ), eMBRegDiscreteCB( ) and
- * eMBRegInputCB( ).
+ * See eMBRegHoldingCB(), eMBRegCoilsCB(), eMBRegDiscreteCB() and
+ * eMBRegInputCB().
*/
+
typedef enum
{
- MB_REG_READ, /*!< Read register values and pass to protocol stack. */
- MB_REG_WRITE /*!< Update register values. */
+ MB_REG_READ, /* Read register values and pass to protocol stack. */
+ MB_REG_WRITE /* Update register values. */
} eMBRegisterMode;
-/*! \ingroup modbus
- * \brief Errorcodes used by all function in the protocol stack.
- */
+/* Errorcodes used by all function in the protocol stack. */
+
typedef enum
{
- MB_ENOERR, /*!< no error. */
- MB_ENOREG, /*!< illegal register address. */
- MB_EINVAL, /*!< illegal argument. */
- MB_EPORTERR, /*!< porting layer error. */
- MB_ENORES, /*!< insufficient resources. */
- MB_EIO, /*!< I/O error. */
- MB_EILLSTATE, /*!< protocol stack in illegal state. */
- MB_ETIMEDOUT /*!< timeout error occurred. */
+ MB_ENOERR, /* no error. */
+ MB_ENOREG, /* illegal register address. */
+ MB_EINVAL, /* illegal argument. */
+ MB_EPORTERR, /* porting layer error. */
+ MB_ENORES, /* insufficient resources. */
+ MB_EIO, /* I/O error. */
+ MB_EILLSTATE, /* protocol stack in illegal state. */
+ MB_ETIMEDOUT /* timeout error occurred. */
} eMBErrorCode;
-/* ----------------------- Function prototypes ------------------------------*/
-/*! \ingroup modbus
- * \brief Initialize the Modbus protocol stack.
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
+
+/* Initialize the Modbus protocol stack.
*
* This functions initializes the ASCII or RTU module and calls the
* init functions of the porting layer to prepare the hardware. Please
* note that the receiver is still disabled and no Modbus frames are
- * processed until eMBEnable( ) has been called.
- *
- * \param eMode If ASCII or RTU mode should be used.
- * \param ucSlaveAddress The slave address. Only frames sent to this
- * address or to the broadcast address are processed.
- * \param ucPort The port to use. E.g. 1 for COM1 on windows. This value
- * is platform dependent and some ports simply choose to ignore it.
- * \param ulBaudRate The baudrate. E.g. B19200. Supported baudrates depend
- * on the porting layer.
- * \param eParity Parity used for serial transmission.
- *
- * \return If no error occurs the function returns eMBErrorCode::MB_ENOERR.
+ * processed until eMBEnable() has been called.
+ *
+ * Input Parameters:
+ * eMode If ASCII or RTU mode should be used.
+ * ucSlaveAddress The slave address. Only frames sent to this
+ * address or to the broadcast address are processed.
+ * ucPort The port to use. E.g. 1 for COM1 on windows. This value
+ * is platform dependent and some ports simply choose to ignore it.
+ * ulBaudRate The baudrate. E.g. B19200. Supported baudrates depend
+ * on the porting layer.
+ * eParity Parity used for serial transmission.
+ *
+ * Returned Value:
+ * If no error occurs the function returns eMBErrorCode::MB_ENOERR.
* The protocol is then in the disabled state and ready for activation
- * by calling eMBEnable( ). Otherwise one of the following error codes
+ * by calling eMBEnable(). Otherwise one of the following error codes
* is returned:
* - eMBErrorCode::MB_EINVAL If the slave address was not valid. Valid
* slave addresses are in the range 1 - 247.
* - eMBErrorCode::MB_EPORTERR IF the porting layer returned an error.
*/
-eMBErrorCode eMBInit( eMBMode eMode, uint8_t ucSlaveAddress,
- uint8_t ucPort, speed_t ulBaudRate, eMBParity eParity );
-/*! \ingroup modbus
- * \brief Initialize the Modbus protocol stack for Modbus TCP.
+eMBErrorCode eMBInit(eMBMode eMode, uint8_t ucSlaveAddress,
+ uint8_t ucPort, speed_t ulBaudRate, eMBParity eParity);
+
+/* Initialize the Modbus protocol stack for Modbus TCP.
*
* This function initializes the Modbus TCP Module. Please note that
- * frame processing is still disabled until eMBEnable( ) is called.
+ * frame processing is still disabled until eMBEnable() is called.
*
- * \param usTCPPort The TCP port to listen on.
- * \return If the protocol stack has been initialized correctly the function
+ * Input Parameters:
+ * usTCPPort The TCP port to listen on.
+ *
+ * Returned Value:
+ * If the protocol stack has been initialized correctly the function
* returns eMBErrorCode::MB_ENOERR. Otherwise one of the following error
* codes is returned:
* - eMBErrorCode::MB_EINVAL If the slave address was not valid. Valid
* slave addresses are in the range 1 - 247.
* - eMBErrorCode::MB_EPORTERR IF the porting layer returned an error.
*/
-eMBErrorCode eMBTCPInit( uint16_t usTCPPort );
-/*! \ingroup modbus
- * \brief Release resources used by the protocol stack.
+eMBErrorCode eMBTCPInit(uint16_t usTCPPort);
+
+/* Release resources used by the protocol stack.
*
* This function disables the Modbus protocol stack and release all
* hardware resources. It must only be called when the protocol stack
* is disabled.
*
- * \note Note all ports implement this function. A port which wants to
- * get an callback must define the macro MB_PORT_HAS_CLOSE to 1.
+ * Note all ports implement this function. A port which wants to
+ * get an callback must define the macro CONFIG_MB_HAVE_CLOSE to 1.
*
- * \return If the resources where released it return eMBErrorCode::MB_ENOERR.
+ * Returned Value:
+ * If the resources where released it return eMBErrorCode::MB_ENOERR.
* If the protocol stack is not in the disabled state it returns
* eMBErrorCode::MB_EILLSTATE.
*/
-eMBErrorCode eMBClose( void );
-/*! \ingroup modbus
- * \brief Enable the Modbus protocol stack.
+eMBErrorCode eMBClose(void);
+
+/* Enable the Modbus protocol stack.
*
* This function enables processing of Modbus frames. Enabling the protocol
* stack is only possible if it is in the disabled state.
*
- * \return If the protocol stack is now in the state enabled it returns
+ * Returned Value:
+ * If the protocol stack is now in the state enabled it returns
* eMBErrorCode::MB_ENOERR. If it was not in the disabled state it
* return eMBErrorCode::MB_EILLSTATE.
*/
-eMBErrorCode eMBEnable( void );
-/*! \ingroup modbus
- * \brief Disable the Modbus protocol stack.
+eMBErrorCode eMBEnable(void);
+
+/* Disable the Modbus protocol stack.
*
* This function disables processing of Modbus frames.
*
- * \return If the protocol stack has been disabled it returns
+ * Returned Value:
+ * If the protocol stack has been disabled it returns
* eMBErrorCode::MB_ENOERR. If it was not in the enabled state it returns
* eMBErrorCode::MB_EILLSTATE.
*/
-eMBErrorCode eMBDisable( void );
-/*! \ingroup modbus
- * \brief The main pooling loop of the Modbus protocol stack.
+eMBErrorCode eMBDisable(void);
+
+/* The main pooling loop of the Modbus protocol stack.
*
* This function must be called periodically. The timer interval required
* is given by the application dependent Modbus slave timeout. Internally the
* function calls xMBPortEventGet() and waits for an event from the receiver or
* transmitter state machines.
*
- * \return If the protocol stack is not in the enabled state the function
+ * Returned Value:
+ * If the protocol stack is not in the enabled state the function
* returns eMBErrorCode::MB_EILLSTATE. Otherwise it returns
* eMBErrorCode::MB_ENOERR.
*/
-eMBErrorCode eMBPoll( void );
+eMBErrorCode eMBPoll(void);
-/*! \ingroup modbus
- * \brief Configure the slave id of the device.
- *
- * This function should be called when the Modbus function <em>Report Slave ID</em>
- * is enabled (By defining CONFIG_MB_FUNC_OTHER_REP_SLAVEID_ENABLED in .config ).
- *
- * \param ucSlaveID Values is returned in the <em>Slave ID</em> byte of the
- * <em>Report Slave ID</em> response.
- * \param xIsRunning If true the <em>Run Indicator Status</em> byte is set to 0xFF.
- * otherwise the <em>Run Indicator Status</em> is 0x00.
- * \param pucAdditional Values which should be returned in the <em>Additional</em>
- * bytes of the <em> Report Slave ID</em> response.
- * \param usAdditionalLen Length of the buffer <code>pucAdditonal</code>.
- *
- * \return If the static buffer defined by CONFIG_MB_FUNC_OTHER_REP_SLAVEID_BUF
+/* Configure the slave id of the device.
+ *
+ * This function should be called when the Modbus function Report Slave ID
+ * is enabled (By defining CONFIG_MB_FUNC_OTHER_REP_SLAVEID_ENABLED in .config).
+ *
+ * Input Parameters:
+ * ucSlaveID Values is returned in the Slave ID byte of the
+ * Report Slave ID response.
+ * xIsRunning If true the Run Indicator Status byte is set to 0xFF.
+ * otherwise the Run Indicator Status is 0x00.
+ * pucAdditional Values which should be returned in the Additional
+ * bytes of the Report Slave ID response.
+ * usAdditionalLen Length of the buffer <code>pucAdditonal</code>.
+ *
+ * Returned Value:
+ * If the static buffer defined by CONFIG_MB_FUNC_OTHER_REP_SLAVEID_BUF
* is too small it returns eMBErrorCode::MB_ENORES. Otherwise
* it returns eMBErrorCode::MB_ENOERR.
*/
-eMBErrorCode eMBSetSlaveID( uint8_t ucSlaveID, bool xIsRunning,
+eMBErrorCode eMBSetSlaveID(uint8_t ucSlaveID, bool xIsRunning,
uint8_t const *pucAdditional,
- uint16_t usAdditionalLen );
+ uint16_t usAdditionalLen);
-/*! \ingroup modbus
- * \brief Registers a callback handler for a given function code.
+/* Registers a callback handler for a given function code.
*
* This function registers a new callback handler for a given function code.
* The callback handler supplied is responsible for interpreting the Modbus PDU and
@@ -252,25 +268,25 @@ eMBErrorCode eMBSetSlaveID( uint8_t ucSlaveID, bool xIsRunning,
* one of the possible Modbus exceptions which results in a Modbus exception frame
* sent by the protocol stack.
*
- * \param ucFunctionCode The Modbus function code for which this handler should
- * be registers. Valid function codes are in the range 1 to 127.
- * \param pxHandler The function handler which should be called in case
- * such a frame is received. If \c NULL a previously registered function handler
- * for this function code is removed.
+ * Input Parameters:
+ * ucFunctionCode The Modbus function code for which this handler should
+ * be registers. Valid function codes are in the range 1 to 127.
+ * pxHandler The function handler which should be called in case
+ * such a frame is received. If \c NULL a previously registered function handler
+ * for this function code is removed.
*
- * \return eMBErrorCode::MB_ENOERR if the handler has been installed. If no
+ * Returned Value:
+ * eMBErrorCode::MB_ENOERR if the handler has been installed. If no
* more resources are available it returns eMBErrorCode::MB_ENORES. In this
* case the values in config.h should be adjusted. If the argument was not
* valid it returns eMBErrorCode::MB_EINVAL.
*/
-eMBErrorCode eMBRegisterCB( uint8_t ucFunctionCode,
- pxMBFunctionHandler pxHandler );
+eMBErrorCode eMBRegisterCB(uint8_t ucFunctionCode,
+ pxMBFunctionHandler pxHandler);
/* ----------------------- Callback -----------------------------------------*/
-/*! \defgroup modbus_registers Modbus Registers
- * \code #include "mb.h" \endcode
- * The protocol stack does not internally allocate any memory for the
+/* The protocol stack does not internally allocate any memory for the
* registers. This makes the protocol stack very small and also usable on
* low end targets. In addition the values don't have to be in the memory
* and could for example be stored in a flash.<br>
@@ -285,132 +301,135 @@ eMBErrorCode eMBRegisterCB( uint8_t ucFunctionCode,
* to update the application register values.
*/
-/*! \ingroup modbus_registers
- * \brief Callback function used if the value of a <em>Input Register</em>
- * is required by the protocol stack. The starting register address is given
- * by \c usAddress and the last register is given by <tt>usAddress +
- * usNRegs - 1</tt>.
- *
- * \param pucRegBuffer A buffer where the callback function should write
- * the current value of the modbus registers to.
- * \param usAddress The starting address of the register. Input registers
- * are in the range 1 - 65535.
- * \param usNRegs Number of registers the callback function must supply.
- *
- * \return The function must return one of the following error codes:
+/* Callback function used if the value of a Input Register is required by
+ * the protocol stack. The starting register address is given by \c
+ * usAddress and the last register is given by usAddress + usNRegs - 1.
+ *
+ * Input Parameters:
+ * pucRegBuffer A buffer where the callback function should write
+ * the current value of the modbus registers to.
+ * usAddress The starting address of the register. Input registers
+ * are in the range 1 - 65535.
+ * usNRegs Number of registers the callback function must supply.
+ *
+ * Returned Value:
+ * The function must return one of the following error codes:
* - eMBErrorCode::MB_ENOERR If no error occurred. In this case a normal
* Modbus response is sent.
* - eMBErrorCode::MB_ENOREG If the application can not supply values
* for registers within this range. In this case a
- * <b>ILLEGAL DATA ADDRESS</b> exception frame is sent as a response.
+ * ILLEGAL DATA ADDRESS exception frame is sent as a response.
* - eMBErrorCode::MB_ETIMEDOUT If the requested register block is
* currently not available and the application dependent response
- * timeout would be violated. In this case a <b>SLAVE DEVICE BUSY</b>
+ * timeout would be violated. In this case a SLAVE DEVICE BUSY
* exception is sent as a response.
* - eMBErrorCode::MB_EIO If an unrecoverable error occurred. In this case
- * a <b>SLAVE DEVICE FAILURE</b> exception is sent as a response.
+ * a SLAVE DEVICE FAILURE exception is sent as a response.
*/
-eMBErrorCode eMBRegInputCB( uint8_t * pucRegBuffer, uint16_t usAddress,
- uint16_t usNRegs );
-
-/*! \ingroup modbus_registers
- * \brief Callback function used if a <em>Holding Register</em> value is
- * read or written by the protocol stack. The starting register address
- * is given by \c usAddress and the last register is given by
- * <tt>usAddress + usNRegs - 1</tt>.
- *
- * \param pucRegBuffer If the application registers values should be updated the
- * buffer points to the new registers values. If the protocol stack needs
- * to now the current values the callback function should write them into
- * this buffer.
- * \param usAddress The starting address of the register.
- * \param usNRegs Number of registers to read or write.
- * \param eMode If eMBRegisterMode::MB_REG_WRITE the application register
- * values should be updated from the values in the buffer. For example
- * this would be the case when the Modbus master has issued an
- * <b>WRITE SINGLE REGISTER</b> command.
- * If the value eMBRegisterMode::MB_REG_READ the application should copy
- * the current values into the buffer \c pucRegBuffer.
- *
- * \return The function must return one of the following error codes:
+eMBErrorCode eMBRegInputCB(uint8_t * pucRegBuffer, uint16_t usAddress,
+ uint16_t usNRegs);
+
+/* Callback function used if a Holding Register value is read or written by
+ * the protocol stack. The starting register address is given by \c usAddress
+ * and the last register is given by usAddress + usNRegs - 1.
+ *
+ * Input Parameters:
+ * pucRegBuffer If the application registers values should be updated the
+ * buffer points to the new registers values. If the protocol stack needs
+ * to now the current values the callback function should write them into
+ * this buffer.
+ * usAddress The starting address of the register.
+ * usNRegs Number of registers to read or write.
+ * eMode If eMBRegisterMode::MB_REG_WRITE the application register
+ * values should be updated from the values in the buffer. For example
+ * this would be the case when the Modbus master has issued an
+ * WRITE SINGLE REGISTER command.
+ * If the value eMBRegisterMode::MB_REG_READ the application should copy
+ * the current values into the buffer \c pucRegBuffer.
+ *
+ * Returned Value:
+ * The function must return one of the following error codes:
* - eMBErrorCode::MB_ENOERR If no error occurred. In this case a normal
* Modbus response is sent.
* - eMBErrorCode::MB_ENOREG If the application can not supply values
* for registers within this range. In this case a
- * <b>ILLEGAL DATA ADDRESS</b> exception frame is sent as a response.
+ * ILLEGAL DATA ADDRESS exception frame is sent as a response.
* - eMBErrorCode::MB_ETIMEDOUT If the requested register block is
* currently not available and the application dependent response
- * timeout would be violated. In this case a <b>SLAVE DEVICE BUSY</b>
+ * timeout would be violated. In this case a SLAVE DEVICE BUSY
* exception is sent as a response.
* - eMBErrorCode::MB_EIO If an unrecoverable error occurred. In this case
- * a <b>SLAVE DEVICE FAILURE</b> exception is sent as a response.
+ * a SLAVE DEVICE FAILURE exception is sent as a response.
*/
-eMBErrorCode eMBRegHoldingCB( uint8_t * pucRegBuffer, uint16_t usAddress,
- uint16_t usNRegs, eMBRegisterMode eMode );
-
-/*! \ingroup modbus_registers
- * \brief Callback function used if a <em>Coil Register</em> value is
- * read or written by the protocol stack. If you are going to use
- * this function you might use the functions xMBUtilSetBits( ) and
- * xMBUtilGetBits( ) for working with bitfields.
- *
- * \param pucRegBuffer The bits are packed in bytes where the first coil
- * starting at address \c usAddress is stored in the LSB of the
- * first byte in the buffer <code>pucRegBuffer</code>.
- * If the buffer should be written by the callback function unused
- * coil values (I.e. if not a multiple of eight coils is used) should be set
- * to zero.
- * \param usAddress The first coil number.
- * \param usNCoils Number of coil values requested.
- * \param eMode If eMBRegisterMode::MB_REG_WRITE the application values should
- * be updated from the values supplied in the buffer \c pucRegBuffer.
- * If eMBRegisterMode::MB_REG_READ the application should store the current
- * values in the buffer \c pucRegBuffer.
- *
- * \return The function must return one of the following error codes:
+eMBErrorCode eMBRegHoldingCB(uint8_t * pucRegBuffer, uint16_t usAddress,
+ uint16_t usNRegs, eMBRegisterMode eMode);
+
+/* Callback function used if a Coil Register value is read or written by the
+ * protocol stack. If you are going to use this function you might use the
+ * functions xMBUtilSetBits() and xMBUtilGetBits() for working with
+ * bitfields.
+ *
+ * Input Parameters:
+ * pucRegBuffer The bits are packed in bytes where the first coil
+ * starting at address \c usAddress is stored in the LSB of the
+ * first byte in the buffer <code>pucRegBuffer</code>.
+ * If the buffer should be written by the callback function unused
+ * coil values (I.e. if not a multiple of eight coils is used) should be set
+ * to zero.
+ * usAddress The first coil number.
+ * usNCoils Number of coil values requested.
+ * eMode If eMBRegisterMode::MB_REG_WRITE the application values should
+ * be updated from the values supplied in the buffer \c pucRegBuffer.
+ * If eMBRegisterMode::MB_REG_READ the application should store the current
+ * values in the buffer \c pucRegBuffer.
+ *
+ * Returned Value:
+ * The function must return one of the following error codes:
* - eMBErrorCode::MB_ENOERR If no error occurred. In this case a normal
* Modbus response is sent.
* - eMBErrorCode::MB_ENOREG If the application does not map an coils
* within the requested address range. In this case a
- * <b>ILLEGAL DATA ADDRESS</b> is sent as a response.
+ * ILLEGAL DATA ADDRESS is sent as a response.
* - eMBErrorCode::MB_ETIMEDOUT If the requested register block is
* currently not available and the application dependent response
- * timeout would be violated. In this case a <b>SLAVE DEVICE BUSY</b>
+ * timeout would be violated. In this case a SLAVE DEVICE BUSY
* exception is sent as a response.
* - eMBErrorCode::MB_EIO If an unrecoverable error occurred. In this case
- * a <b>SLAVE DEVICE FAILURE</b> exception is sent as a response.
+ * a SLAVE DEVICE FAILURE exception is sent as a response.
*/
-eMBErrorCode eMBRegCoilsCB( uint8_t * pucRegBuffer, uint16_t usAddress,
- uint16_t 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 <em>Input Discrete Register</em> value is
- * read by the protocol stack.
+/* Callback function used if a Input Discrete Register value is read by
+ * the protocol stack.
*
* If you are going to use his function you might use the functions
- * xMBUtilSetBits( ) and xMBUtilGetBits( ) for working with bitfields.
- *
- * \param pucRegBuffer The buffer should be updated with the current
- * coil values. The first discrete input starting at \c usAddress must be
- * stored at the LSB of the first byte in the buffer. If the requested number
- * is not a multiple of eight the remaining bits should be set to zero.
- * \param usAddress The starting address of the first discrete input.
- * \param usNDiscrete Number of discrete input values.
- * \return The function must return one of the following error codes:
+ * xMBUtilSetBits() and xMBUtilGetBits() for working with bitfields.
+ *
+ * Input Parameters:
+ * pucRegBuffer The buffer should be updated with the current
+ * coil values. The first discrete input starting at \c usAddress must be
+ * stored at the LSB of the first byte in the buffer. If the requested number
+ * is not a multiple of eight the remaining bits should be set to zero.
+ * usAddress The starting address of the first discrete input.
+ * usNDiscrete Number of discrete input values.
+ *
+ * Returned Value:
+ * The function must return one of the following error codes:
* - eMBErrorCode::MB_ENOERR If no error occurred. In this case a normal
* Modbus response is sent.
* - eMBErrorCode::MB_ENOREG If no such discrete inputs exists.
- * In this case a <b>ILLEGAL DATA ADDRESS</b> exception frame is sent
+ * In this case a ILLEGAL DATA ADDRESS exception frame is sent
* as a response.
* - eMBErrorCode::MB_ETIMEDOUT If the requested register block is
* currently not available and the application dependent response
- * timeout would be violated. In this case a <b>SLAVE DEVICE BUSY</b>
+ * timeout would be violated. In this case a SLAVE DEVICE BUSY
* exception is sent as a response.
* - eMBErrorCode::MB_EIO If an unrecoverable error occurred. In this case
- * a <b>SLAVE DEVICE FAILURE</b> exception is sent as a response.
+ * a SLAVE DEVICE FAILURE exception is sent as a response.
*/
-eMBErrorCode eMBRegDiscreteCB( uint8_t * pucRegBuffer, uint16_t usAddress,
- uint16_t usNDiscrete );
+eMBErrorCode eMBRegDiscreteCB(uint8_t * pucRegBuffer, uint16_t usAddress,
+ uint16_t usNDiscrete);
#ifdef __cplusplus
PR_END_EXTERN_C
diff --git a/apps/include/modbus/mbport.h b/apps/include/modbus/mbport.h
index fbc1c260d..ae2170d2b 100644
--- a/apps/include/modbus/mbport.h
+++ b/apps/include/modbus/mbport.h
@@ -1,4 +1,6 @@
-/*
+/****************************************************************************
+ * apps/include/modbus/mbport.h
+ *
* FreeModbus Libary: A portable Modbus implementation for Modbus ASCII/RTU.
* Copyright (c) 2006 Christian Walter <wolti@sil.at>
* All rights reserved.
@@ -25,108 +27,109 @@
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF
* THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
- * File: $Id: mbport.h,v 1.19 2010/06/06 13:54:40 wolti Exp $
- */
+ ****************************************************************************/
-#ifndef _MB_PORT_H
-#define _MB_PORT_H
+#ifndef __APPS_INCLUDE_MODBUS_MBPORT_H
+#define __APPS_INCLUDE_MODBUS_MBPORT_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
#include <stdint.h>
#include <stdbool.h>
+/****************************************************************************
+ * Public Types
+ ****************************************************************************/
+
#ifdef __cplusplus
PR_BEGIN_EXTERN_C
#endif
-/* ----------------------- Type definitions ---------------------------------*/
-
typedef enum
{
- EV_READY, /*!< Startup finished. */
- EV_FRAME_RECEIVED, /*!< Frame received. */
- EV_EXECUTE, /*!< Execute function. */
- EV_FRAME_SENT /*!< Frame sent. */
+ EV_READY, /* Startup finished. */
+ EV_FRAME_RECEIVED, /* Frame received. */
+ EV_EXECUTE, /* Execute function. */
+ EV_FRAME_SENT /* Frame sent. */
} eMBEventType;
-/*! \ingroup modbus
- * \brief Parity used for characters in serial mode.
+/* Parity used for characters in serial mode.
*
* The parity which should be applied to the characters sent over the serial
* link. Please note that this values are actually passed to the porting
* layer and therefore not all parity modes might be available.
*/
+
typedef enum
{
- MB_PAR_NONE, /*!< No parity. */
- MB_PAR_ODD, /*!< Odd parity. */
- MB_PAR_EVEN /*!< Even parity. */
+ MB_PAR_NONE, /* No parity. */
+ MB_PAR_ODD, /* Odd parity. */
+ MB_PAR_EVEN /* Even parity. */
} eMBParity;
-/* ----------------------- Supporting functions -----------------------------*/
-bool xMBPortEventInit( void );
-
-bool xMBPortEventPost( eMBEventType eEvent );
-
-bool xMBPortEventGet( /*@out@ */ eMBEventType * eEvent );
-
-/* ----------------------- Serial port functions ----------------------------*/
-
-bool xMBPortSerialInit( uint8_t ucPort, speed_t ulBaudRate,
- uint8_t ucDataBits, eMBParity eParity );
-
-void vMBPortClose( void );
-
-void xMBPortSerialClose( void );
-
-void vMBPortSerialEnable( bool xRxEnable, bool xTxEnable );
-
-bool xMBPortSerialGetByte( int8_t * pucByte );
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
-bool xMBPortSerialPutByte( int8_t ucByte );
-
-/* ----------------------- Timers functions ---------------------------------*/
-bool xMBPortTimersInit( uint16_t usTimeOut50us );
-
-void xMBPortTimersClose( void );
-
-void vMBPortTimersEnable( void );
-
-void vMBPortTimersDisable( void );
-
-void vMBPortTimersDelay( uint16_t usTimeOutMS );
-
-/* ----------------------- Callback for the protocol stack ------------------*/
-
-/*!
- * \brief Callback function for the porting layer when a new byte is
- * available.
+/* Callback function for the porting layer when a new byte is available.
*
* Depending upon the mode this callback function is used by the RTU or
* ASCII transmission layers. In any case a call to xMBPortSerialGetByte()
* must immediately return a new character.
*
- * \return <code>true</code> 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.
+ * 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( *pxMBFrameCBTransmitterEmpty ) ( void );
+extern bool(*pxMBFrameCBByteReceived)(void);
+extern bool(*pxMBFrameCBTransmitterEmpty)(void);
+extern bool(*pxMBPortCBTimerExpired)(void);
-extern bool( *pxMBPortCBTimerExpired ) ( void );
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
-/* ----------------------- TCP port functions -------------------------------*/
-bool xMBTCPPortInit( uint16_t usTCPPort );
+/* Supporting functions */
-void vMBTCPPortClose( void );
+bool xMBPortEventInit(void);
+bool xMBPortEventPost(eMBEventType eEvent);
+bool xMBPortEventGet(/*@out@ */ eMBEventType * eEvent);
-void vMBTCPPortDisable( void );
+/* Serial port functions */
-bool xMBTCPPortGetRequest( uint8_t **ppucMBTCPFrame, uint16_t * usTCPLength );
+bool xMBPortSerialInit(uint8_t ucPort, speed_t ulBaudRate,
+ uint8_t ucDataBits, eMBParity eParity);
+#ifdef CONFIG_MB_HAVE_CLOSE
+void vMBPortClose(void);
+#endif
+void xMBPortSerialClose(void);
+void vMBPortSerialEnable(bool xRxEnable, bool xTxEnable);
+bool xMBPortSerialGetByte(int8_t * pucByte);
+bool xMBPortSerialPutByte(int8_t ucByte);
+
+/* Timers functions */
-bool xMBTCPPortSendResponse( const uint8_t *pucMBTCPFrame, uint16_t usTCPLength );
+bool xMBPortTimersInit(uint16_t usTimeOut50us);
+void xMBPortTimersClose(void);
+void vMBPortTimersEnable(void);
+void vMBPortTimersDisable(void);
+void vMBPortTimersDelay(uint16_t usTimeOutMS);
+
+/* TCP port function */
+
+bool xMBTCPPortInit(uint16_t usTCPPort);
+#ifdef CONFIG_MB_HAVE_CLOSE
+void vMBTCPPortClose(void);
+#endif
+void vMBTCPPortDisable(void);
+bool xMBTCPPortGetRequest(uint8_t **ppucMBTCPFrame, uint16_t * usTCPLength);
+bool xMBTCPPortSendResponse(const uint8_t *pucMBTCPFrame, uint16_t usTCPLength);
#ifdef __cplusplus
PR_END_EXTERN_C
#endif
-#endif
+
+#endif /* __APPS_INCLUDE_MODBUS_MBPORT_H */