summaryrefslogtreecommitdiff
path: root/apps
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2015-04-07 15:57:52 -0600
committerGregory Nutt <gnutt@nuttx.org>2015-04-07 15:57:52 -0600
commitb7404a8149bbe0a80991c2d496602bd4cba3f4b0 (patch)
tree87ac985b627e9b2dff0f16b425f777024aa2321d /apps
parent9eb5c1d02c305de6db0b4a23db182b48a2171632 (diff)
downloadpx4-nuttx-b7404a8149bbe0a80991c2d496602bd4cba3f4b0.tar.gz
px4-nuttx-b7404a8149bbe0a80991c2d496602bd4cba3f4b0.tar.bz2
px4-nuttx-b7404a8149bbe0a80991c2d496602bd4cba3f4b0.zip
Modbus: changes to several C file to make them more compatible with NuttX coding style
Diffstat (limited to 'apps')
-rw-r--r--apps/include/modbus/mbport.h4
-rw-r--r--apps/modbus/Kconfig1
-rw-r--r--apps/modbus/ascii/mbascii.c698
-rw-r--r--apps/modbus/mb.c8
-rw-r--r--apps/modbus/nuttx/port.h37
-rw-r--r--apps/modbus/nuttx/portevent.c114
-rw-r--r--apps/modbus/nuttx/portother.c64
-rw-r--r--apps/modbus/nuttx/portserial.c309
-rw-r--r--apps/modbus/nuttx/porttimer.c127
9 files changed, 750 insertions, 612 deletions
diff --git a/apps/include/modbus/mbport.h b/apps/include/modbus/mbport.h
index ae2170d2b..bebe31693 100644
--- a/apps/include/modbus/mbport.h
+++ b/apps/include/modbus/mbport.h
@@ -102,9 +102,7 @@ bool xMBPortEventGet(/*@out@ */ eMBEventType * eEvent);
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);
@@ -118,6 +116,7 @@ void vMBPortTimersEnable(void);
void vMBPortTimersDisable(void);
void vMBPortTimersDelay(uint16_t usTimeOutMS);
+#ifdef CONFIG_MB_TCP_ENABLED
/* TCP port function */
bool xMBTCPPortInit(uint16_t usTCPPort);
@@ -127,6 +126,7 @@ void vMBTCPPortClose(void);
void vMBTCPPortDisable(void);
bool xMBTCPPortGetRequest(uint8_t **ppucMBTCPFrame, uint16_t * usTCPLength);
bool xMBTCPPortSendResponse(const uint8_t *pucMBTCPFrame, uint16_t usTCPLength);
+#endif
#ifdef __cplusplus
PR_END_EXTERN_C
diff --git a/apps/modbus/Kconfig b/apps/modbus/Kconfig
index 2c8c7c605..c62ff5c88 100644
--- a/apps/modbus/Kconfig
+++ b/apps/modbus/Kconfig
@@ -24,6 +24,7 @@ config MB_TCP_ENABLED
config MB_HAVE_CLOSE
bool "Platform close callbacks"
default n
+ depends on MB_TCP_ENABLED
---help---
A port which wants to get an callback must select
CONFIG_MB_HAVE_CLOSE and provide vMBPortClose() as
diff --git a/apps/modbus/ascii/mbascii.c b/apps/modbus/ascii/mbascii.c
index 57ea368a7..387c87f31 100644
--- a/apps/modbus/ascii/mbascii.c
+++ b/apps/modbus/ascii/mbascii.c
@@ -1,4 +1,6 @@
-/*
+/****************************************************************************
+ * apps/modbus/ascii/mbascii.c
+ *
* FreeModbus Libary: A portable Modbus implementation for Modbus ASCII/RTU.
* Copyright (c) 2006 Christian Walter <wolti@sil.at>
* All rights reserved.
@@ -25,19 +27,19 @@
* (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: mbascii.c,v 1.17 2010/06/06 13:47:07 wolti Exp $
- */
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
-/* ----------------------- System includes ----------------------------------*/
#include <nuttx/config.h>
#include <stdlib.h>
#include <string.h>
#include <assert.h>
-/* ----------------------- Platform includes --------------------------------*/
#include "port.h"
-/* ----------------------- Modbus includes ----------------------------------*/
#include <apps/modbus/mb.h>
#include <apps/modbus/mbframe.h>
#include <apps/modbus/mbport.h>
@@ -47,51 +49,63 @@
#ifdef CONFIG_MB_ASCII_ENABLED
-/* ----------------------- Defines ------------------------------------------*/
-#define MB_ASCII_DEFAULT_CR '\r' /*!< Default CR character for Modbus ASCII. */
-#define MB_ASCII_DEFAULT_LF '\n' /*!< Default LF character for Modbus ASCII. */
-#define MB_SER_PDU_SIZE_MIN 3 /*!< Minimum size of a Modbus ASCII frame. */
-#define MB_SER_PDU_SIZE_MAX 256 /*!< Maximum size of a Modbus ASCII frame. */
-#define MB_SER_PDU_SIZE_LRC 1 /*!< Size of LRC field in PDU. */
-#define MB_SER_PDU_ADDR_OFF 0 /*!< Offset of slave address in Ser-PDU. */
-#define MB_SER_PDU_PDU_OFF 1 /*!< Offset of Modbus-PDU in Ser-PDU. */
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+#define MB_ASCII_DEFAULT_CR '\r' /* Default CR character for Modbus ASCII. */
+#define MB_ASCII_DEFAULT_LF '\n' /* Default LF character for Modbus ASCII. */
+#define MB_SER_PDU_SIZE_MIN 3 /* Minimum size of a Modbus ASCII frame. */
+#define MB_SER_PDU_SIZE_MAX 256 /* Maximum size of a Modbus ASCII frame. */
+#define MB_SER_PDU_SIZE_LRC 1 /* Size of LRC field in PDU. */
+#define MB_SER_PDU_ADDR_OFF 0 /* Offset of slave address in Ser-PDU. */
+#define MB_SER_PDU_PDU_OFF 1 /* Offset of Modbus-PDU in Ser-PDU. */
+
+/****************************************************************************
+ * Private Type Definitions
+ ****************************************************************************/
-/* ----------------------- Type definitions ---------------------------------*/
typedef enum
{
- STATE_RX_IDLE, /*!< Receiver is in idle state. */
- STATE_RX_RCV, /*!< Frame is beeing received. */
- STATE_RX_WAIT_EOF /*!< Wait for End of Frame. */
+ STATE_RX_IDLE, /* Receiver is in idle state. */
+ STATE_RX_RCV, /* Frame is beeing received. */
+ STATE_RX_WAIT_EOF /* Wait for End of Frame. */
} eMBRcvState;
typedef enum
{
- STATE_TX_IDLE, /*!< Transmitter is in idle state. */
- STATE_TX_START, /*!< Starting transmission (':' sent). */
- STATE_TX_DATA, /*!< Sending of data (Address, Data, LRC). */
- STATE_TX_END, /*!< End of transmission. */
- STATE_TX_NOTIFY /*!< Notify sender that the frame has been sent. */
+ STATE_TX_IDLE, /* Transmitter is in idle state. */
+ STATE_TX_START, /* Starting transmission (':' sent). */
+ STATE_TX_DATA, /* Sending of data (Address, Data, LRC). */
+ STATE_TX_END, /* End of transmission. */
+ STATE_TX_NOTIFY /* Notify sender that the frame has been sent. */
} eMBSndState;
typedef enum
{
- BYTE_HIGH_NIBBLE, /*!< Character for high nibble of byte. */
- BYTE_LOW_NIBBLE /*!< Character for low nibble of byte. */
+ BYTE_HIGH_NIBBLE, /* Character for high nibble of byte. */
+ BYTE_LOW_NIBBLE /* Character for low nibble of byte. */
} eMBBytePos;
-/* ----------------------- Static functions ---------------------------------*/
-static uint8_t prvucMBint8_t2BIN( uint8_t ucCharacter );
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
-static uint8_t prvucMBBIN2int8_t( uint8_t ucByte );
+static uint8_t prvucMBint8_t2BIN(uint8_t ucCharacter);
+static uint8_t prvucMBBIN2int8_t(uint8_t ucByte);
+static uint8_t prvucMBLRC(uint8_t *pucFrame, uint16_t usLen);
-static uint8_t prvucMBLRC( uint8_t * pucFrame, uint16_t usLen );
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
-/* ----------------------- Static variables ---------------------------------*/
static volatile eMBSndState eSndState;
static volatile eMBRcvState eRcvState;
/* We reuse the Modbus RTU buffer because only one buffer is needed and the
- * RTU buffer is bigger. */
+ * RTU buffer is bigger.
+ */
+
extern volatile uint8_t ucRTUBuf[];
static volatile uint8_t *ucASCIIBuf = ucRTUBuf;
@@ -104,384 +118,434 @@ static volatile uint16_t usSndBufferCount;
static volatile uint8_t ucLRC;
static volatile uint8_t ucMBLFCharacter;
-/* ----------------------- Start implementation -----------------------------*/
-eMBErrorCode
-eMBASCIIInit( uint8_t ucSlaveAddress, uint8_t ucPort, speed_t ulBaudRate, eMBParity eParity )
-{
- eMBErrorCode eStatus = MB_ENOERR;
- ( void )ucSlaveAddress;
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
- ENTER_CRITICAL_SECTION( );
- ucMBLFCharacter = MB_ASCII_DEFAULT_LF;
+static uint8_t prvucMBint8_t2BIN(uint8_t ucCharacter)
+{
+ if ((ucCharacter >= '0') && (ucCharacter <= '9'))
+ {
+ return (uint8_t)(ucCharacter - '0');
+ }
+ else if ((ucCharacter >= 'A') && (ucCharacter <= 'F'))
+ {
+ return (uint8_t)(ucCharacter - 'A' + 0x0A);
+ }
+ else
+ {
+ return 0xFF;
+ }
+}
- if( xMBPortSerialInit( ucPort, ulBaudRate, 7, eParity ) != true )
+static uint8_t prvucMBBIN2int8_t(uint8_t ucByte)
+{
+ if (ucByte <= 0x09)
{
- eStatus = MB_EPORTERR;
+ return (uint8_t)('0' + ucByte);
}
- else if( xMBPortTimersInit( CONFIG_MB_ASCII_TIMEOUT_SEC * 20000UL ) != true )
+ else if ((ucByte >= 0x0A) && (ucByte <= 0x0F))
{
- eStatus = MB_EPORTERR;
+ return (uint8_t)(ucByte - 0x0A + 'A');
}
+ else
+ {
+ /* Programming error. */
- EXIT_CRITICAL_SECTION( );
+ ASSERT(0);
+ }
- return eStatus;
+ return '0';
}
-void
-eMBASCIIStart( void )
+static uint8_t prvucMBLRC(uint8_t * pucFrame, uint16_t usLen)
{
- ENTER_CRITICAL_SECTION( );
- vMBPortSerialEnable( true, false );
- eRcvState = STATE_RX_IDLE;
- EXIT_CRITICAL_SECTION( );
+ uint8_t ucLocalLRC = 0; /* LRC char initialized */
- /* No special startup required for ASCII. */
- ( void )xMBPortEventPost( EV_READY );
+ while (usLen--)
+ {
+ ucLocalLRC += *pucFrame++; /* Add buffer byte without carry */
+ }
+
+ /* Return twos complement */
+
+ ucLocalLRC = (uint8_t) (-((int8_t) ucLocalLRC));
+ return ucLocalLRC;
}
-void
-eMBASCIIStop( void )
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+eMBErrorCode eMBASCIIInit(uint8_t ucSlaveAddress, uint8_t ucPort,
+ speed_t ulBaudRate, eMBParity eParity)
{
- ENTER_CRITICAL_SECTION( );
- vMBPortSerialEnable( false, false );
- vMBPortTimersDisable( );
- EXIT_CRITICAL_SECTION( );
+ eMBErrorCode eStatus = MB_ENOERR;
+ (void)ucSlaveAddress;
+
+ ENTER_CRITICAL_SECTION();
+ ucMBLFCharacter = MB_ASCII_DEFAULT_LF;
+
+ if (xMBPortSerialInit(ucPort, ulBaudRate, 7, eParity) != true)
+ {
+ eStatus = MB_EPORTERR;
+ }
+ else if (xMBPortTimersInit(CONFIG_MB_ASCII_TIMEOUT_SEC * 20000UL) != true)
+ {
+ eStatus = MB_EPORTERR;
+ }
+
+ EXIT_CRITICAL_SECTION();
+ return eStatus;
}
-eMBErrorCode
-eMBASCIIReceive( uint8_t * pucRcvAddress, uint8_t ** pucFrame, uint16_t * pusLength )
+void eMBASCIIStart(void)
{
- eMBErrorCode eStatus = MB_ENOERR;
+ ENTER_CRITICAL_SECTION();
+ vMBPortSerialEnable(true, false);
+ eRcvState = STATE_RX_IDLE;
+ EXIT_CRITICAL_SECTION();
- ENTER_CRITICAL_SECTION( );
- ASSERT( usRcvBufferPos < MB_SER_PDU_SIZE_MAX );
+ /* No special startup required for ASCII. */
- /* Length and CRC check */
- if( ( usRcvBufferPos >= MB_SER_PDU_SIZE_MIN )
- && ( prvucMBLRC( ( uint8_t * ) ucASCIIBuf, usRcvBufferPos ) == 0 ) )
+ (void)xMBPortEventPost(EV_READY);
+}
+
+void eMBASCIIStop(void)
+{
+ ENTER_CRITICAL_SECTION();
+ vMBPortSerialEnable(false, false);
+ vMBPortTimersDisable();
+ EXIT_CRITICAL_SECTION();
+}
+
+eMBErrorCode eMBASCIIReceive(uint8_t *pucRcvAddress, uint8_t **pucFrame,
+ uint16_t *pusLength)
+{
+ eMBErrorCode eStatus = MB_ENOERR;
+
+ ENTER_CRITICAL_SECTION();
+ ASSERT(usRcvBufferPos < MB_SER_PDU_SIZE_MAX);
+
+ /* Length and CRC check */
+
+ if ((usRcvBufferPos >= MB_SER_PDU_SIZE_MIN) &&
+ (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.
- */
- *pucRcvAddress = ucASCIIBuf[MB_SER_PDU_ADDR_OFF];
-
- /* Total length of Modbus-PDU is Modbus-Serial-Line-PDU minus
- * size of address field and CRC checksum.
- */
- *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 = ( uint8_t * ) & ucASCIIBuf[MB_SER_PDU_PDU_OFF];
+ /* Save the address field. All frames are passed to the upper layed
+ * and the decision if a frame is used is done there.
+ */
+
+ *pucRcvAddress = ucASCIIBuf[MB_SER_PDU_ADDR_OFF];
+
+ /* Total length of Modbus-PDU is Modbus-Serial-Line-PDU minus
+ * size of address field and CRC checksum.
+ */
+
+ *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 = (uint8_t *) & ucASCIIBuf[MB_SER_PDU_PDU_OFF];
}
- else
+ else
{
- eStatus = MB_EIO;
+ eStatus = MB_EIO;
}
- EXIT_CRITICAL_SECTION( );
- return eStatus;
+
+ EXIT_CRITICAL_SECTION();
+ return eStatus;
}
-eMBErrorCode
-eMBASCIISend( uint8_t ucSlaveAddress, const uint8_t * pucFrame, uint16_t usLength )
+eMBErrorCode eMBASCIISend(uint8_t ucSlaveAddress, const uint8_t *pucFrame,
+ uint16_t usLength)
{
- eMBErrorCode eStatus = MB_ENOERR;
- uint8_t usLRC;
+ eMBErrorCode eStatus = MB_ENOERR;
+ uint8_t usLRC;
- ENTER_CRITICAL_SECTION( );
- /* Check if the receiver is still in idle state. If not we where too
- * slow with processing the received frame and the master sent another
- * frame on the network. We have to abort sending the frame.
- */
- if( eRcvState == STATE_RX_IDLE )
+ ENTER_CRITICAL_SECTION();
+
+ /* Check if the receiver is still in idle state. If not we where too
+ * slow with processing the received frame and the master sent another
+ * frame on the network. We have to abort sending the frame.
+ */
+
+ if (eRcvState == STATE_RX_IDLE)
{
- /* First byte before the Modbus-PDU is the slave address. */
- pucSndBufferCur = ( uint8_t * ) pucFrame - 1;
- usSndBufferCount = 1;
+ /* First byte before the Modbus-PDU is the slave address. */
+
+ pucSndBufferCur = (uint8_t *) pucFrame - 1;
+ usSndBufferCount = 1;
+
+ /* Now copy the Modbus-PDU into the Modbus-Serial-Line-PDU. */
+
+ pucSndBufferCur[MB_SER_PDU_ADDR_OFF] = ucSlaveAddress;
+ usSndBufferCount += usLength;
- /* Now copy the Modbus-PDU into the Modbus-Serial-Line-PDU. */
- pucSndBufferCur[MB_SER_PDU_ADDR_OFF] = ucSlaveAddress;
- usSndBufferCount += usLength;
+ /* Calculate LRC checksum for Modbus-Serial-Line-PDU. */
- /* Calculate LRC checksum for Modbus-Serial-Line-PDU. */
- usLRC = prvucMBLRC( ( uint8_t * ) pucSndBufferCur, usSndBufferCount );
- ucASCIIBuf[usSndBufferCount++] = usLRC;
+ usLRC = prvucMBLRC((uint8_t *) pucSndBufferCur, usSndBufferCount);
+ ucASCIIBuf[usSndBufferCount++] = usLRC;
- /* Activate the transmitter. */
- eSndState = STATE_TX_START;
- vMBPortSerialEnable( false, true );
+ /* Activate the transmitter. */
+
+ eSndState = STATE_TX_START;
+ vMBPortSerialEnable(false, true);
}
- else
+ else
{
- eStatus = MB_EIO;
+ eStatus = MB_EIO;
}
- EXIT_CRITICAL_SECTION( );
- return eStatus;
+
+ EXIT_CRITICAL_SECTION();
+ return eStatus;
}
-bool
-xMBASCIIReceiveFSM( void )
+bool xMBASCIIReceiveFSM(void)
{
- bool xNeedPoll = false;
- uint8_t ucByte;
- uint8_t ucResult;
+ bool xNeedPoll = false;
+ uint8_t ucByte;
+ uint8_t ucResult;
- ASSERT( eSndState == STATE_TX_IDLE );
+ ASSERT(eSndState == STATE_TX_IDLE);
- ( void )xMBPortSerialGetByte( ( int8_t * ) & ucByte );
- switch ( eRcvState )
+ (void)xMBPortSerialGetByte((int8_t *) & ucByte);
+ switch (eRcvState)
{
- /* A new character is received. If the character is a ':' the input
- * buffer is cleared. A CR-character signals the end of the data
- * block. Other characters are part of the data block and their
- * ASCII value is converted back to a binary representation.
- */
+ /* A new character is received. If the character is a ':' the input
+ * buffer is cleared. A CR-character signals the end of the data
+ * block. Other characters are part of the data block and their
+ * ASCII value is converted back to a binary representation.
+ */
+
case STATE_RX_RCV:
- /* Enable timer for character timeout. */
- vMBPortTimersEnable( );
- if( ucByte == ':' )
+ /* Enable timer for character timeout. */
+
+ vMBPortTimersEnable();
+ if (ucByte == ':')
{
- /* Empty receive buffer. */
- eBytePos = BYTE_HIGH_NIBBLE;
- usRcvBufferPos = 0;
+ /* Empty receive buffer. */
+
+ eBytePos = BYTE_HIGH_NIBBLE;
+ usRcvBufferPos = 0;
}
- else if( ucByte == MB_ASCII_DEFAULT_CR )
+ else if (ucByte == MB_ASCII_DEFAULT_CR)
{
- eRcvState = STATE_RX_WAIT_EOF;
+ eRcvState = STATE_RX_WAIT_EOF;
}
- else
+ else
{
- ucResult = prvucMBint8_t2BIN( ucByte );
- switch ( eBytePos )
- {
- /* High nibble of the byte comes first. We check for
- * a buffer overflow here. */
- case BYTE_HIGH_NIBBLE:
- if( usRcvBufferPos < MB_SER_PDU_SIZE_MAX )
- {
- ucASCIIBuf[usRcvBufferPos] = ( uint8_t )( ucResult << 4 );
- eBytePos = BYTE_LOW_NIBBLE;
- break;
- }
- else
- {
- /* not handled in Modbus specification but seems
- * a resonable implementation. */
- eRcvState = STATE_RX_IDLE;
- /* Disable previously activated timer because of error state. */
- vMBPortTimersDisable( );
- }
+ ucResult = prvucMBint8_t2BIN(ucByte);
+ switch (eBytePos)
+ {
+ /* High nibble of the byte comes first. We check for
+ * a buffer overflow here.
+ */
+
+ case BYTE_HIGH_NIBBLE:
+ if (usRcvBufferPos < MB_SER_PDU_SIZE_MAX)
+ {
+ ucASCIIBuf[usRcvBufferPos] = (uint8_t)(ucResult << 4);
+ eBytePos = BYTE_LOW_NIBBLE;
break;
+ }
+ else
+ {
+ /* not handled in Modbus specification but seems
+ * a resonable implementation.
+ */
- case BYTE_LOW_NIBBLE:
- ucASCIIBuf[usRcvBufferPos] |= ucResult;
- usRcvBufferPos++;
- eBytePos = BYTE_HIGH_NIBBLE;
- break;
- }
+ eRcvState = STATE_RX_IDLE;
+
+ /* Disable previously activated timer because of error state. */
+
+ vMBPortTimersDisable();
+ }
+ break;
+
+ case BYTE_LOW_NIBBLE:
+ ucASCIIBuf[usRcvBufferPos] |= ucResult;
+ usRcvBufferPos++;
+ eBytePos = BYTE_HIGH_NIBBLE;
+ break;
+ }
}
break;
case STATE_RX_WAIT_EOF:
- if( ucByte == ucMBLFCharacter )
+ if (ucByte == ucMBLFCharacter)
{
- /* Disable character timeout timer because all characters are
- * received. */
- vMBPortTimersDisable( );
- /* Receiver is again in idle state. */
- eRcvState = STATE_RX_IDLE;
-
- /* Notify the caller of eMBASCIIReceive that a new frame
- * was received. */
- xNeedPoll = xMBPortEventPost( EV_FRAME_RECEIVED );
+ /* Disable character timeout timer because all characters are
+ * received.
+ */
+
+ vMBPortTimersDisable();
+
+ /* Receiver is again in idle state. */
+
+ eRcvState = STATE_RX_IDLE;
+
+ /* Notify the caller of eMBASCIIReceive that a new frame
+ * was received.
+ */
+
+ xNeedPoll = xMBPortEventPost(EV_FRAME_RECEIVED);
}
- else if( ucByte == ':' )
+ else if (ucByte == ':')
{
- /* Empty receive buffer and back to receive state. */
- eBytePos = BYTE_HIGH_NIBBLE;
- usRcvBufferPos = 0;
- eRcvState = STATE_RX_RCV;
+ /* Empty receive buffer and back to receive state. */
+
+ eBytePos = BYTE_HIGH_NIBBLE;
+ usRcvBufferPos = 0;
+ eRcvState = STATE_RX_RCV;
- /* Enable timer for character timeout. */
- vMBPortTimersEnable( );
+ /* Enable timer for character timeout. */
+
+ vMBPortTimersEnable();
}
- else
+ else
{
- /* Frame is not okay. Delete entire frame. */
- eRcvState = STATE_RX_IDLE;
+ /* Frame is not okay. Delete entire frame. */
+
+ eRcvState = STATE_RX_IDLE;
}
break;
case STATE_RX_IDLE:
- if( ucByte == ':' )
+ if (ucByte == ':')
{
- /* Enable timer for character timeout. */
- vMBPortTimersEnable( );
- /* Reset the input buffers to store the frame. */
- usRcvBufferPos = 0;;
- eBytePos = BYTE_HIGH_NIBBLE;
- eRcvState = STATE_RX_RCV;
+ /* Enable timer for character timeout. */
+
+ vMBPortTimersEnable();
+
+ /* Reset the input buffers to store the frame. */
+
+ usRcvBufferPos = 0;;
+ eBytePos = BYTE_HIGH_NIBBLE;
+ eRcvState = STATE_RX_RCV;
}
break;
}
- return xNeedPoll;
+ return xNeedPoll;
}
-bool
-xMBASCIITransmitFSM( void )
+bool xMBASCIITransmitFSM(void)
{
- bool xNeedPoll = false;
- uint8_t ucByte;
-
- ASSERT( eRcvState == STATE_RX_IDLE );
- switch ( eSndState )
- {
- /* Start of transmission. The start of a frame is defined by sending
- * the character ':'. */
- case STATE_TX_START:
- ucByte = ':';
- xMBPortSerialPutByte( ( int8_t )ucByte );
- eSndState = STATE_TX_DATA;
- eBytePos = BYTE_HIGH_NIBBLE;
- break;
-
- /* Send the data block. Each data byte is encoded as a character hex
- * stream with the high nibble sent first and the low nibble sent
- * last. If all data bytes are exhausted we send a '\r' character
- * to end the transmission. */
- case STATE_TX_DATA:
- if( usSndBufferCount > 0 )
+ bool xNeedPoll = false;
+ uint8_t ucByte;
+
+ ASSERT(eRcvState == STATE_RX_IDLE);
+ switch (eSndState)
+ {
+ /* Start of transmission. The start of a frame is defined by sending
+ * the character ':'.
+ */
+
+ case STATE_TX_START:
+ ucByte = ':';
+ xMBPortSerialPutByte((int8_t)ucByte);
+ eSndState = STATE_TX_DATA;
+ eBytePos = BYTE_HIGH_NIBBLE;
+ break;
+
+ /* Send the data block. Each data byte is encoded as a character hex
+ * stream with the high nibble sent first and the low nibble sent
+ * last. If all data bytes are exhausted we send a '\r' character
+ * to end the transmission.
+ */
+
+ case STATE_TX_DATA:
+ if (usSndBufferCount > 0)
+ {
+ switch (eBytePos)
{
- switch ( eBytePos )
- {
- case BYTE_HIGH_NIBBLE:
- ucByte = prvucMBBIN2int8_t( ( uint8_t )( *pucSndBufferCur >> 4 ) );
- xMBPortSerialPutByte( ( int8_t ) ucByte );
- eBytePos = BYTE_LOW_NIBBLE;
- break;
-
- case BYTE_LOW_NIBBLE:
- ucByte = prvucMBBIN2int8_t( ( uint8_t )( *pucSndBufferCur & 0x0F ) );
- xMBPortSerialPutByte( ( int8_t )ucByte );
- pucSndBufferCur++;
- eBytePos = BYTE_HIGH_NIBBLE;
- usSndBufferCount--;
- break;
- }
- }
- else
- {
- xMBPortSerialPutByte( MB_ASCII_DEFAULT_CR );
- eSndState = STATE_TX_END;
+ case BYTE_HIGH_NIBBLE:
+ ucByte = prvucMBBIN2int8_t((uint8_t)(*pucSndBufferCur >> 4));
+ xMBPortSerialPutByte((int8_t) ucByte);
+ eBytePos = BYTE_LOW_NIBBLE;
+ break;
+
+ case BYTE_LOW_NIBBLE:
+ ucByte = prvucMBBIN2int8_t((uint8_t)(*pucSndBufferCur & 0x0F));
+ xMBPortSerialPutByte((int8_t)ucByte);
+ pucSndBufferCur++;
+ eBytePos = BYTE_HIGH_NIBBLE;
+ usSndBufferCount--;
+ break;
}
- break;
+ }
+ else
+ {
+ xMBPortSerialPutByte(MB_ASCII_DEFAULT_CR);
+ eSndState = STATE_TX_END;
+ }
+ break;
+
+ /* Finish the frame by sending a LF character. */
- /* Finish the frame by sending a LF character. */
case STATE_TX_END:
- xMBPortSerialPutByte( ( int8_t )ucMBLFCharacter );
- /* We need another state to make sure that the CR character has
- * been sent. */
- eSndState = STATE_TX_NOTIFY;
- break;
+ xMBPortSerialPutByte((int8_t)ucMBLFCharacter);
- /* Notify the task which called eMBASCIISend that the frame has
- * been sent. */
- case STATE_TX_NOTIFY:
- eSndState = STATE_TX_IDLE;
- xNeedPoll = xMBPortEventPost( EV_FRAME_SENT );
+ /* We need another state to make sure that the CR character has
+ * been sent.
+ */
- /* Disable transmitter. This prevents another transmit buffer
- * empty interrupt. */
- vMBPortSerialEnable( true, false );
- eSndState = STATE_TX_IDLE;
- break;
+ eSndState = STATE_TX_NOTIFY;
+ break;
- /* We should not get a transmitter event if the transmitter is in
- * idle state. */
- case STATE_TX_IDLE:
- /* enable receiver/disable transmitter. */
- vMBPortSerialEnable( true, false );
- break;
- }
+ /* Notify the task which called eMBASCIISend that the frame has
+ * been sent.
+ */
- return xNeedPoll;
-}
+ case STATE_TX_NOTIFY:
+ eSndState = STATE_TX_IDLE;
+ xNeedPoll = xMBPortEventPost(EV_FRAME_SENT);
-bool
-xMBASCIITimerT1SExpired( void )
-{
- switch ( eRcvState )
- {
- /* If we have a timeout we go back to the idle state and wait for
- * the next frame.
- */
- case STATE_RX_RCV:
- case STATE_RX_WAIT_EOF:
- eRcvState = STATE_RX_IDLE;
- break;
+ /* Disable transmitter. This prevents another transmit buffer
+ * empty interrupt.
+ */
- default:
- ASSERT( ( eRcvState == STATE_RX_RCV ) || ( eRcvState == STATE_RX_WAIT_EOF ) );
- break;
- }
- vMBPortTimersDisable( );
+ vMBPortSerialEnable(true, false);
+ eSndState = STATE_TX_IDLE;
+ break;
- /* no context switch required. */
- return false;
-}
+ /* We should not get a transmitter event if the transmitter is in
+ * idle state.
+ */
+ case STATE_TX_IDLE:
+ /* enable receiver/disable transmitter. */
-static uint8_t
-prvucMBint8_t2BIN( uint8_t ucCharacter )
-{
- if( ( ucCharacter >= '0' ) && ( ucCharacter <= '9' ) )
- {
- return ( uint8_t )( ucCharacter - '0' );
- }
- else if( ( ucCharacter >= 'A' ) && ( ucCharacter <= 'F' ) )
- {
- return ( uint8_t )( ucCharacter - 'A' + 0x0A );
- }
- else
- {
- return 0xFF;
+ vMBPortSerialEnable(true, false);
+ break;
}
+
+ return xNeedPoll;
}
-static uint8_t
-prvucMBBIN2int8_t( uint8_t ucByte )
+bool xMBASCIITimerT1SExpired(void)
{
- if( ucByte <= 0x09 )
- {
- return ( uint8_t )( '0' + ucByte );
- }
- else if( ( ucByte >= 0x0A ) && ( ucByte <= 0x0F ) )
- {
- return ( uint8_t )( ucByte - 0x0A + 'A' );
- }
- else
- {
- /* Programming error. */
- ASSERT( 0 );
- }
- return '0';
-}
+ switch (eRcvState)
+ {
+ /* If we have a timeout we go back to the idle state and wait for
+ * the next frame.
+ */
+ case STATE_RX_RCV:
+ case STATE_RX_WAIT_EOF:
+ eRcvState = STATE_RX_IDLE;
+ break;
+ default:
+ ASSERT((eRcvState == STATE_RX_RCV) || (eRcvState == STATE_RX_WAIT_EOF));
+ break;
+ }
-static uint8_t
-prvucMBLRC( uint8_t * pucFrame, uint16_t usLen )
-{
- uint8_t ucLocalLRC = 0; /* LRC char initialized */
+ vMBPortTimersDisable();
- while( usLen-- )
- {
- ucLocalLRC += *pucFrame++; /* Add buffer byte without carry */
- }
+ /* no context switch required. */
- /* Return twos complement */
- ucLocalLRC = ( uint8_t ) ( -( ( int8_t ) ucLocalLRC ) );
- return ucLocalLRC;
+ return false;
}
#endif
diff --git a/apps/modbus/mb.c b/apps/modbus/mb.c
index 66a68835f..167fb2e47 100644
--- a/apps/modbus/mb.c
+++ b/apps/modbus/mb.c
@@ -160,11 +160,7 @@ eMBErrorCode eMBInit(eMBMode eMode, uint8_t ucSlaveAddress, uint8_t ucPort,
pvMBFrameStopCur = eMBRTUStop;
peMBFrameSendCur = eMBRTUSend;
peMBFrameReceiveCur = eMBRTUReceive;
-#ifdef CONFIG_MB_HAVE_CLOSE
pvMBFrameCloseCur = vMBPortClose;
-#else
- pvMBFrameCloseCur = NULL;
-#endif
pxMBFrameCBByteReceived = xMBRTUReceiveFSM;
pxMBFrameCBTransmitterEmpty = xMBRTUTransmitFSM;
pxMBPortCBTimerExpired = xMBRTUTimerT35Expired;
@@ -178,11 +174,7 @@ eMBErrorCode eMBInit(eMBMode eMode, uint8_t ucSlaveAddress, uint8_t ucPort,
pvMBFrameStopCur = eMBASCIIStop;
peMBFrameSendCur = eMBASCIISend;
peMBFrameReceiveCur = eMBASCIIReceive;
-#ifdef CONFIG_MB_HAVE_CLOSE
pvMBFrameCloseCur = vMBPortClose;
-#else
- pvMBFrameCloseCur = NULL;
-#endif
pxMBFrameCBByteReceived = xMBASCIIReceiveFSM;
pxMBFrameCBTransmitterEmpty = xMBASCIITransmitFSM;
pxMBPortCBTimerExpired = xMBASCIITimerT1SExpired;
diff --git a/apps/modbus/nuttx/port.h b/apps/modbus/nuttx/port.h
index c7e730b41..5b7416873 100644
--- a/apps/modbus/nuttx/port.h
+++ b/apps/modbus/nuttx/port.h
@@ -2,23 +2,30 @@
* apps/modbus/nuttx/port.h
*
* FreeModbus Library: NuttX Port
- * Based on the FreeModbus Linux port by:
+ * Copyright (c) 2006 Christian Walter <wolti@sil.at>
+ * All rights reserved.
*
- * Copyright (C) 2006 Christian Walter <wolti@sil.at>
+ * 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. The name of the author may not be used to endorse or promote products
+ * derived from this software without specific prior written permission.
*
- * 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
+ * THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``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 AUTHOR 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.
*
****************************************************************************/
diff --git a/apps/modbus/nuttx/portevent.c b/apps/modbus/nuttx/portevent.c
index 72c02f8ed..b1076f5a3 100644
--- a/apps/modbus/nuttx/portevent.c
+++ b/apps/modbus/nuttx/portevent.c
@@ -1,76 +1,92 @@
-/*
- * FreeModbus Libary: NuttX Port
- * Based on the FreeModbus Linux port by:
- *
- * Copyright (C) 2006 Christian Walter <wolti@sil.at>
+/****************************************************************************
+ * apps/modbus/nuttx/portevent.c
*
- * 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.
+ * FreeModbus Libary: NuttX Port
+ * Copyright (c) 2006 Christian Walter <wolti@sil.at>
+ * All rights reserved.
*
- * 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.
+ * 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. The name of the author may not be used to endorse or promote products
+ * derived from this software without specific prior written permission.
*
- * 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
+ * THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``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 AUTHOR 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.
*
- * File: $Id: portevent.c,v 1.1 2006/08/01 20:58:49 wolti Exp $
- */
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
-/* ----------------------- Modbus includes ----------------------------------*/
#include <apps/modbus/mb.h>
#include <apps/modbus/mbport.h>
#include "port.h"
-/* ----------------------- Variables ----------------------------------------*/
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
static eMBEventType eQueuedEvent;
-static bool xEventInQueue;
+static bool xEventInQueue;
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
-/* ----------------------- Start implementation -----------------------------*/
-bool
-xMBPortEventInit( void )
+bool xMBPortEventInit(void)
{
- xEventInQueue = false;
- return true;
+ xEventInQueue = false;
+ return true;
}
-bool
-xMBPortEventPost( eMBEventType eEvent )
+bool xMBPortEventPost(eMBEventType eEvent)
{
- xEventInQueue = true;
- eQueuedEvent = eEvent;
- return true;
+ xEventInQueue = true;
+ eQueuedEvent = eEvent;
+ return true;
}
-bool
-xMBPortEventGet( eMBEventType * eEvent )
+bool xMBPortEventGet(eMBEventType * eEvent)
{
- bool xEventHappened = false;
+ bool xEventHappened = false;
- if( xEventInQueue )
+ if (xEventInQueue)
{
- *eEvent = eQueuedEvent;
- xEventInQueue = false;
- xEventHappened = true;
+ *eEvent = eQueuedEvent;
+ xEventInQueue = false;
+ xEventHappened = true;
}
- else
+ else
{
- /* Poll the serial device. The serial device timeouts if no
- * characters have been received within for t3.5 during an
- * active transmission or if nothing happens within a specified
- * amount of time. Both timeouts are configured from the timer
- * init functions.
- */
- ( void )xMBPortSerialPoll( );
+ /* Poll the serial device. The serial device timeouts if no
+ * characters have been received within for t3.5 during an
+ * active transmission or if nothing happens within a specified
+ * amount of time. Both timeouts are configured from the timer
+ * init functions.
+ */
- /* Check if any of the timers have expired. */
- vMBPortTimerPoll( );
+ (void)xMBPortSerialPoll();
+ /* Check if any of the timers have expired. */
+
+ vMBPortTimerPoll();
}
- return xEventHappened;
+
+ return xEventHappened;
}
diff --git a/apps/modbus/nuttx/portother.c b/apps/modbus/nuttx/portother.c
index fef826760..86b8ad255 100644
--- a/apps/modbus/nuttx/portother.c
+++ b/apps/modbus/nuttx/portother.c
@@ -1,27 +1,37 @@
-/*
- * FreeModbus Libary: NuttX Port
- * Based on the FreeModbus Linux port by:
- *
- * Copyright (C) 2006 Christian Walter <wolti@sil.at>
+/****************************************************************************
+ * apps/modbus/nuttx/portother.c
*
- * 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.
+ * FreeModbus Libary: NuttX Port
+ * Copyright (c) 2006 Christian Walter <wolti@sil.at>
+ * All rights reserved.
*
- * 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.
+ * 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. The name of the author may not be used to endorse or promote products
+ * derived from this software without specific prior written permission.
*
- * 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
+ * THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``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 AUTHOR 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.
*
- * File: $Id: portother.c,v 1.1 2006/08/01 20:58:49 wolti Exp $
- */
+ ****************************************************************************/
-/* ----------------------- Standard includes --------------------------------*/
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
#include <nuttx/config.h>
#include <stdio.h>
@@ -33,22 +43,26 @@
#include "port.h"
-/* ----------------------- Modbus includes ----------------------------------*/
-
#include <apps/modbus/mb.h>
#include <apps/modbus/mbport.h>
-/* ----------------------- Defines ------------------------------------------*/
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
#define NELEMS(x) (sizeof((x))/sizeof((x)[0]))
-/* ----------------------- Static variables ---------------------------------*/
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
-static FILE *fLogFile = NULL;
+static FILE *fLogFile = NULL;
static eMBPortLogLevel eLevelMax = MB_LOG_DEBUG;
static pthread_mutex_t xLock = PTHREAD_MUTEX_INITIALIZER;
-/* ----------------------- Start implementation -----------------------------*/
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
void vMBPortLogLevel(eMBPortLogLevel eNewLevelMax)
{
diff --git a/apps/modbus/nuttx/portserial.c b/apps/modbus/nuttx/portserial.c
index c3c7baa37..d3fa39e11 100644
--- a/apps/modbus/nuttx/portserial.c
+++ b/apps/modbus/nuttx/portserial.c
@@ -1,27 +1,37 @@
-/*
- * FreeModbus Libary: NuttX Port
- * Based on the FreeModbus Linux port by:
- *
- * Copyright (C) 2006 Christian Walter <wolti@sil.at>
+/****************************************************************************
+ * apps/modbus/nuttx/portserial.c
*
- * 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.
+ * FreeModbus Libary: NuttX Port
+ * Copyright (c) 2006 Christian Walter <wolti@sil.at>
+ * All rights reserved.
*
- * 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.
+ * 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. The name of the author may not be used to endorse or promote products
+ * derived from this software without specific prior written permission.
*
- * 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
+ * THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``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 AUTHOR 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.
*
- * File: $Id: portserial.c,v 1.3 2006/10/12 08:35:34 wolti Exp $
- */
+ ****************************************************************************/
-/* ----------------------- Standard includes --------------------------------*/
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
#include <nuttx/config.h>
#include <stdio.h>
@@ -42,12 +52,12 @@
#include "port.h"
-/* ----------------------- Modbus includes ----------------------------------*/
-
#include <apps/modbus/mb.h>
#include <apps/modbus/mbport.h>
-/* ----------------------- Defines -----------------------------------------*/
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
#ifdef CONFIG_MB_ASCII_ENABLED
#define BUF_SIZE 513 /* must hold a complete ASCII frame. */
@@ -55,7 +65,9 @@
#define BUF_SIZE 256 /* must hold a complete RTU frame. */
#endif
-/* ----------------------- Static variables ---------------------------------*/
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
static int iSerialFd = -1;
static bool bRxEnabled;
@@ -70,12 +82,97 @@ static int uiTxBufferPos;
static struct termios xOldTIO;
#endif
-/* ----------------------- Function prototypes ------------------------------*/
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+static bool prvbMBPortSerialRead(uint8_t *pucBuffer, uint16_t usNBytes,
+ uint16_t *usNBytesRead);
+static bool prvbMBPortSerialWrite(uint8_t *pucBuffer, uint16_t usNBytes);
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+static bool prvbMBPortSerialRead(uint8_t *pucBuffer, uint16_t usNBytes,
+ uint16_t *usNBytesRead)
+{
+ bool bResult = true;
+ ssize_t res;
+ fd_set rfds;
+ struct timeval tv;
+
+ tv.tv_sec = 0;
+ tv.tv_usec = 50000;
+ FD_ZERO(&rfds);
+ FD_SET(iSerialFd, &rfds);
+
+ /* Wait until character received or timeout. Recover in case of an
+ * interrupted read system call.
+ */
+
+ do
+ {
+ if (select(iSerialFd + 1, &rfds, NULL, NULL, &tv) == -1)
+ {
+ if (errno != EINTR)
+ {
+ bResult = false;
+ }
+ }
+ else if (FD_ISSET(iSerialFd, &rfds))
+ {
+ if ((res = read(iSerialFd, pucBuffer, usNBytes)) == -1)
+ {
+ bResult = false;
+ }
+ else
+ {
+ *usNBytesRead = (uint16_t)res;
+ break;
+ }
+ }
+ else
+ {
+ *usNBytesRead = 0;
+ break;
+ }
+ }
+
+ while (bResult == true);
+ return bResult;
+}
+
+static bool prvbMBPortSerialWrite(uint8_t *pucBuffer, uint16_t usNBytes)
+{
+ ssize_t res;
+ size_t left = (size_t) usNBytes;
+ size_t done = 0;
+
+ while (left > 0)
+ {
+ if ((res = write(iSerialFd, pucBuffer + done, left)) == -1)
+ {
+ if (errno != EINTR)
+ {
+ break;
+ }
+
+ /* call write again because of interrupted system call. */
+
+ continue;
+ }
+
+ done += res;
+ left -= res;
+ }
-static bool prvbMBPortSerialRead(uint8_t *pucBuffer, uint16_t usNBytes, uint16_t *usNBytesRead);
-static bool prvbMBPortSerialWrite(uint8_t *pucBuffer, uint16_t usNBytes);
+ return left == 0 ? true : false;
+}
-/* ----------------------- Begin implementation -----------------------------*/
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
void vMBPortSerialEnable(bool bEnableRx, bool bEnableTx)
{
@@ -141,12 +238,15 @@ bool xMBPortSerialInit(uint8_t ucPort, speed_t ulBaudRate,
{
case MB_PAR_NONE:
break;
+
case MB_PAR_EVEN:
xNewTIO.c_cflag |= PARENB;
break;
+
case MB_PAR_ODD:
xNewTIO.c_cflag |= PARENB | PARODD;
break;
+
default:
bStatus = false;
}
@@ -156,9 +256,11 @@ bool xMBPortSerialInit(uint8_t ucPort, speed_t ulBaudRate,
case 8:
xNewTIO.c_cflag |= CS8;
break;
+
case 7:
xNewTIO.c_cflag |= CS7;
break;
+
default:
bStatus = false;
}
@@ -226,145 +328,74 @@ void vMBPortClose(void)
}
}
-bool prvbMBPortSerialRead(uint8_t *pucBuffer, uint16_t usNBytes, uint16_t *usNBytesRead)
+bool xMBPortSerialPoll(void)
{
- bool bResult = true;
- ssize_t res;
- fd_set rfds;
- struct timeval tv;
-
- tv.tv_sec = 0;
- tv.tv_usec = 50000;
- FD_ZERO(&rfds);
- FD_SET(iSerialFd, &rfds);
+ bool bStatus = true;
+ uint16_t usBytesRead;
+ int i;
- /* Wait until character received or timeout. Recover in case of an
- * interrupted read system call.
- */
-
- do
+ while (bRxEnabled)
{
- if (select(iSerialFd + 1, &rfds, NULL, NULL, &tv) == -1)
- {
- if (errno != EINTR)
- {
- bResult = false;
- }
- }
- else if (FD_ISSET(iSerialFd, &rfds))
+ if (prvbMBPortSerialRead(&ucBuffer[0], BUF_SIZE, &usBytesRead))
{
- if ((res = read(iSerialFd, pucBuffer, usNBytes)) == -1)
- {
- bResult = false;
- }
- else
+ if (usBytesRead == 0)
{
- *usNBytesRead = (uint16_t)res;
- break;
- }
- }
- else
- {
- *usNBytesRead = 0;
- break;
- }
- }
-
- while(bResult == true);
- return bResult;
-}
-
-bool prvbMBPortSerialWrite(uint8_t *pucBuffer, uint16_t usNBytes)
-{
- ssize_t res;
- size_t left = (size_t) usNBytes;
- size_t done = 0;
+ /* timeout with no bytes. */
- while(left > 0)
- {
- if ((res = write(iSerialFd, pucBuffer + done, left)) == -1)
- {
- if (errno != EINTR)
- {
break;
}
-
- /* call write again because of interrupted system call. */
- continue;
- }
-
- done += res;
- left -= res;
- }
-
- return left == 0 ? true : false;
-}
-
-bool
-xMBPortSerialPoll()
-{
- bool bStatus = true;
- uint16_t usBytesRead;
- int i;
-
- while(bRxEnabled)
- {
- if (prvbMBPortSerialRead(&ucBuffer[0], BUF_SIZE, &usBytesRead))
- {
- if (usBytesRead == 0)
- {
- /* timeout with no bytes. */
- break;
- }
- else if (usBytesRead > 0)
+ else if (usBytesRead > 0)
{
- for(i = 0; i < usBytesRead; i++)
+ for (i = 0; i < usBytesRead; i++)
{
- /* Call the modbus stack and let him fill the buffers. */
- (void)pxMBFrameCBByteReceived();
+ /* Call the modbus stack and let him fill the buffers. */
+
+ (void)pxMBFrameCBByteReceived();
}
- uiRxBufferPos = 0;
+
+ uiRxBufferPos = 0;
}
}
- else
+ else
{
- vMBPortLog(MB_LOG_ERROR, "SER-POLL", "read failed on serial device: %d\n",
- errno);
- bStatus = false;
+ vMBPortLog(MB_LOG_ERROR, "SER-POLL", "read failed on serial device: %d\n",
+ errno);
+ bStatus = false;
}
}
- if (bTxEnabled)
+
+ if (bTxEnabled)
{
- while(bTxEnabled)
+ while (bTxEnabled)
{
- (void)pxMBFrameCBTransmitterEmpty();
- /* Call the modbus stack to let him fill the buffer. */
+ (void)pxMBFrameCBTransmitterEmpty();
+
+ /* Call the modbus stack to let him fill the buffer. */
}
- if (!prvbMBPortSerialWrite(&ucBuffer[0], uiTxBufferPos))
+
+ if (!prvbMBPortSerialWrite(&ucBuffer[0], uiTxBufferPos))
{
- vMBPortLog(MB_LOG_ERROR, "SER-POLL", "write failed on serial device: %d\n",
- errno);
- bStatus = false;
+ vMBPortLog(MB_LOG_ERROR, "SER-POLL", "write failed on serial device: %d\n",
+ errno);
+ bStatus = false;
}
}
- return bStatus;
+ return bStatus;
}
-bool
-xMBPortSerialPutByte(int8_t ucByte)
+bool xMBPortSerialPutByte(int8_t ucByte)
{
- ASSERT(uiTxBufferPos < BUF_SIZE);
- ucBuffer[uiTxBufferPos] = ucByte;
- uiTxBufferPos++;
- return true;
+ ASSERT(uiTxBufferPos < BUF_SIZE);
+ ucBuffer[uiTxBufferPos] = ucByte;
+ uiTxBufferPos++;
+ return true;
}
-bool
-xMBPortSerialGetByte(int8_t *pucByte)
+bool xMBPortSerialGetByte(int8_t *pucByte)
{
- ASSERT(uiRxBufferPos < BUF_SIZE);
- *pucByte = ucBuffer[uiRxBufferPos];
- uiRxBufferPos++;
- return true;
+ ASSERT(uiRxBufferPos < BUF_SIZE);
+ *pucByte = ucBuffer[uiRxBufferPos];
+ uiRxBufferPos++;
+ return true;
}
diff --git a/apps/modbus/nuttx/porttimer.c b/apps/modbus/nuttx/porttimer.c
index d688c4f52..09a4596f2 100644
--- a/apps/modbus/nuttx/porttimer.c
+++ b/apps/modbus/nuttx/porttimer.c
@@ -1,27 +1,38 @@
-/*
- * FreeModbus Libary: NuttX Port
- * Based on the FreeModbus Linux port by:
- *
- * Copyright (C) 2006 Christian Walter <wolti@sil.at>
+/****************************************************************************
+ * apps/modbus/nuttx/porttimer.c
*
- * 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.
+ * FreeModbus Libary: NuttX Port
+ * Copyright (c) 2006 Christian Walter <wolti@sil.at>
+ * All rights reserved.
*
- * 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.
+ * 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. The name of the author may not be used to endorse or promote products
+ * derived from this software without specific prior written permission.
*
- * 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
+ * THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``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 AUTHOR 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.
*
- * File: $Id: porttimer.c,v 1.1 2006/08/01 20:58:50 wolti Exp $
- */
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
-/* ----------------------- Standard includes --------------------------------*/
#include <nuttx/config.h>
#include <sys/time.h>
@@ -30,73 +41,75 @@
#include "port.h"
-/* ----------------------- Modbus includes ----------------------------------*/
#include <apps/modbus/mb.h>
#include <apps/modbus/mbport.h>
-/* ----------------------- Defines ------------------------------------------*/
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
-/* ----------------------- Static variables ---------------------------------*/
-uint32_t ulTimeOut;
-bool bTimeoutEnable;
+uint32_t ulTimeOut;
+bool bTimeoutEnable;
static struct timeval xTimeLast;
-/* ----------------------- Start implementation -----------------------------*/
-bool
-xMBPortTimersInit( uint16_t usTim1Timerout50us )
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+bool xMBPortTimersInit(uint16_t usTim1Timerout50us)
{
- ulTimeOut = usTim1Timerout50us / 20U;
- if( ulTimeOut == 0 )
- ulTimeOut = 1;
+ ulTimeOut = usTim1Timerout50us / 20U;
+ if (ulTimeOut == 0)
+ {
+ ulTimeOut = 1;
+ }
- return xMBPortSerialSetTimeout( ulTimeOut );
+ return xMBPortSerialSetTimeout(ulTimeOut);
}
-void
-xMBPortTimersClose( )
+void xMBPortTimersClose()
{
- /* Does not use any hardware resources. */
+ /* Does not use any hardware resources. */
}
-void
-vMBPortTimerPoll( )
+void vMBPortTimerPoll()
{
- uint32_t ulDeltaMS;
- struct timeval xTimeCur;
+ uint32_t ulDeltaMS;
+ struct timeval xTimeCur;
+
+ /* Timers are called from the serial layer because we have no high
+ * res timer in Win32.
+ */
- /* Timers are called from the serial layer because we have no high
- * res timer in Win32. */
- if( bTimeoutEnable )
+ if (bTimeoutEnable)
{
- if( gettimeofday( &xTimeCur, NULL ) != 0 )
+ if (gettimeofday(&xTimeCur, NULL) != 0)
{
- /* gettimeofday failed - retry next time. */
+ /* gettimeofday failed - retry next time. */
}
- else
+ else
{
- ulDeltaMS = ( xTimeCur.tv_sec - xTimeLast.tv_sec ) * 1000L +
- ( xTimeCur.tv_usec - xTimeLast.tv_usec ) * 1000L;
- if( ulDeltaMS > ulTimeOut )
+ ulDeltaMS = (xTimeCur.tv_sec - xTimeLast.tv_sec) * 1000L +
+ (xTimeCur.tv_usec - xTimeLast.tv_usec) * 1000L;
+ if (ulDeltaMS > ulTimeOut)
{
- bTimeoutEnable = false;
- ( void )pxMBPortCBTimerExpired( );
+ bTimeoutEnable = false;
+ (void)pxMBPortCBTimerExpired();
}
}
}
}
-void
-vMBPortTimersEnable( )
+void vMBPortTimersEnable()
{
- int res = gettimeofday( &xTimeLast, NULL );
+ int res = gettimeofday(&xTimeLast, NULL);
- ASSERT( res == 0 );
- bTimeoutEnable = true;
+ ASSERT(res == 0);
+ bTimeoutEnable = true;
}
-void
-vMBPortTimersDisable( )
+void vMBPortTimersDisable()
{
- bTimeoutEnable = false;
+ bTimeoutEnable = false;
}