diff options
| -rw-r--r-- | SimpleMotionV2.pri | 4 | ||||
| -rw-r--r-- | busdevice.c | 169 | ||||
| -rw-r--r-- | pcserialport.c | 102 | ||||
| -rw-r--r-- | simplemotion.c | 6 | ||||
| -rw-r--r-- | simplemotion.h | 3 | ||||
| -rw-r--r-- | simplemotion_defs.h | 217 | ||||
| -rw-r--r-- | tcpclient.c | 189 | ||||
| -rw-r--r-- | tcpclient.h | 22 |
8 files changed, 644 insertions, 68 deletions
diff --git a/SimpleMotionV2.pri b/SimpleMotionV2.pri index 9d2caf5..8222018 100644 --- a/SimpleMotionV2.pri +++ b/SimpleMotionV2.pri @@ -6,9 +6,9 @@ DEPENDPATH += $$PWD DEFINES += SIMPLEMOTIONV2_LIBRARY
SOURCES += $$PWD/sm_consts.c $$PWD/simplemotion.c $$PWD/busdevice.c $$PWD/pcserialport.c \
- $$PWD/bufferedmotion.c $$PWD/devicedeployment.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/bufferedmotion.h $$PWD/devicedeployment.h
+ $$PWD/bufferedmotion.h $$PWD/tcpclient.h $$PWD/devicedeployment.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/pcserialport.c b/pcserialport.c index 2b44add..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> @@ -25,59 +25,129 @@ #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) { int port_handle; 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 diff --git a/simplemotion.c b/simplemotion.c index d78e511..58627cb 100644 --- a/simplemotion.c +++ b/simplemotion.c @@ -34,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;
@@ -420,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);
@@ -644,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)
{
diff --git a/simplemotion.h b/simplemotion.h index dcf499d..c189af8 100644 --- a/simplemotion.h +++ b/simplemotion.h @@ -66,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 );
diff --git a/simplemotion_defs.h b/simplemotion_defs.h index 138c42b..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,8 +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 4096
+ #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
@@ -431,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
@@ -450,10 +532,18 @@ /*for BiSS/SSI encoder
* bits defined as (from LSB):
- * bits 0-7: single turn bits, accepted value range 4-24
+ * bits 0-7: single turn bits, accepted value range 4-32
* bits 8-15: multi turn bits, accepted value range 0-16
- * bits 16-18: serial encoder mode: 000=BiSS, 001=SSI, 010=AMS SSI (SSI+CS+error monitoring), 011=SPI (SSI+CS) 100=GRAY SSI (i.e. SICK TTK70)
+ * ^^ 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
@@ -542,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
@@ -619,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
@@ -638,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
@@ -709,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
@@ -724,17 +833,43 @@ //read only bit field that is can be used to identify device capabilities
//the list below is subject to extend
-#define SMP_DEVICE_CAPABILITIES 6006
- #define DEVICE_CAPABILITY_HOMING BV(0)
- #define DEVICE_CAPABILITY_SERIAL_FBD BV(1)
- #define DEVICE_CAPABILITY_RESTORE_SAVED_CONFIG BV(2)
- #define DEVICE_CAPABILITY_MEASURE_RL BV(3)
- #define DEVICE_CAPABILITY_TORQUE_RIPPLE_COMPENSATION BV(4)
- #define DEVICE_CAPABILITY_NOTCH_FILTER BV(5)
- #define DEVICE_CAPABILITY_TORQUE_EFFECTS BV(6)
- #define DEVICE_CAPABILITY_AUTOSETUP_COMMUTATION_SENSOR BV(7)
- #define DEVICE_CAPABILITY_SENSORLESS_COMMUTATION BV(8)
- #define DEVICE_CAPABILITY_ANALOG_OUTPUT BV(9)
+#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
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 + + |
