Compare commits
42 Commits
| Author | SHA1 | Date | |
|---|---|---|---|
|
|
ed0414b90a | ||
|
|
1d8adf2147 | ||
|
|
4c4aa7aab1 | ||
|
|
b242ec3315 | ||
|
|
f66c600dc7 | ||
|
|
9a41ccd2bc | ||
|
|
9dcc713fab | ||
|
|
ccde6ef15e | ||
|
|
7e06b0ce68 | ||
|
|
37d3ea6567 | ||
|
|
ed168df64e | ||
|
|
1168f7e5ad | ||
|
|
93405efd63 | ||
|
|
484c984e49 | ||
|
|
e6cd5356c9 | ||
|
|
5978ebec24 | ||
|
|
d4a83eae80 | ||
|
|
2e8e938345 | ||
|
|
cc1ca73219 | ||
|
|
b57bd740ab | ||
|
|
8007a2ff6c | ||
|
|
a21e932b5a | ||
|
|
64d62a954a | ||
|
|
f99d9bab77 | ||
|
|
703bbfb03a | ||
|
|
f0ec7a834c | ||
|
|
28f01a9919 | ||
|
|
bf8fccd0d6 | ||
|
|
f27a27ed1b | ||
|
|
485901120c | ||
|
|
1851f4168e | ||
|
|
ab034e93f8 | ||
|
|
0929d23207 | ||
|
|
818f853af0 | ||
|
|
5abaf4ace7 | ||
|
|
2a1111c537 | ||
|
|
d9b088687f | ||
|
|
2790280c4a | ||
|
|
890a81952b | ||
|
|
d878101c62 | ||
|
|
3cd2755645 | ||
|
|
49c804516d |
9
Pcb-1-lan9252/Firmware/.vscode/settings.json
vendored
9
Pcb-1-lan9252/Firmware/.vscode/settings.json
vendored
@@ -1,6 +1,13 @@
|
|||||||
{
|
{
|
||||||
"files.associations": {
|
"files.associations": {
|
||||||
"ecat_slv.h": "c",
|
"ecat_slv.h": "c",
|
||||||
"compare": "cpp"
|
"compare": "cpp",
|
||||||
|
"*.tpp": "cpp",
|
||||||
|
"*.tcc": "cpp",
|
||||||
|
"deque": "cpp",
|
||||||
|
"string": "cpp",
|
||||||
|
"unordered_map": "cpp",
|
||||||
|
"vector": "cpp",
|
||||||
|
"system_error": "cpp"
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
File diff suppressed because it is too large
Load Diff
@@ -4,8 +4,8 @@
|
|||||||
#define USE_FOE 0
|
#define USE_FOE 0
|
||||||
#define USE_EOE 0
|
#define USE_EOE 0
|
||||||
|
|
||||||
#define MBXSIZE 128
|
#define MBXSIZE 512
|
||||||
#define MBXSIZEBOOT 128
|
#define MBXSIZEBOOT 512
|
||||||
#define MBXBUFFERS 3
|
#define MBXBUFFERS 3
|
||||||
|
|
||||||
#define MBX0_sma 0x1000
|
#define MBX0_sma 0x1000
|
||||||
@@ -33,8 +33,8 @@
|
|||||||
#define SM3_smc 0x20
|
#define SM3_smc 0x20
|
||||||
#define SM3_act 1
|
#define SM3_act 1
|
||||||
|
|
||||||
#define MAX_MAPPINGS_SM2 7
|
#define MAX_MAPPINGS_SM2 2
|
||||||
#define MAX_MAPPINGS_SM3 6
|
#define MAX_MAPPINGS_SM3 5
|
||||||
|
|
||||||
#define MAX_RXPDO_SIZE 512
|
#define MAX_RXPDO_SIZE 512
|
||||||
#define MAX_TXPDO_SIZE 512
|
#define MAX_TXPDO_SIZE 512
|
||||||
|
|||||||
Binary file not shown.
@@ -1,12 +1,12 @@
|
|||||||
:2000000080060344640000000000000000001400E1100000D20400000100000002000000D1
|
:2000000080060344640000000000000000001400AA0A0000CCBCBB000200000001000000A1
|
||||||
:2000200000000000000000000000000000000000001080008010800004000000000000001C
|
:20002000000000000000000000000000000000000010000200120002040000000000000096
|
||||||
:200040000000000000000000000000000000000000000000000000000000000000000000A0
|
:200040000000000000000000000000000000000000000000000000000000000000000000A0
|
||||||
:20006000000000000000000000000000000000000000000000000000000000000F00010070
|
:20006000000000000000000000000000000000000000000000000000000000000F00010070
|
||||||
:200080000A002100040C456173657243415432303030096D79456E636F64657206494D479
|
:200080000A002000040C4561736572434154323030300E4D616368696E65436F6E74726F64
|
||||||
:2000A000434259224D6574616C4D7573696E67732045617365724341542032303030206518
|
:2000A0006C06494D474342591A4D6574616C4D7573696E67732045617365724341542032E6
|
||||||
:2000C0006E636F6465721E0010000203010400130000000000000000000011000000000049
|
:2000C000303030001E00100002030104001300000000000000000000110000000000000034
|
||||||
:2000E00000000000000000000000280002000102030029001000001080002600010180104F
|
:2000E000000000000000000028000200010203002900100000100002260001010012000249
|
||||||
:200100008000220001020016000024000103001A000020000104FFFFFFFFFFFFFFFFFFFFC7
|
:20010000220001020016000024000103001A000020000104FFFFFFFFFFFFFFFFFFFFFFFF49
|
||||||
:20012000FFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFDF
|
:20012000FFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFDF
|
||||||
:20014000FFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFBF
|
:20014000FFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFBF
|
||||||
:20016000FFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFF9F
|
:20016000FFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFF9F
|
||||||
|
|||||||
@@ -1,32 +1,39 @@
|
|||||||
{
|
{
|
||||||
"form": {},
|
"form": {
|
||||||
|
"VendorName": "MetalMusings",
|
||||||
|
"VendorID": "0xaaa",
|
||||||
|
"ProductCode": "0xbbbccc",
|
||||||
|
"ProfileNo": "5001",
|
||||||
|
"RevisionNumber": "0x002",
|
||||||
|
"SerialNumber": "0x001",
|
||||||
|
"HWversion": "0.0.1",
|
||||||
|
"SWversion": "0.0.1",
|
||||||
|
"EEPROMsize": "2048",
|
||||||
|
"RxMailboxOffset": "0x1000",
|
||||||
|
"TxMailboxOffset": "0x1200",
|
||||||
|
"MailboxSize": "512",
|
||||||
|
"SM2Offset": "0x1600",
|
||||||
|
"SM3Offset": "0x1A00",
|
||||||
|
"TextGroupType": "MachineControl",
|
||||||
|
"TextGroupName5": "Incremental encoder",
|
||||||
|
"ImageName": "IMGCBY",
|
||||||
|
"TextDeviceType": "EaserCAT2000",
|
||||||
|
"TextDeviceName": "MetalMusings EaserCAT 2000",
|
||||||
|
"Port0Physical": "Y",
|
||||||
|
"Port1Physical": "Y",
|
||||||
|
"Port2Physical": " ",
|
||||||
|
"Port3Physical": " ",
|
||||||
|
"ESC": "LAN9252",
|
||||||
|
"SPImode": "3",
|
||||||
|
"CoeDetailsEnableSDO": "EnableSDO",
|
||||||
|
"CoeDetailsEnableSDOInfo": "EnableSDOInfo",
|
||||||
|
"CoeDetailsEnablePDOAssign": "EnablePDOAssign",
|
||||||
|
"CoeDetailsEnablePDOConfiguration": "EnablePDOConfiguration",
|
||||||
|
"CoeDetailsEnableUploadAtStartup": "EnableUploadAtStartup",
|
||||||
|
"CoeDetailsEnableSDOCompleteAccess": "EnableSDOCompleteAccess"
|
||||||
|
},
|
||||||
"od": {
|
"od": {
|
||||||
"sdo": {
|
"sdo": {
|
||||||
"2000": {
|
|
||||||
"otype": "RECORD",
|
|
||||||
"name": "StepperData",
|
|
||||||
"access": "RO",
|
|
||||||
"items": [
|
|
||||||
{
|
|
||||||
"name": "Max SubIndex"
|
|
||||||
},
|
|
||||||
{
|
|
||||||
"name": "Period",
|
|
||||||
"dtype": "UNSIGNED16",
|
|
||||||
"data": "&Obj.StepperData.Period",
|
|
||||||
"value": "1000",
|
|
||||||
"access": "RO"
|
|
||||||
},
|
|
||||||
{
|
|
||||||
"name": "Resolution",
|
|
||||||
"dtype": "REAL32",
|
|
||||||
"value": "2.5",
|
|
||||||
"access": "RO",
|
|
||||||
"data": "&Obj.StepperData.Resolution"
|
|
||||||
}
|
|
||||||
],
|
|
||||||
"isSDOitem": true
|
|
||||||
},
|
|
||||||
"A": {
|
"A": {
|
||||||
"otype": "RECORD",
|
"otype": "RECORD",
|
||||||
"name": "Error Settings",
|
"name": "Error Settings",
|
||||||
@@ -44,148 +51,83 @@
|
|||||||
},
|
},
|
||||||
"txpdo": {
|
"txpdo": {
|
||||||
"6000": {
|
"6000": {
|
||||||
"otype": "RECORD",
|
|
||||||
"name": "EncoderOut",
|
|
||||||
"access": "RO",
|
|
||||||
"items": [
|
|
||||||
{
|
|
||||||
"name": "Max SubIndex"
|
|
||||||
},
|
|
||||||
{
|
|
||||||
"name": "ECount",
|
|
||||||
"dtype": "INTEGER32",
|
|
||||||
"value": "0",
|
|
||||||
"access": "RO",
|
|
||||||
"data": "&Obj.EncoderOut.ECount"
|
|
||||||
},
|
|
||||||
{
|
|
||||||
"name": "IndexTriggered",
|
|
||||||
"dtype": "UNSIGNED8",
|
|
||||||
"value": "0",
|
|
||||||
"access": "RW",
|
|
||||||
"data": "&Obj.EncoderOut.IndexTriggered"
|
|
||||||
}
|
|
||||||
],
|
|
||||||
"pdo_mappings": [
|
|
||||||
"txpdo"
|
|
||||||
]
|
|
||||||
},
|
|
||||||
"6040": {
|
|
||||||
"otype": "VAR",
|
"otype": "VAR",
|
||||||
"name": "ControlWord",
|
"name": "EncPos",
|
||||||
"access": "RO",
|
"access": "RO",
|
||||||
"pdo_mappings": [
|
"pdo_mappings": [
|
||||||
"txpdo"
|
"txpdo"
|
||||||
],
|
],
|
||||||
"dtype": "UNSIGNED16",
|
"dtype": "REAL32",
|
||||||
"value": "0",
|
"value": "0",
|
||||||
"data": "&Obj.ControlWord"
|
"data": "&Obj.EncPos"
|
||||||
},
|
},
|
||||||
"6060": {
|
"6001": {
|
||||||
"otype": "VAR",
|
"otype": "VAR",
|
||||||
"name": "OpMode",
|
"name": "EncFrequency",
|
||||||
"access": "RO",
|
"access": "RO",
|
||||||
"pdo_mappings": [
|
"pdo_mappings": [
|
||||||
"txpdo"
|
"txpdo"
|
||||||
],
|
],
|
||||||
"dtype": "UNSIGNED8",
|
"dtype": "REAL32",
|
||||||
"value": "0",
|
"value": "0",
|
||||||
"data": "&Obj.OpMode"
|
"data": "&Obj.EncFrequency"
|
||||||
},
|
},
|
||||||
"607A": {
|
"6002": {
|
||||||
"otype": "VAR",
|
"otype": "VAR",
|
||||||
"name": "TargetPosition",
|
"name": "DiffT",
|
||||||
"access": "RO",
|
"access": "RO",
|
||||||
"pdo_mappings": [
|
"pdo_mappings": [
|
||||||
"txpdo"
|
"txpdo"
|
||||||
],
|
],
|
||||||
"dtype": "INTEGER32",
|
"dtype": "UNSIGNED32",
|
||||||
"value": "0",
|
"value": "0",
|
||||||
"data": "&Obj.TargetPosition"
|
"data": "&Obj.DiffT"
|
||||||
},
|
},
|
||||||
"60FF": {
|
"6003": {
|
||||||
"otype": "VAR",
|
"otype": "VAR",
|
||||||
"name": "TargetVelocity",
|
"name": "IndexByte",
|
||||||
"access": "RO",
|
"access": "RO",
|
||||||
"pdo_mappings": [
|
"pdo_mappings": [
|
||||||
"txpdo"
|
"txpdo"
|
||||||
],
|
],
|
||||||
"dtype": "INTEGER32",
|
"dtype": "UNSIGNED32",
|
||||||
"value": "0",
|
"value": "0",
|
||||||
"data": "&Obj.TargetVelocity"
|
"data": "&Obj.IndexByte"
|
||||||
|
},
|
||||||
|
"6004": {
|
||||||
|
"otype": "VAR",
|
||||||
|
"name": "IndexStatus",
|
||||||
|
"access": "RO",
|
||||||
|
"pdo_mappings": [
|
||||||
|
"txpdo"
|
||||||
|
],
|
||||||
|
"dtype": "UNSIGNED32",
|
||||||
|
"value": "0",
|
||||||
|
"data": "&Obj.IndexStatus"
|
||||||
}
|
}
|
||||||
},
|
},
|
||||||
"rxpdo": {
|
"rxpdo": {
|
||||||
"6041": {
|
|
||||||
"otype": "VAR",
|
|
||||||
"name": "StatusWord",
|
|
||||||
"access": "RO",
|
|
||||||
"pdo_mappings": [
|
|
||||||
"rxpdo"
|
|
||||||
],
|
|
||||||
"dtype": "UNSIGNED16",
|
|
||||||
"value": "0",
|
|
||||||
"data": "&Obj.StatusWord"
|
|
||||||
},
|
|
||||||
"6061": {
|
|
||||||
"otype": "VAR",
|
|
||||||
"name": "OpModeDisplay",
|
|
||||||
"access": "RO",
|
|
||||||
"pdo_mappings": [
|
|
||||||
"rxpdo"
|
|
||||||
],
|
|
||||||
"dtype": "UNSIGNED8",
|
|
||||||
"value": "0",
|
|
||||||
"data": "&Obj.OpModeDisplay"
|
|
||||||
},
|
|
||||||
"6064": {
|
|
||||||
"otype": "VAR",
|
|
||||||
"name": "ActualPosition",
|
|
||||||
"access": "RO",
|
|
||||||
"pdo_mappings": [
|
|
||||||
"rxpdo"
|
|
||||||
],
|
|
||||||
"dtype": "INTEGER32",
|
|
||||||
"value": "0",
|
|
||||||
"data": "&Obj.ActualPosition"
|
|
||||||
},
|
|
||||||
"6077": {
|
|
||||||
"otype": "VAR",
|
|
||||||
"name": "ActualTorque",
|
|
||||||
"access": "RO",
|
|
||||||
"pdo_mappings": [
|
|
||||||
"rxpdo"
|
|
||||||
],
|
|
||||||
"dtype": "INTEGER32",
|
|
||||||
"value": "0",
|
|
||||||
"data": "&Obj.ActualTorque"
|
|
||||||
},
|
|
||||||
"7000": {
|
"7000": {
|
||||||
"otype": "RECORD",
|
"otype": "VAR",
|
||||||
"name": "EncoderIn",
|
"name": "EncPosScale",
|
||||||
"access": "RO",
|
"access": "RO",
|
||||||
"items": [
|
|
||||||
{
|
|
||||||
"name": "Max SubIndex"
|
|
||||||
},
|
|
||||||
{
|
|
||||||
"name": "IndexEnable",
|
|
||||||
"dtype": "UNSIGNED8",
|
|
||||||
"value": "0",
|
|
||||||
"access": "RO",
|
|
||||||
"data": "&Obj.EncoderIn.IndexEnable"
|
|
||||||
},
|
|
||||||
{
|
|
||||||
"name": "Reset",
|
|
||||||
"dtype": "UNSIGNED8",
|
|
||||||
"value": "0",
|
|
||||||
"access": "RO",
|
|
||||||
"data": "&Obj.EncoderIn.Reset"
|
|
||||||
}
|
|
||||||
],
|
|
||||||
"pdo_mappings": [
|
"pdo_mappings": [
|
||||||
"rxpdo"
|
"rxpdo"
|
||||||
]
|
],
|
||||||
|
"dtype": "INTEGER32",
|
||||||
|
"value": "0",
|
||||||
|
"data": "&Obj.EncPosScale"
|
||||||
|
},
|
||||||
|
"7001": {
|
||||||
|
"otype": "VAR",
|
||||||
|
"name": "IndexLatchEnable",
|
||||||
|
"access": "RO",
|
||||||
|
"pdo_mappings": [
|
||||||
|
"rxpdo"
|
||||||
|
],
|
||||||
|
"dtype": "UNSIGNED32",
|
||||||
|
"value": "0",
|
||||||
|
"data": "&Obj.IndexLatchEnable"
|
||||||
},
|
},
|
||||||
"60664": {
|
"60664": {
|
||||||
"otype": "VAR",
|
"otype": "VAR",
|
||||||
@@ -196,17 +138,6 @@
|
|||||||
],
|
],
|
||||||
"dtype": "INTEGER32",
|
"dtype": "INTEGER32",
|
||||||
"value": "0"
|
"value": "0"
|
||||||
},
|
|
||||||
"606C": {
|
|
||||||
"otype": "VAR",
|
|
||||||
"name": "ActualVelocity",
|
|
||||||
"access": "RO",
|
|
||||||
"pdo_mappings": [
|
|
||||||
"rxpdo"
|
|
||||||
],
|
|
||||||
"dtype": "INTEGER32",
|
|
||||||
"value": "0",
|
|
||||||
"data": "&Obj.ActualVelocity"
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
},
|
},
|
||||||
|
|||||||
@@ -13,41 +13,27 @@ static const char acName1018_01[] = "Vendor ID";
|
|||||||
static const char acName1018_02[] = "Product Code";
|
static const char acName1018_02[] = "Product Code";
|
||||||
static const char acName1018_03[] = "Revision Number";
|
static const char acName1018_03[] = "Revision Number";
|
||||||
static const char acName1018_04[] = "Serial Number";
|
static const char acName1018_04[] = "Serial Number";
|
||||||
static const char acName1600[] = "StatusWord";
|
static const char acName1600[] = "EncPosScale";
|
||||||
static const char acName1600_00[] = "Max SubIndex";
|
static const char acName1600_00[] = "Max SubIndex";
|
||||||
static const char acName1600_01[] = "StatusWord";
|
static const char acName1600_01[] = "EncPosScale";
|
||||||
static const char acName1601[] = "OpModeDisplay";
|
static const char acName1601[] = "IndexLatchEnable";
|
||||||
static const char acName1601_00[] = "Max SubIndex";
|
static const char acName1601_00[] = "Max SubIndex";
|
||||||
static const char acName1601_01[] = "OpModeDisplay";
|
static const char acName1601_01[] = "IndexLatchEnable";
|
||||||
static const char acName1602[] = "ActualPosition";
|
static const char acName1A00[] = "EncPos";
|
||||||
static const char acName1602_00[] = "Max SubIndex";
|
|
||||||
static const char acName1602_01[] = "ActualPosition";
|
|
||||||
static const char acName1603[] = "ActualVelocity";
|
|
||||||
static const char acName1603_00[] = "Max SubIndex";
|
|
||||||
static const char acName1603_01[] = "ActualVelocity";
|
|
||||||
static const char acName1604[] = "ActualTorque";
|
|
||||||
static const char acName1604_00[] = "Max SubIndex";
|
|
||||||
static const char acName1604_01[] = "ActualTorque";
|
|
||||||
static const char acName1605[] = "EncoderIn";
|
|
||||||
static const char acName1605_00[] = "Max SubIndex";
|
|
||||||
static const char acName1605_01[] = "IndexEnable";
|
|
||||||
static const char acName1605_02[] = "Reset";
|
|
||||||
static const char acName1A00[] = "EncoderOut";
|
|
||||||
static const char acName1A00_00[] = "Max SubIndex";
|
static const char acName1A00_00[] = "Max SubIndex";
|
||||||
static const char acName1A00_01[] = "ECount";
|
static const char acName1A00_01[] = "EncPos";
|
||||||
static const char acName1A00_02[] = "IndexTriggered";
|
static const char acName1A01[] = "EncFrequency";
|
||||||
static const char acName1A01[] = "ControlWord";
|
|
||||||
static const char acName1A01_00[] = "Max SubIndex";
|
static const char acName1A01_00[] = "Max SubIndex";
|
||||||
static const char acName1A01_01[] = "ControlWord";
|
static const char acName1A01_01[] = "EncFrequency";
|
||||||
static const char acName1A02[] = "OpMode";
|
static const char acName1A02[] = "DiffT";
|
||||||
static const char acName1A02_00[] = "Max SubIndex";
|
static const char acName1A02_00[] = "Max SubIndex";
|
||||||
static const char acName1A02_01[] = "OpMode";
|
static const char acName1A02_01[] = "DiffT";
|
||||||
static const char acName1A03[] = "TargetPosition";
|
static const char acName1A03[] = "IndexByte";
|
||||||
static const char acName1A03_00[] = "Max SubIndex";
|
static const char acName1A03_00[] = "Max SubIndex";
|
||||||
static const char acName1A03_01[] = "TargetPosition";
|
static const char acName1A03_01[] = "IndexByte";
|
||||||
static const char acName1A04[] = "TargetVelocity";
|
static const char acName1A04[] = "IndexStatus";
|
||||||
static const char acName1A04_00[] = "Max SubIndex";
|
static const char acName1A04_00[] = "Max SubIndex";
|
||||||
static const char acName1A04_01[] = "TargetVelocity";
|
static const char acName1A04_01[] = "IndexStatus";
|
||||||
static const char acName1C00[] = "Sync Manager Communication Type";
|
static const char acName1C00[] = "Sync Manager Communication Type";
|
||||||
static const char acName1C00_00[] = "Max SubIndex";
|
static const char acName1C00_00[] = "Max SubIndex";
|
||||||
static const char acName1C00_01[] = "Communications Type SM0";
|
static const char acName1C00_01[] = "Communications Type SM0";
|
||||||
@@ -58,10 +44,6 @@ static const char acName1C12[] = "Sync Manager 2 PDO Assignment";
|
|||||||
static const char acName1C12_00[] = "Max SubIndex";
|
static const char acName1C12_00[] = "Max SubIndex";
|
||||||
static const char acName1C12_01[] = "PDO Mapping";
|
static const char acName1C12_01[] = "PDO Mapping";
|
||||||
static const char acName1C12_02[] = "PDO Mapping";
|
static const char acName1C12_02[] = "PDO Mapping";
|
||||||
static const char acName1C12_03[] = "PDO Mapping";
|
|
||||||
static const char acName1C12_04[] = "PDO Mapping";
|
|
||||||
static const char acName1C12_05[] = "PDO Mapping";
|
|
||||||
static const char acName1C12_06[] = "PDO Mapping";
|
|
||||||
static const char acName1C13[] = "Sync Manager 3 PDO Assignment";
|
static const char acName1C13[] = "Sync Manager 3 PDO Assignment";
|
||||||
static const char acName1C13_00[] = "Max SubIndex";
|
static const char acName1C13_00[] = "Max SubIndex";
|
||||||
static const char acName1C13_01[] = "PDO Mapping";
|
static const char acName1C13_01[] = "PDO Mapping";
|
||||||
@@ -69,27 +51,13 @@ static const char acName1C13_02[] = "PDO Mapping";
|
|||||||
static const char acName1C13_03[] = "PDO Mapping";
|
static const char acName1C13_03[] = "PDO Mapping";
|
||||||
static const char acName1C13_04[] = "PDO Mapping";
|
static const char acName1C13_04[] = "PDO Mapping";
|
||||||
static const char acName1C13_05[] = "PDO Mapping";
|
static const char acName1C13_05[] = "PDO Mapping";
|
||||||
static const char acName2000[] = "StepperData";
|
static const char acName6000[] = "EncPos";
|
||||||
static const char acName2000_00[] = "Max SubIndex";
|
static const char acName6001[] = "EncFrequency";
|
||||||
static const char acName2000_01[] = "Period";
|
static const char acName6002[] = "DiffT";
|
||||||
static const char acName2000_02[] = "Resolution";
|
static const char acName6003[] = "IndexByte";
|
||||||
static const char acName6000[] = "EncoderOut";
|
static const char acName6004[] = "IndexStatus";
|
||||||
static const char acName6000_00[] = "Max SubIndex";
|
static const char acName7000[] = "EncPosScale";
|
||||||
static const char acName6000_01[] = "ECount";
|
static const char acName7001[] = "IndexLatchEnable";
|
||||||
static const char acName6000_02[] = "IndexTriggered";
|
|
||||||
static const char acName6040[] = "ControlWord";
|
|
||||||
static const char acName6041[] = "StatusWord";
|
|
||||||
static const char acName6060[] = "OpMode";
|
|
||||||
static const char acName6061[] = "OpModeDisplay";
|
|
||||||
static const char acName6064[] = "ActualPosition";
|
|
||||||
static const char acName606C[] = "ActualVelocity";
|
|
||||||
static const char acName6077[] = "ActualTorque";
|
|
||||||
static const char acName607A[] = "TargetPosition";
|
|
||||||
static const char acName60FF[] = "TargetVelocity";
|
|
||||||
static const char acName7000[] = "EncoderIn";
|
|
||||||
static const char acName7000_00[] = "Max SubIndex";
|
|
||||||
static const char acName7000_01[] = "IndexEnable";
|
|
||||||
static const char acName7000_02[] = "Reset";
|
|
||||||
|
|
||||||
const _objd SDO1000[] =
|
const _objd SDO1000[] =
|
||||||
{
|
{
|
||||||
@@ -97,80 +65,58 @@ const _objd SDO1000[] =
|
|||||||
};
|
};
|
||||||
const _objd SDO1008[] =
|
const _objd SDO1008[] =
|
||||||
{
|
{
|
||||||
{0x0, DTYPE_VISIBLE_STRING, 272, ATYPE_RO, acName1008, 0, "MetalMusings EaserCAT 2000 encoder"},
|
{0x0, DTYPE_VISIBLE_STRING, 208, ATYPE_RO, acName1008, 0, "MetalMusings EaserCAT 2000"},
|
||||||
};
|
};
|
||||||
const _objd SDO1009[] =
|
const _objd SDO1009[] =
|
||||||
{
|
{
|
||||||
{0x0, DTYPE_VISIBLE_STRING, 8, ATYPE_RO, acName1009, 0, "3"},
|
{0x0, DTYPE_VISIBLE_STRING, 40, ATYPE_RO, acName1009, 0, "0.0.1"},
|
||||||
};
|
};
|
||||||
const _objd SDO100A[] =
|
const _objd SDO100A[] =
|
||||||
{
|
{
|
||||||
{0x0, DTYPE_VISIBLE_STRING, 8, ATYPE_RO, acName100A, 0, "4"},
|
{0x0, DTYPE_VISIBLE_STRING, 40, ATYPE_RO, acName100A, 0, "0.0.1"},
|
||||||
};
|
};
|
||||||
const _objd SDO1018[] =
|
const _objd SDO1018[] =
|
||||||
{
|
{
|
||||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1018_00, 4, NULL},
|
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1018_00, 4, NULL},
|
||||||
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1018_01, 4321, NULL},
|
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1018_01, 2730, NULL},
|
||||||
{0x02, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1018_02, 1234, NULL},
|
{0x02, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1018_02, 12303564, NULL},
|
||||||
{0x03, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1018_03, 1, NULL},
|
{0x03, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1018_03, 2, NULL},
|
||||||
{0x04, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1018_04, 2, &Obj.serial},
|
{0x04, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1018_04, 1, &Obj.serial},
|
||||||
};
|
};
|
||||||
const _objd SDO1600[] =
|
const _objd SDO1600[] =
|
||||||
{
|
{
|
||||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1600_00, 1, NULL},
|
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1600_00, 1, NULL},
|
||||||
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1600_01, 0x60410010, NULL},
|
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1600_01, 0x70000020, NULL},
|
||||||
};
|
};
|
||||||
const _objd SDO1601[] =
|
const _objd SDO1601[] =
|
||||||
{
|
{
|
||||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1601_00, 1, NULL},
|
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1601_00, 1, NULL},
|
||||||
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1601_01, 0x60610008, NULL},
|
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1601_01, 0x70010020, NULL},
|
||||||
};
|
|
||||||
const _objd SDO1602[] =
|
|
||||||
{
|
|
||||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1602_00, 1, NULL},
|
|
||||||
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1602_01, 0x60640020, NULL},
|
|
||||||
};
|
|
||||||
const _objd SDO1603[] =
|
|
||||||
{
|
|
||||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1603_00, 1, NULL},
|
|
||||||
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1603_01, 0x606C0020, NULL},
|
|
||||||
};
|
|
||||||
const _objd SDO1604[] =
|
|
||||||
{
|
|
||||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1604_00, 1, NULL},
|
|
||||||
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1604_01, 0x60770020, NULL},
|
|
||||||
};
|
|
||||||
const _objd SDO1605[] =
|
|
||||||
{
|
|
||||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1605_00, 2, NULL},
|
|
||||||
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1605_01, 0x70000108, NULL},
|
|
||||||
{0x02, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1605_02, 0x70000208, NULL},
|
|
||||||
};
|
};
|
||||||
const _objd SDO1A00[] =
|
const _objd SDO1A00[] =
|
||||||
{
|
{
|
||||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1A00_00, 2, NULL},
|
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1A00_00, 1, NULL},
|
||||||
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1A00_01, 0x60000120, NULL},
|
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1A00_01, 0x60000020, NULL},
|
||||||
{0x02, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1A00_02, 0x60000208, NULL},
|
|
||||||
};
|
};
|
||||||
const _objd SDO1A01[] =
|
const _objd SDO1A01[] =
|
||||||
{
|
{
|
||||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1A01_00, 1, NULL},
|
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1A01_00, 1, NULL},
|
||||||
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1A01_01, 0x60400010, NULL},
|
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1A01_01, 0x60010020, NULL},
|
||||||
};
|
};
|
||||||
const _objd SDO1A02[] =
|
const _objd SDO1A02[] =
|
||||||
{
|
{
|
||||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1A02_00, 1, NULL},
|
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1A02_00, 1, NULL},
|
||||||
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1A02_01, 0x60600008, NULL},
|
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1A02_01, 0x60020020, NULL},
|
||||||
};
|
};
|
||||||
const _objd SDO1A03[] =
|
const _objd SDO1A03[] =
|
||||||
{
|
{
|
||||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1A03_00, 1, NULL},
|
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1A03_00, 1, NULL},
|
||||||
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1A03_01, 0x607A0020, NULL},
|
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1A03_01, 0x60030020, NULL},
|
||||||
};
|
};
|
||||||
const _objd SDO1A04[] =
|
const _objd SDO1A04[] =
|
||||||
{
|
{
|
||||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1A04_00, 1, NULL},
|
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1A04_00, 1, NULL},
|
||||||
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1A04_01, 0x60FF0020, NULL},
|
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1A04_01, 0x60040020, NULL},
|
||||||
};
|
};
|
||||||
const _objd SDO1C00[] =
|
const _objd SDO1C00[] =
|
||||||
{
|
{
|
||||||
@@ -182,13 +128,9 @@ const _objd SDO1C00[] =
|
|||||||
};
|
};
|
||||||
const _objd SDO1C12[] =
|
const _objd SDO1C12[] =
|
||||||
{
|
{
|
||||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1C12_00, 6, NULL},
|
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1C12_00, 2, NULL},
|
||||||
{0x01, DTYPE_UNSIGNED16, 16, ATYPE_RO, acName1C12_01, 0x1600, NULL},
|
{0x01, DTYPE_UNSIGNED16, 16, ATYPE_RO, acName1C12_01, 0x1600, NULL},
|
||||||
{0x02, DTYPE_UNSIGNED16, 16, ATYPE_RO, acName1C12_02, 0x1601, NULL},
|
{0x02, DTYPE_UNSIGNED16, 16, ATYPE_RO, acName1C12_02, 0x1601, NULL},
|
||||||
{0x03, DTYPE_UNSIGNED16, 16, ATYPE_RO, acName1C12_03, 0x1602, NULL},
|
|
||||||
{0x04, DTYPE_UNSIGNED16, 16, ATYPE_RO, acName1C12_04, 0x1603, NULL},
|
|
||||||
{0x05, DTYPE_UNSIGNED16, 16, ATYPE_RO, acName1C12_05, 0x1604, NULL},
|
|
||||||
{0x06, DTYPE_UNSIGNED16, 16, ATYPE_RO, acName1C12_06, 0x1605, NULL},
|
|
||||||
};
|
};
|
||||||
const _objd SDO1C13[] =
|
const _objd SDO1C13[] =
|
||||||
{
|
{
|
||||||
@@ -199,59 +141,33 @@ const _objd SDO1C13[] =
|
|||||||
{0x04, DTYPE_UNSIGNED16, 16, ATYPE_RO, acName1C13_04, 0x1A03, NULL},
|
{0x04, DTYPE_UNSIGNED16, 16, ATYPE_RO, acName1C13_04, 0x1A03, NULL},
|
||||||
{0x05, DTYPE_UNSIGNED16, 16, ATYPE_RO, acName1C13_05, 0x1A04, NULL},
|
{0x05, DTYPE_UNSIGNED16, 16, ATYPE_RO, acName1C13_05, 0x1A04, NULL},
|
||||||
};
|
};
|
||||||
const _objd SDO2000[] =
|
|
||||||
{
|
|
||||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName2000_00, 2, NULL},
|
|
||||||
{0x01, DTYPE_UNSIGNED16, 16, ATYPE_RO, acName2000_01, 1000, &Obj.StepperData.Period},
|
|
||||||
{0x02, DTYPE_REAL32, 32, ATYPE_RO, acName2000_02, 0x40200000, &Obj.StepperData.Resolution},
|
|
||||||
};
|
|
||||||
const _objd SDO6000[] =
|
const _objd SDO6000[] =
|
||||||
{
|
{
|
||||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName6000_00, 2, NULL},
|
{0x0, DTYPE_REAL32, 32, ATYPE_RO | ATYPE_TXPDO, acName6000, 0x00000000, &Obj.EncPos},
|
||||||
{0x01, DTYPE_INTEGER32, 32, ATYPE_RO, acName6000_01, 0, &Obj.EncoderOut.ECount},
|
|
||||||
{0x02, DTYPE_UNSIGNED8, 8, ATYPE_RW, acName6000_02, 0, &Obj.EncoderOut.IndexTriggered},
|
|
||||||
};
|
};
|
||||||
const _objd SDO6040[] =
|
const _objd SDO6001[] =
|
||||||
{
|
{
|
||||||
{0x0, DTYPE_UNSIGNED16, 16, ATYPE_RO | ATYPE_TXPDO, acName6040, 0, &Obj.ControlWord},
|
{0x0, DTYPE_REAL32, 32, ATYPE_RO | ATYPE_TXPDO, acName6001, 0x00000000, &Obj.EncFrequency},
|
||||||
};
|
};
|
||||||
const _objd SDO6041[] =
|
const _objd SDO6002[] =
|
||||||
{
|
{
|
||||||
{0x0, DTYPE_UNSIGNED16, 16, ATYPE_RO | ATYPE_RXPDO, acName6041, 0, &Obj.StatusWord},
|
{0x0, DTYPE_UNSIGNED32, 32, ATYPE_RO | ATYPE_TXPDO, acName6002, 0, &Obj.DiffT},
|
||||||
};
|
};
|
||||||
const _objd SDO6060[] =
|
const _objd SDO6003[] =
|
||||||
{
|
{
|
||||||
{0x0, DTYPE_UNSIGNED8, 8, ATYPE_RO | ATYPE_TXPDO, acName6060, 0, &Obj.OpMode},
|
{0x0, DTYPE_UNSIGNED32, 32, ATYPE_RO | ATYPE_TXPDO, acName6003, 0, &Obj.IndexByte},
|
||||||
};
|
};
|
||||||
const _objd SDO6061[] =
|
const _objd SDO6004[] =
|
||||||
{
|
{
|
||||||
{0x0, DTYPE_UNSIGNED8, 8, ATYPE_RO | ATYPE_RXPDO, acName6061, 0, &Obj.OpModeDisplay},
|
{0x0, DTYPE_UNSIGNED32, 32, ATYPE_RO | ATYPE_TXPDO, acName6004, 0, &Obj.IndexStatus},
|
||||||
};
|
|
||||||
const _objd SDO6064[] =
|
|
||||||
{
|
|
||||||
{0x0, DTYPE_INTEGER32, 32, ATYPE_RO | ATYPE_RXPDO, acName6064, 0, &Obj.ActualPosition},
|
|
||||||
};
|
|
||||||
const _objd SDO606C[] =
|
|
||||||
{
|
|
||||||
{0x0, DTYPE_INTEGER32, 32, ATYPE_RO | ATYPE_RXPDO, acName606C, 0, &Obj.ActualVelocity},
|
|
||||||
};
|
|
||||||
const _objd SDO6077[] =
|
|
||||||
{
|
|
||||||
{0x0, DTYPE_INTEGER32, 32, ATYPE_RO | ATYPE_RXPDO, acName6077, 0, &Obj.ActualTorque},
|
|
||||||
};
|
|
||||||
const _objd SDO607A[] =
|
|
||||||
{
|
|
||||||
{0x0, DTYPE_INTEGER32, 32, ATYPE_RO | ATYPE_TXPDO, acName607A, 0, &Obj.TargetPosition},
|
|
||||||
};
|
|
||||||
const _objd SDO60FF[] =
|
|
||||||
{
|
|
||||||
{0x0, DTYPE_INTEGER32, 32, ATYPE_RO | ATYPE_TXPDO, acName60FF, 0, &Obj.TargetVelocity},
|
|
||||||
};
|
};
|
||||||
const _objd SDO7000[] =
|
const _objd SDO7000[] =
|
||||||
{
|
{
|
||||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName7000_00, 2, NULL},
|
{0x0, DTYPE_INTEGER32, 32, ATYPE_RO | ATYPE_RXPDO, acName7000, 0, &Obj.EncPosScale},
|
||||||
{0x01, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName7000_01, 0, &Obj.EncoderIn.IndexEnable},
|
};
|
||||||
{0x02, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName7000_02, 0, &Obj.EncoderIn.Reset},
|
const _objd SDO7001[] =
|
||||||
|
{
|
||||||
|
{0x0, DTYPE_UNSIGNED32, 32, ATYPE_RO | ATYPE_RXPDO, acName7001, 0, &Obj.IndexLatchEnable},
|
||||||
};
|
};
|
||||||
|
|
||||||
const _objectlist SDOobjects[] =
|
const _objectlist SDOobjects[] =
|
||||||
@@ -263,29 +179,20 @@ const _objectlist SDOobjects[] =
|
|||||||
{0x1018, OTYPE_RECORD, 4, 0, acName1018, SDO1018},
|
{0x1018, OTYPE_RECORD, 4, 0, acName1018, SDO1018},
|
||||||
{0x1600, OTYPE_RECORD, 1, 0, acName1600, SDO1600},
|
{0x1600, OTYPE_RECORD, 1, 0, acName1600, SDO1600},
|
||||||
{0x1601, OTYPE_RECORD, 1, 0, acName1601, SDO1601},
|
{0x1601, OTYPE_RECORD, 1, 0, acName1601, SDO1601},
|
||||||
{0x1602, OTYPE_RECORD, 1, 0, acName1602, SDO1602},
|
{0x1A00, OTYPE_RECORD, 1, 0, acName1A00, SDO1A00},
|
||||||
{0x1603, OTYPE_RECORD, 1, 0, acName1603, SDO1603},
|
|
||||||
{0x1604, OTYPE_RECORD, 1, 0, acName1604, SDO1604},
|
|
||||||
{0x1605, OTYPE_RECORD, 2, 0, acName1605, SDO1605},
|
|
||||||
{0x1A00, OTYPE_RECORD, 2, 0, acName1A00, SDO1A00},
|
|
||||||
{0x1A01, OTYPE_RECORD, 1, 0, acName1A01, SDO1A01},
|
{0x1A01, OTYPE_RECORD, 1, 0, acName1A01, SDO1A01},
|
||||||
{0x1A02, OTYPE_RECORD, 1, 0, acName1A02, SDO1A02},
|
{0x1A02, OTYPE_RECORD, 1, 0, acName1A02, SDO1A02},
|
||||||
{0x1A03, OTYPE_RECORD, 1, 0, acName1A03, SDO1A03},
|
{0x1A03, OTYPE_RECORD, 1, 0, acName1A03, SDO1A03},
|
||||||
{0x1A04, OTYPE_RECORD, 1, 0, acName1A04, SDO1A04},
|
{0x1A04, OTYPE_RECORD, 1, 0, acName1A04, SDO1A04},
|
||||||
{0x1C00, OTYPE_ARRAY, 4, 0, acName1C00, SDO1C00},
|
{0x1C00, OTYPE_ARRAY, 4, 0, acName1C00, SDO1C00},
|
||||||
{0x1C12, OTYPE_ARRAY, 6, 0, acName1C12, SDO1C12},
|
{0x1C12, OTYPE_ARRAY, 2, 0, acName1C12, SDO1C12},
|
||||||
{0x1C13, OTYPE_ARRAY, 5, 0, acName1C13, SDO1C13},
|
{0x1C13, OTYPE_ARRAY, 5, 0, acName1C13, SDO1C13},
|
||||||
{0x2000, OTYPE_RECORD, 2, 0, acName2000, SDO2000},
|
{0x6000, OTYPE_VAR, 0, 0, acName6000, SDO6000},
|
||||||
{0x6000, OTYPE_RECORD, 2, 0, acName6000, SDO6000},
|
{0x6001, OTYPE_VAR, 0, 0, acName6001, SDO6001},
|
||||||
{0x6040, OTYPE_VAR, 0, 0, acName6040, SDO6040},
|
{0x6002, OTYPE_VAR, 0, 0, acName6002, SDO6002},
|
||||||
{0x6041, OTYPE_VAR, 0, 0, acName6041, SDO6041},
|
{0x6003, OTYPE_VAR, 0, 0, acName6003, SDO6003},
|
||||||
{0x6060, OTYPE_VAR, 0, 0, acName6060, SDO6060},
|
{0x6004, OTYPE_VAR, 0, 0, acName6004, SDO6004},
|
||||||
{0x6061, OTYPE_VAR, 0, 0, acName6061, SDO6061},
|
{0x7000, OTYPE_VAR, 0, 0, acName7000, SDO7000},
|
||||||
{0x6064, OTYPE_VAR, 0, 0, acName6064, SDO6064},
|
{0x7001, OTYPE_VAR, 0, 0, acName7001, SDO7001},
|
||||||
{0x606C, OTYPE_VAR, 0, 0, acName606C, SDO606C},
|
|
||||||
{0x6077, OTYPE_VAR, 0, 0, acName6077, SDO6077},
|
|
||||||
{0x607A, OTYPE_VAR, 0, 0, acName607A, SDO607A},
|
|
||||||
{0x60FF, OTYPE_VAR, 0, 0, acName60FF, SDO60FF},
|
|
||||||
{0x7000, OTYPE_RECORD, 2, 0, acName7000, SDO7000},
|
|
||||||
{0xffff, 0xff, 0xff, 0xff, NULL, NULL}
|
{0xffff, 0xff, 0xff, 0xff, NULL, NULL}
|
||||||
};
|
};
|
||||||
|
|||||||
@@ -13,36 +13,17 @@ typedef struct
|
|||||||
|
|
||||||
/* Inputs */
|
/* Inputs */
|
||||||
|
|
||||||
struct
|
float EncPos;
|
||||||
{
|
float EncFrequency;
|
||||||
int32_t ECount;
|
uint32_t DiffT;
|
||||||
uint8_t IndexTriggered;
|
uint32_t IndexByte;
|
||||||
} EncoderOut;
|
uint32_t IndexStatus;
|
||||||
uint16_t ControlWord;
|
|
||||||
uint8_t OpMode;
|
|
||||||
int32_t TargetPosition;
|
|
||||||
int32_t TargetVelocity;
|
|
||||||
|
|
||||||
/* Outputs */
|
/* Outputs */
|
||||||
|
|
||||||
uint16_t StatusWord;
|
int32_t EncPosScale;
|
||||||
uint8_t OpModeDisplay;
|
uint32_t IndexLatchEnable;
|
||||||
int32_t ActualPosition;
|
|
||||||
int32_t ActualVelocity;
|
|
||||||
int32_t ActualTorque;
|
|
||||||
struct
|
|
||||||
{
|
|
||||||
uint8_t IndexEnable;
|
|
||||||
uint8_t Reset;
|
|
||||||
} EncoderIn;
|
|
||||||
|
|
||||||
/* Parameters */
|
|
||||||
|
|
||||||
struct
|
|
||||||
{
|
|
||||||
uint16_t Period;
|
|
||||||
float Resolution;
|
|
||||||
} StepperData;
|
|
||||||
} _Objects;
|
} _Objects;
|
||||||
|
|
||||||
extern _Objects Obj;
|
extern _Objects Obj;
|
||||||
|
|||||||
@@ -14,9 +14,10 @@ platform = ststm32
|
|||||||
board = genericSTM32F407VGT6
|
board = genericSTM32F407VGT6
|
||||||
upload_protocol = stlink
|
upload_protocol = stlink
|
||||||
debug_tool = stlink
|
debug_tool = stlink
|
||||||
debug_build_flags = -O0 -g -ggdb
|
debug_build_flags = -O0 -g -ggdb
|
||||||
monitor_port = COM7
|
monitor_port = COM7
|
||||||
monitor_speed = 115200
|
monitor_speed = 115200
|
||||||
build_flags = -Wl,--no-warn-rwx-segment
|
build_flags = -Wl,--no-warn-rwx-segment
|
||||||
lib_deps =
|
lib_deps =
|
||||||
SPI
|
SPI
|
||||||
|
rlogiacco/CircularBuffer@^1.3.3
|
||||||
|
|||||||
@@ -6,44 +6,81 @@ extern "C"
|
|||||||
#include "ecat_slv.h"
|
#include "ecat_slv.h"
|
||||||
#include "utypes.h"
|
#include "utypes.h"
|
||||||
};
|
};
|
||||||
|
#include <CircularBuffer.h>
|
||||||
|
#define RINGBUFFERLEN 101
|
||||||
|
CircularBuffer<double_t, RINGBUFFERLEN> Pos;
|
||||||
|
CircularBuffer<uint32_t, RINGBUFFERLEN> TDelta;
|
||||||
|
|
||||||
int64_t PreviousEncoderCounterValue = 0;
|
int64_t PreviousEncoderCounterValue = 0;
|
||||||
int64_t unwrap_encoder(uint16_t in, int64_t *prev);
|
int64_t unwrap_encoder(uint16_t in, int64_t *prev);
|
||||||
#include <Stm32F4_Encoder.h>
|
#include <Stm32F4_Encoder.h>
|
||||||
Encoder EncoderInit;
|
Encoder EncoderInit;
|
||||||
|
Encoder *encP = &EncoderInit;
|
||||||
|
|
||||||
#include "Stepper.h"
|
// #include "Stepper.h"
|
||||||
|
#define INDEX_PIN PA2
|
||||||
HardwareSerial Serial1(PA10, PA9);
|
HardwareSerial Serial1(PA10, PA9);
|
||||||
_Objects Obj;
|
_Objects Obj;
|
||||||
|
|
||||||
void StepGen(void);
|
void indexPulse(void);
|
||||||
|
double PosScaleRes = 1.0;
|
||||||
|
uint32_t CurPosScale = 1;
|
||||||
|
uint8_t OldLatchCEnable = 0;
|
||||||
|
volatile uint8_t indexPulseFired = 0;
|
||||||
|
uint32_t nFires = 0;
|
||||||
|
volatile uint8_t pleaseZeroTheCounter = 0;
|
||||||
|
uint32_t PrevTime = 0, Prev2Time = 0;
|
||||||
|
|
||||||
volatile uint8_t IndexEnable = 1;
|
|
||||||
volatile uint8_t IndexTriggered = 0;
|
|
||||||
void cb_set_outputs(void) // Master outputs gets here, slave inputs, first operation
|
void cb_set_outputs(void) // Master outputs gets here, slave inputs, first operation
|
||||||
{
|
{
|
||||||
IndexEnable = Obj.EncoderIn.IndexEnable;
|
if (Obj.IndexLatchEnable && !OldLatchCEnable) // Should only happen first time IndexCEnable is set
|
||||||
if (!IndexEnable)
|
{
|
||||||
IndexTriggered = 0;
|
pleaseZeroTheCounter = 1;
|
||||||
|
}
|
||||||
|
OldLatchCEnable = Obj.IndexLatchEnable;
|
||||||
|
|
||||||
|
if (CurPosScale != Obj.EncPosScale && Obj.EncPosScale != 0)
|
||||||
|
{
|
||||||
|
CurPosScale = Obj.EncPosScale;
|
||||||
|
PosScaleRes = 1.0 / double(CurPosScale);
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void cb_get_inputs(void) // Set Master inputs, slave outputs, last operation
|
void cb_get_inputs(void) // Set Master inputs, slave outputs, last operation
|
||||||
{
|
{
|
||||||
// Obj.EncoderOut.ECount = TIM2->CNT;
|
Obj.IndexStatus = 0;
|
||||||
Obj.EncoderOut.ECount = unwrap_encoder(TIM2->CNT, &PreviousEncoderCounterValue);
|
if (indexPulseFired)
|
||||||
Obj.EncoderOut.IndexTriggered = IndexTriggered;
|
{
|
||||||
uint32_t diffT = ESCvar.Time - ESCvar.PrevTime;
|
Obj.IndexStatus = 1;
|
||||||
|
indexPulseFired = 0;
|
||||||
|
nFires++;
|
||||||
|
PreviousEncoderCounterValue = 0;
|
||||||
|
}
|
||||||
|
uint64_t now = micros(); // Exploring the cycle times
|
||||||
|
Obj.DiffT = now - Prev2Time;
|
||||||
|
Prev2Time = PrevTime;
|
||||||
|
PrevTime = now;
|
||||||
|
|
||||||
|
int64_t pos = unwrap_encoder(TIM2->CNT, &PreviousEncoderCounterValue);
|
||||||
|
double CurPos = pos * PosScaleRes;
|
||||||
|
Obj.EncPos = CurPos;
|
||||||
|
|
||||||
|
double diffT = 0;
|
||||||
|
double diffPos = 0;
|
||||||
|
TDelta.push(ESCvar.Time); // Running average over the length of the circular buffer
|
||||||
|
Pos.push(CurPos);
|
||||||
|
if (Pos.size() >= 2)
|
||||||
|
{
|
||||||
|
diffT = 1.0e-9 * (TDelta.last() - TDelta.first()); // Time is in nanoseconds
|
||||||
|
diffPos = fabs(Pos.last() - Pos.first());
|
||||||
|
}
|
||||||
|
Obj.EncFrequency = diffT != 0 ? diffPos / diffT : 0.0; // Revolutions per second
|
||||||
|
|
||||||
|
Obj.IndexByte = digitalRead(INDEX_PIN);
|
||||||
|
if (Obj.IndexByte)
|
||||||
|
Serial1.printf("IS 1\n");
|
||||||
}
|
}
|
||||||
|
|
||||||
void indexPulse(void)
|
|
||||||
{
|
|
||||||
if (IndexEnable && !IndexTriggered)
|
|
||||||
{
|
|
||||||
TIM2->CNT = 0;
|
|
||||||
IndexTriggered = 1;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
static esc_cfg_t config =
|
static esc_cfg_t config =
|
||||||
{
|
{
|
||||||
.user_arg = NULL,
|
.user_arg = NULL,
|
||||||
@@ -52,7 +89,7 @@ static esc_cfg_t config =
|
|||||||
.set_defaults_hook = NULL,
|
.set_defaults_hook = NULL,
|
||||||
.pre_state_change_hook = NULL,
|
.pre_state_change_hook = NULL,
|
||||||
.post_state_change_hook = NULL,
|
.post_state_change_hook = NULL,
|
||||||
.application_hook = StepGen,
|
.application_hook = NULL, // StepGen,
|
||||||
.safeoutput_override = NULL,
|
.safeoutput_override = NULL,
|
||||||
.pre_object_download_hook = NULL,
|
.pre_object_download_hook = NULL,
|
||||||
.post_object_download_hook = NULL,
|
.post_object_download_hook = NULL,
|
||||||
@@ -66,23 +103,17 @@ static esc_cfg_t config =
|
|||||||
|
|
||||||
void setup(void)
|
void setup(void)
|
||||||
{
|
{
|
||||||
uint64_t ff = F_CPU;
|
|
||||||
Serial1.begin(115200);
|
Serial1.begin(115200);
|
||||||
rcc_config();
|
rcc_config();
|
||||||
|
|
||||||
// Set starting count value
|
// Set starting count value
|
||||||
// EncoderInit.SetCount(Tim2, 0);
|
EncoderInit.SetCount(Tim2, 0);
|
||||||
// EncoderInit.SetCount(Tim3, 0);
|
// EncoderInit.SetCount(Tim3, 0);
|
||||||
// EncoderInit.SetCount(Tim4, 0);
|
// EncoderInit.SetCount(Tim4, 0);
|
||||||
// EncoderInit.SetCount(Tim8, 0);
|
// EncoderInit.SetCount(Tim8, 0);
|
||||||
|
|
||||||
attachInterrupt(digitalPinToInterrupt(PA2), indexPulse, RISING); // PA2 = Index pulse
|
|
||||||
StepperSetup();
|
|
||||||
// delay(5000); // To give serial port monitor time to receive
|
|
||||||
Serial1.printf("Before Ecat config\n");
|
|
||||||
ecat_slv_init(&config);
|
ecat_slv_init(&config);
|
||||||
|
attachInterrupt(digitalPinToInterrupt(INDEX_PIN), indexPulse, RISING); // Always when Index triggered
|
||||||
Serial1.printf("Started\n");
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void loop(void)
|
void loop(void)
|
||||||
@@ -110,16 +141,14 @@ int64_t unwrap_encoder(uint16_t in, int64_t *prev)
|
|||||||
return unwrapped + HALF_PERIOD; // remove the shift we applied at the beginning, and return
|
return unwrapped + HALF_PERIOD; // remove the shift we applied at the beginning, and return
|
||||||
}
|
}
|
||||||
|
|
||||||
void StepGen(void)
|
void indexPulse(void)
|
||||||
{
|
{
|
||||||
uint16_t Period = Obj.StepperData.Period; // Period in microseconds, so 1000 is 1 ms.
|
if (pleaseZeroTheCounter)
|
||||||
|
{
|
||||||
float StepperResolution = Obj.StepperData.Resolution; // 2.5 pulses/um
|
TIM2->CNT = 0;
|
||||||
int32_t TargetPosition = Obj.TargetPosition; // um
|
indexPulseFired = 1;
|
||||||
int32_t ActualPosition = 0; // um
|
Pos.clear();
|
||||||
int32_t DistanceToGo = TargetPosition - ActualPosition; // um
|
TDelta.clear();
|
||||||
int32_t PulsesToMake = DistanceToGo * StepperResolution;
|
pleaseZeroTheCounter = 0;
|
||||||
int32_t Frequency = PulsesToMake * 1000000 / Period;
|
}
|
||||||
|
|
||||||
// Check if timer done.
|
|
||||||
}
|
}
|
||||||
@@ -1 +1,3 @@
|
|||||||
fp-info-cache
|
fp-info-cache
|
||||||
|
Ethercat-stm32-backup*
|
||||||
|
*.lck
|
||||||
|
|||||||
@@ -64,7 +64,7 @@
|
|||||||
39,
|
39,
|
||||||
40
|
40
|
||||||
],
|
],
|
||||||
"visible_layers": "002ffe8_00000001",
|
"visible_layers": "002202a_00000001",
|
||||||
"zone_display_mode": 0
|
"zone_display_mode": 0
|
||||||
},
|
},
|
||||||
"meta": {
|
"meta": {
|
||||||
|
|||||||
@@ -1573,7 +1573,7 @@
|
|||||||
(effects (font (size 1.27 1.27)))
|
(effects (font (size 1.27 1.27)))
|
||||||
)
|
)
|
||||||
(property "Value" "22" (at 212.09 106.68 90)
|
(property "Value" "22" (at 212.09 106.68 90)
|
||||||
(effects (font (size 1.27 1.27)) hide)
|
(effects (font (size 1.27 1.27)))
|
||||||
)
|
)
|
||||||
(property "Footprint" "Resistor_SMD:R_0805_2012Metric" (at 207.01 106.172 90)
|
(property "Footprint" "Resistor_SMD:R_0805_2012Metric" (at 207.01 106.172 90)
|
||||||
(effects (font (size 1.27 1.27)) hide)
|
(effects (font (size 1.27 1.27)) hide)
|
||||||
@@ -1731,7 +1731,7 @@
|
|||||||
(effects (font (size 1.27 1.27)))
|
(effects (font (size 1.27 1.27)))
|
||||||
)
|
)
|
||||||
(property "Value" "22" (at 212.09 116.84 90)
|
(property "Value" "22" (at 212.09 116.84 90)
|
||||||
(effects (font (size 1.27 1.27)) hide)
|
(effects (font (size 1.27 1.27)))
|
||||||
)
|
)
|
||||||
(property "Footprint" "Resistor_SMD:R_0805_2012Metric" (at 207.01 116.332 90)
|
(property "Footprint" "Resistor_SMD:R_0805_2012Metric" (at 207.01 116.332 90)
|
||||||
(effects (font (size 1.27 1.27)) hide)
|
(effects (font (size 1.27 1.27)) hide)
|
||||||
|
|||||||
233
Pcb-1-lan9252/LAN9252_eeprom_store_valid/LAN9252_eeprom_store_valid.ino
Executable file
233
Pcb-1-lan9252/LAN9252_eeprom_store_valid/LAN9252_eeprom_store_valid.ino
Executable file
@@ -0,0 +1,233 @@
|
|||||||
|
// Write a valid eeprom for LAN9252.
|
||||||
|
// Uses https://github.com/RobTillaart/I2C_EEPROM
|
||||||
|
//
|
||||||
|
// Wiring:
|
||||||
|
// 4 GND
|
||||||
|
// 5 SDA
|
||||||
|
// 6 SCL
|
||||||
|
// 8 Vcc
|
||||||
|
// (1,2,3,7) A0,A1,A2,WP unconnected => write-enabled at address 0x50
|
||||||
|
//
|
||||||
|
#include <Wire.h>
|
||||||
|
#include <I2C_eeprom.h>
|
||||||
|
const uint8_t eeprom_data[] = {
|
||||||
|
0x80, 0x06, 0x03, 0x44, 0x64, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||||
|
0x00, 0x00, 0x14, 0x00, 0xe1, 0x10, 0x00, 0x00, 0xd2, 0x04, 0x00, 0x00,
|
||||||
|
0x01, 0x00, 0x00, 0x00, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||||
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||||
|
0x00, 0x10, 0x80, 0x00, 0x80, 0x10, 0x80, 0x00, 0x04, 0x00, 0x00, 0x00,
|
||||||
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||||
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||||
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||||
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||||
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||||
|
0x00, 0x00, 0x00, 0x00, 0x0f, 0x00, 0x01, 0x00, 0x0a, 0x00, 0x21, 0x00,
|
||||||
|
0x04, 0x0c, 0x45, 0x61, 0x73, 0x65, 0x72, 0x43, 0x41, 0x54, 0x32, 0x30,
|
||||||
|
0x30, 0x30, 0x09, 0x6d, 0x79, 0x45, 0x6e, 0x63, 0x6f, 0x64, 0x65, 0x72,
|
||||||
|
0x06, 0x49, 0x4d, 0x47, 0x43, 0x42, 0x59, 0x22, 0x4d, 0x65, 0x74, 0x61,
|
||||||
|
0x6c, 0x4d, 0x75, 0x73, 0x69, 0x6e, 0x67, 0x73, 0x20, 0x45, 0x61, 0x73,
|
||||||
|
0x65, 0x72, 0x43, 0x41, 0x54, 0x20, 0x32, 0x30, 0x30, 0x30, 0x20, 0x65,
|
||||||
|
0x6e, 0x63, 0x6f, 0x64, 0x65, 0x72, 0x1e, 0x00, 0x10, 0x00, 0x02, 0x03,
|
||||||
|
0x01, 0x04, 0x00, 0x13, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||||
|
0x00, 0x00, 0x11, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||||
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x28, 0x00, 0x02, 0x00, 0x01, 0x02,
|
||||||
|
0x03, 0x00, 0x29, 0x00, 0x10, 0x00, 0x00, 0x10, 0x80, 0x00, 0x26, 0x00,
|
||||||
|
0x01, 0x01, 0x80, 0x10, 0x80, 0x00, 0x22, 0x00, 0x01, 0x02, 0x00, 0x16,
|
||||||
|
0x00, 0x00, 0x24, 0x00, 0x01, 0x03, 0x00, 0x1a, 0x00, 0x00, 0x20, 0x00,
|
||||||
|
0x01, 0x04, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||||
|
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff
|
||||||
|
};
|
||||||
|
|
||||||
|
|
||||||
|
// 512 kbit bytes
|
||||||
|
#define EEPROM_MAXBYTES 32 * 1024 / 8
|
||||||
|
|
||||||
|
// the address of your EEPROM
|
||||||
|
// 0x50 when A0,A1,A2 are left unconnected
|
||||||
|
#define DEVICEADDRESS (0x50)
|
||||||
|
|
||||||
|
I2C_eeprom eeprom(DEVICEADDRESS, EEPROM_MAXBYTES);
|
||||||
|
|
||||||
|
void setup() {
|
||||||
|
Serial.begin(115200);
|
||||||
|
while (!Serial)
|
||||||
|
;
|
||||||
|
Serial.println("WAIT FOR IT");
|
||||||
|
delay(3000);
|
||||||
|
Serial.println("IT IS BEGINNING");
|
||||||
|
|
||||||
|
Wire.begin();
|
||||||
|
eeprom.begin();
|
||||||
|
#if 0
|
||||||
|
Serial.println("----------------------------------------------");
|
||||||
|
Serial.printf("Writing %d long data\n", sizeof(eeprom_data));
|
||||||
|
uint8_t ok;
|
||||||
|
ok = eeprom.writeBlockVerify(0, eeprom_data, sizeof(eeprom_data));
|
||||||
|
if (ok) {
|
||||||
|
Serial.printf("Success writeBlockVerify\n");
|
||||||
|
} else {
|
||||||
|
Serial.printf("Failed writeBlockVerify\n");
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
Serial.println("----------------------------------------------");
|
||||||
|
Serial.printf("\n VERIFYING\n");
|
||||||
|
for (uint16_t adr = 0; adr < sizeof(eeprom_data); adr++) {
|
||||||
|
uint8_t rB = eeprom.readByte(adr);
|
||||||
|
if (rB != eeprom_data[adr]) {
|
||||||
|
Serial.printf("Not same at addr=%u, read=%u should be %u\n", adr, rB, eeprom_data[adr]);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
Serial.println("----------------------------------------------");
|
||||||
|
Serial.printf("\n VERIFYING DONE\n");
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
void loop() {
|
||||||
|
// Nothing to do during loop
|
||||||
|
}
|
||||||
@@ -30,6 +30,16 @@ The .ioc file can be opened in CubeMX. The STM32F407 processor has functions tie
|
|||||||
|
|
||||||
I have put [Dig_8IN_8OUT.xml](Dig_8IN_8OUT.xml) here, this is an example ESI file for the LAN9252 IC standalone, no MCU needed. It's sometimes handy to have the simplest possible ESI file at ahnd, here it is. You find the ESI file for the Encoder application [here](Firmware/lib/soes/MetalMusings_EaserCAT_2000_encoder.xml)
|
I have put [Dig_8IN_8OUT.xml](Dig_8IN_8OUT.xml) here, this is an example ESI file for the LAN9252 IC standalone, no MCU needed. It's sometimes handy to have the simplest possible ESI file at ahnd, here it is. You find the ESI file for the Encoder application [here](Firmware/lib/soes/MetalMusings_EaserCAT_2000_encoder.xml)
|
||||||
|
|
||||||
|
##### **linuxcnc** contains modifications to make EaserCAT 2000 work
|
||||||
|
|
||||||
|
The configuration files and the hal component I used are placed here.
|
||||||
|
|
||||||
|
##### LAN9252_eeprom_store_valid
|
||||||
|
|
||||||
|
Arduino sketch to program the AT24C32 eeprom with a valid eeprom content. Hook up the eeprom using I2C and run the program. The verification in the of theprogram must be passed for valid programming.
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
###License
|
###License
|
||||||
|
|
||||||
Don't violate the original licenses. No warranties. Use it any way you like.
|
Don't violate the original licenses. No warranties. Use it any way you like.
|
||||||
199
Pcb-1-lan9252/linuxcnc/Turner.hal
Normal file
199
Pcb-1-lan9252/linuxcnc/Turner.hal
Normal file
@@ -0,0 +1,199 @@
|
|||||||
|
# Generated by PNCconf at Sat Sep 10 10:10:56 2016
|
||||||
|
# If you make changes to this file, they will be
|
||||||
|
# overwritten when you run PNCconf again
|
||||||
|
|
||||||
|
loadrt [KINS]KINEMATICS
|
||||||
|
#autoconverted trivkins
|
||||||
|
loadrt [EMCMOT]EMCMOT servo_period_nsec=[EMCMOT]SERVO_PERIOD num_joints=[KINS]JOINTS
|
||||||
|
|
||||||
|
loadusr -W lcec_conf ethercat-conf.xml
|
||||||
|
loadrt lcec
|
||||||
|
loadrt cia402 count=2
|
||||||
|
loadrt metalmusings_encoder
|
||||||
|
|
||||||
|
addf lcec.read-all servo-thread
|
||||||
|
addf cia402.0.read-all servo-thread
|
||||||
|
addf cia402.1.read-all servo-thread
|
||||||
|
addf metalmusings-encoder.0 servo-thread
|
||||||
|
addf motion-command-handler servo-thread
|
||||||
|
addf motion-controller servo-thread
|
||||||
|
|
||||||
|
#*******************
|
||||||
|
# AXIS X
|
||||||
|
#*******************
|
||||||
|
|
||||||
|
# --- joint signals for motion
|
||||||
|
|
||||||
|
net x-pos-cmd <= joint.0.motor-pos-cmd
|
||||||
|
net x-vel-cmd <= joint.0.vel-cmd
|
||||||
|
net x-pos-fb <= joint.0.motor-pos-fb
|
||||||
|
net x-enable <= joint.0.amp-enable-out
|
||||||
|
|
||||||
|
# --- connect stepper driver to joint
|
||||||
|
|
||||||
|
net x-pos-cmd => cia402.0.pos-cmd
|
||||||
|
net x-pos-fb => cia402.0.pos-fb
|
||||||
|
net x-enable => cia402.0.enable
|
||||||
|
|
||||||
|
# --- ect60 settings
|
||||||
|
|
||||||
|
setp cia402.0.csp-mode 1
|
||||||
|
setp cia402.0.pos-scale 5000
|
||||||
|
|
||||||
|
# --- from stepper(ethercat) to cia402
|
||||||
|
|
||||||
|
net x-statusword lcec.0.4.cia-statusword => cia402.0.statusword
|
||||||
|
net x-opmode-display lcec.0.4.opmode-display => cia402.0.opmode-display
|
||||||
|
net x-drv-act-pos lcec.0.4.actual-position => cia402.0.drv-actual-position
|
||||||
|
net x-drv-act-velo lcec.0.4.actual-velocity => cia402.0.drv-actual-velocity
|
||||||
|
|
||||||
|
# --- from cia402 to stepper(ethercat)
|
||||||
|
|
||||||
|
net x-controlword cia402.0.controlword => lcec.0.4.cia-controlword
|
||||||
|
net x-modes-of-operation cia402.0.opmode => lcec.0.4.opmode
|
||||||
|
net x-drv-target-pos cia402.0.drv-target-position => lcec.0.4.target-position
|
||||||
|
net x-drv-target-velo cia402.0.drv-target-velocity => lcec.0.4.target-velocity
|
||||||
|
|
||||||
|
#*******************
|
||||||
|
# AXIS Z
|
||||||
|
#*******************
|
||||||
|
|
||||||
|
# --- joint signals for motion
|
||||||
|
|
||||||
|
net z-pos-cmd <= joint.1.motor-pos-cmd
|
||||||
|
net z-vel-cmd <= joint.1.vel-cmd
|
||||||
|
net z-pos-fb <= joint.1.motor-pos-fb
|
||||||
|
net z-enable <= joint.1.amp-enable-out
|
||||||
|
|
||||||
|
# --- connect stepper driver to the joint
|
||||||
|
|
||||||
|
net z-pos-cmd => cia402.1.pos-cmd
|
||||||
|
net z-pos-fb => cia402.1.pos-fb
|
||||||
|
net z-enable => cia402.1.enable
|
||||||
|
|
||||||
|
# --- ect60 settings
|
||||||
|
|
||||||
|
setp cia402.1.csp-mode 1
|
||||||
|
setp cia402.1.pos-scale 2000
|
||||||
|
|
||||||
|
# --- from servo(ethercat) to cia402
|
||||||
|
|
||||||
|
net z-statusword lcec.0.5.cia-statusword => cia402.1.statusword
|
||||||
|
net z-opmode-display lcec.0.5.opmode-display => cia402.1.opmode-display
|
||||||
|
net z-drv-act-pos lcec.0.5.actual-position => cia402.1.drv-actual-position
|
||||||
|
net z-drv-act-velo lcec.0.5.actual-velocity => cia402.1.drv-actual-velocity
|
||||||
|
|
||||||
|
# --- from cia402 to servo(ethercat)
|
||||||
|
|
||||||
|
net z-controlword cia402.1.controlword => lcec.0.5.cia-controlword
|
||||||
|
net z-modes-of-operation cia402.1.opmode => lcec.0.5.opmode
|
||||||
|
net z-drv-target-pos cia402.1.drv-target-position => lcec.0.5.target-position
|
||||||
|
net z-drv-target-velo cia402.1.drv-target-velocity => lcec.0.5.target-velocity
|
||||||
|
|
||||||
|
#*********************
|
||||||
|
# E-STOP
|
||||||
|
#*********************
|
||||||
|
|
||||||
|
setp iocontrol.0.emc-enable-in 1
|
||||||
|
#net estop iocontrol.0.emc-enable-in lcec.0.1.din-0
|
||||||
|
|
||||||
|
setp lcec.0.3.enc-pos-scale [SPINDLE_9]ENCODER_SCALE
|
||||||
|
setp lcec.0.6.enc-pos-scale [SPINDLE_9]ENCODER_SCALE
|
||||||
|
|
||||||
|
net spindle-revs <= lcec.0.3.enc-pos
|
||||||
|
net spindle-revs <= lcec.0.6.enc-position
|
||||||
|
loadrt invert
|
||||||
|
loadrt mult2 names=mult2.rps,mult2.rpm
|
||||||
|
addf invert.0 servo-thread
|
||||||
|
addf mult2.rps servo-thread
|
||||||
|
addf mult2.rpm servo-thread
|
||||||
|
|
||||||
|
setp invert.0.in [SPINDLE_9]ENCODER_SCALE
|
||||||
|
setp mult2.rpm.in0 -60.0
|
||||||
|
setp mult2.rpm.in0 60.0
|
||||||
|
#net enc-invert-pos-scale mult2.rps.in0 <= invert.0.out
|
||||||
|
net enc-get-freq-rps mult2.rps.in1 <= lcec.0.3.enc-frequency
|
||||||
|
#net spindle-vel-fb-rps mult2.rpm.in1 <= mult2.rps.out
|
||||||
|
#net spindle-vel-fb-rpm mult2.rpm.out
|
||||||
|
net spindle-index-enable lcec.0.3.enc-index-c-enable
|
||||||
|
|
||||||
|
net spindle-vel-fb-rps mult2.rpm.in1 <= lcec.0.6.enc-frequency
|
||||||
|
net spindle-vel-fb-rpm mult2.rpm.out
|
||||||
|
|
||||||
|
net to_encoder metalmusings-encoder.0.index-latch-enable lcec.0.6.enc-index-latch-enable
|
||||||
|
net from_encoder metalmusings-encoder.0.index-status lcec.0.6.index-status
|
||||||
|
net spindle-index-enable metalmusings-encoder.0.index-c-enable
|
||||||
|
|
||||||
|
# ---setup spindle control signals---
|
||||||
|
|
||||||
|
net spindle-vel-cmd-rps <= spindle.0.speed-out-rps
|
||||||
|
net spindle-vel-cmd-rps-abs <= spindle.0.speed-out-rps-abs
|
||||||
|
net spindle-vel-cmd-rpm <= spindle.0.speed-out
|
||||||
|
net spindle-vel-cmd-rpm-abs <= spindle.0.speed-out-abs
|
||||||
|
net spindle-enable <= spindle.0.on
|
||||||
|
net spindle-cw <= spindle.0.forward
|
||||||
|
net spindle-ccw <= spindle.0.reverse
|
||||||
|
net spindle-brake <= spindle.0.brake
|
||||||
|
net spindle-revs => spindle.0.revs
|
||||||
|
net spindle-at-speed => spindle.0.at-speed
|
||||||
|
net spindle-vel-fb-rps => spindle.0.speed-in
|
||||||
|
net spindle-index-enable <=> spindle.0.index-enable
|
||||||
|
|
||||||
|
|
||||||
|
#******************************
|
||||||
|
# connect miscellaneous signals
|
||||||
|
#******************************
|
||||||
|
|
||||||
|
# ---HALUI signals---
|
||||||
|
|
||||||
|
net joint-select-a halui.axis.x.select
|
||||||
|
net x-is-homed halui.joint.0.is-homed
|
||||||
|
net jog-x-pos halui.axis.x.plus
|
||||||
|
net jog-x-neg halui.axis.x.minus
|
||||||
|
net jog-x-analog halui.axis.x.analog
|
||||||
|
net joint-select-b halui.axis.z.select
|
||||||
|
net z-is-homed halui.joint.1.is-homed
|
||||||
|
net jog-z-pos halui.axis.z.plus
|
||||||
|
net jog-z-neg halui.axis.z.minus
|
||||||
|
net jog-z-analog halui.axis.z.analog
|
||||||
|
net jog-selected-pos halui.axis.selected.plus
|
||||||
|
net jog-selected-neg halui.axis.selected.minus
|
||||||
|
net spindle-manual-cw halui.spindle.0.forward
|
||||||
|
net spindle-manual-ccw halui.spindle.0.reverse
|
||||||
|
net spindle-manual-stop halui.spindle.0.stop
|
||||||
|
net machine-is-on halui.machine.is-on
|
||||||
|
net jog-speed halui.axis.jog-speed
|
||||||
|
net MDI-mode halui.mode.is-mdi
|
||||||
|
|
||||||
|
# ---coolant signals---
|
||||||
|
|
||||||
|
net coolant-mist <= iocontrol.0.coolant-mist
|
||||||
|
net coolant-flood <= iocontrol.0.coolant-flood
|
||||||
|
|
||||||
|
# ---probe signal---
|
||||||
|
|
||||||
|
net probe-in => motion.probe-input
|
||||||
|
|
||||||
|
# ---motion control signals---
|
||||||
|
|
||||||
|
net in-position <= motion.in-position
|
||||||
|
net machine-is-enabled <= motion.motion-enabled
|
||||||
|
|
||||||
|
# ---digital in / out signals---
|
||||||
|
|
||||||
|
# ---estop signals---
|
||||||
|
|
||||||
|
net estop-out <= iocontrol.0.user-enable-out
|
||||||
|
net estop-ext => iocontrol.0.emc-enable-in
|
||||||
|
|
||||||
|
# ---manual tool change signals---
|
||||||
|
|
||||||
|
loadusr -W hal_manualtoolchange
|
||||||
|
#net tool-change-request iocontrol.0.tool-change => hal_manualtoolchange.change
|
||||||
|
#net tool-change-confirmed iocontrol.0.tool-changed <= hal_manualtoolchange.changed
|
||||||
|
#net tool-number iocontrol.0.tool-prep-number => hal_manualtoolchange.number
|
||||||
|
#net tool-prepare-loopback iocontrol.0.tool-prepare => iocontrol.0.tool-prepared
|
||||||
|
|
||||||
|
addf cia402.0.write-all servo-thread
|
||||||
|
addf cia402.1.write-all servo-thread
|
||||||
|
addf lcec.write-all servo-thread
|
||||||
82
Pcb-1-lan9252/linuxcnc/ethercat-conf.xml
Normal file
82
Pcb-1-lan9252/linuxcnc/ethercat-conf.xml
Normal file
@@ -0,0 +1,82 @@
|
|||||||
|
<masters>
|
||||||
|
<master idx="0" appTimePeriod="1000000" refClockSyncCycles="5">
|
||||||
|
<slave idx="0" type="EK1100"/>
|
||||||
|
<slave idx="1" type="EL1008"/>
|
||||||
|
<slave idx="2" type="EL2008"/>
|
||||||
|
<slave idx="3" type="EL5101"/>
|
||||||
|
<slave idx="4" type="generic" vid="00000a88" pid="0a880002" configPdos="true">
|
||||||
|
<dcConf assignActivate="300" sync0Cycle="*1" sync0Shift="0"/>
|
||||||
|
<sdoConfig idx="2000" subIdx="0"><sdoDataRaw data ="b8 0b"/></sdoConfig> <!-- Max motor current (3.0A) -->
|
||||||
|
<sdoConfig idx="2003" subIdx="0"><sdoDataRaw data ="64 00"/></sdoConfig> <!-- Standby current percentage (100%) -->
|
||||||
|
<sdoConfig idx="2011" subIdx="0"><sdoDataRaw data ="00 00"/></sdoConfig> <!-- Open loop -->
|
||||||
|
<syncManager idx="2" dir="out">
|
||||||
|
<pdo idx="1600">
|
||||||
|
<pdoEntry idx="6040" subIdx="00" bitLen="16" halPin="cia-controlword" halType="u32"/>
|
||||||
|
<pdoEntry idx="6060" subIdx="00" bitLen="8" halPin="opmode" halType="s32"/>
|
||||||
|
<pdoEntry idx="607A" subIdx="00" bitLen="32" halPin="target-position" halType="s32"/>
|
||||||
|
<pdoEntry idx="60FF" subIdx="00" bitLen="32" halPin="target-velocity" halType="s32"/>
|
||||||
|
</pdo>
|
||||||
|
</syncManager>
|
||||||
|
<syncManager idx="3" dir="in">
|
||||||
|
<pdo idx="1a00">
|
||||||
|
<pdoEntry idx="6041" subIdx="00" bitLen="16" halPin="cia-statusword" halType="u32"/>
|
||||||
|
<pdoEntry idx="6061" subIdx="00" bitLen="8" halPin="opmode-display" halType="s32"/>
|
||||||
|
<pdoEntry idx="6064" subIdx="00" bitLen="32" halPin="actual-position" halType="s32"/>
|
||||||
|
<pdoEntry idx="606C" subIdx="00" bitLen="32" halPin="actual-velocity" halType="s32"/>
|
||||||
|
<pdoEntry idx="6077" subIdx="00" bitLen="32" halPin="actual-torque" halType="s32"/>
|
||||||
|
</pdo>
|
||||||
|
</syncManager>
|
||||||
|
</slave>
|
||||||
|
<slave idx="5" type="generic" vid="00000a88" pid="0a880002" configPdos="true">
|
||||||
|
<dcConf assignActivate="300" sync0Cycle="*1" sync0Shift="0"/>
|
||||||
|
<sdoConfig idx="2000" subIdx="0"><sdoDataRaw data ="68 10"/></sdoConfig> <!-- Max motor current (4.2A) -->
|
||||||
|
<sdoConfig idx="2003" subIdx="0"><sdoDataRaw data ="64 00"/></sdoConfig> <!-- Standby current percentage (100%) -->
|
||||||
|
<sdoConfig idx="2011" subIdx="0"><sdoDataRaw data ="00 00"/></sdoConfig> <!-- Open loop -->
|
||||||
|
<syncManager idx="2" dir="out">
|
||||||
|
<pdo idx="1600">
|
||||||
|
<pdoEntry idx="6040" subIdx="00" bitLen="16" halPin="cia-controlword" halType="u32"/>
|
||||||
|
<pdoEntry idx="6060" subIdx="00" bitLen="8" halPin="opmode" halType="s32"/>
|
||||||
|
<pdoEntry idx="607A" subIdx="00" bitLen="32" halPin="target-position" halType="s32"/>
|
||||||
|
<pdoEntry idx="60FF" subIdx="00" bitLen="32" halPin="target-velocity" halType="s32"/>
|
||||||
|
</pdo>
|
||||||
|
</syncManager>
|
||||||
|
<syncManager idx="3" dir="in">
|
||||||
|
<pdo idx="1a00">
|
||||||
|
<pdoEntry idx="6041" subIdx="00" bitLen="16" halPin="cia-statusword" halType="u32"/>
|
||||||
|
<pdoEntry idx="6061" subIdx="00" bitLen="8" halPin="opmode-display" halType="s32"/>
|
||||||
|
<pdoEntry idx="6064" subIdx="00" bitLen="32" halPin="actual-position" halType="s32"/>
|
||||||
|
<pdoEntry idx="606C" subIdx="00" bitLen="32" halPin="actual-velocity" halType="s32"/>
|
||||||
|
<pdoEntry idx="6077" subIdx="00" bitLen="32" halPin="actual-torque" halType="s32"/>
|
||||||
|
</pdo>
|
||||||
|
</syncManager>
|
||||||
|
</slave>
|
||||||
|
<slave idx="6" type="generic" vid="00aaa" pid="000bbbccc" configPdos="true">
|
||||||
|
<dcConf assignActivate="300" sync0Cycle="*1" sync0Shift="0"/>
|
||||||
|
<syncManager idx="2" dir="out">
|
||||||
|
<pdo idx="1600">
|
||||||
|
<pdoEntry idx="7000" subIdx="00" bitLen="32" halPin="enc-pos-scale" halType="s32"/>
|
||||||
|
</pdo>
|
||||||
|
<pdo idx="1601">
|
||||||
|
<pdoEntry idx="7001" subIdx="00" bitLen="32" halPin="enc-index-latch-enable" halType="u32"/>
|
||||||
|
</pdo>
|
||||||
|
</syncManager>
|
||||||
|
<syncManager idx="3" dir="in">
|
||||||
|
<pdo idx="1a00">
|
||||||
|
<pdoEntry idx="6000" subIdx="00" bitLen="32" halPin="enc-position" halType="float-ieee"/>
|
||||||
|
</pdo>
|
||||||
|
<pdo idx="1a01">
|
||||||
|
<pdoEntry idx="6001" subIdx="00" bitLen="32" halPin="enc-frequency" halType="float-ieee"/>
|
||||||
|
</pdo>
|
||||||
|
<pdo idx="1a02">
|
||||||
|
<pdoEntry idx="6002" subIdx="00" bitLen="32" halPin="DiffT" halType="u32"/>
|
||||||
|
</pdo>
|
||||||
|
<pdo idx="1a03">
|
||||||
|
<pdoEntry idx="6003" subIdx="00" bitLen="32" halPin="index-byte" halType="u32"/>
|
||||||
|
</pdo>
|
||||||
|
<pdo idx="1a04">
|
||||||
|
<pdoEntry idx="6004" subIdx="00" bitLen="32" halPin="index-status" halType="u32"/>
|
||||||
|
</pdo>
|
||||||
|
</syncManager>
|
||||||
|
</slave>
|
||||||
|
</master>
|
||||||
|
</masters>
|
||||||
14
Pcb-1-lan9252/linuxcnc/metalmusings_encoder.comp
Normal file
14
Pcb-1-lan9252/linuxcnc/metalmusings_encoder.comp
Normal file
@@ -0,0 +1,14 @@
|
|||||||
|
component metalmusings_encoder;
|
||||||
|
pin io bit index-c-enable;
|
||||||
|
pin in u32 index-status;
|
||||||
|
pin out u32 index-latch-enable;
|
||||||
|
|
||||||
|
function _;
|
||||||
|
license "GPL";
|
||||||
|
;;
|
||||||
|
|
||||||
|
//main function
|
||||||
|
FUNCTION(_) {
|
||||||
|
index_latch_enable = index_c_enable;
|
||||||
|
index_c_enable = index_status;
|
||||||
|
}
|
||||||
3
Pcb-2-Ax58100/Kicad/Ax58100-stm32-ethercat/.gitignore
vendored
Normal file
3
Pcb-2-Ax58100/Kicad/Ax58100-stm32-ethercat/.gitignore
vendored
Normal file
@@ -0,0 +1,3 @@
|
|||||||
|
AX58100-stm32-ethercat-backups
|
||||||
|
.~lock*
|
||||||
|
fp-info-cache
|
||||||
3915
Pcb-2-Ax58100/Kicad/Ax58100-stm32-ethercat/AX48100.kicad_sch
Executable file
3915
Pcb-2-Ax58100/Kicad/Ax58100-stm32-ethercat/AX48100.kicad_sch
Executable file
File diff suppressed because it is too large
Load Diff
4788
Pcb-2-Ax58100/Kicad/Ax58100-stm32-ethercat/AX58100_phy_etc.kicad_sch
Executable file
4788
Pcb-2-Ax58100/Kicad/Ax58100-stm32-ethercat/AX58100_phy_etc.kicad_sch
Executable file
File diff suppressed because it is too large
Load Diff
40
Pcb-2-Ax58100/Kicad/Ax58100-stm32-ethercat/Ax58100-stm32-ethercat.csv
Executable file
40
Pcb-2-Ax58100/Kicad/Ax58100-stm32-ethercat/Ax58100-stm32-ethercat.csv
Executable file
@@ -0,0 +1,40 @@
|
|||||||
|
"Id";"Designator";"Footprint";"Quantity";"Designation";"Supplier and ref";
|
||||||
|
1;"J8";"JST_XH_B4B-XH-A_1x04_P2.50mm_Vertical";1;"Stepper 2";;;
|
||||||
|
2;"U1";"LQFP-80-1EP_10x10mm_P0.4mm_EP5.3x4.5mm_ThermalVias";1;"AX58100";;;
|
||||||
|
3;"B3,B7,B4,B6,B5";"C_0805_2012Metric";5;"BLM18EG221SN1D";;;
|
||||||
|
4;"R59,R61,R51,R45,R60,R58,R50,R57,R53,R52,R56,R55,R46,R54";"R_0805_2012Metric";14;"1k";;;
|
||||||
|
5;"U5";"LQFP-100_14x14mm_P0.5mm";1;"STM32F407VGT6";;;
|
||||||
|
6;"U2";"SOIC-8_3.9x4.9mm_P1.27mm";1;"24LC32A";;;
|
||||||
|
7;"R3,R49,R2,R48,R1";"R_0805_2012Metric";5;"22";;;
|
||||||
|
8;"C23,C21,C24,C22,C19,C25,C26,C20";"C_0805_2012Metric";8;"10pF";;;
|
||||||
|
9;"J3,J4,J5";"JST_XH_B6B-XH-A_1x06_P2.50mm_Vertical";3;"Conn_01x06_Pin";;;
|
||||||
|
10;"J9";"PinHeader_1x04_P2.54mm_Vertical";1;"I2C bus2";;;
|
||||||
|
11;"C45,C36,C34,C37,C38,C9,C39,C27,C13,C12,C40,C10,C8,C6,C29,C11,C46,C28,C3,C33,C41,C5,C2,C31,C18,C43,C14,C4,C7,C1";"C_0805_2012Metric";30;"0.1uF";;;
|
||||||
|
12;"Y2";"Crystal_HC49-U_Vertical";1;"8 MHz";;;
|
||||||
|
13;"R11,R7,R30,R12,R5,R10,R38,R13,R40,R33,R8";"R_0805_2012Metric";11;"4.7k";;;
|
||||||
|
14;"D1,D2";"LED_0805_2012Metric";2;"Green led";;;
|
||||||
|
15;"R28,R39,R25,R41,R26,R44,R27";"R_0805_2012Metric";7;"510";;;
|
||||||
|
16;"J14";"JST_XH_B5B-XH-A_1x05_P2.50mm_Vertical";1;"Encoder 4";;;
|
||||||
|
17;"C35,C32,C44,C30";"C_0805_2012Metric";4;"10uF";;;
|
||||||
|
18;"C49,C53";"C_0805_2012Metric";2;"2.2uF";;;
|
||||||
|
19;"D4,D5";"LED_0805_2012Metric";2;"Blue led";;;
|
||||||
|
20;"R22,R18,R19,R20,R17,R23,R21,R24";"R_0805_2012Metric";8;"49.9";;;
|
||||||
|
21;"C17,C15";"C_0805_2012Metric";2;"18pF";;;
|
||||||
|
22;"Y1";"Crystal_SMD_SeikoEpson_TSX3225-4Pin_3.2x2.5mm";1;"NXK25.000AE12F-KAB6-12";;;
|
||||||
|
23;"J12";"JST_XH_B5B-XH-A_1x05_P2.50mm_Vertical";1;"Encoder 2";;;
|
||||||
|
24;"J1";"JST_XH_B2B-XH-A_1x02_P2.50mm_Vertical";1;"Conn_01x02_Pin";;;
|
||||||
|
25;"IN1,OUT1";"PulseJack JB0011D01BNL";2;"J0011D01BNL";;;
|
||||||
|
26;"J2";"JST_XH_B4B-XH-A_1x04_P2.50mm_Vertical";1;"STLINK";;;
|
||||||
|
27;"C52,C51";"C_0805_2012Metric";2;"22pF";;;
|
||||||
|
28;"B2,B1";"C_0805_2012Metric";2;"BLM18EG221S";;;
|
||||||
|
29;"J10";"JST_XH_B3B-XH-A_1x03_P2.50mm_Vertical";1;"DAC1";;;
|
||||||
|
30;"U4";"SOT-223-3_TabPin2";1;"AMS1117-3.3";;;
|
||||||
|
31;"J7";"JST_XH_B4B-XH-A_1x04_P2.50mm_Vertical";1;"Stepper 1";;;
|
||||||
|
32;"J6";"JST_XH_B4B-XH-A_1x04_P2.50mm_Vertical";1;"Serial usart1";;;
|
||||||
|
33;"SW1";"SW_Push_1P1T_XKB_TS-1187A";1;"SW PB";;;
|
||||||
|
34;"C16";"C_0805_2012Metric";1;"1uF";;;
|
||||||
|
35;"D3";"LED_0805_2012Metric";1;"Red led";;;
|
||||||
|
36;"J13";"JST_XH_B5B-XH-A_1x05_P2.50mm_Vertical";1;"Encoder 3";;;
|
||||||
|
37;"J11";"JST_XH_B5B-XH-A_1x05_P2.50mm_Vertical";1;"Encoder 1";;;
|
||||||
|
38;"U3";"SOT-223-3_TabPin2";1;"AMS1117-1.2";;;
|
||||||
|
39;"R6";"R_0805_2012Metric";1;"12k 1%";;;
|
||||||
|
2277
Pcb-2-Ax58100/Kicad/Ax58100-stm32-ethercat/Ax58100-stm32-ethercat.dsn
Executable file
2277
Pcb-2-Ax58100/Kicad/Ax58100-stm32-ethercat/Ax58100-stm32-ethercat.dsn
Executable file
File diff suppressed because it is too large
Load Diff
47847
Pcb-2-Ax58100/Kicad/Ax58100-stm32-ethercat/Ax58100-stm32-ethercat.kicad_pcb
Executable file
47847
Pcb-2-Ax58100/Kicad/Ax58100-stm32-ethercat/Ax58100-stm32-ethercat.kicad_pcb
Executable file
File diff suppressed because it is too large
Load Diff
77
Pcb-2-Ax58100/Kicad/Ax58100-stm32-ethercat/Ax58100-stm32-ethercat.kicad_prl
Executable file
77
Pcb-2-Ax58100/Kicad/Ax58100-stm32-ethercat/Ax58100-stm32-ethercat.kicad_prl
Executable file
@@ -0,0 +1,77 @@
|
|||||||
|
{
|
||||||
|
"board": {
|
||||||
|
"active_layer": 0,
|
||||||
|
"active_layer_preset": "",
|
||||||
|
"auto_track_width": true,
|
||||||
|
"hidden_netclasses": [],
|
||||||
|
"hidden_nets": [],
|
||||||
|
"high_contrast_mode": 0,
|
||||||
|
"net_color_mode": 1,
|
||||||
|
"opacity": {
|
||||||
|
"images": 0.6,
|
||||||
|
"pads": 1.0,
|
||||||
|
"tracks": 1.0,
|
||||||
|
"vias": 1.0,
|
||||||
|
"zones": 0.6
|
||||||
|
},
|
||||||
|
"selection_filter": {
|
||||||
|
"dimensions": true,
|
||||||
|
"footprints": true,
|
||||||
|
"graphics": true,
|
||||||
|
"keepouts": true,
|
||||||
|
"lockedItems": false,
|
||||||
|
"otherItems": true,
|
||||||
|
"pads": true,
|
||||||
|
"text": true,
|
||||||
|
"tracks": true,
|
||||||
|
"vias": true,
|
||||||
|
"zones": true
|
||||||
|
},
|
||||||
|
"visible_items": [
|
||||||
|
0,
|
||||||
|
1,
|
||||||
|
2,
|
||||||
|
3,
|
||||||
|
4,
|
||||||
|
5,
|
||||||
|
8,
|
||||||
|
9,
|
||||||
|
10,
|
||||||
|
11,
|
||||||
|
12,
|
||||||
|
13,
|
||||||
|
15,
|
||||||
|
16,
|
||||||
|
17,
|
||||||
|
18,
|
||||||
|
19,
|
||||||
|
20,
|
||||||
|
21,
|
||||||
|
22,
|
||||||
|
23,
|
||||||
|
24,
|
||||||
|
25,
|
||||||
|
26,
|
||||||
|
27,
|
||||||
|
28,
|
||||||
|
29,
|
||||||
|
30,
|
||||||
|
32,
|
||||||
|
33,
|
||||||
|
34,
|
||||||
|
35,
|
||||||
|
36,
|
||||||
|
39,
|
||||||
|
40
|
||||||
|
],
|
||||||
|
"visible_layers": "7ffffff_80000001",
|
||||||
|
"zone_display_mode": 0
|
||||||
|
},
|
||||||
|
"meta": {
|
||||||
|
"filename": "Ax58100-stm32-ethercat.kicad_prl",
|
||||||
|
"version": 3
|
||||||
|
},
|
||||||
|
"project": {
|
||||||
|
"files": []
|
||||||
|
}
|
||||||
|
}
|
||||||
506
Pcb-2-Ax58100/Kicad/Ax58100-stm32-ethercat/Ax58100-stm32-ethercat.kicad_pro
Executable file
506
Pcb-2-Ax58100/Kicad/Ax58100-stm32-ethercat/Ax58100-stm32-ethercat.kicad_pro
Executable file
@@ -0,0 +1,506 @@
|
|||||||
|
{
|
||||||
|
"board": {
|
||||||
|
"3dviewports": [],
|
||||||
|
"design_settings": {
|
||||||
|
"defaults": {
|
||||||
|
"board_outline_line_width": 0.09999999999999999,
|
||||||
|
"copper_line_width": 0.19999999999999998,
|
||||||
|
"copper_text_italic": false,
|
||||||
|
"copper_text_size_h": 1.5,
|
||||||
|
"copper_text_size_v": 1.5,
|
||||||
|
"copper_text_thickness": 0.3,
|
||||||
|
"copper_text_upright": false,
|
||||||
|
"courtyard_line_width": 0.049999999999999996,
|
||||||
|
"dimension_precision": 4,
|
||||||
|
"dimension_units": 3,
|
||||||
|
"dimensions": {
|
||||||
|
"arrow_length": 1270000,
|
||||||
|
"extension_offset": 500000,
|
||||||
|
"keep_text_aligned": true,
|
||||||
|
"suppress_zeroes": false,
|
||||||
|
"text_position": 0,
|
||||||
|
"units_format": 1
|
||||||
|
},
|
||||||
|
"fab_line_width": 0.09999999999999999,
|
||||||
|
"fab_text_italic": false,
|
||||||
|
"fab_text_size_h": 1.0,
|
||||||
|
"fab_text_size_v": 1.0,
|
||||||
|
"fab_text_thickness": 0.15,
|
||||||
|
"fab_text_upright": false,
|
||||||
|
"other_line_width": 0.15,
|
||||||
|
"other_text_italic": false,
|
||||||
|
"other_text_size_h": 1.0,
|
||||||
|
"other_text_size_v": 1.0,
|
||||||
|
"other_text_thickness": 0.15,
|
||||||
|
"other_text_upright": false,
|
||||||
|
"pads": {
|
||||||
|
"drill": 0.762,
|
||||||
|
"height": 1.524,
|
||||||
|
"width": 1.524
|
||||||
|
},
|
||||||
|
"silk_line_width": 0.15,
|
||||||
|
"silk_text_italic": false,
|
||||||
|
"silk_text_size_h": 1.0,
|
||||||
|
"silk_text_size_v": 1.0,
|
||||||
|
"silk_text_thickness": 0.15,
|
||||||
|
"silk_text_upright": false,
|
||||||
|
"zones": {
|
||||||
|
"min_clearance": 0.5
|
||||||
|
}
|
||||||
|
},
|
||||||
|
"diff_pair_dimensions": [
|
||||||
|
{
|
||||||
|
"gap": 0.0,
|
||||||
|
"via_gap": 0.0,
|
||||||
|
"width": 0.0
|
||||||
|
}
|
||||||
|
],
|
||||||
|
"drc_exclusions": [],
|
||||||
|
"meta": {
|
||||||
|
"version": 2
|
||||||
|
},
|
||||||
|
"rule_severities": {
|
||||||
|
"annular_width": "error",
|
||||||
|
"clearance": "error",
|
||||||
|
"connection_width": "warning",
|
||||||
|
"copper_edge_clearance": "error",
|
||||||
|
"copper_sliver": "warning",
|
||||||
|
"courtyards_overlap": "error",
|
||||||
|
"diff_pair_gap_out_of_range": "error",
|
||||||
|
"diff_pair_uncoupled_length_too_long": "error",
|
||||||
|
"drill_out_of_range": "error",
|
||||||
|
"duplicate_footprints": "warning",
|
||||||
|
"extra_footprint": "warning",
|
||||||
|
"footprint": "error",
|
||||||
|
"footprint_type_mismatch": "ignore",
|
||||||
|
"hole_clearance": "error",
|
||||||
|
"hole_near_hole": "error",
|
||||||
|
"invalid_outline": "error",
|
||||||
|
"isolated_copper": "warning",
|
||||||
|
"item_on_disabled_layer": "error",
|
||||||
|
"items_not_allowed": "error",
|
||||||
|
"length_out_of_range": "error",
|
||||||
|
"lib_footprint_issues": "warning",
|
||||||
|
"lib_footprint_mismatch": "warning",
|
||||||
|
"malformed_courtyard": "error",
|
||||||
|
"microvia_drill_out_of_range": "error",
|
||||||
|
"missing_courtyard": "ignore",
|
||||||
|
"missing_footprint": "warning",
|
||||||
|
"net_conflict": "warning",
|
||||||
|
"npth_inside_courtyard": "ignore",
|
||||||
|
"padstack": "warning",
|
||||||
|
"pth_inside_courtyard": "ignore",
|
||||||
|
"shorting_items": "error",
|
||||||
|
"silk_edge_clearance": "warning",
|
||||||
|
"silk_over_copper": "warning",
|
||||||
|
"silk_overlap": "warning",
|
||||||
|
"skew_out_of_range": "error",
|
||||||
|
"solder_mask_bridge": "error",
|
||||||
|
"starved_thermal": "error",
|
||||||
|
"text_height": "warning",
|
||||||
|
"text_thickness": "warning",
|
||||||
|
"through_hole_pad_without_hole": "error",
|
||||||
|
"too_many_vias": "error",
|
||||||
|
"track_dangling": "warning",
|
||||||
|
"track_width": "error",
|
||||||
|
"tracks_crossing": "error",
|
||||||
|
"unconnected_items": "error",
|
||||||
|
"unresolved_variable": "error",
|
||||||
|
"via_dangling": "warning",
|
||||||
|
"zones_intersect": "error"
|
||||||
|
},
|
||||||
|
"rules": {
|
||||||
|
"max_error": 0.005,
|
||||||
|
"min_clearance": 0.0,
|
||||||
|
"min_connection": 0.0,
|
||||||
|
"min_copper_edge_clearance": 0.0,
|
||||||
|
"min_hole_clearance": 0.25,
|
||||||
|
"min_hole_to_hole": 0.25,
|
||||||
|
"min_microvia_diameter": 0.19999999999999998,
|
||||||
|
"min_microvia_drill": 0.09999999999999999,
|
||||||
|
"min_resolved_spokes": 2,
|
||||||
|
"min_silk_clearance": 0.0,
|
||||||
|
"min_text_height": 0.7999999999999999,
|
||||||
|
"min_text_thickness": 0.08,
|
||||||
|
"min_through_hole_diameter": 0.3,
|
||||||
|
"min_track_width": 0.0,
|
||||||
|
"min_via_annular_width": 0.09999999999999999,
|
||||||
|
"min_via_diameter": 0.5,
|
||||||
|
"solder_mask_clearance": 0.0,
|
||||||
|
"solder_mask_min_width": 0.0,
|
||||||
|
"solder_mask_to_copper_clearance": 0.0,
|
||||||
|
"use_height_for_length_calcs": true
|
||||||
|
},
|
||||||
|
"teardrop_options": [
|
||||||
|
{
|
||||||
|
"td_allow_use_two_tracks": true,
|
||||||
|
"td_curve_segcount": 5,
|
||||||
|
"td_on_pad_in_zone": false,
|
||||||
|
"td_onpadsmd": true,
|
||||||
|
"td_onroundshapesonly": false,
|
||||||
|
"td_ontrackend": false,
|
||||||
|
"td_onviapad": true
|
||||||
|
}
|
||||||
|
],
|
||||||
|
"teardrop_parameters": [
|
||||||
|
{
|
||||||
|
"td_curve_segcount": 0,
|
||||||
|
"td_height_ratio": 1.0,
|
||||||
|
"td_length_ratio": 0.5,
|
||||||
|
"td_maxheight": 2.0,
|
||||||
|
"td_maxlen": 1.0,
|
||||||
|
"td_target_name": "td_round_shape",
|
||||||
|
"td_width_to_size_filter_ratio": 0.9
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"td_curve_segcount": 0,
|
||||||
|
"td_height_ratio": 1.0,
|
||||||
|
"td_length_ratio": 0.5,
|
||||||
|
"td_maxheight": 2.0,
|
||||||
|
"td_maxlen": 1.0,
|
||||||
|
"td_target_name": "td_rect_shape",
|
||||||
|
"td_width_to_size_filter_ratio": 0.9
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"td_curve_segcount": 0,
|
||||||
|
"td_height_ratio": 1.0,
|
||||||
|
"td_length_ratio": 0.5,
|
||||||
|
"td_maxheight": 2.0,
|
||||||
|
"td_maxlen": 1.0,
|
||||||
|
"td_target_name": "td_track_end",
|
||||||
|
"td_width_to_size_filter_ratio": 0.9
|
||||||
|
}
|
||||||
|
],
|
||||||
|
"track_widths": [
|
||||||
|
0.0
|
||||||
|
],
|
||||||
|
"via_dimensions": [
|
||||||
|
{
|
||||||
|
"diameter": 0.0,
|
||||||
|
"drill": 0.0
|
||||||
|
}
|
||||||
|
],
|
||||||
|
"zones_allow_external_fillets": false
|
||||||
|
},
|
||||||
|
"layer_presets": [],
|
||||||
|
"viewports": []
|
||||||
|
},
|
||||||
|
"boards": [],
|
||||||
|
"cvpcb": {
|
||||||
|
"equivalence_files": []
|
||||||
|
},
|
||||||
|
"erc": {
|
||||||
|
"erc_exclusions": [],
|
||||||
|
"meta": {
|
||||||
|
"version": 0
|
||||||
|
},
|
||||||
|
"pin_map": [
|
||||||
|
[
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
1,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
2
|
||||||
|
],
|
||||||
|
[
|
||||||
|
0,
|
||||||
|
2,
|
||||||
|
0,
|
||||||
|
1,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
1,
|
||||||
|
0,
|
||||||
|
2,
|
||||||
|
2,
|
||||||
|
2,
|
||||||
|
2
|
||||||
|
],
|
||||||
|
[
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
1,
|
||||||
|
0,
|
||||||
|
1,
|
||||||
|
0,
|
||||||
|
1,
|
||||||
|
2
|
||||||
|
],
|
||||||
|
[
|
||||||
|
0,
|
||||||
|
1,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
1,
|
||||||
|
1,
|
||||||
|
2,
|
||||||
|
1,
|
||||||
|
1,
|
||||||
|
2
|
||||||
|
],
|
||||||
|
[
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
1,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
2
|
||||||
|
],
|
||||||
|
[
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
2
|
||||||
|
],
|
||||||
|
[
|
||||||
|
1,
|
||||||
|
1,
|
||||||
|
1,
|
||||||
|
1,
|
||||||
|
1,
|
||||||
|
0,
|
||||||
|
1,
|
||||||
|
1,
|
||||||
|
1,
|
||||||
|
1,
|
||||||
|
1,
|
||||||
|
2
|
||||||
|
],
|
||||||
|
[
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
1,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
1,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
2
|
||||||
|
],
|
||||||
|
[
|
||||||
|
0,
|
||||||
|
2,
|
||||||
|
1,
|
||||||
|
2,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
1,
|
||||||
|
0,
|
||||||
|
2,
|
||||||
|
2,
|
||||||
|
2,
|
||||||
|
2
|
||||||
|
],
|
||||||
|
[
|
||||||
|
0,
|
||||||
|
2,
|
||||||
|
0,
|
||||||
|
1,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
1,
|
||||||
|
0,
|
||||||
|
2,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
2
|
||||||
|
],
|
||||||
|
[
|
||||||
|
0,
|
||||||
|
2,
|
||||||
|
1,
|
||||||
|
1,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
1,
|
||||||
|
0,
|
||||||
|
2,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
2
|
||||||
|
],
|
||||||
|
[
|
||||||
|
2,
|
||||||
|
2,
|
||||||
|
2,
|
||||||
|
2,
|
||||||
|
2,
|
||||||
|
2,
|
||||||
|
2,
|
||||||
|
2,
|
||||||
|
2,
|
||||||
|
2,
|
||||||
|
2,
|
||||||
|
2
|
||||||
|
]
|
||||||
|
],
|
||||||
|
"rule_severities": {
|
||||||
|
"bus_definition_conflict": "error",
|
||||||
|
"bus_entry_needed": "error",
|
||||||
|
"bus_to_bus_conflict": "error",
|
||||||
|
"bus_to_net_conflict": "error",
|
||||||
|
"conflicting_netclasses": "error",
|
||||||
|
"different_unit_footprint": "error",
|
||||||
|
"different_unit_net": "error",
|
||||||
|
"duplicate_reference": "error",
|
||||||
|
"duplicate_sheet_names": "error",
|
||||||
|
"endpoint_off_grid": "warning",
|
||||||
|
"extra_units": "error",
|
||||||
|
"global_label_dangling": "warning",
|
||||||
|
"hier_label_mismatch": "error",
|
||||||
|
"label_dangling": "error",
|
||||||
|
"lib_symbol_issues": "warning",
|
||||||
|
"missing_bidi_pin": "warning",
|
||||||
|
"missing_input_pin": "warning",
|
||||||
|
"missing_power_pin": "error",
|
||||||
|
"missing_unit": "warning",
|
||||||
|
"multiple_net_names": "warning",
|
||||||
|
"net_not_bus_member": "warning",
|
||||||
|
"no_connect_connected": "warning",
|
||||||
|
"no_connect_dangling": "warning",
|
||||||
|
"pin_not_connected": "error",
|
||||||
|
"pin_not_driven": "error",
|
||||||
|
"pin_to_pin": "warning",
|
||||||
|
"power_pin_not_driven": "error",
|
||||||
|
"similar_labels": "warning",
|
||||||
|
"simulation_model_issue": "ignore",
|
||||||
|
"unannotated": "error",
|
||||||
|
"unit_value_mismatch": "error",
|
||||||
|
"unresolved_variable": "error",
|
||||||
|
"wire_dangling": "error"
|
||||||
|
}
|
||||||
|
},
|
||||||
|
"libraries": {
|
||||||
|
"pinned_footprint_libs": [],
|
||||||
|
"pinned_symbol_libs": []
|
||||||
|
},
|
||||||
|
"meta": {
|
||||||
|
"filename": "Ax58100-stm32-ethercat.kicad_pro",
|
||||||
|
"version": 1
|
||||||
|
},
|
||||||
|
"net_settings": {
|
||||||
|
"classes": [
|
||||||
|
{
|
||||||
|
"bus_width": 12,
|
||||||
|
"clearance": 0.15,
|
||||||
|
"diff_pair_gap": 0.25,
|
||||||
|
"diff_pair_via_gap": 0.25,
|
||||||
|
"diff_pair_width": 0.2,
|
||||||
|
"line_style": 0,
|
||||||
|
"microvia_diameter": 0.3,
|
||||||
|
"microvia_drill": 0.1,
|
||||||
|
"name": "Default",
|
||||||
|
"pcb_color": "rgba(0, 0, 0, 0.000)",
|
||||||
|
"schematic_color": "rgba(0, 0, 0, 0.000)",
|
||||||
|
"track_width": 0.2,
|
||||||
|
"via_diameter": 0.8,
|
||||||
|
"via_drill": 0.4,
|
||||||
|
"wire_width": 6
|
||||||
|
}
|
||||||
|
],
|
||||||
|
"meta": {
|
||||||
|
"version": 3
|
||||||
|
},
|
||||||
|
"net_colors": null,
|
||||||
|
"netclass_assignments": null,
|
||||||
|
"netclass_patterns": []
|
||||||
|
},
|
||||||
|
"pcbnew": {
|
||||||
|
"last_paths": {
|
||||||
|
"gencad": "",
|
||||||
|
"idf": "",
|
||||||
|
"netlist": "C:/Program Files/KiCad/7.0/",
|
||||||
|
"specctra_dsn": "Ax58100-stm32-ethercat.dsn",
|
||||||
|
"step": "",
|
||||||
|
"vrml": ""
|
||||||
|
},
|
||||||
|
"page_layout_descr_file": ""
|
||||||
|
},
|
||||||
|
"schematic": {
|
||||||
|
"annotate_start_num": 0,
|
||||||
|
"drawing": {
|
||||||
|
"dashed_lines_dash_length_ratio": 12.0,
|
||||||
|
"dashed_lines_gap_length_ratio": 3.0,
|
||||||
|
"default_line_thickness": 6.0,
|
||||||
|
"default_text_size": 50.0,
|
||||||
|
"field_names": [],
|
||||||
|
"intersheets_ref_own_page": false,
|
||||||
|
"intersheets_ref_prefix": "",
|
||||||
|
"intersheets_ref_short": false,
|
||||||
|
"intersheets_ref_show": false,
|
||||||
|
"intersheets_ref_suffix": "",
|
||||||
|
"junction_size_choice": 3,
|
||||||
|
"label_size_ratio": 0.375,
|
||||||
|
"pin_symbol_size": 25.0,
|
||||||
|
"text_offset_ratio": 0.15
|
||||||
|
},
|
||||||
|
"legacy_lib_dir": "",
|
||||||
|
"legacy_lib_list": [],
|
||||||
|
"meta": {
|
||||||
|
"version": 1
|
||||||
|
},
|
||||||
|
"net_format_name": "",
|
||||||
|
"page_layout_descr_file": "",
|
||||||
|
"plot_directory": "",
|
||||||
|
"spice_current_sheet_as_root": false,
|
||||||
|
"spice_external_command": "spice \"%I\"",
|
||||||
|
"spice_model_current_sheet_as_root": true,
|
||||||
|
"spice_save_all_currents": false,
|
||||||
|
"spice_save_all_voltages": false,
|
||||||
|
"subpart_first_id": 65,
|
||||||
|
"subpart_id_separator": 0
|
||||||
|
},
|
||||||
|
"sheets": [
|
||||||
|
[
|
||||||
|
"5597aedc-b607-407f-bbfd-31b3b298ecb1",
|
||||||
|
""
|
||||||
|
],
|
||||||
|
[
|
||||||
|
"9f485422-734f-43d3-94ea-443cbc453d2e",
|
||||||
|
"AX58100"
|
||||||
|
],
|
||||||
|
[
|
||||||
|
"5bf93325-f5d9-4344-9bf3-f5fc91bc1622",
|
||||||
|
"AX58100 phys etc"
|
||||||
|
],
|
||||||
|
[
|
||||||
|
"d564400f-40ba-4aca-9c2a-14ec52a8353b",
|
||||||
|
"STM32F4"
|
||||||
|
],
|
||||||
|
[
|
||||||
|
"0a376a6c-0f15-42f8-81f6-3a55619be267",
|
||||||
|
"Peripherals"
|
||||||
|
]
|
||||||
|
],
|
||||||
|
"text_variables": {}
|
||||||
|
}
|
||||||
87
Pcb-2-Ax58100/Kicad/Ax58100-stm32-ethercat/Ax58100-stm32-ethercat.kicad_sch
Executable file
87
Pcb-2-Ax58100/Kicad/Ax58100-stm32-ethercat/Ax58100-stm32-ethercat.kicad_sch
Executable file
@@ -0,0 +1,87 @@
|
|||||||
|
(kicad_sch (version 20230121) (generator eeschema)
|
||||||
|
|
||||||
|
(uuid 5597aedc-b607-407f-bbfd-31b3b298ecb1)
|
||||||
|
|
||||||
|
(paper "A3")
|
||||||
|
|
||||||
|
(lib_symbols
|
||||||
|
)
|
||||||
|
|
||||||
|
|
||||||
|
(text "Huvudsida" (at 162.56 85.09 0)
|
||||||
|
(effects (font (size 1.27 1.27)) (justify left bottom))
|
||||||
|
(uuid adf2be63-7ec7-44be-837f-901ddbc80717)
|
||||||
|
)
|
||||||
|
|
||||||
|
(sheet (at 144.78 224.79) (size 71.12 16.51) (fields_autoplaced)
|
||||||
|
(stroke (width 0.1524) (type solid))
|
||||||
|
(fill (color 0 0 0 0.0000))
|
||||||
|
(uuid 0a376a6c-0f15-42f8-81f6-3a55619be267)
|
||||||
|
(property "Sheetname" "Peripherals" (at 144.78 224.0784 0)
|
||||||
|
(effects (font (size 1.27 1.27)) (justify left bottom))
|
||||||
|
)
|
||||||
|
(property "Sheetfile" "peripherals.kicad_sch" (at 144.78 241.8846 0)
|
||||||
|
(effects (font (size 1.27 1.27)) (justify left top))
|
||||||
|
)
|
||||||
|
(instances
|
||||||
|
(project "AX58100-stm32-ethercat"
|
||||||
|
(path "/5597aedc-b607-407f-bbfd-31b3b298ecb1" (page "5"))
|
||||||
|
)
|
||||||
|
)
|
||||||
|
)
|
||||||
|
|
||||||
|
(sheet (at 234.95 198.12) (size 102.87 34.29) (fields_autoplaced)
|
||||||
|
(stroke (width 0.1524) (type solid))
|
||||||
|
(fill (color 0 0 0 0.0000))
|
||||||
|
(uuid 5bf93325-f5d9-4344-9bf3-f5fc91bc1622)
|
||||||
|
(property "Sheetname" "AX58100 phys etc" (at 234.95 197.4084 0)
|
||||||
|
(effects (font (size 1.27 1.27)) (justify left bottom))
|
||||||
|
)
|
||||||
|
(property "Sheetfile" "AX58100_phy_etc.kicad_sch" (at 234.95 232.9946 0)
|
||||||
|
(effects (font (size 1.27 1.27)) (justify left top))
|
||||||
|
)
|
||||||
|
(instances
|
||||||
|
(project "AX58100-stm32-ethercat"
|
||||||
|
(path "/5597aedc-b607-407f-bbfd-31b3b298ecb1" (page "3"))
|
||||||
|
)
|
||||||
|
)
|
||||||
|
)
|
||||||
|
|
||||||
|
(sheet (at 233.68 123.19) (size 93.98 60.96) (fields_autoplaced)
|
||||||
|
(stroke (width 0.1524) (type solid))
|
||||||
|
(fill (color 0 0 0 0.0000))
|
||||||
|
(uuid 9f485422-734f-43d3-94ea-443cbc453d2e)
|
||||||
|
(property "Sheetname" "AX58100" (at 233.68 122.4784 0)
|
||||||
|
(effects (font (size 1.27 1.27)) (justify left bottom))
|
||||||
|
)
|
||||||
|
(property "Sheetfile" "AX48100.kicad_sch" (at 233.68 184.7346 0)
|
||||||
|
(effects (font (size 1.27 1.27)) (justify left top))
|
||||||
|
)
|
||||||
|
(instances
|
||||||
|
(project "AX58100-stm32-ethercat"
|
||||||
|
(path "/5597aedc-b607-407f-bbfd-31b3b298ecb1" (page "2"))
|
||||||
|
)
|
||||||
|
)
|
||||||
|
)
|
||||||
|
|
||||||
|
(sheet (at 142.24 200.66) (size 74.93 17.78) (fields_autoplaced)
|
||||||
|
(stroke (width 0.1524) (type solid))
|
||||||
|
(fill (color 0 0 0 0.0000))
|
||||||
|
(uuid d564400f-40ba-4aca-9c2a-14ec52a8353b)
|
||||||
|
(property "Sheetname" "STM32F4" (at 142.24 199.9484 0)
|
||||||
|
(effects (font (size 1.27 1.27)) (justify left bottom))
|
||||||
|
)
|
||||||
|
(property "Sheetfile" "STM32F4.kicad_sch" (at 142.24 219.0246 0)
|
||||||
|
(effects (font (size 1.27 1.27)) (justify left top))
|
||||||
|
)
|
||||||
|
(instances
|
||||||
|
(project "AX58100-stm32-ethercat"
|
||||||
|
(path "/5597aedc-b607-407f-bbfd-31b3b298ecb1" (page "4"))
|
||||||
|
)
|
||||||
|
)
|
||||||
|
)
|
||||||
|
|
||||||
|
(sheet_instances
|
||||||
|
(path "/" (page "1"))
|
||||||
|
)
|
||||||
|
)
|
||||||
BIN
Pcb-2-Ax58100/Kicad/Ax58100-stm32-ethercat/Ax58100-stm32-ethercat.ods
Executable file
BIN
Pcb-2-Ax58100/Kicad/Ax58100-stm32-ethercat/Ax58100-stm32-ethercat.ods
Executable file
Binary file not shown.
5130
Pcb-2-Ax58100/Kicad/Ax58100-stm32-ethercat/Ax58100-stm32-ethercat.ses
Executable file
5130
Pcb-2-Ax58100/Kicad/Ax58100-stm32-ethercat/Ax58100-stm32-ethercat.ses
Executable file
File diff suppressed because it is too large
Load Diff
2888
Pcb-2-Ax58100/Kicad/Ax58100-stm32-ethercat/Ax58100-stm32-ethercat.xml
Executable file
2888
Pcb-2-Ax58100/Kicad/Ax58100-stm32-ethercat/Ax58100-stm32-ethercat.xml
Executable file
File diff suppressed because it is too large
Load Diff
4543
Pcb-2-Ax58100/Kicad/Ax58100-stm32-ethercat/STM32F4.kicad_sch
Executable file
4543
Pcb-2-Ax58100/Kicad/Ax58100-stm32-ethercat/STM32F4.kicad_sch
Executable file
File diff suppressed because it is too large
Load Diff
1856
Pcb-2-Ax58100/Kicad/Ax58100-stm32-ethercat/peripherals.kicad_sch
Executable file
1856
Pcb-2-Ax58100/Kicad/Ax58100-stm32-ethercat/peripherals.kicad_sch
Executable file
File diff suppressed because it is too large
Load Diff
@@ -6,7 +6,14 @@ that I used during the creation of my own EtherCAT device.
|
|||||||
This job is documented in a series of Youtube videos, from my first attempts to understand
|
This job is documented in a series of Youtube videos, from my first attempts to understand
|
||||||
how EtherCAT works, to making my own pcb, program it and testing it in LinuxCNC.
|
how EtherCAT works, to making my own pcb, program it and testing it in LinuxCNC.
|
||||||
|
|
||||||
## My own EtherCat device 4. The PCB is here
|
## Make my own EtherCat device 5. The lathe is alive
|
||||||
|
|
||||||
|
I hook up the EaserCAT 2000 board to my mini-lathe and make it work.
|
||||||
|
Documentation is available here, please select the *Video5* branch.
|
||||||
|
|
||||||
|
[](https://youtu.be/wOtMrlHCCic)0
|
||||||
|
|
||||||
|
## Make my own EtherCat device 4. The PCB is here
|
||||||
|
|
||||||
In this video it starts to be interesting. I have got the pcb and I try to make it work.
|
In this video it starts to be interesting. I have got the pcb and I try to make it work.
|
||||||
Now I finally make documentation available, see [this folder](Pcb-1-lan9252).
|
Now I finally make documentation available, see [this folder](Pcb-1-lan9252).
|
||||||
|
|||||||
Reference in New Issue
Block a user