diff --git a/Cards/EaserCAT-3000-Digital-Stepper-Analog-Encoder-Frequency/Firmware/lib/soes-esi/MetalMusings_EaserCAT_3000.xml b/Cards/EaserCAT-3000-Digital-Stepper-Analog-Encoder-Frequency/Firmware/lib/soes-esi/MetalMusings_EaserCAT_3000.xml
index 1172ab6..0b37f7a 100755
--- a/Cards/EaserCAT-3000-Digital-Stepper-Analog-Encoder-Frequency/Firmware/lib/soes-esi/MetalMusings_EaserCAT_3000.xml
+++ b/Cards/EaserCAT-3000-Digital-Stepper-Analog-Encoder-Frequency/Firmware/lib/soes-esi/MetalMusings_EaserCAT_3000.xml
@@ -77,7 +77,7 @@
DT1600
- 48
+ 80
0
Max SubIndex
@@ -90,7 +90,7 @@
1
- EncScale
+ IndexLatchEnable
UDINT
32
16
@@ -98,6 +98,16 @@
ro
+
+ 2
+ Scale
+ UDINT
+ 32
+ 48
+
+ ro
+
+
DT1601
@@ -317,6 +327,54 @@
DT160A
+ 48
+
+ 0
+ Max SubIndex
+ USINT
+ 8
+ 0
+
+ ro
+
+
+
+ 1
+ Voltage
+ UDINT
+ 32
+ 16
+
+ ro
+
+
+
+
+ DT1A00
+ 48
+
+ 0
+ Max SubIndex
+ USINT
+ 8
+ 0
+
+ ro
+
+
+
+ 1
+ FrequencyCounterFrequency
+ UDINT
+ 32
+ 16
+
+ ro
+
+
+
+
+ DT1A01
144
0
@@ -360,7 +418,7 @@
4
- Frequency
+ Velocity
UDINT
32
112
@@ -369,78 +427,6 @@
-
- DT1612
- 48
-
- 0
- Max SubIndex
- USINT
- 8
- 0
-
- ro
-
-
-
- 1
- EncIndexLatchEnable
- UDINT
- 32
- 16
-
- ro
-
-
-
-
- DT1A00
- 48
-
- 0
- Max SubIndex
- USINT
- 8
- 0
-
- ro
-
-
-
- 1
- EncPosition
- UDINT
- 32
- 16
-
- ro
-
-
-
-
- DT1A01
- 48
-
- 0
- Max SubIndex
- USINT
- 8
- 0
-
- ro
-
-
-
- 1
- EncVelocity
- UDINT
- 32
- 16
-
- ro
-
-
-
DT1A02
48
@@ -561,54 +547,6 @@
-
- DT1A07
- 48
-
- 0
- Max SubIndex
- USINT
- 8
- 0
-
- ro
-
-
-
- 1
- IndexByte
- UDINT
- 32
- 16
-
- ro
-
-
-
-
- DT1A08
- 48
-
- 0
- Max SubIndex
- USINT
- 8
- 0
-
- ro
-
-
-
- 1
- IndexStatus
- UDINT
- 32
- 16
-
- ro
-
-
-
DT1C00ARR
USINT
@@ -676,15 +614,15 @@
DT1C13ARR
UINT
- 144
+ 112
1
- 9
+ 7
DT1C13
- 160
+ 128
0
Max SubIndex
@@ -698,7 +636,7 @@
Elements
DT1C13ARR
- 144
+ 112
16
ro
@@ -706,7 +644,7 @@
- DT700A
+ DT6001
96
0
@@ -726,7 +664,7 @@
16
ro
- R
+ T
@@ -737,7 +675,7 @@
24
ro
- R
+ T
@@ -748,15 +686,51 @@
32
ro
- R
+ T
4
- Frequency
+ Velocity
REAL
32
64
+
+ ro
+ T
+
+
+
+
+ DT7000
+ 56
+
+ 0
+ Max SubIndex
+ USINT
+ 8
+ 0
+
+ ro
+
+
+
+ 1
+ IndexLatchEnable
+ USINT
+ 8
+ 16
+
+ ro
+ R
+
+
+
+ 2
+ Scale
+ REAL
+ 32
+ 24
ro
R
@@ -881,20 +855,26 @@
+
+
-
-
-
-
-
-
- PDO Mapping
-
- #x1A07
-
-
-
- PDO Mapping
-
- #x1A08
-
-
@@ -1661,7 +1563,7 @@
-
-
@@ -1958,12 +1849,19 @@
Inputs
#x1600
- EncScale
+ EncoderOut
#x7000
- #x0
+ #x1
+ 8
+ IndexLatchEnable
+ USINT
+
+
+ #x7000
+ #x2
32
- EncScale
+ Scale
REAL
@@ -2068,55 +1966,55 @@
#x160A
- EncoderIn
+ Voltage
#x700A
+ #x0
+ 32
+ Voltage
+ REAL
+
+
+
+ #x1A00
+ FrequencyCounterFrequency
+
+ #x6000
+ #x0
+ 32
+ FrequencyCounterFrequency
+ REAL
+
+
+
+ #x1A01
+ EncoderIn
+
+ #x6001
#x1
8
IndexStatus
USINT
- #x700A
+ #x6001
#x2
8
IndexByte
USINT
- #x700A
+ #x6001
#x3
32
Position
REAL
- #x700A
+ #x6001
#x4
32
- Frequency
- REAL
-
-
-
- #x1A00
- EncPosition
-
- #x6000
- #x0
- 32
- EncPosition
- REAL
-
-
-
- #x1A01
- EncVelocity
-
- #x6001
- #x0
- 32
- EncVelocity
+ Velocity
REAL
@@ -2175,30 +2073,8 @@
REAL
-
- #x1A07
- IndexByte
-
- #x6007
- #x0
- 32
- IndexByte
- UDINT
-
-
-
- #x1A08
- IndexStatus
-
- #x6008
- #x0
- 32
- IndexStatus
- UDINT
-
-
-
+
@@ -2219,4 +2095,4 @@
-
+
\ No newline at end of file
diff --git a/Cards/EaserCAT-3000-Digital-Stepper-Analog-Encoder-Frequency/Firmware/lib/soes-esi/ecat_options.h b/Cards/EaserCAT-3000-Digital-Stepper-Analog-Encoder-Frequency/Firmware/lib/soes-esi/ecat_options.h
index 4106ca0..b9b66d1 100755
--- a/Cards/EaserCAT-3000-Digital-Stepper-Analog-Encoder-Frequency/Firmware/lib/soes-esi/ecat_options.h
+++ b/Cards/EaserCAT-3000-Digital-Stepper-Analog-Encoder-Frequency/Firmware/lib/soes-esi/ecat_options.h
@@ -33,8 +33,8 @@
#define SM3_smc 0x20
#define SM3_act 1
-#define MAX_MAPPINGS_SM2 14
-#define MAX_MAPPINGS_SM3 7
+#define MAX_MAPPINGS_SM2 12
+#define MAX_MAPPINGS_SM3 10
#define MAX_RXPDO_SIZE 512
#define MAX_TXPDO_SIZE 512
diff --git a/Cards/EaserCAT-3000-Digital-Stepper-Analog-Encoder-Frequency/Firmware/lib/soes-esi/eeprom.bin b/Cards/EaserCAT-3000-Digital-Stepper-Analog-Encoder-Frequency/Firmware/lib/soes-esi/eeprom.bin
index 619c11a..e5685d6 100755
Binary files a/Cards/EaserCAT-3000-Digital-Stepper-Analog-Encoder-Frequency/Firmware/lib/soes-esi/eeprom.bin and b/Cards/EaserCAT-3000-Digital-Stepper-Analog-Encoder-Frequency/Firmware/lib/soes-esi/eeprom.bin differ
diff --git a/Cards/EaserCAT-3000-Digital-Stepper-Analog-Encoder-Frequency/Firmware/lib/soes-esi/eeprom.hex b/Cards/EaserCAT-3000-Digital-Stepper-Analog-Encoder-Frequency/Firmware/lib/soes-esi/eeprom.hex
index 2bcb9d2..f7a9cce 100755
--- a/Cards/EaserCAT-3000-Digital-Stepper-Analog-Encoder-Frequency/Firmware/lib/soes-esi/eeprom.hex
+++ b/Cards/EaserCAT-3000-Digital-Stepper-Analog-Encoder-Frequency/Firmware/lib/soes-esi/eeprom.hex
@@ -4,7 +4,7 @@
:20006000000000000000000000000000000000000000000000000000000000000F00010070
:200080000A001F00040B434E4320636F6E74726F6C0E4D616368696E65436F6E74726F6C8F
:2000A00006494D474342591A4D6574616C4D7573696E677320456173657243415420333021
-:2000C00030301E00100002030104003F000000000000000000001100000000000000000038
+:2000C00030301E001000020301040013000000000000000000001100000000000000000064
:2000E000000000000000280002000102030029001000001000022600010100120002220027
:2001000001020016000024000103001A000020000104FFFFFFFFFFFFFFFFFFFFFFFFFFFF6D
:20012000FFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFDF
diff --git a/Cards/EaserCAT-3000-Digital-Stepper-Analog-Encoder-Frequency/Firmware/lib/soes-esi/esi.json b/Cards/EaserCAT-3000-Digital-Stepper-Analog-Encoder-Frequency/Firmware/lib/soes-esi/esi.json
index 3e7b05f..ef4fd8e 100755
--- a/Cards/EaserCAT-3000-Digital-Stepper-Analog-Encoder-Frequency/Firmware/lib/soes-esi/esi.json
+++ b/Cards/EaserCAT-3000-Digital-Stepper-Analog-Encoder-Frequency/Firmware/lib/soes-esi/esi.json
@@ -144,25 +144,55 @@
},
"6000": {
"otype": "VAR",
- "name": "EncPosition",
+ "name": "FrequencyCounterFrequency",
"access": "RO",
"pdo_mappings": [
"txpdo"
],
"dtype": "REAL32",
"value": "0",
- "data": "&Obj.EncPosition"
+ "data": "&Obj.FrequencyCounterFrequency"
},
"6001": {
- "otype": "VAR",
- "name": "EncVelocity",
+ "otype": "RECORD",
+ "name": "EncoderIn",
"access": "RO",
+ "items": [
+ {
+ "name": "Max SubIndex"
+ },
+ {
+ "name": "IndexStatus",
+ "dtype": "UNSIGNED8",
+ "data": "&Obj.EncoderIn.IndexStatus",
+ "value": "0",
+ "access": "RO"
+ },
+ {
+ "name": "IndexByte",
+ "dtype": "UNSIGNED8",
+ "value": "0",
+ "access": "RO",
+ "data": "&Obj.EncoderIn.IndexByte"
+ },
+ {
+ "name": "Position",
+ "dtype": "REAL32",
+ "value": "0",
+ "access": "RO",
+ "data": "&Obj.EncoderIn.Position"
+ },
+ {
+ "name": "Velocity",
+ "dtype": "REAL32",
+ "value": "0",
+ "access": "RO",
+ "data": "&Obj.EncoderIn.Velocity"
+ }
+ ],
"pdo_mappings": [
"txpdo"
- ],
- "dtype": "REAL32",
- "value": "0",
- "data": "&Obj.EncVelocity"
+ ]
},
"6002": {
"otype": "VAR",
@@ -218,41 +248,35 @@
"dtype": "REAL32",
"value": "0",
"data": "&Obj.ActualPosition4"
- },
- "6007": {
- "otype": "VAR",
- "name": "IndexByte",
- "access": "RO",
- "pdo_mappings": [
- "txpdo"
- ],
- "dtype": "UNSIGNED32",
- "value": "0",
- "data": "&Obj.IndexByte"
- },
- "6008": {
- "otype": "VAR",
- "name": "IndexStatus",
- "access": "RO",
- "pdo_mappings": [
- "txpdo"
- ],
- "dtype": "UNSIGNED32",
- "value": "0",
- "data": "&Obj.IndexStatus"
}
},
"rxpdo": {
"7000": {
- "otype": "VAR",
- "name": "EncScale",
+ "otype": "RECORD",
+ "name": "EncoderOut",
"access": "RO",
+ "items": [
+ {
+ "name": "Max SubIndex"
+ },
+ {
+ "name": "IndexLatchEnable",
+ "dtype": "UNSIGNED8",
+ "data": "&Obj.EncoderOut.IndexLatchEnable",
+ "value": "0",
+ "access": "RO"
+ },
+ {
+ "name": "Scale",
+ "dtype": "REAL32",
+ "value": "0",
+ "access": "RO",
+ "data": "&Obj.EncoderOut.Scale"
+ }
+ ],
"pdo_mappings": [
"rxpdo"
- ],
- "dtype": "REAL32",
- "value": "0",
- "data": "&Obj.EncScale"
+ ]
},
"7001": {
"otype": "VAR",
@@ -364,45 +388,15 @@
"value": "0"
},
"700A": {
- "otype": "RECORD",
- "name": "EncoderIn",
+ "otype": "VAR",
+ "name": "Voltage",
"access": "RO",
- "items": [
- {
- "name": "Max SubIndex"
- },
- {
- "name": "IndexStatus",
- "dtype": "UNSIGNED8",
- "data": "&Obj.EncoderIn.IndexStatus",
- "value": "0",
- "access": "RO"
- },
- {
- "name": "IndexByte",
- "dtype": "UNSIGNED8",
- "value": "0",
- "access": "RO",
- "data": "&Obj.EncoderIn.IndexByte"
- },
- {
- "name": "Position",
- "dtype": "REAL32",
- "value": "0",
- "access": "RO",
- "data": "&Obj.EncoderIn.Position"
- },
- {
- "name": "Frequency",
- "dtype": "REAL32",
- "value": "0",
- "access": "RO",
- "data": "&Obj.EncoderIn.Frequency"
- }
- ],
"pdo_mappings": [
"rxpdo"
- ]
+ ],
+ "dtype": "REAL32",
+ "value": "0",
+ "data": "&Obj.Voltage"
}
}
},
@@ -426,4 +420,4 @@
"Sync1shiftTime": "0"
}
]
-}
+}
\ No newline at end of file
diff --git a/Cards/EaserCAT-3000-Digital-Stepper-Analog-Encoder-Frequency/Firmware/lib/soes-esi/objectlist.c b/Cards/EaserCAT-3000-Digital-Stepper-Analog-Encoder-Frequency/Firmware/lib/soes-esi/objectlist.c
index b43910c..807ff10 100755
--- a/Cards/EaserCAT-3000-Digital-Stepper-Analog-Encoder-Frequency/Firmware/lib/soes-esi/objectlist.c
+++ b/Cards/EaserCAT-3000-Digital-Stepper-Analog-Encoder-Frequency/Firmware/lib/soes-esi/objectlist.c
@@ -13,9 +13,10 @@ static const char acName1018_01[] = "Vendor ID";
static const char acName1018_02[] = "Product Code";
static const char acName1018_03[] = "Revision Number";
static const char acName1018_04[] = "Serial Number";
-static const char acName1600[] = "EncScale";
+static const char acName1600[] = "EncoderOut";
static const char acName1600_00[] = "Max SubIndex";
-static const char acName1600_01[] = "EncScale";
+static const char acName1600_01[] = "IndexLatchEnable";
+static const char acName1600_02[] = "Scale";
static const char acName1601[] = "Output4";
static const char acName1601_00[] = "Max SubIndex";
static const char acName1601_01[] = "Output4";
@@ -43,18 +44,18 @@ static const char acName1608_01[] = "CommandedPosition3";
static const char acName1609[] = "CommandedPosition4";
static const char acName1609_00[] = "Max SubIndex";
static const char acName1609_01[] = "CommandedPosition4";
-static const char acName160A[] = "EncoderIn";
+static const char acName160A[] = "Voltage";
static const char acName160A_00[] = "Max SubIndex";
-static const char acName160A_01[] = "IndexStatus";
-static const char acName160A_02[] = "IndexByte";
-static const char acName160A_03[] = "Position";
-static const char acName160A_04[] = "Frequency";
-static const char acName1A00[] = "Velocity";
+static const char acName160A_01[] = "Voltage";
+static const char acName1A00[] = "FrequencyCounterFrequency";
static const char acName1A00_00[] = "Max SubIndex";
-static const char acName1A00_01[] = "EncPosition";
-static const char acName1A01[] = "EncVelocity";
+static const char acName1A00_01[] = "FrequencyCounterFrequency";
+static const char acName1A01[] = "EncoderIn";
static const char acName1A01_00[] = "Max SubIndex";
-static const char acName1A01_01[] = "EncVelocity";
+static const char acName1A01_01[] = "IndexStatus";
+static const char acName1A01_02[] = "IndexByte";
+static const char acName1A01_03[] = "Position";
+static const char acName1A01_04[] = "Velocity";
static const char acName1A02[] = "Input8";
static const char acName1A02_00[] = "Max SubIndex";
static const char acName1A02_01[] = "Input8";
@@ -70,12 +71,6 @@ static const char acName1A05_01[] = "ActualPosition3";
static const char acName1A06[] = "ActualPosition4";
static const char acName1A06_00[] = "Max SubIndex";
static const char acName1A06_01[] = "ActualPosition4";
-static const char acName1A07[] = "IndexByte";
-static const char acName1A07_00[] = "Max SubIndex";
-static const char acName1A07_01[] = "IndexByte";
-static const char acName1A08[] = "IndexStatus";
-static const char acName1A08_00[] = "Max SubIndex";
-static const char acName1A08_01[] = "IndexStatus";
static const char acName1C00[] = "Sync Manager Communication Type";
static const char acName1C00_00[] = "Max SubIndex";
static const char acName1C00_01[] = "Communications Type SM0";
@@ -104,8 +99,6 @@ static const char acName1C13_04[] = "PDO Mapping";
static const char acName1C13_05[] = "PDO Mapping";
static const char acName1C13_06[] = "PDO Mapping";
static const char acName1C13_07[] = "PDO Mapping";
-static const char acName1C13_08[] = "PDO Mapping";
-static const char acName1C13_09[] = "PDO Mapping";
static const char acName2000[] = "BasePeriod";
static const char acName2001[] = "StepsPerMM1";
static const char acName2002[] = "StepsPerMM2";
@@ -115,16 +108,22 @@ static const char acName2005[] = "MaxAcceleration1";
static const char acName2006[] = "MaxAcceleration2";
static const char acName2007[] = "MaxAcceleration3";
static const char acName2008[] = "MaxAcceleration4";
-static const char acName6000[] = "Velocity";
-static const char acName6001[] = "Frequency";
+static const char acName6000[] = "FrequencyCounterFrequency";
+static const char acName6001[] = "EncoderIn";
+static const char acName6001_00[] = "Max SubIndex";
+static const char acName6001_01[] = "IndexStatus";
+static const char acName6001_02[] = "IndexByte";
+static const char acName6001_03[] = "Position";
+static const char acName6001_04[] = "Velocity";
static const char acName6002[] = "Input8";
static const char acName6003[] = "ActualPosition1";
static const char acName6004[] = "ActualPosition2";
static const char acName6005[] = "ActualPosition3";
static const char acName6006[] = "ActualPosition4";
-static const char acName6007[] = "IndexByte";
-static const char acName6008[] = "IndexStatus";
-static const char acName7000[] = "EncScale";
+static const char acName7000[] = "EncoderOut";
+static const char acName7000_00[] = "Max SubIndex";
+static const char acName7000_01[] = "IndexLatchEnable";
+static const char acName7000_02[] = "Scale";
static const char acName7001[] = "Output4";
static const char acName7002[] = "Enable1";
static const char acName7003[] = "Enable2";
@@ -134,12 +133,7 @@ static const char acName7006[] = "CommandedPosition1";
static const char acName7007[] = "CommandedPosition2";
static const char acName7008[] = "CommandedPosition3";
static const char acName7009[] = "CommandedPosition4";
-static const char acName700A[] = "EncoderIn";
-static const char acName700A_00[] = "Max SubIndex";
-static const char acName700A_01[] = "IndexStatus";
-static const char acName700A_02[] = "IndexByte";
-static const char acName700A_03[] = "Position";
-static const char acName700A_04[] = "Frequency";
+static const char acName700A[] = "Voltage";
const _objd SDO1000[] =
{
@@ -167,8 +161,9 @@ const _objd SDO1018[] =
};
const _objd SDO1600[] =
{
- {0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1600_00, 1, NULL},
- {0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1600_01, 0x70000020, NULL},
+ {0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1600_00, 2, NULL},
+ {0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1600_01, 0x70000108, NULL},
+ {0x02, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1600_02, 0x70000220, NULL},
};
const _objd SDO1601[] =
{
@@ -217,16 +212,8 @@ const _objd SDO1609[] =
};
const _objd SDO160A[] =
{
- {0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName160A_00, 4, NULL},
- {0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName160A_01, 0x700A0108, NULL},
- {0x02, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName160A_02, 0x700A0208, NULL},
- {0x03, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName160A_03, 0x700A0320, NULL},
- {0x04, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName160A_04, 0x700A0420, NULL},
-};
-const _objd SDO1612[] =
-{
- {0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1612_00, 1, NULL},
- {0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1612_01, 0x70120008, NULL},
+ {0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName160A_00, 1, NULL},
+ {0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName160A_01, 0x700A0020, NULL},
};
const _objd SDO1A00[] =
{
@@ -235,8 +222,11 @@ const _objd SDO1A00[] =
};
const _objd SDO1A01[] =
{
- {0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1A01_00, 1, NULL},
- {0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1A01_01, 0x60010020, NULL},
+ {0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1A01_00, 4, NULL},
+ {0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1A01_01, 0x60010108, NULL},
+ {0x02, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1A01_02, 0x60010208, NULL},
+ {0x03, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1A01_03, 0x60010320, NULL},
+ {0x04, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1A01_04, 0x60010420, NULL},
};
const _objd SDO1A02[] =
{
@@ -263,16 +253,6 @@ const _objd SDO1A06[] =
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1A06_00, 1, NULL},
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1A06_01, 0x60060020, NULL},
};
-const _objd SDO1A07[] =
-{
- {0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1A07_00, 1, NULL},
- {0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1A07_01, 0x60070020, NULL},
-};
-const _objd SDO1A08[] =
-{
- {0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1A08_00, 1, NULL},
- {0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1A08_01, 0x60080020, NULL},
-};
const _objd SDO1C00[] =
{
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1C00_00, 4, NULL},
@@ -298,7 +278,7 @@ const _objd SDO1C12[] =
};
const _objd SDO1C13[] =
{
- {0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1C13_00, 9, NULL},
+ {0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1C13_00, 7, NULL},
{0x01, DTYPE_UNSIGNED16, 16, ATYPE_RO, acName1C13_01, 0x1A00, NULL},
{0x02, DTYPE_UNSIGNED16, 16, ATYPE_RO, acName1C13_02, 0x1A01, NULL},
{0x03, DTYPE_UNSIGNED16, 16, ATYPE_RO, acName1C13_03, 0x1A02, NULL},
@@ -306,8 +286,6 @@ const _objd SDO1C13[] =
{0x05, DTYPE_UNSIGNED16, 16, ATYPE_RO, acName1C13_05, 0x1A04, NULL},
{0x06, DTYPE_UNSIGNED16, 16, ATYPE_RO, acName1C13_06, 0x1A05, NULL},
{0x07, DTYPE_UNSIGNED16, 16, ATYPE_RO, acName1C13_07, 0x1A06, NULL},
- {0x08, DTYPE_UNSIGNED16, 16, ATYPE_RO, acName1C13_08, 0x1A07, NULL},
- {0x09, DTYPE_UNSIGNED16, 16, ATYPE_RO, acName1C13_09, 0x1A08, NULL},
};
const _objd SDO2000[] =
{
@@ -347,11 +325,15 @@ const _objd SDO2008[] =
};
const _objd SDO6000[] =
{
- {0x0, DTYPE_REAL32, 32, ATYPE_RO | ATYPE_TXPDO, acName6000, 0x00000000, &Obj.EncPosition},
+ {0x0, DTYPE_REAL32, 32, ATYPE_RO | ATYPE_TXPDO, acName6000, 0x00000000, &Obj.FrequencyCounterFrequency},
};
const _objd SDO6001[] =
{
- {0x0, DTYPE_REAL32, 32, ATYPE_RO | ATYPE_TXPDO, acName6001, 0x00000000, &Obj.EncVelocity},
+ {0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName6001_00, 4, NULL},
+ {0x01, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName6001_01, 0, &Obj.EncoderIn.IndexStatus},
+ {0x02, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName6001_02, 0, &Obj.EncoderIn.IndexByte},
+ {0x03, DTYPE_REAL32, 32, ATYPE_RO, acName6001_03, 0x00000000, &Obj.EncoderIn.Position},
+ {0x04, DTYPE_REAL32, 32, ATYPE_RO, acName6001_04, 0x00000000, &Obj.EncoderIn.Velocity},
};
const _objd SDO6002[] =
{
@@ -373,17 +355,11 @@ const _objd SDO6006[] =
{
{0x0, DTYPE_REAL32, 32, ATYPE_RO | ATYPE_TXPDO, acName6006, 0x00000000, &Obj.ActualPosition4},
};
-const _objd SDO6007[] =
-{
- {0x0, DTYPE_UNSIGNED32, 32, ATYPE_RO | ATYPE_TXPDO, acName6007, 0, &Obj.IndexByte},
-};
-const _objd SDO6008[] =
-{
- {0x0, DTYPE_UNSIGNED32, 32, ATYPE_RO | ATYPE_TXPDO, acName6008, 0, &Obj.IndexStatus},
-};
const _objd SDO7000[] =
{
- {0x0, DTYPE_REAL32, 32, ATYPE_RO | ATYPE_RXPDO, acName7000, 0x00000000, &Obj.EncScale},
+ {0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName7000_00, 2, NULL},
+ {0x01, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName7000_01, 0, &Obj.EncoderOut.IndexLatchEnable},
+ {0x02, DTYPE_REAL32, 32, ATYPE_RO, acName7000_02, 0x00000000, &Obj.EncoderOut.Scale},
};
const _objd SDO7001[] =
{
@@ -423,15 +399,7 @@ const _objd SDO7009[] =
};
const _objd SDO700A[] =
{
- {0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName700A_00, 4, NULL},
- {0x01, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName700A_01, 0, &Obj.EncoderIn.IndexStatus},
- {0x02, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName700A_02, 0, &Obj.EncoderIn.IndexByte},
- {0x03, DTYPE_REAL32, 32, ATYPE_RO, acName700A_03, 0x00000000, &Obj.EncoderIn.Position},
- {0x04, DTYPE_REAL32, 32, ATYPE_RO, acName700A_04, 0x00000000, &Obj.EncoderIn.Frequency},
-};
-const _objd SDO7012[] =
-{
- {0x0, DTYPE_UNSIGNED8, 8, ATYPE_RO | ATYPE_RXPDO, acName7012, 0, &Obj.EncIndexLatchEnable},
+ {0x0, DTYPE_REAL32, 32, ATYPE_RO | ATYPE_RXPDO, acName700A, 0x00000000, &Obj.Voltage},
};
const _objectlist SDOobjects[] =
@@ -441,7 +409,7 @@ const _objectlist SDOobjects[] =
{0x1009, OTYPE_VAR, 0, 0, acName1009, SDO1009},
{0x100A, OTYPE_VAR, 0, 0, acName100A, SDO100A},
{0x1018, OTYPE_RECORD, 4, 0, acName1018, SDO1018},
- {0x1600, OTYPE_RECORD, 1, 0, acName1600, SDO1600},
+ {0x1600, OTYPE_RECORD, 2, 0, acName1600, SDO1600},
{0x1601, OTYPE_RECORD, 1, 0, acName1601, SDO1601},
{0x1602, OTYPE_RECORD, 1, 0, acName1602, SDO1602},
{0x1603, OTYPE_RECORD, 1, 0, acName1603, SDO1603},
@@ -451,16 +419,14 @@ const _objectlist SDOobjects[] =
{0x1607, OTYPE_RECORD, 1, 0, acName1607, SDO1607},
{0x1608, OTYPE_RECORD, 1, 0, acName1608, SDO1608},
{0x1609, OTYPE_RECORD, 1, 0, acName1609, SDO1609},
- {0x160A, OTYPE_RECORD, 4, 0, acName160A, SDO160A},
+ {0x160A, OTYPE_RECORD, 1, 0, acName160A, SDO160A},
{0x1A00, OTYPE_RECORD, 1, 0, acName1A00, SDO1A00},
- {0x1A01, OTYPE_RECORD, 1, 0, acName1A01, SDO1A01},
+ {0x1A01, OTYPE_RECORD, 4, 0, acName1A01, SDO1A01},
{0x1A02, OTYPE_RECORD, 1, 0, acName1A02, SDO1A02},
{0x1A03, OTYPE_RECORD, 1, 0, acName1A03, SDO1A03},
{0x1A04, OTYPE_RECORD, 1, 0, acName1A04, SDO1A04},
{0x1A05, OTYPE_RECORD, 1, 0, acName1A05, SDO1A05},
{0x1A06, OTYPE_RECORD, 1, 0, acName1A06, SDO1A06},
- {0x1A07, OTYPE_RECORD, 1, 0, acName1A07, SDO1A07},
- {0x1A08, OTYPE_RECORD, 1, 0, acName1A08, SDO1A08},
{0x1C00, OTYPE_ARRAY, 4, 0, acName1C00, SDO1C00},
{0x1C12, OTYPE_ARRAY, 11, 0, acName1C12, SDO1C12},
{0x1C13, OTYPE_ARRAY, 7, 0, acName1C13, SDO1C13},
@@ -474,15 +440,13 @@ const _objectlist SDOobjects[] =
{0x2007, OTYPE_VAR, 0, 0, acName2007, SDO2007},
{0x2008, OTYPE_VAR, 0, 0, acName2008, SDO2008},
{0x6000, OTYPE_VAR, 0, 0, acName6000, SDO6000},
- {0x6001, OTYPE_VAR, 0, 0, acName6001, SDO6001},
+ {0x6001, OTYPE_RECORD, 4, 0, acName6001, SDO6001},
{0x6002, OTYPE_VAR, 0, 0, acName6002, SDO6002},
{0x6003, OTYPE_VAR, 0, 0, acName6003, SDO6003},
{0x6004, OTYPE_VAR, 0, 0, acName6004, SDO6004},
{0x6005, OTYPE_VAR, 0, 0, acName6005, SDO6005},
{0x6006, OTYPE_VAR, 0, 0, acName6006, SDO6006},
- {0x6007, OTYPE_VAR, 0, 0, acName6007, SDO6007},
- {0x6008, OTYPE_VAR, 0, 0, acName6008, SDO6008},
- {0x7000, OTYPE_VAR, 0, 0, acName7000, SDO7000},
+ {0x7000, OTYPE_RECORD, 2, 0, acName7000, SDO7000},
{0x7001, OTYPE_VAR, 0, 0, acName7001, SDO7001},
{0x7002, OTYPE_VAR, 0, 0, acName7002, SDO7002},
{0x7003, OTYPE_VAR, 0, 0, acName7003, SDO7003},
@@ -492,6 +456,6 @@ const _objectlist SDOobjects[] =
{0x7007, OTYPE_VAR, 0, 0, acName7007, SDO7007},
{0x7008, OTYPE_VAR, 0, 0, acName7008, SDO7008},
{0x7009, OTYPE_VAR, 0, 0, acName7009, SDO7009},
- {0x700A, OTYPE_RECORD, 4, 0, acName700A, SDO700A},
+ {0x700A, OTYPE_VAR, 0, 0, acName700A, SDO700A},
{0xffff, 0xff, 0xff, 0xff, NULL, NULL}
};
diff --git a/Cards/EaserCAT-3000-Digital-Stepper-Analog-Encoder-Frequency/Firmware/lib/soes-esi/utypes.h b/Cards/EaserCAT-3000-Digital-Stepper-Analog-Encoder-Frequency/Firmware/lib/soes-esi/utypes.h
index 531027f..fd838a4 100755
--- a/Cards/EaserCAT-3000-Digital-Stepper-Analog-Encoder-Frequency/Firmware/lib/soes-esi/utypes.h
+++ b/Cards/EaserCAT-3000-Digital-Stepper-Analog-Encoder-Frequency/Firmware/lib/soes-esi/utypes.h
@@ -13,19 +13,27 @@ typedef struct
/* Inputs */
- float EncPosition;
- float EncVelocity;
+ float FrequencyCounterFrequency;
+ struct
+ {
+ uint8_t IndexStatus;
+ uint8_t IndexByte;
+ float Position;
+ float Velocity;
+ } EncoderIn;
uint8_t Input8;
float ActualPosition1;
float ActualPosition2;
float ActualPosition3;
float ActualPosition4;
- uint32_t IndexByte;
- uint32_t IndexStatus;
/* Outputs */
- float EncScale;
+ struct
+ {
+ uint8_t IndexLatchEnable;
+ float Scale;
+ } EncoderOut;
uint8_t Output4;
uint8_t Enable1;
uint8_t Enable2;
@@ -35,13 +43,7 @@ typedef struct
float CommandedPosition2;
float CommandedPosition3;
float CommandedPosition4;
- struct
- {
- uint8_t IndexStatus;
- uint8_t IndexByte;
- float Position;
- float Frequency;
- } EncoderIn;
+ float Voltage;
/* Parameters */
diff --git a/Cards/EaserCAT-3000-Digital-Stepper-Analog-Encoder-Frequency/Firmware/src/main.cpp b/Cards/EaserCAT-3000-Digital-Stepper-Analog-Encoder-Frequency/Firmware/src/main.cpp
index 125f59e..14b3c7c 100755
--- a/Cards/EaserCAT-3000-Digital-Stepper-Analog-Encoder-Frequency/Firmware/src/main.cpp
+++ b/Cards/EaserCAT-3000-Digital-Stepper-Analog-Encoder-Frequency/Firmware/src/main.cpp
@@ -1,3 +1,4 @@
+// EaserCAT 3000
#include
#include
extern "C"
@@ -16,7 +17,7 @@ HardwareSerial Serial1(PA10, PA9);
////// Digital IO
const byte INPUTS[8] = {PE8, PE9, PE10, PE11, PE12, PE13, PE14, PE15};
const byte OUTPUTS[4] = {PC5, PB0, PB1, PE7};
-//const byte THCAD_PIN = PA2; // CAN BE PA0, should be PA0
+
#define bitset(byte, nbit) ((byte) |= (1 << (nbit)))
#define bitclear(byte, nbit) ((byte) &= ~(1 << (nbit)))
#define bitflip(byte, nbit) ((byte) ^= (1 << (nbit)))
@@ -82,9 +83,9 @@ void cb_set_outputs(void) // Get Master outputs, slave inputs, first operation
{
for (int i = 0; i < 4; i++)
digitalWrite(OUTPUTS[i], bitcheck(Obj.Output4, i) ? HIGH : LOW);
- // analogWrite(DAC1_pin, Obj.Voltage);
- Encoder1.setLatch(Obj.EncIndexLatchEnable);
- Encoder1.setScale(Obj.EncScale);
+ analogWrite(DAC1_pin, Obj.Voltage);
+ Encoder1.setLatch(Obj.EncoderOut.IndexLatchEnable);
+ Encoder1.setScale(Obj.EncoderOut.Scale);
posScale1 = Obj.StepsPerMM1; // Scale perhaps changed
posScale2 = Obj.StepsPerMM2;
@@ -109,8 +110,8 @@ void cb_set_outputs(void) // Get Master outputs, slave inputs, first operation
void cb_get_inputs(void) // Set Master inputs, slave outputs, last operation
{
float scale = 1;
- if (Obj.EncScale != 0.0)
- scale = Obj.EncScale;
+ if (Obj.EncoderOut.Scale != 0.0)
+ scale = Obj.EncoderOut.Scale;
for (int i = 0; i < 8; i++)
if (digitalRead(INPUTS[i]) == HIGH)
@@ -118,10 +119,10 @@ void cb_get_inputs(void) // Set Master inputs, slave outputs, last operation
else
bitClear(Obj.Input8, i);
- Obj.IndexStatus = Encoder1.indexHappened();
- Obj.EncPosition = Encoder1.currentPos();
- Obj.IndexByte = Encoder1.getIndexState();
- Obj.EncVelocity = Obj.EncScale * Encoder1.frequency(longTime.extendTime(micros()));
+ Obj.EncoderIn.IndexStatus = Encoder1.indexHappened();
+ Obj.EncoderIn.Position = Encoder1.currentPos();
+ Obj.EncoderIn.IndexByte = Encoder1.getIndexState();
+ Obj.EncoderIn.Velocity = Obj.EncoderOut.Scale * Encoder1.frequency(longTime.extendTime(micros()));
Obj.ActualPosition1 = Step->stepgen_array[0].pos_fb;
Obj.ActualPosition2 = Step->stepgen_array[1].pos_fb;
diff --git a/Cards/EaserCAT-3000-Digital-Stepper-Analog-Encoder-Frequency/linuxcnc/configs/sim.axis/e3000.hal b/Cards/EaserCAT-3000-Digital-Stepper-Analog-Encoder-Frequency/linuxcnc/configs/sim.axis/e3000.hal
index b954f88..70c1ba3 100644
--- a/Cards/EaserCAT-3000-Digital-Stepper-Analog-Encoder-Frequency/linuxcnc/configs/sim.axis/e3000.hal
+++ b/Cards/EaserCAT-3000-Digital-Stepper-Analog-Encoder-Frequency/linuxcnc/configs/sim.axis/e3000.hal
@@ -21,16 +21,16 @@ addf lcec.write-all servo-thread
net emc-enable => iocontrol.0.emc-enable-in
sets emc-enable 1
-net x-enable joint.0.amp-enable-out lcec.0.E3000.enable1-0
-net x-pos-cmd joint.0.motor-pos-cmd lcec.0.E3000.commandedPosition1
-net x-pos-fb joint.0.motor-pos-fb lcec.0.E3000.actualPosition1
+net x-enable joint.0.amp-enable-out lcec.0.E3000.Enable1-0
+net x-pos-cmd joint.0.motor-pos-cmd lcec.0.E3000.CommandedPosition1
+net x-pos-fb joint.0.motor-pos-fb lcec.0.E3000.ActualPosition1
-net y-enable joint.1.amp-enable-out lcec.0.E3000.enable2-0
-net y-pos-cmd joint.1.motor-pos-cmd lcec.0.E3000.commandedPosition2
-net y-pos-fb joint.1.motor-pos-fb lcec.0.E3000.actualPosition2
+net y-enable joint.1.amp-enable-out lcec.0.E3000.Enable2-0
+net y-pos-cmd joint.1.motor-pos-cmd lcec.0.E3000.CommandedPosition2
+net y-pos-fb joint.1.motor-pos-fb lcec.0.E3000.ActualPosition2
-net z-enable joint.2.amp-enable-out lcec.0.E3000.enable3-0
-net z-pos-cmd joint.2.motor-pos-cmd lcec.0.E3000.commandedPosition3
-net z-pos-fb joint.2.motor-pos-fb lcec.0.E3000.actualPosition3
+net z-enable joint.2.amp-enable-out lcec.0.E3000.Enable3-0
+net z-pos-cmd joint.2.motor-pos-cmd lcec.0.E3000.CommandedPosition3
+net z-pos-fb joint.2.motor-pos-fb lcec.0.E3000.ActualPosition3
diff --git a/Cards/EaserCAT-3000-Digital-Stepper-Analog-Encoder-Frequency/linuxcnc/configs/sim.axis/ethercat-conf.xml b/Cards/EaserCAT-3000-Digital-Stepper-Analog-Encoder-Frequency/linuxcnc/configs/sim.axis/ethercat-conf.xml
index 40ce515..9412275 100644
--- a/Cards/EaserCAT-3000-Digital-Stepper-Analog-Encoder-Frequency/linuxcnc/configs/sim.axis/ethercat-conf.xml
+++ b/Cards/EaserCAT-3000-Digital-Stepper-Analog-Encoder-Frequency/linuxcnc/configs/sim.axis/ethercat-conf.xml
@@ -11,83 +11,85 @@
+
-
-
+
+
+
-
+
-
-
+
+
-
-
+
+
-
-
+
+
-
-
+
+
-
-
+
+
-
-
+
+
-
-
+
+
-
-
+
+
-
-
-
-
-
+
+
-
-
+
+
-
-
+
+
+
+
+
-
+
-
+
-
+
-
+
-
+