Browse Source

Don't use strerror in apps/modbus; Add CONFIG_MB_TERMIOS to enable/suppress use of termios.h interfaces

git-svn-id: https://nuttx.svn.sourceforge.net/svnroot/nuttx/trunk@4968 7fd9a85b-ad96-42d3-883c-3090e2eb8679
sbg
patacongo 13 years ago
parent
commit
ad37fa6505
  1. 6
      apps/ChangeLog.txt
  2. 9
      apps/modbus/Kconfig
  3. 4
      apps/modbus/README.txt
  4. 62
      apps/modbus/nuttx/portother.c
  5. 308
      apps/modbus/nuttx/portserial.c

6
apps/ChangeLog.txt

@ -255,5 +255,7 @@
has been added to the NuttX apps/ source tree. has been added to the NuttX apps/ source tree.
* apps/examples/modbus: A port of the freemodbus-v1.5.0 "demo" * apps/examples/modbus: A port of the freemodbus-v1.5.0 "demo"
program that will be used to verify the FreeModBus port program that will be used to verify the FreeModBus port
* apps/modbus: Don't use strerror(). It is just too big.
* apps/modbus: Add CONFIG_MB_TERMIOS. If the driver doesn't support
termios ioctls, then don't bother trying to configure the baud, parity
etc.

9
apps/modbus/Kconfig

@ -24,6 +24,15 @@ config MB_TCP_ENABLED
depends on MODBUS depends on MODBUS
default y default y
config MB_TERMIOS
bool "Driver TERMIOS supported"
depends on MB_ASCII_ENABLED || MB_RTU_ENABLED
default n
---help---
Serial driver supports termios.h interfaces (tcsetattr, tcflush, etc.).
If this is not defined, then the terminal settings (baud, parity, etc).
are not configurable at runtime; serial streams will not be flushed when closed.
config MB_ASCII_TIMEOUT_SEC config MB_ASCII_TIMEOUT_SEC
int "Character timeout" int "Character timeout"
depends on MB_ASCII_ENABLED depends on MB_ASCII_ENABLED

4
apps/modbus/README.txt

@ -60,6 +60,10 @@ The NuttX-named configuration options that are available include:
CONFIG_MB_ASCII_ENABLED - Modbus ASCII support CONFIG_MB_ASCII_ENABLED - Modbus ASCII support
CONFIG_MB_RTU_ENABLED - Modbus RTU support CONFIG_MB_RTU_ENABLED - Modbus RTU support
CONFIG_MB_TCP_ENABLED - Modbus TCP support CONFIG_MB_TCP_ENABLED - Modbus TCP support
CONFIG_MB_TERMIOS - Serial driver supports termios.h interfaces (tcsetattr,
tcflush, etc.). If this is not defined, then the terminal settings (baud,
parity, etc.) are not configurable at runtime; serial streams will not be
flushed when closed.
CONFIG_MB_ASCII_TIMEOUT_SEC - Character timeout value for Modbus ASCII. The CONFIG_MB_ASCII_TIMEOUT_SEC - Character timeout value for Modbus ASCII. The
character timeout value is not fixed for Modbus ASCII and is therefore character timeout value is not fixed for Modbus ASCII and is therefore
a configuration option. It should be set to the maximum expected delay a configuration option. It should be set to the maximum expected delay

62
apps/modbus/nuttx/portother.c

@ -22,6 +22,7 @@
*/ */
/* ----------------------- Standard includes --------------------------------*/ /* ----------------------- Standard includes --------------------------------*/
#include <nuttx/config.h> #include <nuttx/config.h>
#include <stdio.h> #include <stdio.h>
#include <stdlib.h> #include <stdlib.h>
@ -33,72 +34,73 @@
#include "port.h" #include "port.h"
/* ----------------------- Modbus includes ----------------------------------*/ /* ----------------------- Modbus includes ----------------------------------*/
#include <apps/modbus/mb.h> #include <apps/modbus/mb.h>
#include <apps/modbus/mbport.h> #include <apps/modbus/mbport.h>
/* ----------------------- Defines ------------------------------------------*/ /* ----------------------- Defines ------------------------------------------*/
#define NELEMS( x ) ( sizeof( ( x ) )/sizeof( ( x )[0] ) )
#define NELEMS(x) (sizeof((x))/sizeof((x)[0]))
/* ----------------------- Static variables ---------------------------------*/ /* ----------------------- Static variables ---------------------------------*/
static FILE *fLogFile = NULL; static FILE *fLogFile = NULL;
static eMBPortLogLevel eLevelMax = MB_LOG_DEBUG; static eMBPortLogLevel eLevelMax = MB_LOG_DEBUG;
static pthread_mutex_t xLock = PTHREAD_MUTEX_INITIALIZER; static pthread_mutex_t xLock = PTHREAD_MUTEX_INITIALIZER;
/* ----------------------- Start implementation -----------------------------*/ /* ----------------------- Start implementation -----------------------------*/
void
vMBPortLogLevel( eMBPortLogLevel eNewLevelMax ) void vMBPortLogLevel(eMBPortLogLevel eNewLevelMax)
{ {
eLevelMax = eNewLevelMax; eLevelMax = eNewLevelMax;
} }
void void vMBPortLogFile(FILE * fNewLogFile)
vMBPortLogFile( FILE * fNewLogFile )
{ {
fLogFile = fNewLogFile; fLogFile = fNewLogFile;
} }
void void vMBPortLog(eMBPortLogLevel eLevel, const char * szModule, const char * szFmt, ...)
vMBPortLog( eMBPortLogLevel eLevel, const char * szModule, const char * szFmt, ... )
{ {
char szBuf[512]; char szBuf[512];
int i; int i;
va_list args; va_list args;
FILE *fOutput = fLogFile == NULL ? stderr : fLogFile; FILE *fOutput = fLogFile == NULL ? stderr : fLogFile;
static const char *arszLevel2Str[] = { "ERROR", "WARN", "INFO", "DEBUG" }; static const char *arszLevel2Str[] = { "ERROR", "WARN", "INFO", "DEBUG" };
i = snprintf( szBuf, NELEMS( szBuf ), "%s: %s: ", arszLevel2Str[eLevel], szModule ); i = snprintf(szBuf, NELEMS(szBuf), "%s: %s: ", arszLevel2Str[eLevel], szModule);
if( i != 0 ) if (i != 0)
{ {
va_start( args, szFmt ); va_start(args, szFmt);
i += vsnprintf( &szBuf[i], NELEMS( szBuf ) - i, szFmt, args ); i += vsnprintf(&szBuf[i], NELEMS(szBuf) - i, szFmt, args);
va_end( args ); va_end(args);
} }
if( i != 0 ) if (i != 0)
{ {
if( eLevel <= eLevelMax ) if (eLevel <= eLevelMax)
{ {
fputs( szBuf, fOutput ); fputs(szBuf, fOutput);
} }
} }
} }
void void vMBPortEnterCritical(void)
vMBPortEnterCritical( void )
{ {
if( pthread_mutex_lock( &xLock ) != 0 ) int ret = pthread_mutex_lock(&xLock);
if (ret != 0)
{ {
vMBPortLog( MB_LOG_ERROR, "OTHER", "Locking primitive failed: %s\n", strerror( errno ) ); vMBPortLog(MB_LOG_ERROR, "OTHER", "Locking primitive failed: %d\n", ret);
} }
} }
void void vMBPortExitCritical(void)
vMBPortExitCritical( void )
{ {
if( pthread_mutex_unlock( &xLock ) != 0 ) int ret = pthread_mutex_unlock(&xLock);
if (ret != 0)
{ {
vMBPortLog( MB_LOG_ERROR, "OTHER", "Locking primitive failed: %s\n", strerror( errno ) ); vMBPortLog(MB_LOG_ERROR, "OTHER", "Locking primitive failed: %d\n", ret);
} }
} }

308
apps/modbus/nuttx/portserial.c

@ -22,6 +22,7 @@
*/ */
/* ----------------------- Standard includes --------------------------------*/ /* ----------------------- Standard includes --------------------------------*/
#include <nuttx/config.h> #include <nuttx/config.h>
#include <stdio.h> #include <stdio.h>
#include <stdlib.h> #include <stdlib.h>
@ -31,17 +32,22 @@
#include <sys/stat.h> #include <sys/stat.h>
#include <sys/select.h> #include <sys/select.h>
#include <fcntl.h> #include <fcntl.h>
#include <termios.h>
#include <unistd.h> #include <unistd.h>
#include <assert.h> #include <assert.h>
#ifdef CONFIG_MB_TERMIOS
# include <termios.h>
#endif
#include "port.h" #include "port.h"
/* ----------------------- Modbus includes ----------------------------------*/ /* ----------------------- Modbus includes ----------------------------------*/
#include <apps/modbus/mb.h> #include <apps/modbus/mb.h>
#include <apps/modbus/mbport.h> #include <apps/modbus/mbport.h>
/* ----------------------- Defines -----------------------------------------*/ /* ----------------------- Defines -----------------------------------------*/
#ifdef CONFIG_MB_ASCII_ENABLED #ifdef CONFIG_MB_ASCII_ENABLED
#define BUF_SIZE 513 /* must hold a complete ASCII frame. */ #define BUF_SIZE 513 /* must hold a complete ASCII frame. */
#else #else
@ -49,6 +55,7 @@
#endif #endif
/* ----------------------- Static variables ---------------------------------*/ /* ----------------------- Static variables ---------------------------------*/
static int iSerialFd = -1; static int iSerialFd = -1;
static bool bRxEnabled; static bool bRxEnabled;
static bool bTxEnabled; static bool bTxEnabled;
@ -58,277 +65,298 @@ static uint8_t ucBuffer[BUF_SIZE];
static int uiRxBufferPos; static int uiRxBufferPos;
static int uiTxBufferPos; static int uiTxBufferPos;
#ifdef CONFIG_MB_TERMIOS
static struct termios xOldTIO; static struct termios xOldTIO;
#endif
/* ----------------------- Function prototypes ------------------------------*/ /* ----------------------- Function prototypes ------------------------------*/
static bool prvbMBPortSerialRead( uint8_t * pucBuffer, uint16_t usNBytes, uint16_t * usNBytesRead );
static bool prvbMBPortSerialWrite( uint8_t * pucBuffer, uint16_t usNBytes ); static bool prvbMBPortSerialRead(uint8_t *pucBuffer, uint16_t usNBytes, uint16_t *usNBytesRead);
static bool prvbMBPortSerialWrite(uint8_t *pucBuffer, uint16_t usNBytes);
/* ----------------------- Begin implementation -----------------------------*/ /* ----------------------- Begin implementation -----------------------------*/
void
vMBPortSerialEnable( bool bEnableRx, bool bEnableTx ) void vMBPortSerialEnable(bool bEnableRx, bool bEnableTx)
{ {
/* it is not allowed that both receiver and transmitter are enabled. */ /* it is not allowed that both receiver and transmitter are enabled. */
ASSERT( !bEnableRx || !bEnableTx );
ASSERT(!bEnableRx || !bEnableTx);
if( bEnableRx ) if (bEnableRx)
{ {
( void )tcflush( iSerialFd, TCIFLUSH ); #ifdef CONFIG_MB_TERMIOS
uiRxBufferPos = 0; (void)tcflush(iSerialFd, TCIFLUSH);
bRxEnabled = true; #endif
uiRxBufferPos = 0;
bRxEnabled = true;
} }
else else
{ {
bRxEnabled = false; bRxEnabled = false;
} }
if( bEnableTx )
if (bEnableTx)
{ {
bTxEnabled = true; bTxEnabled = true;
uiTxBufferPos = 0; uiTxBufferPos = 0;
} }
else else
{ {
bTxEnabled = false; bTxEnabled = false;
} }
} }
bool bool xMBPortSerialInit(uint8_t ucPort, uint32_t ulBaudRate,
xMBPortSerialInit( uint8_t ucPort, uint32_t ulBaudRate, uint8_t ucDataBits, eMBParity eParity ) uint8_t ucDataBits, eMBParity eParity)
{ {
char szDevice[16]; char szDevice[16];
bool bStatus = true; bool bStatus = true;
struct termios xNewTIO; #ifdef CONFIG_MB_TERMIOS
speed_t xNewSpeed; struct termios xNewTIO;
speed_t xNewSpeed;
#endif
snprintf( szDevice, 16, "/dev/ttyS%d", ucPort ); snprintf(szDevice, 16, "/dev/ttyS%d", ucPort);
if( ( iSerialFd = open( szDevice, O_RDWR | O_NOCTTY ) ) < 0 ) if ((iSerialFd = open(szDevice, O_RDWR | O_NOCTTY)) < 0)
{ {
vMBPortLog( MB_LOG_ERROR, "SER-INIT", "Can't open serial port %s: %s\n", szDevice, vMBPortLog(MB_LOG_ERROR, "SER-INIT", "Can't open serial port %s: %d\n",
strerror( errno ) ); szDevice, errno);
} }
else if( tcgetattr( iSerialFd, &xOldTIO ) != 0 )
#ifdef CONFIG_MB_TERMIOS
else if (tcgetattr(iSerialFd, &xOldTIO) != 0)
{ {
vMBPortLog( MB_LOG_ERROR, "SER-INIT", "Can't get settings from port %s: %s\n", szDevice, vMBPortLog(MB_LOG_ERROR, "SER-INIT", "Can't get settings from port %s: %d\n",
strerror( errno ) ); szDevice, errno);
} }
else else
{ {
bzero( &xNewTIO, sizeof( struct termios ) ); bzero(&xNewTIO, sizeof(struct termios));
xNewTIO.c_iflag |= IGNBRK | INPCK; xNewTIO.c_iflag |= IGNBRK | INPCK;
xNewTIO.c_cflag |= CREAD | CLOCAL; xNewTIO.c_cflag |= CREAD | CLOCAL;
switch ( eParity ) switch (eParity)
{ {
case MB_PAR_NONE: case MB_PAR_NONE:
break; break;
case MB_PAR_EVEN: case MB_PAR_EVEN:
xNewTIO.c_cflag |= PARENB; xNewTIO.c_cflag |= PARENB;
break; break;
case MB_PAR_ODD: case MB_PAR_ODD:
xNewTIO.c_cflag |= PARENB | PARODD; xNewTIO.c_cflag |= PARENB | PARODD;
break; break;
default: default:
bStatus = false; bStatus = false;
} }
switch ( ucDataBits )
switch (ucDataBits)
{ {
case 8: case 8:
xNewTIO.c_cflag |= CS8; xNewTIO.c_cflag |= CS8;
break; break;
case 7: case 7:
xNewTIO.c_cflag |= CS7; xNewTIO.c_cflag |= CS7;
break; break;
default: default:
bStatus = false; bStatus = false;
} }
switch ( ulBaudRate )
switch (ulBaudRate)
{ {
case 9600: case 9600:
xNewSpeed = B9600; xNewSpeed = B9600;
break; break;
case 19200: case 19200:
xNewSpeed = B19200; xNewSpeed = B19200;
break; break;
case 38400: case 38400:
xNewSpeed = B38400; xNewSpeed = B38400;
break; break;
case 57600: case 57600:
xNewSpeed = B57600; xNewSpeed = B57600;
break; break;
case 115200: case 115200:
xNewSpeed = B115200; xNewSpeed = B115200;
break; break;
default: default:
bStatus = false; bStatus = false;
} }
if( bStatus )
if (bStatus)
{ {
if( cfsetispeed( &xNewTIO, xNewSpeed ) != 0 ) if (cfsetispeed(&xNewTIO, xNewSpeed) != 0)
{ {
vMBPortLog( MB_LOG_ERROR, "SER-INIT", "Can't set baud rate %ld for port %s: %s\n", vMBPortLog(MB_LOG_ERROR, "SER-INIT", "Can't set baud rate %ld for port %s: %d\n",
ulBaudRate, strerror( errno ) ); ulBaudRate, errno);
} }
else if( cfsetospeed( &xNewTIO, xNewSpeed ) != 0 ) else if (cfsetospeed(&xNewTIO, xNewSpeed) != 0)
{ {
vMBPortLog( MB_LOG_ERROR, "SER-INIT", "Can't set baud rate %ld for port %s: %s\n", vMBPortLog(MB_LOG_ERROR, "SER-INIT", "Can't set baud rate %ld for port %s: %d\n",
ulBaudRate, szDevice, strerror( errno ) ); ulBaudRate, szDevice, errno);
} }
else if( tcsetattr( iSerialFd, TCSANOW, &xNewTIO ) != 0 ) else if (tcsetattr(iSerialFd, TCSANOW, &xNewTIO) != 0)
{ {
vMBPortLog( MB_LOG_ERROR, "SER-INIT", "Can't set settings for port %s: %s\n", vMBPortLog(MB_LOG_ERROR, "SER-INIT", "Can't set settings for port %s: %d\n",
szDevice, strerror( errno ) ); szDevice, errno);
} }
else else
{ {
vMBPortSerialEnable( false, false ); vMBPortSerialEnable(false, false);
bStatus = true; bStatus = true;
} }
} }
} }
return bStatus; #endif
return bStatus;
} }
bool bool xMBPortSerialSetTimeout(uint32_t ulNewTimeoutMs)
xMBPortSerialSetTimeout( uint32_t ulNewTimeoutMs )
{ {
if( ulNewTimeoutMs > 0 ) if (ulNewTimeoutMs > 0)
{ {
ulTimeoutMs = ulNewTimeoutMs; ulTimeoutMs = ulNewTimeoutMs;
} }
else else
{ {
ulTimeoutMs = 1; ulTimeoutMs = 1;
} }
return true;
return true;
} }
void void vMBPortClose(void)
vMBPortClose( void )
{ {
if( iSerialFd != -1 ) if (iSerialFd != -1)
{ {
( void )tcsetattr( iSerialFd, TCSANOW, &xOldTIO ); #ifdef CONFIG_MB_TERMIOS
( void )close( iSerialFd ); (void)tcsetattr(iSerialFd, TCSANOW, &xOldTIO);
iSerialFd = -1; #endif
(void)close(iSerialFd);
iSerialFd = -1;
} }
} }
bool bool prvbMBPortSerialRead(uint8_t *pucBuffer, uint16_t usNBytes, uint16_t *usNBytesRead)
prvbMBPortSerialRead( uint8_t * pucBuffer, uint16_t usNBytes, uint16_t * usNBytesRead )
{ {
bool bResult = true; bool bResult = true;
ssize_t res; ssize_t res;
fd_set rfds; fd_set rfds;
struct timeval tv; struct timeval tv;
tv.tv_sec = 0; tv.tv_sec = 0;
tv.tv_usec = 50000; tv.tv_usec = 50000;
FD_ZERO( &rfds ); FD_ZERO(&rfds);
FD_SET( iSerialFd, &rfds ); FD_SET(iSerialFd, &rfds);
/* Wait until character received or timeout. Recover in case of an /* Wait until character received or timeout. Recover in case of an
* interrupted read system call. */ * interrupted read system call.
do */
do
{ {
if( select( iSerialFd + 1, &rfds, NULL, NULL, &tv ) == -1 ) if (select(iSerialFd + 1, &rfds, NULL, NULL, &tv) == -1)
{ {
if( errno != EINTR ) if (errno != EINTR)
{ {
bResult = false; bResult = false;
} }
} }
else if( FD_ISSET( iSerialFd, &rfds ) ) else if (FD_ISSET(iSerialFd, &rfds))
{ {
if( ( res = read( iSerialFd, pucBuffer, usNBytes ) ) == -1 ) if ((res = read(iSerialFd, pucBuffer, usNBytes)) == -1)
{ {
bResult = false; bResult = false;
} }
else else
{ {
*usNBytesRead = ( uint16_t ) res; *usNBytesRead = (uint16_t)res;
break; break;
} }
} }
else else
{ {
*usNBytesRead = 0; *usNBytesRead = 0;
break; break;
} }
} }
while( bResult == true );
return bResult; while(bResult == true);
return bResult;
} }
bool bool prvbMBPortSerialWrite(uint8_t *pucBuffer, uint16_t usNBytes)
prvbMBPortSerialWrite( uint8_t * pucBuffer, uint16_t usNBytes )
{ {
ssize_t res; ssize_t res;
size_t left = ( size_t ) usNBytes; size_t left = (size_t) usNBytes;
size_t done = 0; size_t done = 0;
while( left > 0 ) while(left > 0)
{ {
if( ( res = write( iSerialFd, pucBuffer + done, left ) ) == -1 ) if ((res = write(iSerialFd, pucBuffer + done, left)) == -1)
{ {
if( errno != EINTR ) if (errno != EINTR)
{ {
break; break;
} }
/* call write again because of interrupted system call. */
continue; /* call write again because of interrupted system call. */
continue;
} }
done += res;
left -= res; done += res;
left -= res;
} }
return left == 0 ? true : false;
return left == 0 ? true : false;
} }
bool bool
xMBPortSerialPoll( ) xMBPortSerialPoll()
{ {
bool bStatus = true; bool bStatus = true;
uint16_t usBytesRead; uint16_t usBytesRead;
int i; int i;
while( bRxEnabled ) while(bRxEnabled)
{ {
if( prvbMBPortSerialRead( &ucBuffer[0], BUF_SIZE, &usBytesRead ) ) if (prvbMBPortSerialRead(&ucBuffer[0], BUF_SIZE, &usBytesRead))
{ {
if( usBytesRead == 0 ) if (usBytesRead == 0)
{ {
/* timeout with no bytes. */ /* timeout with no bytes. */
break; 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. */ /* Call the modbus stack and let him fill the buffers. */
( void )pxMBFrameCBByteReceived( ); (void)pxMBFrameCBByteReceived();
} }
uiRxBufferPos = 0; uiRxBufferPos = 0;
} }
} }
else else
{ {
vMBPortLog( MB_LOG_ERROR, "SER-POLL", "read failed on serial device: %s\n", vMBPortLog(MB_LOG_ERROR, "SER-POLL", "read failed on serial device: %d\n",
strerror( errno ) ); errno);
bStatus = false; bStatus = false;
} }
} }
if( bTxEnabled ) if (bTxEnabled)
{ {
while( bTxEnabled ) while(bTxEnabled)
{ {
( void )pxMBFrameCBTransmitterEmpty( ); (void)pxMBFrameCBTransmitterEmpty();
/* Call the modbus stack to let him fill the buffer. */ /* 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: %s\n", vMBPortLog(MB_LOG_ERROR, "SER-POLL", "write failed on serial device: %d\n",
strerror( errno ) ); errno);
bStatus = false; bStatus = false;
} }
} }
@ -337,18 +365,18 @@ xMBPortSerialPoll( )
} }
bool bool
xMBPortSerialPutByte( int8_t ucByte ) xMBPortSerialPutByte(int8_t ucByte)
{ {
ASSERT( uiTxBufferPos < BUF_SIZE ); ASSERT(uiTxBufferPos < BUF_SIZE);
ucBuffer[uiTxBufferPos] = ucByte; ucBuffer[uiTxBufferPos] = ucByte;
uiTxBufferPos++; uiTxBufferPos++;
return true; return true;
} }
bool bool
xMBPortSerialGetByte( int8_t * pucByte ) xMBPortSerialGetByte(int8_t *pucByte)
{ {
ASSERT( uiRxBufferPos < BUF_SIZE ); ASSERT(uiRxBufferPos < BUF_SIZE);
*pucByte = ucBuffer[uiRxBufferPos]; *pucByte = ucBuffer[uiRxBufferPos];
uiRxBufferPos++; uiRxBufferPos++;
return true; return true;

Loading…
Cancel
Save