summaryrefslogtreecommitdiff
path: root/apps/modbus/nuttx
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-07-21 14:56:21 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-07-21 14:56:21 +0000
commitfcfd6c4d7ca3cc8d2751652a79a08d64eb8ec5a3 (patch)
treea06bbe9986c21dae6763e584c9ab79394cb3b99b /apps/modbus/nuttx
parent1dc0e8b8c5b6e03fcfcdcbc89efd512f934eaca5 (diff)
downloadpx4-nuttx-fcfd6c4d7ca3cc8d2751652a79a08d64eb8ec5a3.tar.gz
px4-nuttx-fcfd6c4d7ca3cc8d2751652a79a08d64eb8ec5a3.tar.bz2
px4-nuttx-fcfd6c4d7ca3cc8d2751652a79a08d64eb8ec5a3.zip
FreeModBus is now integrated with the Nuttx configuration system
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@4961 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'apps/modbus/nuttx')
-rw-r--r--apps/modbus/nuttx/port.h75
-rw-r--r--apps/modbus/nuttx/portevent.c72
-rw-r--r--apps/modbus/nuttx/portother.c102
-rw-r--r--apps/modbus/nuttx/portserial.c352
-rw-r--r--apps/modbus/nuttx/porttimer.c98
5 files changed, 699 insertions, 0 deletions
diff --git a/apps/modbus/nuttx/port.h b/apps/modbus/nuttx/port.h
new file mode 100644
index 000000000..4102628b4
--- /dev/null
+++ b/apps/modbus/nuttx/port.h
@@ -0,0 +1,75 @@
+/*
+ * FreeModbus Libary: Linux Port
+ * Copyright (C) 2006 Christian Walter <wolti@sil.at>
+ *
+ * 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
+ *
+ * File: $Id: port.h,v 1.1 2006/08/01 20:58:49 wolti Exp $
+ */
+
+#ifndef _PORT_H
+#define _PORT_H
+
+#include <assert.h>
+
+#define INLINE
+#define PR_BEGIN_EXTERN_C extern "C" {
+#define PR_END_EXTERN_C }
+
+#ifdef __cplusplus
+PR_BEGIN_EXTERN_C
+#endif
+/* ----------------------- Defines ------------------------------------------*/
+#define ENTER_CRITICAL_SECTION( ) vMBPortEnterCritical()
+#define EXIT_CRITICAL_SECTION( ) vMBPortExitCritical()
+#define MB_PORT_HAS_CLOSE 1
+#ifndef TRUE
+#define TRUE 1
+#endif
+#ifndef FALSE
+#define FALSE 0
+#endif
+/* ----------------------- Type definitions ---------------------------------*/
+ typedef enum
+{
+ MB_LOG_ERROR = 0,
+ MB_LOG_WARN = 1,
+ MB_LOG_INFO = 2,
+ MB_LOG_DEBUG = 3
+} eMBPortLogLevel;
+
+typedef char BOOL;
+typedef unsigned char UCHAR;
+typedef char CHAR;
+typedef unsigned short USHORT;
+typedef short SHORT;
+
+typedef unsigned long ULONG;
+typedef long LONG;
+
+/* ----------------------- Function prototypes ------------------------------*/
+
+void vMBPortEnterCritical( void );
+void vMBPortExitCritical( void );
+void vMBPortLog( eMBPortLogLevel eLevel, const CHAR * szModule,
+ const CHAR * szFmt, ... );
+void vMBPortTimerPoll( );
+BOOL xMBPortSerialPoll( );
+BOOL xMBPortSerialSetTimeout( ULONG dwTimeoutMs );
+
+#ifdef __cplusplus
+PR_END_EXTERN_C
+#endif
+#endif
diff --git a/apps/modbus/nuttx/portevent.c b/apps/modbus/nuttx/portevent.c
new file mode 100644
index 000000000..dd7a6fef8
--- /dev/null
+++ b/apps/modbus/nuttx/portevent.c
@@ -0,0 +1,72 @@
+/*
+ * FreeModbus Libary: Linux Port
+ * Copyright (C) 2006 Christian Walter <wolti@sil.at>
+ *
+ * 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
+ *
+ * File: $Id: portevent.c,v 1.1 2006/08/01 20:58:49 wolti Exp $
+ */
+
+/* ----------------------- Modbus includes ----------------------------------*/
+#include "mb.h"
+#include "mbport.h"
+
+/* ----------------------- Variables ----------------------------------------*/
+static eMBEventType eQueuedEvent;
+static BOOL xEventInQueue;
+
+/* ----------------------- Start implementation -----------------------------*/
+BOOL
+xMBPortEventInit( void )
+{
+ xEventInQueue = FALSE;
+ return TRUE;
+}
+
+BOOL
+xMBPortEventPost( eMBEventType eEvent )
+{
+ xEventInQueue = TRUE;
+ eQueuedEvent = eEvent;
+ return TRUE;
+}
+
+BOOL
+xMBPortEventGet( eMBEventType * eEvent )
+{
+ BOOL xEventHappened = FALSE;
+
+ if( xEventInQueue )
+ {
+ *eEvent = eQueuedEvent;
+ xEventInQueue = FALSE;
+ xEventHappened = TRUE;
+ }
+ 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( );
+
+ /* Check if any of the timers have expired. */
+ vMBPortTimerPoll( );
+
+ }
+ return xEventHappened;
+}
diff --git a/apps/modbus/nuttx/portother.c b/apps/modbus/nuttx/portother.c
new file mode 100644
index 000000000..bb7068940
--- /dev/null
+++ b/apps/modbus/nuttx/portother.c
@@ -0,0 +1,102 @@
+/*
+ * FreeModbus Libary: Linux Port
+ * Copyright (C) 2006 Christian Walter <wolti@sil.at>
+ *
+ * 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
+ *
+ * File: $Id: portother.c,v 1.1 2006/08/01 20:58:49 wolti Exp $
+ */
+
+/* ----------------------- Standard includes --------------------------------*/
+#include <nuttx/config.h>
+#include <stdio.h>
+#include <stdlib.h>
+#include <stdarg.h>
+#include <string.h>
+#include <errno.h>
+#include <pthread.h>
+
+#include "port.h"
+
+/* ----------------------- Modbus includes ----------------------------------*/
+#include "mb.h"
+#include "mbport.h"
+
+/* ----------------------- Defines ------------------------------------------*/
+#define NELEMS( x ) ( sizeof( ( x ) )/sizeof( ( x )[0] ) )
+
+/* ----------------------- Static variables ---------------------------------*/
+static FILE *fLogFile = NULL;
+static eMBPortLogLevel eLevelMax = MB_LOG_DEBUG;
+static pthread_mutex_t xLock = PTHREAD_MUTEX_INITIALIZER;
+
+/* ----------------------- Start implementation -----------------------------*/
+void
+vMBPortLogLevel( eMBPortLogLevel eNewLevelMax )
+{
+ eLevelMax = eNewLevelMax;
+}
+
+void
+vMBPortLogFile( FILE * fNewLogFile )
+{
+ fLogFile = fNewLogFile;
+}
+
+void
+vMBPortLog( eMBPortLogLevel eLevel, const CHAR * szModule, const CHAR * szFmt, ... )
+{
+ CHAR szBuf[512];
+ int i;
+ va_list args;
+ FILE *fOutput = fLogFile == NULL ? stderr : fLogFile;
+
+ static const char *arszLevel2Str[] = { "ERROR", "WARN", "INFO", "DEBUG" };
+
+ i = snprintf( szBuf, NELEMS( szBuf ), "%s: %s: ", arszLevel2Str[eLevel], szModule );
+
+ if( i != 0 )
+ {
+ va_start( args, szFmt );
+ i += vsnprintf( &szBuf[i], NELEMS( szBuf ) - i, szFmt, args );
+ va_end( args );
+ }
+
+ if( i != 0 )
+ {
+ if( eLevel <= eLevelMax )
+ {
+ fputs( szBuf, fOutput );
+ }
+ }
+}
+
+void
+vMBPortEnterCritical( void )
+{
+ if( pthread_mutex_lock( &xLock ) != 0 )
+ {
+ vMBPortLog( MB_LOG_ERROR, "OTHER", "Locking primitive failed: %s\n", strerror( errno ) );
+ }
+}
+
+void
+vMBPortExitCritical( void )
+{
+ if( pthread_mutex_unlock( &xLock ) != 0 )
+ {
+ vMBPortLog( MB_LOG_ERROR, "OTHER", "Locking primitive failed: %s\n", strerror( errno ) );
+ }
+}
diff --git a/apps/modbus/nuttx/portserial.c b/apps/modbus/nuttx/portserial.c
new file mode 100644
index 000000000..bacab6a23
--- /dev/null
+++ b/apps/modbus/nuttx/portserial.c
@@ -0,0 +1,352 @@
+/*
+ * FreeModbus Libary: Linux Port
+ * Copyright (C) 2006 Christian Walter <wolti@sil.at>
+ *
+ * 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
+ *
+ * File: $Id: portserial.c,v 1.3 2006/10/12 08:35:34 wolti Exp $
+ */
+
+/* ----------------------- Standard includes --------------------------------*/
+#include <nuttx/config.h>
+#include <stdio.h>
+#include <stdlib.h>
+#include <errno.h>
+#include <string.h>
+#include <sys/types.h>
+#include <sys/stat.h>
+#include <sys/select.h>
+#include <fcntl.h>
+#include <termios.h>
+#include <unistd.h>
+
+#include "port.h"
+
+/* ----------------------- Modbus includes ----------------------------------*/
+#include "mb.h"
+#include "mbport.h"
+
+/* ----------------------- Defines -----------------------------------------*/
+#ifdef CONFIG_MB_ASCII_ENABLED
+#define BUF_SIZE 513 /* must hold a complete ASCII frame. */
+#else
+#define BUF_SIZE 256 /* must hold a complete RTU frame. */
+#endif
+
+/* ----------------------- Static variables ---------------------------------*/
+static int iSerialFd = -1;
+static BOOL bRxEnabled;
+static BOOL bTxEnabled;
+
+static ULONG ulTimeoutMs;
+static UCHAR ucBuffer[BUF_SIZE];
+static int uiRxBufferPos;
+static int uiTxBufferPos;
+
+static struct termios xOldTIO;
+
+/* ----------------------- Function prototypes ------------------------------*/
+static BOOL prvbMBPortSerialRead( UCHAR * pucBuffer, USHORT usNBytes, USHORT * usNBytesRead );
+static BOOL prvbMBPortSerialWrite( UCHAR * pucBuffer, USHORT usNBytes );
+
+/* ----------------------- Begin implementation -----------------------------*/
+void
+vMBPortSerialEnable( BOOL bEnableRx, BOOL bEnableTx )
+{
+ /* it is not allowed that both receiver and transmitter are enabled. */
+ assert( !bEnableRx || !bEnableTx );
+
+ if( bEnableRx )
+ {
+ ( void )tcflush( iSerialFd, TCIFLUSH );
+ uiRxBufferPos = 0;
+ bRxEnabled = TRUE;
+ }
+ else
+ {
+ bRxEnabled = FALSE;
+ }
+ if( bEnableTx )
+ {
+ bTxEnabled = TRUE;
+ uiTxBufferPos = 0;
+ }
+ else
+ {
+ bTxEnabled = FALSE;
+ }
+}
+
+BOOL
+xMBPortSerialInit( UCHAR ucPort, ULONG ulBaudRate, UCHAR ucDataBits, eMBParity eParity )
+{
+ CHAR szDevice[16];
+ BOOL bStatus = TRUE;
+
+ struct termios xNewTIO;
+ speed_t xNewSpeed;
+
+ snprintf( szDevice, 16, "/dev/ttyS%d", ucPort );
+
+ if( ( iSerialFd = open( szDevice, O_RDWR | O_NOCTTY ) ) < 0 )
+ {
+ vMBPortLog( MB_LOG_ERROR, "SER-INIT", "Can't open serial port %s: %s\n", szDevice,
+ strerror( errno ) );
+ }
+ else if( tcgetattr( iSerialFd, &xOldTIO ) != 0 )
+ {
+ vMBPortLog( MB_LOG_ERROR, "SER-INIT", "Can't get settings from port %s: %s\n", szDevice,
+ strerror( errno ) );
+ }
+ else
+ {
+ bzero( &xNewTIO, sizeof( struct termios ) );
+
+ xNewTIO.c_iflag |= IGNBRK | INPCK;
+ xNewTIO.c_cflag |= CREAD | CLOCAL;
+ switch ( eParity )
+ {
+ 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;
+ }
+ switch ( ucDataBits )
+ {
+ case 8:
+ xNewTIO.c_cflag |= CS8;
+ break;
+ case 7:
+ xNewTIO.c_cflag |= CS7;
+ break;
+ default:
+ bStatus = FALSE;
+ }
+ switch ( ulBaudRate )
+ {
+ case 9600:
+ xNewSpeed = B9600;
+ break;
+ case 19200:
+ xNewSpeed = B19200;
+ break;
+ case 38400:
+ xNewSpeed = B38400;
+ break;
+ case 57600:
+ xNewSpeed = B57600;
+ break;
+ case 115200:
+ xNewSpeed = B115200;
+ break;
+ default:
+ bStatus = FALSE;
+ }
+ if( bStatus )
+ {
+ if( cfsetispeed( &xNewTIO, xNewSpeed ) != 0 )
+ {
+ vMBPortLog( MB_LOG_ERROR, "SER-INIT", "Can't set baud rate %ld for port %s: %s\n",
+ ulBaudRate, strerror( errno ) );
+ }
+ else if( cfsetospeed( &xNewTIO, xNewSpeed ) != 0 )
+ {
+ vMBPortLog( MB_LOG_ERROR, "SER-INIT", "Can't set baud rate %ld for port %s: %s\n",
+ ulBaudRate, szDevice, strerror( errno ) );
+ }
+ else if( tcsetattr( iSerialFd, TCSANOW, &xNewTIO ) != 0 )
+ {
+ vMBPortLog( MB_LOG_ERROR, "SER-INIT", "Can't set settings for port %s: %s\n",
+ szDevice, strerror( errno ) );
+ }
+ else
+ {
+ vMBPortSerialEnable( FALSE, FALSE );
+ bStatus = TRUE;
+ }
+ }
+ }
+ return bStatus;
+}
+
+BOOL
+xMBPortSerialSetTimeout( ULONG ulNewTimeoutMs )
+{
+ if( ulNewTimeoutMs > 0 )
+ {
+ ulTimeoutMs = ulNewTimeoutMs;
+ }
+ else
+ {
+ ulTimeoutMs = 1;
+ }
+ return TRUE;
+}
+
+void
+vMBPortClose( void )
+{
+ if( iSerialFd != -1 )
+ {
+ ( void )tcsetattr( iSerialFd, TCSANOW, &xOldTIO );
+ ( void )close( iSerialFd );
+ iSerialFd = -1;
+ }
+}
+
+BOOL
+prvbMBPortSerialRead( UCHAR * pucBuffer, USHORT usNBytes, USHORT * 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 = ( USHORT ) res;
+ break;
+ }
+ }
+ else
+ {
+ *usNBytesRead = 0;
+ break;
+ }
+ }
+ while( bResult == TRUE );
+ return bResult;
+}
+
+BOOL
+prvbMBPortSerialWrite( UCHAR * pucBuffer, USHORT 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;
+ }
+ return left == 0 ? TRUE : FALSE;
+}
+
+BOOL
+xMBPortSerialPoll( )
+{
+ BOOL bStatus = TRUE;
+ USHORT usBytesRead;
+ int i;
+
+ while( bRxEnabled )
+ {
+ if( prvbMBPortSerialRead( &ucBuffer[0], BUF_SIZE, &usBytesRead ) )
+ {
+ if( usBytesRead == 0 )
+ {
+ /* timeout with no bytes. */
+ break;
+ }
+ else if( usBytesRead > 0 )
+ {
+ for( i = 0; i < usBytesRead; i++ )
+ {
+ /* Call the modbus stack and let him fill the buffers. */
+ ( void )pxMBFrameCBByteReceived( );
+ }
+ uiRxBufferPos = 0;
+ }
+ }
+ else
+ {
+ vMBPortLog( MB_LOG_ERROR, "SER-POLL", "read failed on serial device: %s\n",
+ strerror( errno ) );
+ bStatus = FALSE;
+ }
+ }
+ if( bTxEnabled )
+ {
+ while( bTxEnabled )
+ {
+ ( void )pxMBFrameCBTransmitterEmpty( );
+ /* Call the modbus stack to let him fill the buffer. */
+ }
+ if( !prvbMBPortSerialWrite( &ucBuffer[0], uiTxBufferPos ) )
+ {
+ vMBPortLog( MB_LOG_ERROR, "SER-POLL", "write failed on serial device: %s\n",
+ strerror( errno ) );
+ bStatus = FALSE;
+ }
+ }
+
+ return bStatus;
+}
+
+BOOL
+xMBPortSerialPutByte( CHAR ucByte )
+{
+ assert( uiTxBufferPos < BUF_SIZE );
+ ucBuffer[uiTxBufferPos] = ucByte;
+ uiTxBufferPos++;
+ return TRUE;
+}
+
+BOOL
+xMBPortSerialGetByte( CHAR * pucByte )
+{
+ assert( uiRxBufferPos < BUF_SIZE );
+ *pucByte = ucBuffer[uiRxBufferPos];
+ uiRxBufferPos++;
+ return TRUE;
+}
diff --git a/apps/modbus/nuttx/porttimer.c b/apps/modbus/nuttx/porttimer.c
new file mode 100644
index 000000000..c440e4f1f
--- /dev/null
+++ b/apps/modbus/nuttx/porttimer.c
@@ -0,0 +1,98 @@
+/*
+ * FreeModbus Libary: Linux Port
+ * Copyright (C) 2006 Christian Walter <wolti@sil.at>
+ *
+ * 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
+ *
+ * File: $Id: porttimer.c,v 1.1 2006/08/01 20:58:50 wolti Exp $
+ */
+
+/* ----------------------- Standard includes --------------------------------*/
+#include <nuttx/config.h>
+#include <stdlib.h>
+#include <sys/time.h>
+
+#include "port.h"
+
+/* ----------------------- Modbus includes ----------------------------------*/
+#include "mb.h"
+#include "mbport.h"
+
+/* ----------------------- Defines ------------------------------------------*/
+
+/* ----------------------- Static variables ---------------------------------*/
+ULONG ulTimeOut;
+BOOL bTimeoutEnable;
+
+static struct timeval xTimeLast;
+
+/* ----------------------- Start implementation -----------------------------*/
+BOOL
+xMBPortTimersInit( USHORT usTim1Timerout50us )
+{
+ ulTimeOut = usTim1Timerout50us / 20U;
+ if( ulTimeOut == 0 )
+ ulTimeOut = 1;
+
+ return xMBPortSerialSetTimeout( ulTimeOut );
+}
+
+void
+xMBPortTimersClose( )
+{
+ /* Does not use any hardware resources. */
+}
+
+void
+vMBPortTimerPoll( )
+{
+ ULONG ulDeltaMS;
+ struct timeval xTimeCur;
+
+ /* Timers are called from the serial layer because we have no high
+ * res timer in Win32. */
+ if( bTimeoutEnable )
+ {
+ if( gettimeofday( &xTimeCur, NULL ) != 0 )
+ {
+ /* gettimeofday failed - retry next time. */
+ }
+ else
+ {
+ ulDeltaMS = ( xTimeCur.tv_sec - xTimeLast.tv_sec ) * 1000L +
+ ( xTimeCur.tv_usec - xTimeLast.tv_usec ) * 1000L;
+ if( ulDeltaMS > ulTimeOut )
+ {
+ bTimeoutEnable = FALSE;
+ ( void )pxMBPortCBTimerExpired( );
+ }
+ }
+ }
+}
+
+void
+vMBPortTimersEnable( )
+{
+ int res = gettimeofday( &xTimeLast, NULL );
+
+ assert( res == 0 );
+ bTimeoutEnable = TRUE;
+}
+
+void
+vMBPortTimersDisable( )
+{
+ bTimeoutEnable = FALSE;
+}