diff options
| author | Tero Kontkanen <tero.kontkanen@granitedevices.fi> | 2017-05-29 22:34:15 +0300 |
|---|---|---|
| committer | Tero Kontkanen <tero.kontkanen@granitedevices.fi> | 2017-05-29 22:34:15 +0300 |
| commit | 67db22dfed3306a6aaf2a9ba6fc814c8b4163ece (patch) | |
| tree | 2ccd75a64a4d25b3b2b1964157d8af35940a99ec | |
| parent | f065efc4607c8adcc31266748bd1e20ca39090b9 (diff) | |
| parent | a60052b1d6a620e64d300f07e9edd26a963cd889 (diff) | |
| download | SimpleMotionV2-67db22dfed3306a6aaf2a9ba6fc814c8b4163ece.tar.gz SimpleMotionV2-67db22dfed3306a6aaf2a9ba6fc814c8b4163ece.zip | |
Merge branch 'develop': Summary of changes:
-Added communication TCP IP port
-Added device deployment API
-Added buffered motion API
-New version of simplemotion_defs.h
-Various fixes & MacOS support
| -rw-r--r-- | README.md | 36 | ||||
| -rw-r--r-- | SimpleMotionV2.pri | 6 | ||||
| -rw-r--r-- | bufferedmotion.c | 218 | ||||
| -rw-r--r-- | bufferedmotion.h | 67 | ||||
| -rw-r--r-- | busdevice.c | 169 | ||||
| -rw-r--r-- | busdevice.h | 2 | ||||
| -rw-r--r-- | devicedeployment.c | 687 | ||||
| -rw-r--r-- | devicedeployment.h | 113 | ||||
| -rw-r--r-- | pcserialport.c | 112 | ||||
| -rw-r--r-- | simplemotion.c | 78 | ||||
| -rw-r--r-- | simplemotion.h | 31 | ||||
| -rw-r--r-- | simplemotion_defs.h | 216 | ||||
| -rw-r--r-- | simplemotion_private.h | 12 | ||||
| -rw-r--r-- | tcpclient.c | 189 | ||||
| -rw-r--r-- | tcpclient.h | 22 |
15 files changed, 1823 insertions, 135 deletions
@@ -1,7 +1,39 @@ SimpleMotionV2 ============== -SimpleMotion V2 library +This is a SimpleMotion V2 library, which is an API to control motor controller from any programmable platform, such as PC, PLC or MCU. -For more information, see: +For main documentation, see: http://granitedevices.com/wiki/SimpleMotion_V2 + + +Files & usage +============= + +There are files that are needed for basic SimpleMotion usage, and files that are optional and needed only for certain features. Following may be useful info when porting library to different platforms (such as embedded MCU) to avoid unnecessary work on some files. + +Compulsory +---------- + +- simplemotion.c/.h +- sm485.h +- sm_consts.c +- simplemotion_defs.h +- simplemotion_private.h +- busdevice.c/.h + +Platform specific +----------------- +Following files probably need modification if ported to another platform + +- pcserialport.c/.h - Contains a driver for communication device interface. This driver controls serial/COM port on Unix & Windows. Also busdevice.c/.h need to be modified accordingly if this driver is removed or modified. + +A typical platform port would involve writing a communication driver that implements same functions as pcserialport.c and adding their relevant calls to busdevice.c/.h. + +Feature specific +---------------- + +- bufferedmotion.c/.h - Library used for buffered motion stream applications +- devicedeployment.c/.h - Library used for installing firmware and loading settings into target devices. Can be used to configure devices automatically in-system. + +For practical usage examples, refer to https://github.com/GraniteDevices/SimpleMotionV2Examples
\ No newline at end of file diff --git a/SimpleMotionV2.pri b/SimpleMotionV2.pri index 29dc8e7..8222018 100644 --- a/SimpleMotionV2.pri +++ b/SimpleMotionV2.pri @@ -5,8 +5,10 @@ DEPENDPATH += $$PWD DEFINES += SIMPLEMOTIONV2_LIBRARY
-SOURCES += $$PWD/sm_consts.c $$PWD/simplemotion.c $$PWD/busdevice.c $$PWD/pcserialport.c
+SOURCES += $$PWD/sm_consts.c $$PWD/simplemotion.c $$PWD/busdevice.c $$PWD/pcserialport.c \
+ $$PWD/bufferedmotion.c $$PWD/tcpclient.c $$PWD/devicedeployment.c
HEADERS += $$PWD/simplemotion_private.h\
- $$PWD/pcserialport.h $$PWD/busdevice.h $$PWD/simplemotion.h $$PWD/sm485.h $$PWD/simplemotion_defs.h
+ $$PWD/pcserialport.h $$PWD/busdevice.h $$PWD/simplemotion.h $$PWD/sm485.h $$PWD/simplemotion_defs.h \
+ $$PWD/bufferedmotion.h $$PWD/tcpclient.h $$PWD/devicedeployment.h
diff --git a/bufferedmotion.c b/bufferedmotion.c new file mode 100644 index 0000000..a593069 --- /dev/null +++ b/bufferedmotion.c @@ -0,0 +1,218 @@ +#include "simplemotion.h" +#include "simplemotion_private.h" +#include "bufferedmotion.h" +#include "sm485.h" + +/** initialize buffered motion for one axis with address and samplerate (Hz) */ +SM_STATUS smBufferedInit(BufferedMotionAxis *newAxis, smbus handle, smaddr deviceAddress, smint32 sampleRate, smint16 readParamAddr, smuint8 readDataLength ) +{ + //value out of range + if(sampleRate<1 || sampleRate>2500) + return recordStatus(handle,SM_ERR_PARAMETER); + + newAxis->initialized=smfalse; + newAxis->bushandle=handle; + newAxis->samplerate=sampleRate; + newAxis->deviceAddress=deviceAddress; + newAxis->readParamAddr=readParamAddr; + newAxis->readParamLength=readDataLength; + newAxis->readParamInitialized=smfalse; + newAxis->numberOfDiscardableReturnDataPackets=0; + newAxis->driveClock=0; + newAxis->bufferFill=0; + newAxis->numberOfPendingReadPackets=0; + + //discard any existing data in buffer, and to get correct reading of device buffer size + smSetParameter( newAxis->bushandle, newAxis->deviceAddress, SMP_SYSTEM_CONTROL,SMP_SYSTEM_CONTROL_ABORTBUFFERED); + + //after abort, we can read the maximum size of data in device buffer + smRead1Parameter(newAxis->bushandle,newAxis->deviceAddress,SMP_BUFFER_FREE_BYTES,&newAxis->bufferLength); + newAxis->bufferFreeBytes=newAxis->bufferLength; + + //set input smoothing filter on [CIS] if samplerate is not maximum. with filter samplerates 250,500,750,1000,1250 etc run smooth. + if(sampleRate<2500) + { + if(smRead1Parameter(handle,deviceAddress,SMP_DRIVE_FLAGS,&newAxis->driveFlagsBeforeInit)!=SM_OK) + return getCumulativeStatus(handle);//if error happens in read, dont set the flags + + smSetParameter(handle,deviceAddress,SMP_DRIVE_FLAGS,newAxis->driveFlagsBeforeInit|FLAG_USE_INPUT_LP_FILTER); + } + + //set buffer execution rate to max so init commands go fast + smSetParameter(handle,deviceAddress,SMP_BUFFERED_CMD_PERIOD,10000/2500); + + //set acceleration to "infinite" to avoid modification of user supplied trajectory inside drive + smRead1Parameter(handle,deviceAddress,SMP_TRAJ_PLANNER_ACCEL,&newAxis->driveAccelerationBeforeInit);//store original for restoration + smSetParameter(handle,deviceAddress,SMP_TRAJ_PLANNER_ACCEL,32767); + + //set buffer execution rate + smSetParameter(handle,deviceAddress,SMP_BUFFERED_CMD_PERIOD,10000/sampleRate); + + //FIXME can cause unnecessary initialized=false status if there was error flags in cumulative status before calling this func + if(getCumulativeStatus(handle)==SM_OK) + newAxis->initialized=smtrue; + + return getCumulativeStatus(handle); +} + +/** uninitialize axis from buffered motion, recommended to call this before closing bus so drive's adjusted parameters are restored to originals*/ +SM_STATUS smBufferedDeinit( BufferedMotionAxis *axis ) +{ + smBufferedAbort(axis); + + //restore drive in pre-init state + if(axis->initialized==smtrue) + { + smSetParameter(axis->bushandle,axis->deviceAddress,SMP_TRAJ_PLANNER_ACCEL,axis->driveAccelerationBeforeInit); + smSetParameter(axis->bushandle,axis->deviceAddress,SMP_DRIVE_FLAGS,axis->driveFlagsBeforeInit); + } + + axis->initialized=smfalse; + axis->readParamInitialized=smfalse; + + return getCumulativeStatus(axis->bushandle); +} + + +/* this also starts buffered motion when it's not running*/ +SM_STATUS smBufferedRunAndSyncClocks(BufferedMotionAxis *axis) +{ + return smGetBufferClock( axis->bushandle, axis->deviceAddress, &axis->driveClock ); +} + +SM_STATUS smBufferedGetFree(BufferedMotionAxis *axis, smint32 *numBytesFree ) +{ + smint32 freebytes; + + if(smRead1Parameter(axis->bushandle,axis->deviceAddress,SMP_BUFFER_FREE_BYTES,&freebytes)!=SM_OK) + { + *numBytesFree=0;//read has failed, assume 0 + return getCumulativeStatus(axis->bushandle); + } + + axis->bufferFreeBytes=freebytes; + axis->bufferFill=100*(axis->bufferLength-freebytes)/axis->bufferLength;//calc buffer fill 0-100% + + *numBytesFree=freebytes; + + return getCumulativeStatus(axis->bushandle); +} + +smint32 smBufferedGetMaxFillSize(BufferedMotionAxis *axis, smint32 numBytesFree ) +{ + //even if we have lots of free space in buffer, we can only send up to SM485_MAX_PAYLOAD_BYTES bytes at once in one SM transmission + if(numBytesFree>SM485_MAX_PAYLOAD_BYTES) + numBytesFree=SM485_MAX_PAYLOAD_BYTES; + + //calculate number of points that can be uploaded to buffer (max size SM485_MAX_PAYLOAD_BYTES bytes and fill consumption is 2+4+2+3*(n-1) bytes) + if(axis->readParamInitialized==smtrue) + //*numPoints=(freebytes-2-4-2)/3+1; + return numBytesFree/4; + else + //*numPoints=(freebytes-2-4-2 -2-2-2-2)/3+1;//if read data uninitialized, it takes extra 8 bytes to init on next fill, so reduce it here + return (numBytesFree-2-3-2-3-2)/4;//if read data uninitialized, it takes extra n bytes to init on next fill, so reduce it here +} + +smint32 smBufferedGetBytesConsumed(BufferedMotionAxis *axis, smint32 numFillPoints ) +{ + //calculate number of bytes that the number of fill points will consume from buffer + if(axis->readParamInitialized==smtrue) + return numFillPoints*4; + else + return numFillPoints*4 +2+3+2+3+2;//if read data uninitialized, it takes extra n bytes to init on next fill, so reduce it here +} + + +SM_STATUS smBufferedFillAndReceive(BufferedMotionAxis *axis, smint32 numFillPoints, smint32 *fillPoints, smint32 *numReceivedPoints, smint32 *receivedPoints, smint32 *bytesFilled ) +{ + smint32 bytesUsed=0; + + //if(freeBytesInDeviceBuffer>=cmdBufferSizeBytes) +// emit message(Warning,"Buffer underrun on axis "+QString::number(ax)); + + //freeBytesInDeviceBuffer-=8; +// if(drives[ax].bufferedStreamInitialized==false) +// cmdBufferSizeBytes=freeBytesInDeviceBuffer;//get empty buffer size + + //first initialize the stream if not done yet + if(axis->readParamInitialized==smfalse) + { + //set acceleration to "infinite" to avoid modification of user supplied trajectory inside drive + smAppendSMCommandToQueue(axis->bushandle,SMPCMD_SETPARAMADDR,SMP_RETURN_PARAM_ADDR); + smAppendSMCommandToQueue(axis->bushandle,SM_WRITE_VALUE_24B,axis->readParamAddr); + smAppendSMCommandToQueue(axis->bushandle,SMPCMD_SETPARAMADDR,SMP_RETURN_PARAM_LEN); + smAppendSMCommandToQueue(axis->bushandle,SM_WRITE_VALUE_24B,axis->readParamLength); + smAppendSMCommandToQueue(axis->bushandle,SMPCMD_SETPARAMADDR,SMP_ABSOLUTE_SETPOINT); + bytesUsed+=2+3+2+3+2; + + //next time we read return data, we discard first 4 return packets to avoid unexpected read data to user + axis->numberOfDiscardableReturnDataPackets+=5; + axis->readParamInitialized=smtrue; + } + + if(numFillPoints>=1)//send first fill data + { + smAppendSMCommandToQueue(axis->bushandle,SM_WRITE_VALUE_32B,fillPoints[0]); + bytesUsed+=4; + axis->numberOfPendingReadPackets+=1; + } + + //send rest of data as increments + if(numFillPoints>=2) + { + int i; + //smAppendSMCommandToQueue(axis->bushandle,SMPCMD_SETPARAMADDR,SMP_ABSOLUTE_SETPOINT); + //smAppendSMCommandToQueue(axis->bushandle,SMPCMD_SETPARAMADDR,SMP_INCREMENTAL_SETPOINT); + //axis->numberOfPendingReadPackets++;//FIXME ei toimi ihan oikein tää koska skippaa äskeisen writevaluen + + for(i=1;i<numFillPoints;i++) + { + //smAppendSMCommandToQueue(axis->bushandle,SM_WRITE_VALUE_24B, fillPoints[i]-fillPoints[i-1] ); + smAppendSMCommandToQueue(axis->bushandle,SM_WRITE_VALUE_32B,fillPoints[i]); + bytesUsed+=4; + axis->numberOfPendingReadPackets++; + } + } + + //send the commands that were added with smAppendSMCommandToQueue. this also reads all return packets that are available (executed already) + smUploadCommandQueueToDeviceBuffer(axis->bushandle,axis->deviceAddress); + + //read all available return data from stream (commands that have been axecuted in drive so far) + //return data works like FIFO for all sent commands (each sent stream command will produce return data packet that we fetch here) + { + smint32 bufferedReturnBytesReceived,readval; + int n=0; + + //read return data buffer + smBytesReceived(axis->bushandle,&bufferedReturnBytesReceived);//get amount of data available + //qDebug()<<axis<<"return data bytes"<<bufferedReturnBytesReceived; + while(bufferedReturnBytesReceived>1)//loop until we have read it all + { + smGetQueuedSMCommandReturnValue(axis->bushandle, &readval); + smBytesReceived(axis->bushandle,&bufferedReturnBytesReceived); + + if(axis->numberOfDiscardableReturnDataPackets>0) + { + //discard this return data as it's intialization return packets + axis->numberOfDiscardableReturnDataPackets--; + } + else//its read data that user expects + { + receivedPoints[n]=readval; + n++; + axis->numberOfPendingReadPackets--; + } + } + *numReceivedPoints=n; + } + + *bytesFilled=bytesUsed; + return getCumulativeStatus(axis->bushandle); +} + +/** this will stop executing buffered motion immediately and discard rest of already filled buffer on a given axis. May cause drive fault state such as tracking error if done at high speed because stop happens without deceleration.*/ +SM_STATUS smBufferedAbort(BufferedMotionAxis *axis) +{ + return smSetParameter( axis->bushandle, axis->deviceAddress, SMP_SYSTEM_CONTROL,SMP_SYSTEM_CONTROL_ABORTBUFFERED); +} + diff --git a/bufferedmotion.h b/bufferedmotion.h new file mode 100644 index 0000000..bbd646c --- /dev/null +++ b/bufferedmotion.h @@ -0,0 +1,67 @@ +#ifndef BUFFEREDMOTION_H +#define BUFFEREDMOTION_H + +#ifdef __cplusplus +extern "C"{ +#endif + +#include "simplemotion.h" + +//typedef enum _smBufferedState {BufferedStop=0,BufferedRun=1} smBufferedState; + +typedef struct _BufferedMotionAxis { + smbool initialized; + smbool readParamInitialized; + smint32 numberOfDiscardableReturnDataPackets; + smint32 numberOfPendingReadPackets;//number of read data packets that should be arriving from device (to read rest of pending data, use smBufferedFillAndReceive(numFillPoints=0) until this variable this goes to zero) + smbus bushandle; + smaddr deviceAddress; + smint32 samplerate; + smint16 readParamAddr; + smuint8 readParamLength; + smint32 driveFlagsBeforeInit; + smint32 driveAccelerationBeforeInit; + smuint16 driveClock;//clock counter is updated at smBufferedRunAndSyncClocks only for the one axis that is used with that func. clock is running up at 10kHz count rate, meaning that it rolls over every 6.5536 secs + smint32 bufferLength;//buffer lenght in bytes of the device. note this may be different in different devices types. so call smBufferedGetFree on the device that has the smallest buffer. however as of 2.2016 all GD drives have 2048 bytes buffers. + smint32 bufferFreeBytes;//number of bytes free in buffer, updated at smBufferedGetFree + smint32 bufferFill;//percentage of buffer fill, updated at smBufferedGetFree. this should stay above 50% to ensure gapless motion. if gaps occur, check SMV2USB adpater COM port latency setting (set to 1ms) or try lower samplerate. +} BufferedMotionAxis; + +/** initialize buffered motion for one axis with address and samplerate (Hz) */ +/* returnDataLenght must be one of following: +#define SM_RETURN_STATUS 3 +//return value contains a read value from address defined by SMP_RETURN_PARAM_ADDR +//consumes 2 byte from payload buffer. can contain value up to 14 bits. value greater than 14 bits is clipped (padded with 0s) +#define SM_RETURN_VALUE_16B 2 +//return value contains a read value from address defined by SMP_RETURN_PARAM_ADDR +//consumes 3 byte from payload buffer. can contain value up to 14 bits. value greater than 22 bits is clipped (padded with 0s) +#define SM_RETURN_VALUE_24B 1 +//return value contains a read value from address defined by SMP_RETURN_PARAM_ADDR +//consumes 4 byte from payload buffer. can contain value up to 30 bits. value greater than 14 bits is clipped (padded with 0s) +#define SM_RETURN_VALUE_32B 0 + +Note return data per one FillAndReceive must not exceed 120 bytes. So max allowed numFillPoints will depend on returnDataLength. +numFillPoints must be equal or below 30 for 32B, 40 for 24B and 60 for 16B. +*/ +LIB SM_STATUS smBufferedInit( BufferedMotionAxis *newAxis, smbus handle, smaddr deviceAddress, smint32 sampleRate, smint16 readParamAddr, smuint8 readDataLength ); + +/** uninitialize axis from buffered motion, recommended to call this before closing bus so drive's adjusted parameters are restored to originals*/ +LIB SM_STATUS smBufferedDeinit( BufferedMotionAxis *axis ); + +/* this also starts buffered motion when it's not running*/ +LIB SM_STATUS smBufferedRunAndSyncClocks( BufferedMotionAxis *axis ); +LIB SM_STATUS smBufferedGetFree(BufferedMotionAxis *axis, smint32 *numBytesFree ); +LIB smint32 smBufferedGetMaxFillSize(BufferedMotionAxis *axis, smint32 numBytesFree ); +LIB smint32 smBufferedGetBytesConsumed(BufferedMotionAxis *axis, smint32 numFillPoints ); +LIB SM_STATUS smBufferedFillAndReceive( BufferedMotionAxis *axis, smint32 numFillPoints, smint32 *fillPoints, smint32 *numReceivedPoints, smint32 *receivedPoints, smint32 *bytesFilled ); +/** This will stop executing buffered motion immediately and discard rest of already filled buffer on a given axis. May cause drive fault state such as tracking error if done at high speed because stop happens without deceleration. +Note: this will not stop motion, but just stop executing the sent buffered commands. The last executed motion point will be still followed by drive. So this is bad function +for quick stopping stopping, for stop to the actual place consider using disable drive instead (prefferably phsyical input disable). +*/ +LIB SM_STATUS smBufferedAbort(BufferedMotionAxis *axis); + + +#ifdef __cplusplus +} +#endif +#endif // BUFFEREDMOTION_H diff --git a/busdevice.c b/busdevice.c index c4f89a1..b73da3f 100644 --- a/busdevice.c +++ b/busdevice.c @@ -1,11 +1,17 @@ #include "busdevice.h" #include "pcserialport.h" +#include "tcpclient.h" + #include <string.h> +#include <errno.h> +#include <stdlib.h> +#include <ctype.h> #define BD_NONE 0 #define BD_RS 1 #define BD_FTDI 2 +#define BD_TCP 3 //how much bytes available in transmit buffer #define TANSMIT_BUFFER_LENGTH 128 @@ -46,6 +52,117 @@ void smBDinit() bdInitialized=smtrue; } +//accepted TCP/IP address format is nnn.nnn.nnn.nnn:pppp where n is IP address numbers and p is port number +static int validateIpAddress(const char *s, const char **pip_end, + const char **pport_start) +{ + int octets = 0; + int ch = 0, prev = 0; + int len = 0; + const char *ip_end = NULL; + const char *port_start = NULL; + + while (*s) + { + ch = *s; + + if (isdigit(ch)) + { + ++len; + // Octet len must be 1-3 digits + if (len > 3) + { + return -1; + } + } + else if (ch == '.' && isdigit(prev)) + { + ++octets; + len = 0; + // No more than 4 octets please + if (octets > 4) + { + return -1; + } + } + else if (ch == ':' && isdigit(prev)) + { + ++octets; + // We want exactly 4 octets at this point + if (octets != 4) + { + return -1; + } + ip_end = s; + ++s; + port_start = s; + while (isdigit((ch = *s))) + ++s; + // After port we want the end of the string + if (ch != '\0') + return -1; + // This will skip over the ++s below + continue; + } + else + { + return -1; + } + + prev = ch; + ++s; + } + + // We reached the end of the string and did not encounter the port + if (*s == '\0' && ip_end == NULL) + { + ++octets; + ip_end = s; + } + + // Check that there are exactly 4 octets + if (octets != 4) + return -1; + + if (pip_end) + *pip_end = ip_end; + + if (pport_start) + *pport_start = port_start; + + return 0; +} + +static int parseIpAddress(const char *s, char *ip, size_t ipsize, short *port) +{ + const char *ip_end, *port_start; + + if (validateIpAddress(s, &ip_end, &port_start) == -1) + return -1; + + // If ip=NULL, we just report that the parsing was ok + if (!ip) + return 0; + + if (ipsize < ip_end - s + 1) + return -1; + + memcpy(ip, s, ip_end - s); + ip[ip_end - s] = '\0'; + + if (port_start) + { + *port = 0; + while (*port_start) + { + *port = *port * 10 + (*port_start - '0'); + ++port_start; + } + } + + return 0; +} + //ie "COM1" "VSD2USB" //return -1 if fails, otherwise handle number smbusdevicehandle smBDOpen( const char *devicename ) @@ -75,10 +192,24 @@ smbusdevicehandle smBDOpen( const char *devicename ) BusDevice[handle].bdType=BD_RS; BusDevice[handle].txBufferUsed=0; } - else//no other bus types supproted yet - { - return -1; - } + else if (validateIpAddress(devicename, NULL, NULL) == 0) + { + char ip[128]; + short port = 4001; + if (parseIpAddress(devicename, ip, sizeof(ip), &port) < 0) + return -1; + BusDevice[handle].comPort=OpenTCPPort( ip, port ); + if( BusDevice[handle].comPort == -1 ) + { + return -1; //failed to open + } + BusDevice[handle].bdType=BD_TCP; + BusDevice[handle].txBufferUsed=0; + } + else//no other bus types supproted yet + { + return -1; + } //success BusDevice[handle].cumulativeSmStatus=0; @@ -105,6 +236,12 @@ smbool smBDClose( const smbusdevicehandle handle ) BusDevice[handle].opened=smfalse; return smtrue; } + else if( BusDevice[handle].bdType==BD_TCP ) + { + CloseTCPport( BusDevice[handle].comPort ); + BusDevice[handle].opened=smfalse; + return smtrue; + } return smfalse; } @@ -119,7 +256,7 @@ smbool smBDWrite(const smbusdevicehandle handle, const smuint8 byte ) //check if handle valid & open if( smIsBDHandleOpen(handle)==smfalse ) return smfalse; - if( BusDevice[handle].bdType==BD_RS ) + if( BusDevice[handle].bdType==BD_RS || BusDevice[handle].bdType==BD_TCP ) { if(BusDevice[handle].txBufferUsed<TANSMIT_BUFFER_LENGTH) { @@ -153,6 +290,20 @@ smbool smBDTransmit(const smbusdevicehandle handle) return smfalse; } } + else if( BusDevice[handle].bdType==BD_TCP ) + { + if(SendTCPBuf(BusDevice[handle].comPort,BusDevice[handle].txBuffer, BusDevice[handle].txBufferUsed)==BusDevice[handle].txBufferUsed) + { + BusDevice[handle].txBufferUsed=0; + return smtrue; + } + else + { + BusDevice[handle].txBufferUsed=0; + return smfalse; + } + } + return smfalse; } @@ -170,6 +321,14 @@ smbool smBDRead( const smbusdevicehandle handle, smuint8 *byte ) if( n!=1 ) return smfalse; else return smtrue; } + else if( BusDevice[handle].bdType==BD_TCP ) + { + int n; + n=PollTCPPort(BusDevice[handle].comPort, byte, 1); + if( n!=1 ) return smfalse; + else return smtrue; + } + return smfalse; } diff --git a/busdevice.h b/busdevice.h index 580cda8..6a02a26 100644 --- a/busdevice.h +++ b/busdevice.h @@ -7,7 +7,7 @@ #include "simplemotion.h" #include "simplemotion_private.h" -typedef smint8 smbusdevicehandle; +typedef smint16 smbusdevicehandle; #define SM_BAUDRATE 460800 diff --git a/devicedeployment.c b/devicedeployment.c new file mode 100644 index 0000000..18e9748 --- /dev/null +++ b/devicedeployment.c @@ -0,0 +1,687 @@ +#include "devicedeployment.h" +#include <stdio.h> +#include <string.h> +#include <stdlib.h> +#include <simplemotion_private.h> +#include <math.h> + +#if defined(__unix__) || defined(__APPLE__) +#include <unistd.h> +void sleep_ms(int millisecs) +{ + usleep(millisecs*1000); +} +#else +#include <windows.h> +void sleep_ms(int millisecs) +{ + Sleep(millisecs); +} +#endif + +int globalErrorDetailCode=0; + +smbool loadBinaryFile( const char *filename, smuint8 **data, int *numbytes ); + +int smGetDeploymentToolErrroDetail() +{ + return globalErrorDetailCode; +} + +//return -1 if EOF +//readPosition should be initialized to 0 and not touched by caller after that. this func will increment it after each call. +unsigned int readFileLine( const smuint8 *data, const int dataLen, int *readPosition, int charlimit, char *output, smbool *eof) +{ + int len=0; + char c; + do + { + if(*readPosition>=dataLen)//end of data buffer + { + *eof=smtrue; + c=0; + } + else + { + *eof=smfalse; + c=data[*readPosition+len]; + (*readPosition)++; + } + + //eol or eof + if( *eof==smtrue || c=='\n' || c=='\r' || len>=charlimit-1 ) + { + output[len]=0;//terminate str + return len; + } + + output[len]=c; + len++; + } while(1); + return len; +} + +typedef struct +{ + int address; + double value; + smbool readOnly; + double scale; + double offset; +} Parameter; + +smbool parseParameter( const smuint8 *drcData, const int drcDataLen, int idx, Parameter *param ) +{ + const int maxLineLen=100; + char line[maxLineLen]; + char scanline[maxLineLen]; + smbool gotaddr=smfalse,gotvalue=smfalse, gotreadonly=smfalse, gotscale=smfalse,gotoffset=smfalse; + unsigned int readbytes; + int readPosition=0; + smbool eof; + + do//loop trhu all lines of file + { + readbytes=readFileLine(drcData,drcDataLen,&readPosition,maxLineLen,line,&eof);//read line + + //try read address + sprintf(scanline,"%d\\addr=",idx); + if(!strncmp(line,scanline,strlen(scanline)) && readbytes > strlen(scanline))//string starts with correct line + if(sscanf(line+strlen(scanline),"%d",¶m->address)==1)//parse number after the start of line + gotaddr=smtrue;//number parse success + + //try read value + sprintf(scanline,"%d\\value=",idx); + if(!strncmp(line,scanline,strlen(scanline)) && readbytes > strlen(scanline))//string starts with correct line + if(sscanf(line+strlen(scanline),"%lf",¶m->value)==1)//parse number after the start of line + gotvalue=smtrue;//number parse success + + //try read offset + sprintf(scanline,"%d\\offset=",idx); + if(!strncmp(line,scanline,strlen(scanline)) && readbytes > strlen(scanline))//string starts with correct line + if(sscanf(line+strlen(scanline),"%lf",¶m->offset)==1)//parse number after the start of line + gotoffset=smtrue;//number parse success + + //try read scale + sprintf(scanline,"%d\\scaling=",idx); + if(!strncmp(line,scanline,strlen(scanline)) && readbytes > strlen(scanline))//string starts with correct line + if(sscanf(line+strlen(scanline),"%lf",¶m->scale)==1)//parse number after the start of line + gotscale=smtrue;//number parse success + + //try read readonly status + sprintf(scanline,"%d\\readonly=true",idx);//check if readonly=true + if(!strncmp(line,scanline,strlen(scanline)) && readbytes >= strlen(scanline))//line match + { + param->readOnly=smtrue; + gotreadonly=smtrue; + } + sprintf(scanline,"%d\\readonly=false",idx);//check if readonly=false + if(!strncmp(line,scanline,strlen(scanline)) && readbytes >= strlen(scanline))//line match + { + param->readOnly=smfalse; + gotreadonly=smtrue; + } + } + while( (gotvalue==smfalse || gotaddr==smfalse || gotreadonly==smfalse || gotscale==smfalse || gotoffset==smfalse) && eof==smfalse ); + + if(gotvalue==smtrue&&gotaddr==smtrue&&gotoffset==smtrue&&gotscale==smtrue&&gotreadonly==smtrue) + { + return smtrue; + } + + return smfalse;//not found +} + +/** + * @brief smConfigureParameters Configures all target device parameters from file and performs device restart if necessary. This can take few seconds to complete. This may take 2-5 seconds to call. + * @param smhandle SM bus handle, must be opened before call + * @param smaddress Target SM device address + * @param filename .DRC file name + * @param mode Combined from CONFIGMODE_ define bits (can logic OR mutliple values). + * @return Enum LoadConfigurationStatus + * + * Requires DRC file version 111 or later to use CONFIGMODE_REQUIRE_SAME_FW. + */ +LoadConfigurationStatus smLoadConfiguration(const smbus smhandle, const int smaddress, const char *filename, unsigned int mode , int *skippedCount, int *errorCount) +{ + LoadConfigurationStatus ret; + smuint8 *drcData=NULL; + int drcDataLength; + + if(loadBinaryFile(filename,&drcData,&drcDataLength)!=smtrue) + return CFGUnableToOpenFile; + + ret = smLoadConfigurationFromBuffer( smhandle, smaddress, drcData, drcDataLength, mode, skippedCount, errorCount ); + free(drcData); + + return ret; +} + +/** + * @brief smConfigureParametersFromBuffer Same as smConfigureParameters but reads data from user specified memory address instead of file. Configures all target device parameters from file and performs device restart if necessary. This can take few seconds to complete. This may take 2-5 seconds to call. + * @param smhandle SM bus handle, must be opened before call + * @param smaddress Target SM device address + * @param drcData Pointer to to a memory where .drc file is loaded + * @param drcDataLen Number of bytes available in the drcData buffer + * @param mode Combined from CONFIGMODE_ define bits (can logic OR mutliple values). + * @return Enum LoadConfigurationStatus + * + * Requires DRC file version 111 or later to use CONFIGMODE_REQUIRE_SAME_FW. + */ +LIB LoadConfigurationStatus smLoadConfigurationFromBuffer( const smbus smhandle, const int smaddress, const smuint8 *drcData, const int drcDataLength, unsigned int mode, int *skippedCount, int *errorCount ) +{ + //test connection + smint32 devicetype; + SM_STATUS stat; + int ignoredCount=0; + int setErrors=0; + smint32 CB1Value; + int changed=0; + *skippedCount=-1; + *errorCount=-1; + + //test connection + resetCumulativeStatus(smhandle); + stat=smRead1Parameter(smhandle,smaddress,SMP_DEVICE_TYPE,&devicetype); + if(stat!=SM_OK) + return CFGCommunicationError; + + //smSetParameter( smhandle, smaddress, SMP_RETURN_PARAM_LEN, SMPRET_CMD_STATUS );//get command status as feedback from each executed SM command + + if(mode&CONFIGMODE_DISABLE_DURING_CONFIG) + { + smRead1Parameter( smhandle, smaddress, SMP_CONTROL_BITS1, &CB1Value ); + smSetParameter( smhandle, smaddress, SMP_CONTROL_BITS1, 0);//disable drive + } + + if(getCumulativeStatus( smhandle )!=SM_OK ) + return CFGCommunicationError; + + smDebug(smhandle,Low,"Setting parameters\n"); + + int i=1; + smbool readOk; + do + { + Parameter param; + readOk=parseParameter(drcData,drcDataLength,i,¶m); + + if(readOk==smtrue && param.readOnly==smfalse) + { + smint32 currentValue; + + int configFileValue=round(param.value*param.scale-param.offset); + + //set parameter to device + if(smRead1Parameter( smhandle, smaddress, param.address, ¤tValue )==SM_OK) + { + if(currentValue!=configFileValue ) //set only if different + { + resetCumulativeStatus( smhandle ); + smint32 dummy; + smint32 cmdSetAddressStatus; + smint32 cmdSetValueStatus; + + //use low level SM commands so we can get execution status of each subpacet: + smAppendSMCommandToQueue( smhandle, SM_SET_WRITE_ADDRESS, SMP_RETURN_PARAM_LEN ); + smAppendSMCommandToQueue( smhandle, SM_WRITE_VALUE_24B, SMPRET_CMD_STATUS ); + smAppendSMCommandToQueue( smhandle, SM_SET_WRITE_ADDRESS, param.address ); + smAppendSMCommandToQueue( smhandle, SM_WRITE_VALUE_32B, configFileValue ); + smExecuteCommandQueue( smhandle, smaddress ); + smGetQueuedSMCommandReturnValue( smhandle, &dummy ); + smGetQueuedSMCommandReturnValue( smhandle, &dummy ); + smGetQueuedSMCommandReturnValue( smhandle, &cmdSetAddressStatus ); + smGetQueuedSMCommandReturnValue( smhandle, &cmdSetValueStatus ); + + //check if above code succeed + if( getCumulativeStatus(smhandle)!=SM_OK || cmdSetAddressStatus!=SMP_CMD_STATUS_ACK || cmdSetValueStatus!=SMP_CMD_STATUS_ACK ) + { + SM_STATUS stat=getCumulativeStatus(smhandle); + setErrors++; + smDebug(smhandle,Low,"Failed to write parameter value %d to address %d (status: %d %d %d)\n",configFileValue,param.address,(int)stat,cmdSetAddressStatus,cmdSetValueStatus); + } + + changed++; + } + } + else//device doesn't have such parameter. perhaps wrong model or fw version. + { + ignoredCount++; + smDebug(smhandle,Low,"Ignoring parameter parameter value %d to address %d\n",configFileValue,param.address); + } + } + + i++; + } while(readOk==smtrue); + + *skippedCount=ignoredCount; + *errorCount=setErrors; + + resetCumulativeStatus( smhandle ); + + //save to flash if some value was changed + if(changed>0) + smSetParameter( smhandle, smaddress, SMP_SYSTEM_CONTROL, SMP_SYSTEM_CONTROL_SAVECFG ); + + if(mode&CONFIGMODE_CLEAR_FAULTS_AFTER_CONFIG ) + { + smDebug(smhandle,Low,"Restting faults\n"); + smSetParameter( smhandle, smaddress, SMP_FAULTS, 0 );//reset faults + } + + //re-enable drive + if(mode&CONFIGMODE_DISABLE_DURING_CONFIG) + { + smDebug(smhandle,Low,"Restoring CONTROL_BITS1 to value 0x%x\n",CB1Value); + smSetParameter( smhandle, smaddress, SMP_CONTROL_BITS1, CB1Value );//restore controbits1 (enable if it was enabled before) + } + + smint32 statusbits; + smRead1Parameter( smhandle, smaddress, SMP_STATUS, &statusbits ); + + //restart drive if necessary or if forced + if( (statusbits&STAT_PERMANENT_STOP) || (mode&CONFIGMODE_ALWAYS_RESTART_TARGET) ) + { + smDebug(smhandle,Low,"Restarting device\n"); + smSetParameter( smhandle, smaddress, SMP_SYSTEM_CONTROL, SMP_SYSTEM_CONTROL_RESTART ); + sleep_ms(2000);//wait power-on + } + + if(getCumulativeStatus(smhandle)!=SM_OK) + return CFGCommunicationError; + + return CFGComplete; +} + +/** + * @brief smGetDeviceFirmwareUniqueID Reads installed firmware binary checksum that can be used to verify whether a wanted FW version is installed + * @param smhandle SM bus handle, must be opened before call + * @param smaddress Target SM device address. Can be device in DFU mode or main operating mode. For Argon, one device in a bus must be started into DFU mode by DIP switches and smaddress must be set to 255. + * @param UID result will be written to this pointer + * @return smtrue if success, smfalse if failed (if communication otherwise works, then probably UID feature not present in this firmware version) + */ +smbool smGetDeviceFirmwareUniqueID( smbus smhandle, int deviceaddress, smuint32 *UID )//FIXME gives questionable value if device is in DFU mode. Check FW side. +{ + smint32 fwBinaryChecksum; + resetCumulativeStatus(smhandle); + smSetParameter( smhandle, deviceaddress, SMP_SYSTEM_CONTROL, SMP_SYSTEM_CONTROL_GET_SPECIAL_DATA); + smRead1Parameter( smhandle, deviceaddress, SMP_DEBUGPARAM1, &fwBinaryChecksum ); + *UID=(smuint32) fwBinaryChecksum; + + if(getCumulativeStatus(smhandle)==SM_OK) + return smtrue; + else + return smfalse; +} + +FirmwareUploadStatus verifyFirmwareData(smuint8 *data, smuint32 numbytes, int connectedDeviceTypeId, + smuint32 *primaryMCUDataOffset, smuint32 *primaryMCUDataLenth, + smuint32 *secondaryMCUDataOffset,smuint32 *secondaryMCUDataLength ) +{ + //see http://granitedevices.com/wiki/Argon_firmware_file_format + + smuint32 filetype; + filetype=((smuint32*)data)[0]; + if(filetype!=0x57464447) //check header string "GDFW" + return FWInvalidFile; + + smuint16 filever, deviceid; + smuint32 primaryMCUSize, secondaryMCUSize; + + filever=((smuint16*)data)[2]; + deviceid=((smuint16*)data)[3]; + primaryMCUSize=((smuint32*)data)[2]; + secondaryMCUSize=((smuint32*)data)[3]; + if(secondaryMCUSize==0xffffffff) + secondaryMCUSize=0;//it is not present + + if(filever!=300) + return FWIncompatibleFW; + + if(deviceid/1000!=connectedDeviceTypeId/1000)//compare only device and model family. AABBCC so AAB is compared value, ARGON=004 IONI=011 + return FWIncompatibleFW; + + //get checksum and check it + smuint32 cksum,cksumcalc=0; + smuint32 i; + smuint32 cksumOffset=4+2+2+4+4+primaryMCUSize+secondaryMCUSize; + if(cksumOffset>numbytes-4) + return FWInvalidFile; + cksum=((smuint32*)(data+cksumOffset))[0]; + + for(i=0;i< numbytes-4;i++) + { + cksumcalc+=data[i]; + } + + if(cksum!=cksumcalc) + return FWIncompatibleFW; + + //let caller know where the firmware data is located in buffer + *primaryMCUDataOffset=4+2+2+4+4; + *primaryMCUDataLenth=primaryMCUSize; + *secondaryMCUDataOffset=*primaryMCUDataOffset+*primaryMCUDataLenth; + *secondaryMCUDataLength=secondaryMCUSize; + + return FWComplete; +} + +smbool loadBinaryFile( const char *filename, smuint8 **data, int *numbytes ) +{ + FILE *f; + f=fopen(filename,"rb"); + if(f==NULL) + return smfalse; + + *numbytes=0; + + //get length + fseek(f,0,SEEK_END); + int length=ftell(f); + fseek(f,0,SEEK_SET); + + //allocate buffer + *data=malloc(length); + if(*data==NULL) + { + fclose(f); + return smfalse; + } + + //read + *numbytes=fread(*data,1,length,f); + if(*numbytes!=length)//failed to read it all + { + free(*data); + *numbytes=0; + fclose(f); + return smfalse; + } + + fclose(f); + return smtrue;//successl +} + + + +//flashing STM32 (host side mcu) +smbool flashFirmwarePrimaryMCU( smbus smhandle, int deviceaddress, const smuint8 *data, smint32 size, int *progress ) +{ + smint32 ret; + static smint32 deviceType, fwVersion; + static int uploadIndex; + int c; + const int BL_CHUNK_LEN=32; + static enum {Init,Upload,Finish} state=Init; + + if(state==Init) + { + resetCumulativeStatus( smhandle ); + smRead2Parameters( smhandle, deviceaddress, SMP_FIRMWARE_VERSION, &fwVersion, SMP_DEVICE_TYPE,&deviceType ); + + if(getCumulativeStatus(smhandle)!=SM_OK) + { + state=Init; + return smfalse; + } + +/* kommentoitu pois koska ei haluta erasoida parskuja koska parametri SMO ei saisi nollautua mielellään + + if(deviceType!=4000)//argon does not support BL function 11 + smSetParameter(smhandle,deviceaddress,SMP_BOOTLOADER_FUNCTION,11);//BL func on ioni 11 = do mass erase on STM32, also confifuration + else//does not reset on ioni and drives that support preserving settings. but resets on argon +*/ + smSetParameter(smhandle,deviceaddress,SMP_BOOTLOADER_FUNCTION,1);//BL func 1 = do mass erase on STM32. On Non-Argon devices it doesn't reset confifuration + + sleep_ms(2000);//wait some time. 500ms too little 800ms barely enough + + //flash + smSetParameter(smhandle,deviceaddress,SMP_RETURN_PARAM_LEN, SMPRET_CMD_STATUS); + + if(getCumulativeStatus(smhandle)!=SM_OK) + { + state=Init; + return smfalse; + } + + state=Upload; + uploadIndex=0; + *progress=5; + } + else if(state==Upload) + { + size/=2;//bytes to 16 bit words + + //upload data in 32=BL_CHUNK_LEN word chunks + for(;uploadIndex<size;) + { + smAppendSMCommandToQueue( smhandle, SMPCMD_SETPARAMADDR, SMP_BOOTLOADER_UPLOAD ); + for(c=0;c<BL_CHUNK_LEN;c++) + { + smuint16 upword; + //pad end of file with constant to make full chunk + if(uploadIndex>=size) + upword=0xeeee; + else + upword=((smuint16*)data)[uploadIndex]; + smAppendSMCommandToQueue( smhandle, SMPCMD_24B, upword ); + uploadIndex++; + } + + smAppendSMCommandToQueue( smhandle, SMPCMD_SETPARAMADDR, SMP_BOOTLOADER_FUNCTION ); + smAppendSMCommandToQueue( smhandle, SMPCMD_24B, 2);//BL func 2 = do write on STM32 + smExecuteCommandQueue( smhandle, deviceaddress ); + + //read return packets + for(c=0;c<BL_CHUNK_LEN+3;c++) + { + smGetQueuedSMCommandReturnValue( smhandle,&ret ); + + if(getCumulativeStatus(smhandle)!=SM_OK) + { + state=Init; + return smfalse; + } + } + + *progress=5+90*uploadIndex/size;//gives value 5-95 + if(*progress>=94)//95 will indicate that progress is complete. dont let it indicate that yet. + *progress=94; + + if(uploadIndex%256==0) + { + //printf("upload %d\n",uploadIndex); + return smtrue;//in progress. return often to make upload non-blocking + } + } + if(uploadIndex>=size)//finished + { + state=Finish; + } + } + else if(state==Finish) + { + //verify STM32 flash if supported by BL version + if(fwVersion>=1210) + { + smSetParameter(smhandle,deviceaddress,SMP_BOOTLOADER_FUNCTION,3);//BL func 3 = verify STM32 FW integrity + smint32 faults; + smRead1Parameter(smhandle,deviceaddress,SMP_FAULTS,&faults); + + if(getCumulativeStatus(smhandle)!=SM_OK) + { + state=Init; + *progress=0; + return smfalse; + } + + if(faults&FLT_FLASHING_COMMSIDE_FAIL) + { + //printf("verify failed\n"); + *progress=0; + state=Init; + return smfalse; + } + else + { + //printf("verify success\n"); + } + } + + *progress=95;//my job is complete + state=Init; + } + + return smtrue; +} + + +typedef enum { StatIdle=0, StatEnterDFU, StatFindDFUDevice, StatLoadFile, StatUpload, StatLaunch } UploadState;//state machine status + +//free buffer and return given status code +FirmwareUploadStatus abortFWUpload( FirmwareUploadStatus stat, smuint8 *fwData, UploadState *state, int errorDetailCode ) +{ + globalErrorDetailCode=errorDetailCode; + *state=StatIdle; + free(fwData); + return stat; +} + +/** + * @brief smFirmwareUpload Sets drive in firmware upgrade mode if necessary and uploads a new firmware. Call this many until it returns value 100 (complete) or a negative value (error). + * @param smhandle SM bus handle, must be opened before call + * @param smaddress Target SM device address. Can be device in DFU mode or main operating mode. For Argon, one device in a bus must be started into DFU mode by DIP switches and smaddress must be set to 255. + * @param filename .gdf file name + * @return Enum FirmwareUploadStatus that indicates errors or Complete status. Typecast to integer to get progress value 0-100. + */ +FirmwareUploadStatus smFirmwareUpload( const smbus smhandle, const int smaddress, const char *firmware_filename ) +{ + static smuint8 *fwData=NULL; + static int fwDataLength; + static smuint32 primaryMCUDataOffset, primaryMCUDataLenth; + static smuint32 secondaryMCUDataOffset,secondaryMCUDataLength; + static UploadState state=StatIdle;//state machine status + static smint32 deviceType=0; + static int DFUAddress; + static int progress=0; + + SM_STATUS stat; + + //state machine + if(state==StatIdle) + { + + //check if device is in DFU mode already + smint32 busMode; + stat=smRead2Parameters(smhandle,smaddress,SMP_BUS_MODE,&busMode, SMP_DEVICE_TYPE, &deviceType); + if(stat==SM_OK && busMode==SMP_BUS_MODE_DFU) + { + state=StatLoadFile; + } + else if(stat==SM_OK && busMode!=0)//device not in bus mode + { + if(deviceType==4000)//argon does not support restarting in DFU mode by software + { + return abortFWUpload(FWConnectionError,fwData,&state,200); + } + + //restart device into DFU mode + state=StatEnterDFU; + + stat=smSetParameter(smhandle,smaddress,SMP_SYSTEM_CONTROL,64);//reset device to DFU command + if(stat!=SM_OK) + return abortFWUpload(FWConnectionError,fwData,&state,300); + } + else + state=StatFindDFUDevice;//search DFU device in brute force, fallback for older BL versions that don't preserve same smaddress than non-DFU mode + //return abortFWUpload(FWConnectionError,fwData,&state,301); + + progress=1; + DFUAddress=smaddress; + } + + else if(state==StatEnterDFU) + { + sleep_ms(2500);//wait device to reboot in DFU mode. probably shorter delay would do. + + //check if device is in DFU mode already + smint32 busMode; + stat=smRead2Parameters(smhandle,smaddress, SMP_BUS_MODE,&busMode, SMP_DEVICE_TYPE, &deviceType); + if(stat==SM_OK && busMode==0)//busmode 0 is DFU mode + { + state=StatLoadFile; + } + else + state=StatFindDFUDevice;//search DFU device in brute force, fallback for older BL versions that don't preserve same smaddress than non-DFU mode + + progress=2; + } + + else if(state==StatFindDFUDevice) + { + int i; + for(i=245;i<=255;i++) + { + smint32 busMode; + stat=smRead2Parameters(smhandle,i, SMP_BUS_MODE,&busMode, SMP_DEVICE_TYPE, &deviceType); + if(stat==SM_OK && busMode==0)//busmode 0 is DFU mode + { + state=StatLoadFile; + DFUAddress=i; + break;//DFU found, break out of for loop + } + } + + if(i==256)//DFU device not found + return abortFWUpload(CFGConnectingDFUModeFailed,fwData,&state,400);//setting DFU mode failed + + progress=3; + } + + else if(state==StatLoadFile) + { + if(loadBinaryFile(firmware_filename,&fwData,&fwDataLength)!=smtrue) + return FWFileNotReadable; + + FirmwareUploadStatus stat=verifyFirmwareData(fwData, fwDataLength, deviceType, + &primaryMCUDataOffset, &primaryMCUDataLenth, + &secondaryMCUDataOffset, &secondaryMCUDataLength); + if(stat!=FWComplete)//error in verify + { + return abortFWUpload(stat,fwData,&state,100); + } + + //all good, upload firmware + state=StatUpload; + + progress=4; + } + + else if(state==StatUpload) + { + smbool ret=flashFirmwarePrimaryMCU(smhandle,DFUAddress,fwData+primaryMCUDataOffset,primaryMCUDataLenth,&progress); + if(ret==smfalse)//failed + { + return abortFWUpload(FWConnectionError,fwData,&state,1000); + } + else + { + if(progress>=95) + state=StatLaunch; + } + } + + else if(state==StatLaunch) + { + smSetParameter(smhandle,DFUAddress,SMP_BOOTLOADER_FUNCTION,4);//BL func 4 = launch. + sleep_ms(2000); + progress=100; + state=StatIdle; + } + + return (FirmwareUploadStatus)progress; +} + + + + diff --git a/devicedeployment.h b/devicedeployment.h new file mode 100644 index 0000000..f86c7dc --- /dev/null +++ b/devicedeployment.h @@ -0,0 +1,113 @@ +/* Device deployment library based on SimpleMotionV2 lib. Features: + * + * - install .gdf format firmware to drive + * - load .drc settings file to drive + * - read installed firmware binary checksum from device - this may be used to verify that exact correct FW build is installed in the drive + * + * TODO: + * - Support Argon. Currently tested only on IONI/ATOMI series drives. Currently FW upgrade on Argon will fail, but settings load may work. + * - Add some way of reading binary checksum from .gdf file or settings file. Now user must read it from device and store that number somewhere manually. + */ + +#ifndef SMDEPLOYMENTTOOL_H +#define SMDEPLOYMENTTOOL_H + +#ifdef WIN32 +//dll specs +#ifdef BUILD_DLL + #define LIB __declspec(dllexport) +#else +// #define LIB __declspec(dllimport) +#define LIB +#endif +#else +#define LIB +#endif + + +#include "simplemotion.h" + + +#ifdef __cplusplus +extern "C"{ +#endif + + +typedef enum +{ + FWComplete=100, + FWInvalidFile=-1, + FWConnectionError=-2, + FWIncompatibleFW=-3, + FWConnectionLoss=-4, + FWUnsupportedTargetDevice=-5, + FWFileNotReadable=-6 +} FirmwareUploadStatus; + +/** + * @brief smFirmwareUpload Sets drive in firmware upgrade mode if necessary and uploads a new firmware. Call this many until it returns value 100 (complete) or a negative value (error). + * @param smhandle SM bus handle, must be opened before call + * @param smaddress Target SM device address + * @param filename .gdf file name + * @return Enum FirmwareUploadStatus that indicates errors or Complete status. Typecast to integer to get progress value 0-100. + */ +LIB FirmwareUploadStatus smFirmwareUpload(const smbus smhandle, const int smaddress, const char *firmware_filename ); + +typedef enum +{ + CFGComplete=100, + CFGInvalidFile=-1, + CFGCommunicationError=-2, + CFGConnectingDFUModeFailed=-3, + CFGIncompatibleFW=-4, + CFGUnsupportedTargetDevice=-5, + CFGUnableToOpenFile=-6 + +} LoadConfigurationStatus; + +//TODO implement: #define CONFIGMODE_REQUIRE_SAME_FW 1 //will return IncompatibleFW if firmware checksum does not match the one in .drc files. if this error is returned, perform smFirmwareUpload and perform smLoadConfiguration again. Requires DRC file version 111 or later (if not met, returns InvalidFile). +#define CONFIGMODE_ALWAYS_RESTART_TARGET 2 //will perform device restart after setup even when it's not required +#define CONFIGMODE_DISABLE_DURING_CONFIG 4 //will set device in disabled state during configuration +#define CONFIGMODE_CLEAR_FAULTS_AFTER_CONFIG 8 //will perform clear faults command after configuration + +/** + * @brief smConfigureParameters Configures all target device parameters from file and performs device restart if necessary. This can take few seconds to complete. This may take 2-5 seconds to call. + * @param smhandle SM bus handle, must be opened before call + * @param smaddress Target SM device address + * @param filename .DRC file name + * @param mode Combined from CONFIGMODE_ define bits (can logic OR mutliple values). + * @return Enum LoadConfigurationStatus + * + * Requires DRC file version 111 or later to use CONFIGMODE_REQUIRE_SAME_FW. + */ +LIB LoadConfigurationStatus smLoadConfiguration( const smbus smhandle, const int smaddress, const char *filename, unsigned int mode, int *skippedCount, int *errorCount ); + +/** + * @brief smConfigureParametersFromBuffer Same as smConfigureParameters but reads data from user specified memory address instead of file. Configures all target device parameters from file and performs device restart if necessary. This can take few seconds to complete. This may take 2-5 seconds to call. + * @param smhandle SM bus handle, must be opened before call + * @param smaddress Target SM device address + * @param drcData Pointer to to a memory where .drc file is loaded + * @param drcDataLen Number of bytes available in the drcData buffer + * @param mode Combined from CONFIGMODE_ define bits (can logic OR mutliple values). + * @return Enum LoadConfigurationStatus + * + * Requires DRC file version 111 or later to use CONFIGMODE_REQUIRE_SAME_FW. + */ +LIB LoadConfigurationStatus smLoadConfigurationFromBuffer(const smbus smhandle, const int smaddress, const smuint8 *drcData, const int drcDataLength, unsigned int mode, int *skippedCount, int *errorCount ); + + +/** + * @brief smGetDeviceFirmwareUniqueID Reads installed firmware binary checksum that can be used to verify whether a wanted FW version is installed + * @param smhandle SM bus handle, must be opened before call + * @param smaddress Target SM device address. Can be device in DFU mode or main operating mode. For Argon, one device in a bus must be started into DFU mode by DIP switches and smaddress must be set to 255. + * @param UID result will be written to this pointer + * @return smtrue if success, smfalse if failed (if communication otherwise works, then probably UID feature not present in this firmware version) + */ +smbool smGetDeviceFirmwareUniqueID( smbus smhandle, int deviceaddress, smuint32 *UID ); + + + +#ifdef __cplusplus +} +#endif +#endif // SMDEPLOYMENTTOOL_H diff --git a/pcserialport.c b/pcserialport.c index 792f079..35a7668 100644 --- a/pcserialport.c +++ b/pcserialport.c @@ -14,7 +14,7 @@ #include "pcserialport.h" #include "simplemotion_private.h" //needed for timeout variable -#ifdef __unix__ +#if defined(__unix__) || defined(__APPLE__) #include <termios.h> #include <limits.h> @@ -23,6 +23,15 @@ #include <fcntl.h> #include <sys/stat.h> #include <sys/types.h> +#include <string.h> + +#if defined(__APPLE__) +#include <CoreFoundation/CoreFoundation.h> +#include <IOKit/IOKitLib.h> +#include <IOKit/serial/IOSerialKeys.h> +#include <IOKit/serial/ioss.h> +#include <IOKit/IOBSD.h> +#endif smint32 serialPortOpen(const char * port_device_name, smint32 baudrate_bps) { @@ -30,54 +39,122 @@ smint32 serialPortOpen(const char * port_device_name, smint32 baudrate_bps) int err; int baudrateEnumValue; struct termios new_port_settings; + int customBaudRate = 0; + + port_handle = open(port_device_name, O_RDWR | O_NOCTTY); + + if(port_handle==-1) + { + smDebug(-1, Low, "Serial port error: port open failed"); + return(port_handle); + } switch(baudrate_bps) { +#if defined(B9600) case 9600 : baudrateEnumValue = B9600; break; +#endif +#if defined(B19200) case 19200 : baudrateEnumValue = B19200; break; +#endif +#if defined(B38400) case 38400 : baudrateEnumValue = B38400; break; +#endif +#if defined(B57600) case 57600 : baudrateEnumValue = B57600; break; +#endif +#if defined(B115200) case 115200 : baudrateEnumValue = B115200; break; +#endif +#if defined(B230400) case 230400 : baudrateEnumValue = B230400; break; +#endif +#if defined(B460800) case 460800 : baudrateEnumValue = B460800; break; +#endif +#if defined(B500000) case 500000 : baudrateEnumValue = B500000; break; +#endif +#if defined(B576000) case 576000 : baudrateEnumValue = B576000; break; +#endif +#if defined(B921600) case 921600 : baudrateEnumValue = B921600; break; +#endif +#if defined(B1000000) case 1000000 : baudrateEnumValue = B1000000; break; +#endif +#if defined(B1152000) case 1115200 : baudrateEnumValue = B1152000; break; +#endif +#if defined(B1500000) case 1500000 : baudrateEnumValue = B1500000; break; +#endif +#if defined(B2000000) case 2000000 : baudrateEnumValue = B2000000; break; +#endif +#if defined(B2500000) case 2500000 : baudrateEnumValue = B2500000; break; +#endif +#if defined(B3000000) case 3000000 : baudrateEnumValue = B3000000; break; +#endif +#if defined(B3500000) case 3500000 : baudrateEnumValue = B3500000; break; +#endif +#if defined(B4000000) case 4000000 : baudrateEnumValue = B4000000; break; - default : smDebug(-1,Low,"Serial port error: unsupported baudrate\n"); - return(1); - break; - } - - port_handle = open(port_device_name, O_RDWR | O_NOCTTY ); - if(port_handle==-1) - { - smDebug(-1, Low, "Serial port error: port open failed"); - return(port_handle); +#endif + default: + customBaudRate = 1; +#if defined(__APPLE__) + if (ioctl(port_handle, IOSSIOSPEED, &baudrate_bps) == -1) + { + smDebug(-1, Low, "Serial port error: unsupported baudrate\n"); + close(port_handle); + return -1; + } +#else + smDebug(-1,Low,"Serial port error: unsupported baudrate\n"); + close(port_handle); + return(-1); + break; +#endif } memset(&new_port_settings, 0, sizeof(new_port_settings)); //reset struct - new_port_settings.c_cflag = baudrateEnumValue | CS8 | CLOCAL | CREAD; + new_port_settings.c_cflag = CS8 | CLOCAL | CREAD; new_port_settings.c_iflag = IGNPAR; new_port_settings.c_oflag = 0; new_port_settings.c_lflag = 0; new_port_settings.c_cc[VMIN] = 0; /* non blocking mode */ new_port_settings.c_cc[VTIME] = readTimeoutMs/100; /* timeout 100 ms steps */ - err = tcsetattr(port_handle, TCSANOW, &new_port_settings); + + if (!customBaudRate) + { +#if defined(_BSD_SOURCE) + cfsetspeed(&new_port_settings, baudrateEnumValue); +#else + cfsetispeed(&new_port_settings, baudrateEnumValue); + cfsetospeed(&new_port_settings, baudrateEnumValue); +#endif + } + + // Activate settings + err = tcsetattr(port_handle, TCSANOW, &new_port_settings); if(err==-1) { - close(port_handle); - smDebug(-1, Low, "Serial port error: failed to set port parameters"); - return -1; + close(port_handle); + smDebug(-1, Low, "Serial port error: failed to set port parameters"); + return -1; } + + //flush any stray bytes from device receive buffer that may reside in it + //note: according to following page, delay before this may be necessary http://stackoverflow.com/questions/13013387/clearing-the-serial-ports-buffer + usleep(100000); + tcflush(port_handle,TCIOFLUSH); + return port_handle; } @@ -167,6 +244,9 @@ smint32 serialPortOpen(const char *port_device_name, smint32 baudrate_bps) return(-1); } + //flush any stray bytes from device receive buffer that may reside in it + PurgeComm((HANDLE)port_handle,PURGE_RXABORT|PURGE_RXCLEAR|PURGE_TXABORT|PURGE_TXCLEAR); + return( (smint32)port_handle); } diff --git a/simplemotion.c b/simplemotion.c index cdee1d1..58627cb 100644 --- a/simplemotion.c +++ b/simplemotion.c @@ -1,15 +1,5 @@ -//Copyright (c) Granite Devices Oy
-
-/*
- This program is free software; you can redistribute it and/or modify
- it under the terms of the GNU General Public License as published by
- the Free Software Foundation; version 2 of the License.
- This program 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 General Public License for more details.
-*/
+//Copyright (c) Granite Devices Oy
#include <stdio.h>
#include <string.h>
@@ -44,7 +34,7 @@ SM_STATUS smReceiveReturnPacket( smbus bushandle ); typedef struct SM_BUS_
{
- smint8 bdHandle;
+ smbusdevicehandle bdHandle;
smbool opened;
enum RecvState recv_state,recv_state_next;
@@ -168,7 +158,7 @@ SM_STATUS smSetTimeout( smuint16 millsecs ) return SM_ERR_PARAMETER;
}
-unsigned long smGetVersion()
+smuint32 smGetVersion()
{
return SM_VERSION;
}
@@ -225,25 +215,25 @@ smbus smOpenBus( const char * devicename ) return handle;
}
-/** Change baudrate of SM communication port. This does not affect already opened ports but the next smOpenBus will be opened at the new speed.
- Calling this is optional. By default SM bus and all slave devices operates at 460800 BPS speed.
- Parameters:
- -bps: bus speed in bits per second. for possible choices, see rs232.c (but note that all speeds are not necessarily supported by SM devices)
- Typical usage is:
- - first call smSetParameter(handle,0,SMP_BUS_SPEED,N) to change speed of all connected slaves to N PBS
- - then close port with smCloseBus
- - then call smSetBaudrate(N)
- - then open bus again with smOpenBus
-
- Note that in upcoming SM device firmware versions, bitrate will be reset to default (460800) if device side SM bus watchdog timer has been enabled, and it timeouts.
- This allows re-establishing connection at defautl speed if connection breaks up and SM bus watchdog timeout gets exceeded. To identify is device supports this,
- read parameter SMP_SM_VERSION. Values above 25 support this feature. Value 25 and below will not reset baudrate.
-
- Note also that SMP_BUS_SPEED will not be saved in device flash memory - it will reset to default at every reset & power on.
- */
+/** Change baudrate of SM communication port. This does not affect already opened ports but the next smOpenBus will be opened at the new speed.
+ Calling this is optional. By default SM bus and all slave devices operates at 460800 BPS speed.
+ Parameters:
+ -bps: bus speed in bits per second. for possible choices, see rs232.c (but note that all speeds are not necessarily supported by SM devices)
+ Typical usage is:
+ - first call smSetParameter(handle,0,SMP_BUS_SPEED,N) to change speed of all connected slaves to N PBS
+ - then close port with smCloseBus
+ - then call smSetBaudrate(N)
+ - then open bus again with smOpenBus
+
+ Note that in upcoming SM device firmware versions, bitrate will be reset to default (460800) if device side SM bus watchdog timer has been enabled, and it timeouts.
+ This allows re-establishing connection at defautl speed if connection breaks up and SM bus watchdog timeout gets exceeded. To identify is device supports this,
+ read parameter SMP_SM_VERSION. Values above 25 support this feature. Value 25 and below will not reset baudrate.
+
+ Note also that SMP_BUS_SPEED will not be saved in device flash memory - it will reset to default at every reset & power on.
+ */
LIB void smSetBaudrate( unsigned long pbs )
{
- SMBusBaudrate=pbs;
+ SMBusBaudrate=pbs;
}
/** Close connection to given bus handle number. This frees communication link therefore makes it available for other apps for opening.
@@ -319,7 +309,6 @@ smbool smTransmitBuffer( const smbus handle ) SM_STATUS smSendSMCMD( smbus handle, smuint8 cmdid, smuint8 addr, smuint8 datalen, smuint8 *cmddata )
{
int i;
- smuint8 data;
smuint16 sendcrc;
//check if bus handle is valid & opened
@@ -431,7 +420,7 @@ SM_STATUS smReceiveErrorHandler( smbus handle, smbool flushrx ) smbool success;
do{
smuint8 rx;
- success=smBDRead(handle,&rx);
+ success=smBDRead(smBus[handle].bdHandle,&rx);
}while(success==smtrue);
}
smResetSM485variables(handle);
@@ -442,7 +431,6 @@ SM_STATUS smReceiveErrorHandler( smbus handle, smbool flushrx ) SM_STATUS smAppendSMCommandToQueue( smbus handle, int smpCmdType,smint32 paramvalue )
{
- smuint8 txbyte;
int cmdlength;
//check if bus handle is valid & opened
@@ -476,12 +464,6 @@ SM_STATUS smAppendSMCommandToQueue( smbus handle, int smpCmdType,smint32 paramva SMPayloadCommand16 newcmd;
newcmd.ID=SMPCMD_SETPARAMADDR;
newcmd.param=paramvalue;
-
- // bufput8bit( smBus[handle].recv_rsbuf, smBus[handle].cmd_send_queue_bytes, 5);
- // bufput8bit( smBus[handle].recv_rsbuf, smBus[handle].cmd_send_queue_bytes, 6);
- /*
-FIXME
- ei toimi, menee vaa nollaa*/
bufput8bit( smBus[handle].recv_rsbuf, smBus[handle].cmd_send_queue_bytes++, ((unsigned char*)&newcmd)[1]);
bufput8bit( smBus[handle].recv_rsbuf, smBus[handle].cmd_send_queue_bytes++, ((unsigned char*)&newcmd)[0]);
}
@@ -582,7 +564,7 @@ SM_STATUS smGetQueuedSMCommandReturnValue( const smbus bushandle, smint32 *retV if(smBus[bushandle].cmd_recv_queue_bytes>=smBus[bushandle].recv_payloadsize)
{
- smDebug(Trace,bushandle,"Packet receive error, return data coudn't be parsed\n");
+ smDebug(bushandle,Trace, "Packet receive error, return data coudn't be parsed\n");
//return 0
if(retValue!=NULL) *retValue=0;//check every time if retValue is set NULL by caller -> don't store anything to it if its NULL
@@ -603,7 +585,7 @@ SM_STATUS smGetQueuedSMCommandReturnValue( const smbus bushandle, smint32 *retV smuint8 *readBuf=(smuint8*)&read;
readBuf[1]=rxbyte;
readBuf[0]=bufget8bit(smBus[bushandle].recv_rsbuf, smBus[bushandle].cmd_recv_queue_bytes++);
- smDebug(Trace,bushandle,"RET16B: %d\n",read.retData);
+ smDebug(bushandle,Trace,"RET16B: %d\n",read.retData);
if(retValue!=NULL) *retValue=read.retData;
return recordStatus(bushandle,SM_OK);
@@ -616,7 +598,7 @@ SM_STATUS smGetQueuedSMCommandReturnValue( const smbus bushandle, smint32 *retV readBuf[2]=rxbyte;
readBuf[1]=bufget8bit(smBus[bushandle].recv_rsbuf, smBus[bushandle].cmd_recv_queue_bytes++);
readBuf[0]=bufget8bit(smBus[bushandle].recv_rsbuf, smBus[bushandle].cmd_recv_queue_bytes++);
- smDebug(Trace,bushandle,"RET24B: %d\n",read.retData);
+ smDebug(bushandle,Trace,"RET24B: %d\n",read.retData);
if(retValue!=NULL) *retValue=read.retData;
return recordStatus(bushandle,SM_OK);
@@ -630,7 +612,7 @@ SM_STATUS smGetQueuedSMCommandReturnValue( const smbus bushandle, smint32 *retV readBuf[2]=bufget8bit(smBus[bushandle].recv_rsbuf, smBus[bushandle].cmd_recv_queue_bytes++);
readBuf[1]=bufget8bit(smBus[bushandle].recv_rsbuf, smBus[bushandle].cmd_recv_queue_bytes++);
readBuf[0]=bufget8bit(smBus[bushandle].recv_rsbuf, smBus[bushandle].cmd_recv_queue_bytes++);
- smDebug(Trace,bushandle,"RET32B: %d\n",read.retData);
+ smDebug(bushandle,Trace,"RET32B: %d\n",read.retData);
if(retValue!=NULL) *retValue=read.retData;
return recordStatus(bushandle,SM_OK);
@@ -641,7 +623,7 @@ SM_STATUS smGetQueuedSMCommandReturnValue( const smbus bushandle, smint32 *retV SMPayloadCommandRet8 read;
smuint8 *readBuf=(smuint8*)&read;
readBuf[0]=rxbyte;
- smDebug(Trace,bushandle,"RET_OTHER: %d\n",read.retData);
+ smDebug(bushandle,Trace,"RET_OTHER: %d\n",read.retData);
if(retValue!=NULL) *retValue=read.retData;
return recordStatus(bushandle,SM_OK);
@@ -662,7 +644,7 @@ SM_STATUS smReceiveReturnPacket( smbus bushandle ) smuint8 ret;
SM_STATUS stat;
- smbool succ=smBDRead(bushandle,&ret);
+ smbool succ=smBDRead(smBus[bushandle].bdHandle,&ret);
if(succ==smfalse)
{
@@ -879,7 +861,7 @@ SM_STATUS smGetBufferClock( const smbus handle, const smaddr targetaddr, smuint1 if(stat!=SM_OK) return recordStatus(handle,stat); //maybe timeouted
if(clock!=NULL)
- *clock=bufget16bit(smBus[handle].recv_rsbuf,0);
+ memcpy(clock,smBus[handle].recv_rsbuf,sizeof(smuint16));
smBus[handle].recv_storepos=0;
@@ -962,10 +944,12 @@ SM_STATUS getCumulativeStatus( const smbus handle ) }
/** Reset cululative status so getCumultiveStatus returns 0 after calling this until one of the other functions are called*/
-void resetCumulativeStatus( const smbus handle )
+SM_STATUS resetCumulativeStatus( const smbus handle )
{
if(smIsHandleOpen(handle)==smfalse) return SM_ERR_NODEVICE;
smBus[handle].cumulativeSmStatus=0;
+
+ return SM_OK;
}
diff --git a/simplemotion.h b/simplemotion.h index 913a595..c189af8 100644 --- a/simplemotion.h +++ b/simplemotion.h @@ -1,17 +1,6 @@ //Global SimpleMotion functions & definitions
//Copyright (c) Granite Devices Oy
-/*
- This program is free software; you can redistribute it and/or modify
- it under the terms of the GNU General Public License as published by
- the Free Software Foundation; version 2 of the License.
-
- This program 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 General Public License for more details.
-*/
-
#ifndef SIMPLEMOTION_H
#define SIMPLEMOTION_H
@@ -28,6 +17,7 @@ #endif
#include <stdio.h>
+#include <stdint.h>
#include "simplemotion_defs.h"
@@ -49,13 +39,13 @@ extern "C"{ ///////////////////////////////////////////////////////////////////////////////////////
//declare SM lib types
typedef long smbus;
-typedef unsigned long smuint32;
-typedef unsigned short smuint16;
-typedef unsigned char smuint8;
-typedef long smint32;
-typedef short smint16;
-typedef char smint8;
-typedef char smbool;
+typedef uint32_t smuint32;
+typedef uint16_t smuint16;
+typedef uint8_t smuint8;
+typedef int32_t smint32;
+typedef int16_t smint16;
+typedef int8_t smint8;
+typedef int8_t smbool;
#define smtrue 1
#define smfalse 0
typedef int SM_STATUS;
@@ -76,7 +66,8 @@ typedef enum _smVerbosityLevel {Off,Low,Mid,High,Trace} smVerbosityLevel; ///////////////////////////////////////////////////////////////////////////////////////
/** Open SM RS485 communication bus. Parameters:
- -devicename: "USB2VSD" or com port as "COMx" where x=1-16
+ -devicename: "USB2VSD" or com port as "COMx" where x=1-n
+ -devicename for TCP/IP connection format is nnn.nnn.nnn.nnn:pppp where n is IP address numbers and p is port number for TCP/IP connection
-return value: handle to be used with all other commands, -1 if fails
*/
LIB smbus smOpenBus( const char * devicename );
@@ -123,7 +114,7 @@ LIB void smSetDebugOutput( smVerbosityLevel level, FILE *stream ); /** This function returns all occurred SM_STATUS bits after smOpenBus or resetCumulativeStatus call*/
LIB SM_STATUS getCumulativeStatus( const smbus handle );
/** Reset cululative status so getCumultiveStatus returns 0 after calling this until one of the other functions are called*/
-LIB void resetCumulativeStatus( const smbus handle );
+LIB SM_STATUS resetCumulativeStatus( const smbus handle );
/** SMV2 Device communication functionss */
diff --git a/simplemotion_defs.h b/simplemotion_defs.h index ec3e2f7..34dca1e 100644 --- a/simplemotion_defs.h +++ b/simplemotion_defs.h @@ -84,9 +84,10 @@ -/*
- * SimpleMotion V2 constants
- */
+//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
+// SimpleMotion V2 constants
+//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
+
/* broadcast address, if packet is sent to SM_BROADCAST_ADDR then all nodes in the network
* will read it but no-one will send a reply because it would cause packet collision*/
@@ -165,22 +166,40 @@ *
*/
-//if command is to set param addr to this -> NOP
-#define SMP_ADDR_NOP 0x3fff
-
-//SMPCommand values that are returned with every SMPCommand when SMPRET_OTHER set as SMP_RETURN_PARAM_LEN:
-#define SMP_CMD_STATUS_ACK 0
-#define SMP_CMD_STATUS_NACK 1
-#define SMP_CMD_STATUS_INVALID_ADDR 2
-#define SMP_CMD_STATUS_INVALID_VALUE 4
-#define SMP_CMD_STATUS_VALUE_TOO_HIGH 8
-#define SMP_CMD_STATUS_VALUE_TOO_LOW 16
-#define SMP_CMD_STATUS_OTHER_MASK32 (3L<<30) //1byte packet. payload codes:
+/* Following is a list of status (SMP_CMD_STATUS_) values that are the result of every SM subpacket command.
+ *
+ * To read directly this value on each SM subpacket command, set SMPRET_OTHER as SMP_RETURN_PARAM_LEN. In this
+ * case, user can not read value of the variable.
+ *
+ * As alternative to direct reading like above:
+ * All executed SM subpacket commands also modify SMP_CUMULATIVE_STATUS. User can
+ * read SMP_CUMULATIVE_STATUS to check whihc status bits the previous commands have set
+ * (i.e. to check if all parameters were reawd/written succesfully). Once bit is set in cumulative status, it will stick there
+ * until user clears this value by writing 0 to SMP_CUMULATIVE_STATUS. Procedure for using SMP_CUMULATIVE_STATUS:
+ *
+ * 1. Set SMP_CUMULATIVE_STATUS to 0
+ * 2. Write/read some SMP parameters
+ * 3. Read SMP_CUMULATIVE_STATUS and check which SMP_CMD_STATUS bits have been set.
+ *
+ * If all all above read/writes were succesfull, it contains only bit SMP_CMD_STATUS_ACK. If something else is returned, investigate which
+ * read/write operation caused the error (i.e. by narrowing the SMP_CUMULATIVE_STATUS monitoring range).
+ */
+#define SMP_CMD_STATUS_ACK 0 /* subpacket command executed successfully */
+#define SMP_CMD_STATUS_NACK 1 /* subpacket command failed, perhaps writing into read-only variable or invalid value */
+#define SMP_CMD_STATUS_INVALID_ADDR 2 /* subpacket command has been targetted in invalid SMP parameter address, perhaps parameter is not supported in target device */
+#define SMP_CMD_STATUS_INVALID_VALUE 4 /* attempt to set invalid value into parameter */
+#define SMP_CMD_STATUS_VALUE_TOO_HIGH 8 /* attempt to too high value into parameter */
+#define SMP_CMD_STATUS_VALUE_TOO_LOW 16 /* attempt to too low value into parameter */
//params 0-63 are reserved for SM specific params, application specifics are >64-8090
#define SMP_SM_RESERVED_ADDRESS_SPACE 63
+//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
+// SimpleMotion common parameter definitions start below. These parameters are mandatory on SimpleMotion devices.
+//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
+
//SMP=Simple motion parameter
+
#define SMP_NULL 0
#define SMP_NODE_ADDRSS 1
#define SMP_BUS_MODE 2
@@ -197,12 +216,18 @@ #define SMP_BUS_SPEED 5
#define SMP_BUFFER_FREE_BYTES 6
#define SMP_BUFFERED_CMD_STATUS 7
+ //bit mask
+ #define SM_BUFCMD_STAT_IDLE 1
+ #define SM_BUFCMD_STAT_RUN 2
+ #define SM_BUFCMD_STAT_UNDERRUN 4
+ #define SM_BUFCMD_STAT_OVERRUN 8
+
#define SMP_BUFFERED_CMD_PERIOD 8
#define SMP_RETURN_PARAM_ADDR 9
#define SMP_RETURN_PARAM_LEN 10
/*SMP_TIMOUT defines how long device waits for one packet to transmit before discarding it. unit 0.1 milliseconds*/
#define SMP_TIMEOUT 12
-#define SMP_CUMULATIVE_STATUS 13 //error bits are set here if any, (SMP_CMD_STATUS_... bits). clear by writing 0
+#define SMP_CUMULATIVE_STATUS 13 //error bits are set here if any, (SMP_CMD_STATUS_... bits). clear by writing 0. For practical usage of SMP_CUMULATIVE_STATUS, see definitions of SMP_CMD_STATUS_ bits above.
#define SMP_ADDRESS_OFFSET 14 /*used to set or offset device address along physical method, i.e. DIP SW + offset to allow greater range of addresses than switch allows. */
/* SMP_FAULT_BEHAVIOR defines maximum amount of time between to valid received SM packets to device and other SM
* fault behavior that affect drive operation.
@@ -219,14 +244,70 @@ #define SMP_FAULT_BEHAVIOR 15
-//bit mask
-#define SM_BUFCMD_STAT_IDLE 1
-#define SM_BUFCMD_STAT_RUN 2
-#define SM_BUFCMD_STAT_UNDERRUN 4
-#define SM_BUFCMD_STAT_OVERRUN 8
-//each DIGITAL variable is 16 bits thus holds 16 i/o's
+//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
+// SimpleMotion device specific parameter definitions start below. Note: all parameters are not available in all device types/versions. To test which are available,
+// try reading them. If SMP_CMD_STATUS_INVALID_ADDR bit is being set into SMP_CUMULATIVE_STATUS on the read attempt, it means parameter doesn't exist in the target device.
+//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
+
+
+//choose input from SMP_DIGITAL_IN_VALUES_1 to be used as home switch.
+//note: this might not have effect depending on other parameters (i.e. if output is consumed by some built-in functionality)
+#define SMP_HOME_SWITCH_SOURCE_SELECT 100
+
+//choose signal to be forwarded into aux output of drive (on IONI it is GPO5)
+/*list of aux sources
+ * value signal
+ * 0 constant 0
+ * 1 constant 1 (default)
+ */
+#define SMP_AUX_OUTPUT_SOURCE_SELECT 101
+
+//each DIGITAL variable holds one bit for each physical digital input
+/*SMP_DIGITAL_IN_VALUES_1 on GD motor drives:
+ * bit physical input
+ * 0 GPI1
+ * 1 GPI2
+ * 2 GPI3
+ * 3 GPI4
+ * 4 GPI5
+ * 5 HSIN1
+ * 6 HSIN2
+ * 7 Analog In 1 as digital value
+ * 8 Analog In 2 as digital value
+ * 9 ENC A
+ * 10 ENC B
+ * 11 ENC C
+ * 12 ENC D
+ * 13 Hall U
+ * 14 Hall V
+ * 15 Hall W
+ * 16 reserved
+ * 17 reserved
+ * 18 reserved
+ * 19 reserved
+ * 20 GPI6
+ * 21- reserved
+ */
#define SMP_DIGITAL_IN_VALUES_1 128
+ #define SMP_DIG_IN1_GPI1 BV(0)
+ #define SMP_DIG_IN1_GPI2 BV(1)
+ #define SMP_DIG_IN1_GPI3 BV(2)
+ #define SMP_DIG_IN1_GPI4 BV(3)
+ #define SMP_DIG_IN1_GPI5 BV(4)
+ #define SMP_DIG_IN1_GPI6 BV(20)
+ #define SMP_DIG_IN1_HSIN1 BV(5)
+ #define SMP_DIG_IN1_HSIN2 BV(6)
+ #define SMP_DIG_IN1_ANA1 BV(7)
+ #define SMP_DIG_IN1_ANA2 BV(8)
+ #define SMP_DIG_IN1_ENCA BV(9)
+ #define SMP_DIG_IN1_ENCB BV(10)
+ #define SMP_DIG_IN1_ENCC BV(11)
+ #define SMP_DIG_IN1_ENCD BV(12)
+ #define SMP_DIG_IN1_HALLU BV(13)
+ #define SMP_DIG_IN1_HALLV BV(14)
+ #define SMP_DIG_IN1_HALLW BV(15)
+
#define SMP_DIGITAL_IN_VALUES_2 129
#define SMP_DIGITAL_IN_VALUES_3 130
#define SMP_DIGITAL_IN_VALUES_4 131
@@ -261,8 +342,6 @@ #define SMP_ANALOG_OUT_VALUE_5 188
// continue to .. 200
-
-
/*
* List of motor control parameters.
*
@@ -352,6 +431,10 @@ #define SMP_SYSTEM_CONTROL_GET_SPECIAL_DATA 1024
//stores encoder index position in SMP_DEBUGPARAM_1. while busy (index not found) SMP_DEBUGPARAM_2 will be 100, after found it is 200.
#define SMP_SYSTEM_CONTROL_CAPTURE_INDEX_POSITION 2048
+ //start a procedure to automatically configure hall sensors direction & offset, or other absolute sensor capable of commutation
+ #define SMP_SYSTEM_CONTROL_START_COMMUTATION_SENSOR_AUTOSETUP 4096
+ //load settings that are saved in device flash memory. useful when changing parameters on the fly and want to restore originals, or when app is started and drive may have unknown parameter modifications active.
+ #define SMP_SYSTEM_CONTROL_RESTORE_SAVED_CONFIG 8192
//write SM bus SM_CRCINIT constant modifier. special purposes only, don't use if unsure because
//it is one time programmable variable (permanently irreversible operation, can't be ever reset to default by provided methods)
#define SMP_SYSTEM_CONTROL_MODIFY_CRCINIT 262144
@@ -429,10 +512,11 @@ #define FLAG_ALLOW_VOLTAGE_CLIPPING BV(10)
#define FLAG_USE_INPUT_LP_FILTER BV(11)
#define FLAG_USE_PID_CONTROLLER BV(12)//PIV is the default if bit is 0/*obsolete*/
- #define FLAG_INVERTED_HALLS BV(13)
- #define FLAG_USE_HALLS BV(14)
+ #define FLAG_INVERTED_HALLS BV(13) /*becoming obsolete, no effect on device where param SMP_COMMUTATION_SENSOR_CONFIG is present */
+ #define FLAG_USE_HALLS BV(14) /*becoming obsolete, no effect on device where param SMP_COMMUTATION_SENSOR_CONFIG is present */
#define FLAG_MECH_BRAKE_DURING_PHASING BV(15)
#define FLAG_LIMIT_SWITCHES_NORMALLY_OPEN_TYPE BV(16)
+ #define FLAG_ENABLE_MOTOR_SOUND_NOTIFICATIONS BV(17)
#define SMP_MOTION_FAULT_THRESHOLD 568
#define SMP_HV_VOLTAGE_HI_LIMIT 569
#define SMP_HV_VOLTAGE_LOW_LIMIT 570
@@ -446,11 +530,20 @@ #define EL_MODE_SIMUCUBE 2
#define EL_MODE_IONIZER 3
-/*for BiSS encoder
- * bits defined as:
- * lowest 8 bits: single turn bits, value range 4-24
- * next 8 bits: multi turn bits, value range 0-16
+/*for BiSS/SSI encoder
+ * bits defined as (from LSB):
+ * bits 0-7: single turn bits, accepted value range 4-32
+ * bits 8-15: multi turn bits, accepted value range 0-16
+ * ^^ sum of MT and ST must be max 32
+ * bits 16-19: serial encoder mode (see below)
* rest: reserved for future use (always 0)
+ *
+ * Serial encoder read modes (bits 16-19):
+ * 0 BiSS C
+ * 1 BiSS B
+ * 2 SSI
+ * 3 SSI gray
+ * 4 AMS SSI
*/
#define SMP_SERIAL_ENC_BITS 574
@@ -539,7 +632,18 @@ #define SMP_PHASESEARCH_VOLTAGE_SLOPE 480
//by default this is calculated from other motor params:
#define SMP_PHASESEARCH_CURRENT 481
-//selector value 0-9 = 100 - 3300Hz (see Granity):
+/* Commutation angle congiuration, i.e. for hall sensors or absolute encoder. can be automatically set with SMP_SYSTEM_CONTROL_START_COMMUTATION_SENSOR_AUTOSET.
+ * Format:
+ * bits 0-15 LSB: commutation sensor offset 0-65535 represents commutation angle offset 0-360 electical degrees
+ * bit 16: invert sensor count direction
+ * bit 17: enable commutation sensor
+ * bits 18-31: reserved, always 0
+ */
+#define SMP_COMMUTATION_SENSOR_CONFIG 482
+ #define SMP_COMMUTATION_SENSOR_CONFIG_ANGLE_MASK 0xFFFF
+ #define SMP_COMMUTATION_SENSOR_CONFIG_INVERT_MASK 0x10000
+ #define SMP_COMMUTATION_SENSOR_CONFIG_ENABLE_MASK 0x20000
+//low pass filter selector, value 0=100Hz, 9=3300Hz, 10=4700Hz, 11=unlimited (see Granity for all options):
#define SMP_TORQUE_LPF_BANDWIDTH 490
//motor rev to rotary/linear unit scale. like 5mm/rev or 0.1rev/rev. 30bit parameter & scale 100000=1.0
@@ -616,6 +720,9 @@ #define HOMING_ENABLED BV(7) /*if 0, homing cant be started */
#define _HOMING_CFG_MAX_VALUE 0x00ff
+//defines from which direction & distance home switch will be approached for second time (eliminate switch hysteresis)
+#define SMP_TRAJ_PLANNER_HOMING_SECOND_APPROACH_DISTANCE 807
+
//starting and stopping homing:
#define SMP_HOMING_CONTROL 7532
@@ -635,6 +742,7 @@ #define SMP_ACTUAL_POSITION_FB 903
#define SMP_SCOPE_CHANNEL_VALUE 904
#define SMP_SCOPE_CHANNEL_SELECT 905
+#define SMP_ACTUAL_POSITION_FB_NEVER_RESETTING 906 /*this is same than SMP_ACTUAL_POSITION_FB but does not reset to 0 on homing or init (it is always the original counter value at power-on)*/
#define SMP_MECH_BRAKE_RELEASE_DELAY 910
#define SMP_MECH_BRAKE_ENGAGE_DELAY 911
@@ -706,11 +814,15 @@ #define TRIG_FAULT 2
#define TRIG_TARGETCHANGE 3
#define TRIG_TARGETCHANGE_POS 4
- #define TRIG_SERIALCMD 5
+ #define TRIG_EXTERNAL_INPUT 5
#define SMP_CAPTURE_SAMPLERATE 5012
//rdonly
#define SMP_CAPTURE_BUF_LENGHT 5013
+//SMP_CAPTURE_BEFORE_TRIGGER_PERCENTS sets how much samples will be preserved before trigger event. Value 0 is traditional, +n starts capture n percents before trigger (relative to whole capture length), -n after trigger. Value range -1000000%..+100%.
+#define SMP_CAPTURE_BEFORE_TRIGGER_PERCENTS 5014
+//SMP_CAPTURE_STATE, states: 0=idle (capture complete or not started), 1=waiting for trigger, 2=capturing. to start capture, write value 1 here starting from IONI FW V1110
+#define SMP_CAPTURE_STATE 5015
//this is looped 0-n to make samples 0-n readable from SMP_CAPTURE_BUFFER_GET_VALUE
#define SMP_CAPTURE_BUFFER_GET_ADDR 5333
#define SMP_CAPTURE_BUFFER_GET_VALUE 5334
@@ -718,7 +830,47 @@ //#define RUNTIME_FEATURES1 6000
#define SMP_SERIAL_NR 6002
#define SMP_UID_NR 6003
-#define SMP_DRIVE_CAPABILITIES 6006
+
+//read only bit field that is can be used to identify device capabilities
+//the list below is subject to extend
+#define SMP_DEVICE_CAPABILITIES1 6006
+ #define DEVICE_CAPABILITY1_PMDC BV(0)
+ #define DEVICE_CAPABILITY1_PMAC BV(1)
+ #define DEVICE_CAPABILITY1_STEPPER BV(2)
+ #define DEVICE_CAPABILITY1_TORQUE BV(3)
+ #define DEVICE_CAPABILITY1_POSITIONING BV(4)
+ #define DEVICE_CAPABILITY1_VELOCITY BV(5)
+ #define DEVICE_CAPABILITY1_TRAJ_PLANNER BV(6)
+ #define DEVICE_CAPABILITY1_HALLS BV(7)
+ #define DEVICE_CAPABILITY1_INDEXER BV(8)
+ #define DEVICE_CAPABILITY1_HOMING BV(9)
+ #define DEVICE_CAPABILITY1_REF_PULSETRAIN BV(10)
+ #define DEVICE_CAPABILITY1_REF_PWM BV(11)
+ #define DEVICE_CAPABILITY1_REF_ANALOG BV(12)
+ #define DEVICE_CAPABILITY1_REF_QUADRATURE BV(13)
+ #define DEVICE_CAPABILITY1_FB_QUADRATURE BV(14)
+ #define DEVICE_CAPABILITY1_FB_SSI BV(15)
+ #define DEVICE_CAPABILITY1_FB_BISS BV(16)
+ #define DEVICE_CAPABILITY1_FB_SINCOS BV(17)
+ #define DEVICE_CAPABILITY1_GEARING BV(18)
+ #define DEVICE_CAPABILITY1_AUTOSETUP_COMMUTATION_SENSOR BV(19)
+
+//read only bit field that is can be used to identify device capabilities
+//the list below is subject to extend
+#define SMP_DEVICE_CAPABILITIES2 6007
+ #define DEVICE_CAPABILITY2_RESTORE_SAVED_CONFIG BV(0)
+ #define DEVICE_CAPABILITY2_MEASURE_RL BV(1)
+ #define DEVICE_CAPABILITY2_TORQUE_RIPPLE_COMPENSATION BV(2)
+ #define DEVICE_CAPABILITY2_NOTCH_FILTER BV(3)
+ #define DEVICE_CAPABILITY2_TORQUE_EFFECTS BV(4)
+ #define DEVICE_CAPABILITY2_SENSORLESS_COMMUTATION BV(5)
+ #define DEVICE_CAPABILITY2_ANALOG_OUTPUT BV(6)
+ #define DEVICE_CAPABILITY2_SCOPE_TRIGGER_DELAY BV(7) /*also means that params SMP_CAPTURE_BEFORE_TRIGGER_PERCENTS and SMP_CAPTURE_STATE exist */
+ #define DEVICE_CAPABILITY2_SCOPE_EXTERNAL_TRIGGER BV(8)
+ #define DEVICE_CAPABILITY2_SOUND_NOTIFICATIONS_FROM_MOTOR BV(9)
+ #define DEVICE_CAPABILITY2_ASSIGN_HOME_AND_AUX_IO BV(10)
+ #define DEVICE_CAPABILITY2_HOMING_SECOND_APPROACH BV(11)
+
#define SMP_FIRMWARE_VERSION 6010
#define SMP_FIRMWARE_BACKWARDS_COMP_VERSION 6011
#define SMP_GC_FIRMWARE_VERSION 6014
diff --git a/simplemotion_private.h b/simplemotion_private.h index e0f70f3..67128b7 100644 --- a/simplemotion_private.h +++ b/simplemotion_private.h @@ -1,16 +1,6 @@ //Internal functions & definitions, not for library user
//Copyright (c) Granite Devices Oy
-/*
- This program is free software; you can redistribute it and/or modify
- it under the terms of the GNU General Public License as published by
- the Free Software Foundation; version 2 of the License.
-
- This program 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 General Public License for more details.
-*/
#ifndef SIMPLEMOTION_PRIVATE_H
#define SIMPLEMOTION_PRIVATE_H
@@ -48,6 +38,8 @@ extern smuint16 readTimeoutMs; //I.e Low=low frequency, so it gets displayed when global verbosity level is set to at least Low or set it to Trace which gets filtered
//out if global verbisity level is set less than Trace
void smDebug( smbus handle, smVerbosityLevel verbositylevel, char *format, ...);
+//accumulates status to internal variable by ORing the bits. returns same value that is fed as paramter
+SM_STATUS recordStatus( const smbus handle, const SM_STATUS stat );
SM_STATUS smRawCmd( const char *axisname, smuint8 cmd, smuint16 val, smuint32 *retdata );
diff --git a/tcpclient.c b/tcpclient.c new file mode 100644 index 0000000..31fb2f2 --- /dev/null +++ b/tcpclient.c @@ -0,0 +1,189 @@ +#include "simplemotion_private.h" +#include "tcpclient.h" +#include <stdio.h> + +#if defined(_WIN32) +#if defined(CM_NONE) +#undef CM_NONE +#endif +#include <winsock2.h> +#include <ws2tcpip.h> +#define close closesocket +#define read(SOCKET, BUF, LEN) recv((SOCKET), (BUF), (LEN), 0) +#define write(SOCKET, BUF, LEN) send((SOCKET), (BUF), (LEN), 0) +#ifdef errno +#undef errno +#endif +#define errno (WSAGetLastError()) +#ifdef EINPROGRESS +#undef EINPROGRESS +#endif +#define EINPROGRESS WSAEWOULDBLOCK +#else +#include <sys/types.h> +#include <sys/socket.h> +#include <netinet/in.h> +#include <sys/time.h> +#include <netdb.h> +#include <netinet/tcp.h> +#include <arpa/inet.h> +#include <unistd.h> +#include <fcntl.h> +#include <errno.h> +#endif + +#if defined(_WIN32) +static int initwsa() +{ + WORD req; + WSADATA data; + req = MAKEWORD(2, 2); + int err = WSAStartup(req, &data); + if (err != 0) + { + printf("WSAStartup failed\n"); + return 0; + } + return 1; +} +#endif + +int OpenTCPPort(const char * ip_addr, int port) +{ + int sockfd; + struct sockaddr_in server; + struct timeval tv; + fd_set myset; + int res, valopt; + socklen_t lon; + long arg; + +#if defined(_WIN32) + initwsa(); +#endif + + //Create socket + sockfd = socket(AF_INET , SOCK_STREAM , IPPROTO_TCP); + if (sockfd == -1) + { + return -1; + } + + // Set OFF NAGLE algorithm to reduce latency with small packets + /* + int one = 1; + setsockopt(sockfd, IPPROTO_TCP, TCP_NODELAY, (void *)&one, sizeof(one)); + */ + + server.sin_addr.s_addr = inet_addr(ip_addr); + server.sin_family = AF_INET; + server.sin_port = htons(port); + + // Set non-blocking when trying to establish the connection +#if !defined(_WIN32) + arg = fcntl(sockfd, F_GETFL, NULL); + arg |= O_NONBLOCK; + fcntl(sockfd, F_SETFL, arg); +#else + arg = 1; + ioctlsocket(sockfd, FIONBIO, &arg); +#endif + + res = connect(sockfd, (struct sockaddr *)&server, sizeof(server)); + + if (res < 0) + { + if (errno == EINPROGRESS) + { + tv.tv_sec = 5; + tv.tv_usec = 0; + FD_ZERO(&myset); + FD_SET(sockfd, &myset); + if (select(sockfd+1, NULL, &myset, NULL, &tv) > 0) + { + lon = sizeof(int); + getsockopt(sockfd, SOL_SOCKET, SO_ERROR, (void*)(&valopt), &lon); + if (valopt) + { + return -1; + } + } + else + { + return -1; + } + } + else + { + return -1; + } + } + + // Set to blocking mode again +#if !defined(_WIN32) + arg = fcntl(sockfd, F_GETFL, NULL); + arg &= (~O_NONBLOCK); + fcntl(sockfd, F_SETFL, arg); +#else + arg = 0; + ioctlsocket(sockfd, FIONBIO, &arg); +#endif + + return sockfd; +} + +// Read bytes from socket +int PollTCPPort(int sockfd, unsigned char *buf, int size) +{ + int n; + fd_set input; + FD_ZERO(&input); + FD_SET(sockfd, &input); + struct timeval timeout; + timeout.tv_sec = 0; + timeout.tv_usec = readTimeoutMs * 1000; + + n = select(sockfd + 1, &input, NULL, NULL, &timeout); + + // Error or timeout + if (n < 1) + { + return(-1); + } + if(!FD_ISSET(sockfd, &input)) + { + return(-1); + } + + n = read(sockfd, buf, size); + return(n); +} + +int SendTCPByte(int sockfd, unsigned char byte) +{ + int n; + n = write(sockfd, &byte, 1); + if(n<0) + return(1); + return(0); +} + + +int SendTCPBuf(int sockfd, unsigned char *buf, int size) +{ + int sent = write(sockfd, buf, size); + if (sent != size) + { + return sent; + } + return sent; +} + + +void CloseTCPport(int sockfd) +{ + close(sockfd); +#if defined(_WIN32) + WSACleanup(); +#endif +} diff --git a/tcpclient.h b/tcpclient.h new file mode 100644 index 0000000..ea02e42 --- /dev/null +++ b/tcpclient.h @@ -0,0 +1,22 @@ +#ifndef tcpclient_INCLUDED +#define tcpclient_INCLUDED + +#ifdef __cplusplus +extern "C" { +#endif + +//return port handle or -1 if fails +int OpenTCPPort(const char * ip_addr, int port); +int PollTCPPort(int, unsigned char *, int); +int SendTCPByte(int, unsigned char); +int SendTCPBuf(int, unsigned char *, int); +void CloseTCPport(int); + + +#ifdef __cplusplus +} /* extern "C" */ +#endif + +#endif + + |
