summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2015-04-06 10:57:50 -0600
committerGregory Nutt <gnutt@nuttx.org>2015-04-06 10:57:50 -0600
commitb582189e430a7f91d62968115cc886f5effc61b8 (patch)
tree253363806d5b879a4528776963489c03fa5e535b
parentb5e9e99b631b5dd05afec2416ced77125ddbfcb2 (diff)
downloadpx4-nuttx-b582189e430a7f91d62968115cc886f5effc61b8.tar.gz
px4-nuttx-b582189e430a7f91d62968115cc886f5effc61b8.tar.bz2
px4-nuttx-b582189e430a7f91d62968115cc886f5effc61b8.zip
apps/modbus: Fix some complile problems when TCP is enabled
-rw-r--r--apps/modbus/tcp/mbtcp.c130
-rw-r--r--apps/modbus/tcp/mbtcp.h30
2 files changed, 85 insertions, 75 deletions
diff --git a/apps/modbus/tcp/mbtcp.c b/apps/modbus/tcp/mbtcp.c
index 7a8f5095f..c71fdc34a 100644
--- a/apps/modbus/tcp/mbtcp.c
+++ b/apps/modbus/tcp/mbtcp.c
@@ -1,4 +1,6 @@
-/*
+/****************************************************************************
+ * apps/modbus/tcp/mbtcp.c
+ *
* FreeModbus Libary: A portable Modbus implementation for Modbus ASCII/RTU.
* Copyright (c) 2006 Christian Walter <wolti@sil.at>
* All rights reserved.
@@ -25,27 +27,26 @@
* (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: mbtcp.c,v 1.3 2006/12/07 22:10:34 wolti Exp $
- */
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
-/* ----------------------- System includes ----------------------------------*/
#include <nuttx/config.h>
#include <stdlib.h>
#include <string.h>
-/* ----------------------- Platform includes --------------------------------*/
-#include "port.h"
-
-/* ----------------------- Modbus includes ----------------------------------*/
-#include <apps/modbusmb.h>
-#include <apps/modbusmbframe.h>
-#include <apps/modbusmbport.h>
+#include <apps/modbus/mb.h>
+#include "port.h"
#include "mbtcp.h"
#ifdef CONFIG_MB_TCP_ENABLED
-/* ----------------------- Defines ------------------------------------------*/
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
/* ----------------------- MBAP Header --------------------------------------*/
/*
@@ -76,84 +77,87 @@
#define MB_TCP_PROTOCOL_ID 0 /* 0 = Modbus Protocol */
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
-/* ----------------------- Start implementation -----------------------------*/
-eMBErrorCode
-eMBTCPDoInit( uint16_t ucTCPPort )
+eMBErrorCode eMBTCPDoInit(uint16_t ucTCPPort)
{
- eMBErrorCode eStatus = MB_ENOERR;
+ eMBErrorCode eStatus = MB_ENOERR;
- if( xMBTCPPortInit( ucTCPPort ) == false )
+ if (xMBTCPPortInit(ucTCPPort) == false)
{
- eStatus = MB_EPORTERR;
+ eStatus = MB_EPORTERR;
}
- return eStatus;
+
+ return eStatus;
}
-void
-eMBTCPStart( void )
+void eMBTCPStart(void)
{
}
-void
-eMBTCPStop( void )
+void eMBTCPStop(void)
{
- /* Make sure that no more clients are connected. */
- vMBTCPPortDisable( );
+ /* Make sure that no more clients are connected. */
+
+ vMBTCPPortDisable();
}
-eMBErrorCode
-eMBTCPReceive( uint8_t * pucRcvAddress, uint8_t ** ppucFrame, uint16_t * pusLength )
+eMBErrorCode eMBTCPReceive(uint8_t *pucRcvAddress, uint8_t **ppucFrame, uint16_t *pusLength)
{
- eMBErrorCode eStatus = MB_EIO;
- uint8_t *pucMBTCPFrame;
- uint16_t usLength;
- uint16_t usPID;
+ eMBErrorCode eStatus = MB_EIO;
+ 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];
+ usPID = pucMBTCPFrame[MB_TCP_PID] << 8U;
+ usPID |= pucMBTCPFrame[MB_TCP_PID + 1];
- if( usPID == MB_TCP_PROTOCOL_ID )
+ if (usPID == MB_TCP_PROTOCOL_ID)
{
- *ppucFrame = &pucMBTCPFrame[MB_TCP_FUNC];
- *pusLength = usLength - MB_TCP_FUNC;
- eStatus = MB_ENOERR;
-
- /* Modbus TCP does not use any addresses. Fake the source address such
- * that the processing part deals with this frame.
- */
- *pucRcvAddress = MB_TCP_PSEUDO_ADDRESS;
+ *ppucFrame = &pucMBTCPFrame[MB_TCP_FUNC];
+ *pusLength = usLength - MB_TCP_FUNC;
+ eStatus = MB_ENOERR;
+
+ /* Modbus TCP does not use any addresses. Fake the source address such
+ * that the processing part deals with this frame.
+ */
+
+ *pucRcvAddress = MB_TCP_PSEUDO_ADDRESS;
}
}
- else
+ else
{
- eStatus = MB_EIO;
+ eStatus = MB_EIO;
}
- return eStatus;
+
+ return eStatus;
}
-eMBErrorCode
-eMBTCPSend( uint8_t _unused, const uint8_t * pucFrame, uint16_t usLength )
+eMBErrorCode eMBTCPSend(uint8_t _unused, const uint8_t * pucFrame, uint16_t usLength)
{
- eMBErrorCode eStatus = MB_ENOERR;
- 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
- * only have to update the length in the header. Note that the length
- * header includes the size of the Modbus PDU and the UID Byte. Therefore
- * the length is usLength plus one.
- */
- pucMBTCPFrame[MB_TCP_LEN] = ( usLength + 1 ) >> 8U;
- pucMBTCPFrame[MB_TCP_LEN + 1] = ( usLength + 1 ) & 0xFF;
- if( xMBTCPPortSendResponse( pucMBTCPFrame, usTCPLength ) == false )
+ eMBErrorCode eStatus = MB_ENOERR;
+ 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
+ * only have to update the length in the header. Note that the length
+ * header includes the size of the Modbus PDU and the UID Byte. Therefore
+ * the length is usLength plus one.
+ */
+
+ pucMBTCPFrame[MB_TCP_LEN] = (usLength + 1) >> 8U;
+ pucMBTCPFrame[MB_TCP_LEN + 1] = (usLength + 1) & 0xFF;
+ if (xMBTCPPortSendResponse(pucMBTCPFrame, usTCPLength) == false)
{
- eStatus = MB_EIO;
+ eStatus = MB_EIO;
}
- return eStatus;
+
+ return eStatus;
}
#endif
diff --git a/apps/modbus/tcp/mbtcp.h b/apps/modbus/tcp/mbtcp.h
index f00152810..421896dee 100644
--- a/apps/modbus/tcp/mbtcp.h
+++ b/apps/modbus/tcp/mbtcp.h
@@ -28,26 +28,32 @@
* File: $Id: mbtcp.h,v 1.2 2006/12/07 22:10:34 wolti Exp $
*/
-#ifndef _MB_TCP_H
-#define _MB_TCP_H
+#ifndef __APPS_MODBUS_TCP_MBTCP_H
+#define __APPS_MODBUS_TCP_MBTCP_H
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
#ifdef __cplusplus
PR_BEGIN_EXTERN_C
#endif
-/* ----------------------- Defines ------------------------------------------*/
#define MB_TCP_PSEUDO_ADDRESS 255
-/* ----------------------- Function prototypes ------------------------------*/
- eMBErrorCode eMBTCPDoInit( uint16_t ucTCPPort );
-void eMBTCPStart( void );
-void eMBTCPStop( void );
-eMBErrorCode eMBTCPReceive( uint8_t * pucRcvAddress, uint8_t ** pucFrame,
- uint16_t * pusLength );
-eMBErrorCode eMBTCPSend( uint8_t _unused, const uint8_t * pucFrame,
- uint16_t usLength );
+/****************************************************************************
+ * Public Function Protototypes
+ ****************************************************************************/
+
+eMBErrorCode eMBTCPDoInit(uint16_t ucTCPPort);
+void eMBTCPStart(void);
+void eMBTCPStop(void);
+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
#endif
-#endif
+#endif /* __APPS_MODBUS_TCP_MBTCP_H */