Tested in the lathe. Works, of course

This commit is contained in:
Hakan Bastedt
2023-12-24 23:28:10 +01:00
parent c972fef18f
commit 49c804516d
13 changed files with 874 additions and 1883 deletions

View File

@@ -1,6 +1,7 @@
{
"files.associations": {
"ecat_slv.h": "c",
"compare": "cpp"
"compare": "cpp",
"*.tpp": "cpp"
}
}

View File

@@ -0,0 +1,710 @@
<?xml version="1.0" encoding="UTF-8"?>
<EtherCATInfo>
<Vendor>
<Id>2730</Id>
<Name LcId="1033">MetalMusings</Name>
</Vendor>
<Descriptions>
<Groups>
<Group>
<Type>MachineControl</Type>
<Name LcId="1033">Incremental encoder</Name>
</Group>
</Groups>
<Devices>
<Device Physics="YY ">
<Type ProductCode="#xbbbccc" RevisionNo="#x2">EaserCAT2000</Type>
<Name LcId="1033">MetalMusings EaserCAT 2000</Name>
<GroupType>MachineControl</GroupType>
<Profile>
<ProfileNo>5001</ProfileNo>
<AddInfo>0</AddInfo>
<Dictionary>
<DataTypes>
<DataType>
<Name>DT1018</Name>
<BitSize>144</BitSize>
<SubItem>
<SubIdx>0</SubIdx>
<Name>Max SubIndex</Name>
<Type>USINT</Type>
<BitSize>8</BitSize>
<BitOffs>0</BitOffs>
<Flags>
<Access>ro</Access>
</Flags>
</SubItem>
<SubItem>
<SubIdx>1</SubIdx>
<Name>Vendor ID</Name>
<Type>UDINT</Type>
<BitSize>32</BitSize>
<BitOffs>16</BitOffs>
<Flags>
<Access>ro</Access>
</Flags>
</SubItem>
<SubItem>
<SubIdx>2</SubIdx>
<Name>Product Code</Name>
<Type>UDINT</Type>
<BitSize>32</BitSize>
<BitOffs>48</BitOffs>
<Flags>
<Access>ro</Access>
</Flags>
</SubItem>
<SubItem>
<SubIdx>3</SubIdx>
<Name>Revision Number</Name>
<Type>UDINT</Type>
<BitSize>32</BitSize>
<BitOffs>80</BitOffs>
<Flags>
<Access>ro</Access>
</Flags>
</SubItem>
<SubItem>
<SubIdx>4</SubIdx>
<Name>Serial Number</Name>
<Type>UDINT</Type>
<BitSize>32</BitSize>
<BitOffs>112</BitOffs>
<Flags>
<Access>ro</Access>
</Flags>
</SubItem>
</DataType>
<DataType>
<Name>DT1600</Name>
<BitSize>48</BitSize>
<SubItem>
<SubIdx>0</SubIdx>
<Name>Max SubIndex</Name>
<Type>USINT</Type>
<BitSize>8</BitSize>
<BitOffs>0</BitOffs>
<Flags>
<Access>ro</Access>
</Flags>
</SubItem>
<SubItem>
<SubIdx>1</SubIdx>
<Name>EncPosScale</Name>
<Type>UDINT</Type>
<BitSize>32</BitSize>
<BitOffs>16</BitOffs>
<Flags>
<Access>ro</Access>
</Flags>
</SubItem>
</DataType>
<DataType>
<Name>DT1601</Name>
<BitSize>48</BitSize>
<SubItem>
<SubIdx>0</SubIdx>
<Name>Max SubIndex</Name>
<Type>USINT</Type>
<BitSize>8</BitSize>
<BitOffs>0</BitOffs>
<Flags>
<Access>ro</Access>
</Flags>
</SubItem>
<SubItem>
<SubIdx>1</SubIdx>
<Name>EncIndexCEnable</Name>
<Type>UDINT</Type>
<BitSize>32</BitSize>
<BitOffs>16</BitOffs>
<Flags>
<Access>ro</Access>
</Flags>
</SubItem>
</DataType>
<DataType>
<Name>DT1A00</Name>
<BitSize>48</BitSize>
<SubItem>
<SubIdx>0</SubIdx>
<Name>Max SubIndex</Name>
<Type>USINT</Type>
<BitSize>8</BitSize>
<BitOffs>0</BitOffs>
<Flags>
<Access>ro</Access>
</Flags>
</SubItem>
<SubItem>
<SubIdx>1</SubIdx>
<Name>EncPos</Name>
<Type>UDINT</Type>
<BitSize>32</BitSize>
<BitOffs>16</BitOffs>
<Flags>
<Access>ro</Access>
</Flags>
</SubItem>
</DataType>
<DataType>
<Name>DT1A01</Name>
<BitSize>48</BitSize>
<SubItem>
<SubIdx>0</SubIdx>
<Name>Max SubIndex</Name>
<Type>USINT</Type>
<BitSize>8</BitSize>
<BitOffs>0</BitOffs>
<Flags>
<Access>ro</Access>
</Flags>
</SubItem>
<SubItem>
<SubIdx>1</SubIdx>
<Name>EncFrequency</Name>
<Type>UDINT</Type>
<BitSize>32</BitSize>
<BitOffs>16</BitOffs>
<Flags>
<Access>ro</Access>
</Flags>
</SubItem>
</DataType>
<DataType>
<Name>DT1C00ARR</Name>
<BaseType>USINT</BaseType>
<BitSize>32</BitSize>
<ArrayInfo>
<LBound>1</LBound>
<Elements>4</Elements>
</ArrayInfo>
</DataType>
<DataType>
<Name>DT1C00</Name>
<BitSize>48</BitSize>
<SubItem>
<SubIdx>0</SubIdx>
<Name>Max SubIndex</Name>
<Type>USINT</Type>
<BitSize>8</BitSize>
<BitOffs>0</BitOffs>
<Flags>
<Access>ro</Access>
</Flags>
</SubItem>
<SubItem>
<Name>Elements</Name>
<Type>DT1C00ARR</Type>
<BitSize>32</BitSize>
<BitOffs>16</BitOffs>
<Flags>
<Access>ro</Access>
</Flags>
</SubItem>
</DataType>
<DataType>
<Name>DT1C12ARR</Name>
<BaseType>UINT</BaseType>
<BitSize>32</BitSize>
<ArrayInfo>
<LBound>1</LBound>
<Elements>2</Elements>
</ArrayInfo>
</DataType>
<DataType>
<Name>DT1C12</Name>
<BitSize>48</BitSize>
<SubItem>
<SubIdx>0</SubIdx>
<Name>Max SubIndex</Name>
<Type>USINT</Type>
<BitSize>8</BitSize>
<BitOffs>0</BitOffs>
<Flags>
<Access>ro</Access>
</Flags>
</SubItem>
<SubItem>
<Name>Elements</Name>
<Type>DT1C12ARR</Type>
<BitSize>32</BitSize>
<BitOffs>16</BitOffs>
<Flags>
<Access>ro</Access>
</Flags>
</SubItem>
</DataType>
<DataType>
<Name>DT1C13ARR</Name>
<BaseType>UINT</BaseType>
<BitSize>32</BitSize>
<ArrayInfo>
<LBound>1</LBound>
<Elements>2</Elements>
</ArrayInfo>
</DataType>
<DataType>
<Name>DT1C13</Name>
<BitSize>48</BitSize>
<SubItem>
<SubIdx>0</SubIdx>
<Name>Max SubIndex</Name>
<Type>USINT</Type>
<BitSize>8</BitSize>
<BitOffs>0</BitOffs>
<Flags>
<Access>ro</Access>
</Flags>
</SubItem>
<SubItem>
<Name>Elements</Name>
<Type>DT1C13ARR</Type>
<BitSize>32</BitSize>
<BitOffs>16</BitOffs>
<Flags>
<Access>ro</Access>
</Flags>
</SubItem>
</DataType>
<DataType>
<Name>UDINT</Name>
<BitSize>32</BitSize>
</DataType>
<DataType>
<Name>STRING(26)</Name>
<BitSize>208</BitSize>
</DataType>
<DataType>
<Name>STRING(5)</Name>
<BitSize>40</BitSize>
</DataType>
<DataType>
<Name>USINT</Name>
<BitSize>8</BitSize>
</DataType>
<DataType>
<Name>UINT</Name>
<BitSize>16</BitSize>
</DataType>
<DataType>
<Name>REAL</Name>
<BitSize>32</BitSize>
</DataType>
<DataType>
<Name>DINT</Name>
<BitSize>32</BitSize>
</DataType>
</DataTypes>
<Objects>
<Object>
<Index>#x1000</Index>
<Name>Device Type</Name>
<Type>UDINT</Type>
<BitSize>32</BitSize>
<Info>
<DefaultValue>5001</DefaultValue>
</Info>
<Flags>
<Access>ro</Access>
<Category>m</Category>
</Flags>
</Object>
<Object>
<Index>#x1008</Index>
<Name>Device Name</Name>
<Type>STRING(26)</Type>
<BitSize>208</BitSize>
<Info>
<DefaultString>MetalMusings EaserCAT 2000</DefaultString>
</Info>
<Flags>
<Access>ro</Access>
</Flags>
</Object>
<Object>
<Index>#x1009</Index>
<Name>Hardware Version</Name>
<Type>STRING(5)</Type>
<BitSize>40</BitSize>
<Info>
<DefaultString>0.0.1</DefaultString>
</Info>
<Flags>
<Access>ro</Access>
<Category>o</Category>
</Flags>
</Object>
<Object>
<Index>#x100A</Index>
<Name>Software Version</Name>
<Type>STRING(5)</Type>
<BitSize>40</BitSize>
<Info>
<DefaultString>0.0.1</DefaultString>
</Info>
<Flags>
<Access>ro</Access>
</Flags>
</Object>
<Object>
<Index>#x1018</Index>
<Name>Identity Object</Name>
<Type>DT1018</Type>
<BitSize>144</BitSize>
<Info>
<SubItem>
<Name>Max SubIndex</Name>
<Info>
<DefaultValue>4</DefaultValue>
</Info>
</SubItem>
<SubItem>
<Name>Vendor ID</Name>
<Info>
<DefaultValue>2730</DefaultValue>
</Info>
</SubItem>
<SubItem>
<Name>Product Code</Name>
<Info>
<DefaultValue>12303564</DefaultValue>
</Info>
</SubItem>
<SubItem>
<Name>Revision Number</Name>
<Info>
<DefaultValue>2</DefaultValue>
</Info>
</SubItem>
<SubItem>
<Name>Serial Number</Name>
<Info>
<DefaultValue>1</DefaultValue>
</Info>
</SubItem>
</Info>
<Flags>
<Access>ro</Access>
</Flags>
</Object>
<Object>
<Index>#x1600</Index>
<Name>EncPosScale</Name>
<Type>DT1600</Type>
<BitSize>48</BitSize>
<Info>
<SubItem>
<Name>Max SubIndex</Name>
<Info>
<DefaultValue>1</DefaultValue>
</Info>
</SubItem>
<SubItem>
<Name>EncPosScale</Name>
<Info>
<DefaultValue>#x70000020</DefaultValue>
</Info>
</SubItem>
</Info>
<Flags>
<Access>ro</Access>
</Flags>
</Object>
<Object>
<Index>#x1601</Index>
<Name>EncIndexCEnable</Name>
<Type>DT1601</Type>
<BitSize>48</BitSize>
<Info>
<SubItem>
<Name>Max SubIndex</Name>
<Info>
<DefaultValue>1</DefaultValue>
</Info>
</SubItem>
<SubItem>
<Name>EncIndexCEnable</Name>
<Info>
<DefaultValue>#x70010020</DefaultValue>
</Info>
</SubItem>
</Info>
<Flags>
<Access>ro</Access>
</Flags>
</Object>
<Object>
<Index>#x1A00</Index>
<Name>EncPos</Name>
<Type>DT1A00</Type>
<BitSize>48</BitSize>
<Info>
<SubItem>
<Name>Max SubIndex</Name>
<Info>
<DefaultValue>1</DefaultValue>
</Info>
</SubItem>
<SubItem>
<Name>EncPos</Name>
<Info>
<DefaultValue>#x60000020</DefaultValue>
</Info>
</SubItem>
</Info>
<Flags>
<Access>ro</Access>
</Flags>
</Object>
<Object>
<Index>#x1A01</Index>
<Name>EncFrequency</Name>
<Type>DT1A01</Type>
<BitSize>48</BitSize>
<Info>
<SubItem>
<Name>Max SubIndex</Name>
<Info>
<DefaultValue>1</DefaultValue>
</Info>
</SubItem>
<SubItem>
<Name>EncFrequency</Name>
<Info>
<DefaultValue>#x60010020</DefaultValue>
</Info>
</SubItem>
</Info>
<Flags>
<Access>ro</Access>
</Flags>
</Object>
<Object>
<Index>#x1C00</Index>
<Name>Sync Manager Communication Type</Name>
<Type>DT1C00</Type>
<BitSize>48</BitSize>
<Info>
<SubItem>
<Name>Max SubIndex</Name>
<Info>
<DefaultValue>4</DefaultValue>
</Info>
</SubItem>
<SubItem>
<Name>Communications Type SM0</Name>
<Info>
<DefaultValue>1</DefaultValue>
</Info>
</SubItem>
<SubItem>
<Name>Communications Type SM1</Name>
<Info>
<DefaultValue>2</DefaultValue>
</Info>
</SubItem>
<SubItem>
<Name>Communications Type SM2</Name>
<Info>
<DefaultValue>3</DefaultValue>
</Info>
</SubItem>
<SubItem>
<Name>Communications Type SM3</Name>
<Info>
<DefaultValue>4</DefaultValue>
</Info>
</SubItem>
</Info>
<Flags>
<Access>ro</Access>
</Flags>
</Object>
<Object>
<Index>#x1C12</Index>
<Name>Sync Manager 2 PDO Assignment</Name>
<Type>DT1C12</Type>
<BitSize>48</BitSize>
<Info>
<SubItem>
<Name>Max SubIndex</Name>
<Info>
<DefaultValue>2</DefaultValue>
</Info>
</SubItem>
<SubItem>
<Name>PDO Mapping</Name>
<Info>
<DefaultValue>#x1600</DefaultValue>
</Info>
</SubItem>
<SubItem>
<Name>PDO Mapping</Name>
<Info>
<DefaultValue>#x1601</DefaultValue>
</Info>
</SubItem>
</Info>
<Flags>
<Access>ro</Access>
</Flags>
</Object>
<Object>
<Index>#x1C13</Index>
<Name>Sync Manager 3 PDO Assignment</Name>
<Type>DT1C13</Type>
<BitSize>48</BitSize>
<Info>
<SubItem>
<Name>Max SubIndex</Name>
<Info>
<DefaultValue>2</DefaultValue>
</Info>
</SubItem>
<SubItem>
<Name>PDO Mapping</Name>
<Info>
<DefaultValue>#x1A00</DefaultValue>
</Info>
</SubItem>
<SubItem>
<Name>PDO Mapping</Name>
<Info>
<DefaultValue>#x1A01</DefaultValue>
</Info>
</SubItem>
</Info>
<Flags>
<Access>ro</Access>
</Flags>
</Object>
<Object>
<Index>#x6000</Index>
<Name>EncPos</Name>
<Type>REAL</Type>
<BitSize>32</BitSize>
<Info>
<DefaultValue>0</DefaultValue>
</Info>
<Flags>
<Access>ro</Access>
<PdoMapping>T</PdoMapping>
</Flags>
</Object>
<Object>
<Index>#x6001</Index>
<Name>EncFrequency</Name>
<Type>REAL</Type>
<BitSize>32</BitSize>
<Info>
<DefaultValue>0</DefaultValue>
</Info>
<Flags>
<Access>ro</Access>
<PdoMapping>T</PdoMapping>
</Flags>
</Object>
<Object>
<Index>#x7000</Index>
<Name>EncPosScale</Name>
<Type>DINT</Type>
<BitSize>32</BitSize>
<Info>
<DefaultValue>0</DefaultValue>
</Info>
<Flags>
<Access>ro</Access>
<PdoMapping>R</PdoMapping>
</Flags>
</Object>
<Object>
<Index>#x7001</Index>
<Name>EncIndexCEnable</Name>
<Type>UDINT</Type>
<BitSize>32</BitSize>
<Info>
<DefaultValue>0</DefaultValue>
</Info>
<Flags>
<Access>ro</Access>
<PdoMapping>R</PdoMapping>
</Flags>
</Object>
</Objects>
</Dictionary>
</Profile>
<Fmmu>Outputs</Fmmu>
<Fmmu>Inputs</Fmmu>
<Fmmu>MBoxState</Fmmu>
<Sm DefaultSize="512" StartAddress="#x1000" ControlByte="#x26" Enable="1">MBoxOut</Sm>
<Sm DefaultSize="512" StartAddress="#x1200" ControlByte="#x22" Enable="1">MBoxIn</Sm>
<Sm StartAddress="#x1600" ControlByte="#x24" Enable="1">Outputs</Sm>
<Sm StartAddress="#x1A00" ControlByte="#x20" Enable="1">Inputs</Sm>
<RxPdo Fixed="true" Mandatory="true" Sm="2">
<Index>#x1600</Index>
<Name>EncPosScale</Name>
<Entry>
<Index>#x7000</Index>
<SubIndex>#x0</SubIndex>
<BitLen>32</BitLen>
<Name>EncPosScale</Name>
<DataType>DINT</DataType>
</Entry>
</RxPdo>
<RxPdo Fixed="true" Mandatory="true" Sm="2">
<Index>#x1601</Index>
<Name>EncIndexCEnable</Name>
<Entry>
<Index>#x7001</Index>
<SubIndex>#x0</SubIndex>
<BitLen>32</BitLen>
<Name>EncIndexCEnable</Name>
<DataType>UDINT</DataType>
</Entry>
</RxPdo>
<TxPdo Fixed="true" Mandatory="true" Sm="3">
<Index>#x1A00</Index>
<Name>EncPos</Name>
<Entry>
<Index>#x6000</Index>
<SubIndex>#x0</SubIndex>
<BitLen>32</BitLen>
<Name>EncPos</Name>
<DataType>REAL</DataType>
</Entry>
</TxPdo>
<TxPdo Fixed="true" Mandatory="true" Sm="3">
<Index>#x1A01</Index>
<Name>EncFrequency</Name>
<Entry>
<Index>#x6001</Index>
<SubIndex>#x0</SubIndex>
<BitLen>32</BitLen>
<Name>EncFrequency</Name>
<DataType>REAL</DataType>
</Entry>
</TxPdo>
<Mailbox DataLinkLayer="true">
<CoE SdoInfo="true" PdoAssign="false" PdoConfig="false" PdoUpload="true" CompleteAccess="false" />
</Mailbox>
<Dc>
<OpMode>
<Name>SM-Synchron</Name>
<Desc>SM-Synchron</Desc>
<AssignActivate>#x000</AssignActivate>
</OpMode>
<OpMode>
<Name>DC</Name>
<Desc>DC-Synchron</Desc>
<AssignActivate>#x300</AssignActivate>
</OpMode>
</Dc>
<Eeprom>
<ByteSize>2048</ByteSize>
<ConfigData>80060344640000</ConfigData>
</Eeprom>
</Device>
</Devices>
</Descriptions>
</EtherCATInfo>

View File

@@ -4,8 +4,8 @@
#define USE_FOE 0
#define USE_EOE 0
#define MBXSIZE 128
#define MBXSIZEBOOT 128
#define MBXSIZE 512
#define MBXSIZEBOOT 512
#define MBXBUFFERS 3
#define MBX0_sma 0x1000
@@ -33,8 +33,8 @@
#define SM3_smc 0x20
#define SM3_act 1
#define MAX_MAPPINGS_SM2 7
#define MAX_MAPPINGS_SM3 6
#define MAX_MAPPINGS_SM2 2
#define MAX_MAPPINGS_SM3 2
#define MAX_RXPDO_SIZE 512
#define MAX_TXPDO_SIZE 512

View File

@@ -1,12 +1,12 @@
:2000000080060344640000000000000000001400E1100000D20400000100000002000000D1
:2000200000000000000000000000000000000000001080008010800004000000000000001C
:2000000080060344640000000000000000001400AA0A0000CCBCBB000200000001000000A1
:20002000000000000000000000000000000000000010000200120002040000000000000096
:200040000000000000000000000000000000000000000000000000000000000000000000A0
:20006000000000000000000000000000000000000000000000000000000000000F00010070
:200080000A002100040C456173657243415432303030096D79456E636F64657206494D479
:2000A000434259224D6574616C4D7573696E67732045617365724341542032303030206518
:2000C0006E636F6465721E0010000203010400130000000000000000000011000000000049
:2000E00000000000000000000000280002000102030029001000001080002600010180104F
:200100008000220001020016000024000103001A000020000104FFFFFFFFFFFFFFFFFFFFC7
:200080000A002000040C4561736572434154323030300E4D616368696E65436F6E74726F64
:2000A0006C06494D474342591A4D6574616C4D7573696E67732045617365724341542032E6
:2000C000303030001E00100002030104001300000000000000000000110000000000000034
:2000E000000000000000000028000200010203002900100000100002260001010012000249
:20010000220001020016000024000103001A000020000104FFFFFFFFFFFFFFFFFFFFFFFF49
:20012000FFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFDF
:20014000FFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFBF
:20016000FFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFF9F

View File

@@ -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": {
"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": {
"otype": "RECORD",
"name": "Error Settings",
@@ -44,148 +51,50 @@
},
"txpdo": {
"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",
"name": "ControlWord",
"name": "EncPos",
"access": "RO",
"pdo_mappings": [
"txpdo"
],
"dtype": "UNSIGNED16",
"dtype": "REAL32",
"value": "0",
"data": "&Obj.ControlWord"
"data": "&Obj.EncPos"
},
"6060": {
"6001": {
"otype": "VAR",
"name": "OpMode",
"name": "EncFrequency",
"access": "RO",
"pdo_mappings": [
"txpdo"
],
"dtype": "UNSIGNED8",
"dtype": "REAL32",
"value": "0",
"data": "&Obj.OpMode"
},
"607A": {
"otype": "VAR",
"name": "TargetPosition",
"access": "RO",
"pdo_mappings": [
"txpdo"
],
"dtype": "INTEGER32",
"value": "0",
"data": "&Obj.TargetPosition"
},
"60FF": {
"otype": "VAR",
"name": "TargetVelocity",
"access": "RO",
"pdo_mappings": [
"txpdo"
],
"dtype": "INTEGER32",
"value": "0",
"data": "&Obj.TargetVelocity"
"data": "&Obj.EncFrequency"
}
},
"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": {
"otype": "RECORD",
"name": "EncoderIn",
"otype": "VAR",
"name": "EncPosScale",
"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": [
"rxpdo"
]
],
"dtype": "INTEGER32",
"value": "0",
"data": "&Obj.EncPosScale"
},
"7001": {
"otype": "VAR",
"name": "EncIndexCEnable",
"access": "RO",
"pdo_mappings": [
"rxpdo"
],
"dtype": "UNSIGNED32",
"value": "0",
"data": "&Obj.EncIndexCEnable"
},
"60664": {
"otype": "VAR",
@@ -196,17 +105,6 @@
],
"dtype": "INTEGER32",
"value": "0"
},
"606C": {
"otype": "VAR",
"name": "ActualVelocity",
"access": "RO",
"pdo_mappings": [
"rxpdo"
],
"dtype": "INTEGER32",
"value": "0",
"data": "&Obj.ActualVelocity"
}
}
},

View File

@@ -13,41 +13,18 @@ static const char acName1018_01[] = "Vendor ID";
static const char acName1018_02[] = "Product Code";
static const char acName1018_03[] = "Revision Number";
static const char acName1018_04[] = "Serial Number";
static const char acName1600[] = "StatusWord";
static const char acName1600[] = "EncPosScale";
static const char acName1600_00[] = "Max SubIndex";
static const char acName1600_01[] = "StatusWord";
static const char acName1601[] = "OpModeDisplay";
static const char acName1600_01[] = "EncPosScale";
static const char acName1601[] = "EncIndexCEnable";
static const char acName1601_00[] = "Max SubIndex";
static const char acName1601_01[] = "OpModeDisplay";
static const char acName1602[] = "ActualPosition";
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 acName1601_01[] = "EncIndexCEnable";
static const char acName1A00[] = "EncPos";
static const char acName1A00_00[] = "Max SubIndex";
static const char acName1A00_01[] = "ECount";
static const char acName1A00_02[] = "IndexTriggered";
static const char acName1A01[] = "ControlWord";
static const char acName1A00_01[] = "EncPos";
static const char acName1A01[] = "EncFrequency";
static const char acName1A01_00[] = "Max SubIndex";
static const char acName1A01_01[] = "ControlWord";
static const char acName1A02[] = "OpMode";
static const char acName1A02_00[] = "Max SubIndex";
static const char acName1A02_01[] = "OpMode";
static const char acName1A03[] = "TargetPosition";
static const char acName1A03_00[] = "Max SubIndex";
static const char acName1A03_01[] = "TargetPosition";
static const char acName1A04[] = "TargetVelocity";
static const char acName1A04_00[] = "Max SubIndex";
static const char acName1A04_01[] = "TargetVelocity";
static const char acName1A01_01[] = "EncFrequency";
static const char acName1C00[] = "Sync Manager Communication Type";
static const char acName1C00_00[] = "Max SubIndex";
static const char acName1C00_01[] = "Communications Type SM0";
@@ -58,38 +35,14 @@ static const char acName1C12[] = "Sync Manager 2 PDO Assignment";
static const char acName1C12_00[] = "Max SubIndex";
static const char acName1C12_01[] = "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_00[] = "Max SubIndex";
static const char acName1C13_01[] = "PDO Mapping";
static const char acName1C13_02[] = "PDO Mapping";
static const char acName1C13_03[] = "PDO Mapping";
static const char acName1C13_04[] = "PDO Mapping";
static const char acName1C13_05[] = "PDO Mapping";
static const char acName2000[] = "StepperData";
static const char acName2000_00[] = "Max SubIndex";
static const char acName2000_01[] = "Period";
static const char acName2000_02[] = "Resolution";
static const char acName6000[] = "EncoderOut";
static const char acName6000_00[] = "Max SubIndex";
static const char acName6000_01[] = "ECount";
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";
static const char acName6000[] = "EncPos";
static const char acName6001[] = "EncFrequency";
static const char acName7000[] = "EncPosScale";
static const char acName7001[] = "EncIndexCEnable";
const _objd SDO1000[] =
{
@@ -97,80 +50,43 @@ const _objd SDO1000[] =
};
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[] =
{
{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[] =
{
{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[] =
{
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1018_00, 4, NULL},
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1018_01, 4321, NULL},
{0x02, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1018_02, 1234, NULL},
{0x03, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1018_03, 1, NULL},
{0x04, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1018_04, 2, &Obj.serial},
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1018_01, 2730, NULL},
{0x02, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1018_02, 12303564, NULL},
{0x03, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1018_03, 2, NULL},
{0x04, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1018_04, 1, &Obj.serial},
};
const _objd SDO1600[] =
{
{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[] =
{
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1601_00, 1, NULL},
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1601_01, 0x60610008, 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},
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1601_01, 0x70010020, NULL},
};
const _objd SDO1A00[] =
{
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1A00_00, 2, NULL},
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1A00_01, 0x60000120, NULL},
{0x02, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1A00_02, 0x60000208, NULL},
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1A00_00, 1, NULL},
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1A00_01, 0x60000020, NULL},
};
const _objd SDO1A01[] =
{
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1A01_00, 1, NULL},
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1A01_01, 0x60400010, NULL},
};
const _objd SDO1A02[] =
{
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1A02_00, 1, NULL},
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1A02_01, 0x60600008, NULL},
};
const _objd SDO1A03[] =
{
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1A03_00, 1, NULL},
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1A03_01, 0x607A0020, NULL},
};
const _objd SDO1A04[] =
{
{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, acName1A01_01, 0x60010020, NULL},
};
const _objd SDO1C00[] =
{
@@ -182,76 +98,31 @@ const _objd SDO1C00[] =
};
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},
{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[] =
{
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1C13_00, 5, NULL},
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1C13_00, 2, NULL},
{0x01, DTYPE_UNSIGNED16, 16, ATYPE_RO, acName1C13_01, 0x1A00, NULL},
{0x02, DTYPE_UNSIGNED16, 16, ATYPE_RO, acName1C13_02, 0x1A01, NULL},
{0x03, DTYPE_UNSIGNED16, 16, ATYPE_RO, acName1C13_03, 0x1A02, NULL},
{0x04, DTYPE_UNSIGNED16, 16, ATYPE_RO, acName1C13_04, 0x1A03, 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[] =
{
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName6000_00, 2, NULL},
{0x01, DTYPE_INTEGER32, 32, ATYPE_RO, acName6000_01, 0, &Obj.EncoderOut.ECount},
{0x02, DTYPE_UNSIGNED8, 8, ATYPE_RW, acName6000_02, 0, &Obj.EncoderOut.IndexTriggered},
{0x0, DTYPE_REAL32, 32, ATYPE_RO | ATYPE_TXPDO, acName6000, 0x00000000, &Obj.EncPos},
};
const _objd SDO6040[] =
const _objd SDO6001[] =
{
{0x0, DTYPE_UNSIGNED16, 16, ATYPE_RO | ATYPE_TXPDO, acName6040, 0, &Obj.ControlWord},
};
const _objd SDO6041[] =
{
{0x0, DTYPE_UNSIGNED16, 16, ATYPE_RO | ATYPE_RXPDO, acName6041, 0, &Obj.StatusWord},
};
const _objd SDO6060[] =
{
{0x0, DTYPE_UNSIGNED8, 8, ATYPE_RO | ATYPE_TXPDO, acName6060, 0, &Obj.OpMode},
};
const _objd SDO6061[] =
{
{0x0, DTYPE_UNSIGNED8, 8, ATYPE_RO | ATYPE_RXPDO, acName6061, 0, &Obj.OpModeDisplay},
};
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},
{0x0, DTYPE_REAL32, 32, ATYPE_RO | ATYPE_TXPDO, acName6001, 0x00000000, &Obj.EncFrequency},
};
const _objd SDO7000[] =
{
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName7000_00, 2, NULL},
{0x01, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName7000_01, 0, &Obj.EncoderIn.IndexEnable},
{0x02, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName7000_02, 0, &Obj.EncoderIn.Reset},
{0x0, DTYPE_INTEGER32, 32, ATYPE_RO | ATYPE_RXPDO, acName7000, 0, &Obj.EncPosScale},
};
const _objd SDO7001[] =
{
{0x0, DTYPE_UNSIGNED32, 32, ATYPE_RO | ATYPE_RXPDO, acName7001, 0, &Obj.EncIndexCEnable},
};
const _objectlist SDOobjects[] =
@@ -263,29 +134,14 @@ const _objectlist SDOobjects[] =
{0x1018, OTYPE_RECORD, 4, 0, acName1018, SDO1018},
{0x1600, OTYPE_RECORD, 1, 0, acName1600, SDO1600},
{0x1601, OTYPE_RECORD, 1, 0, acName1601, SDO1601},
{0x1602, OTYPE_RECORD, 1, 0, acName1602, SDO1602},
{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},
{0x1A00, OTYPE_RECORD, 1, 0, acName1A00, SDO1A00},
{0x1A01, OTYPE_RECORD, 1, 0, acName1A01, SDO1A01},
{0x1A02, OTYPE_RECORD, 1, 0, acName1A02, SDO1A02},
{0x1A03, OTYPE_RECORD, 1, 0, acName1A03, SDO1A03},
{0x1A04, OTYPE_RECORD, 1, 0, acName1A04, SDO1A04},
{0x1C00, OTYPE_ARRAY, 4, 0, acName1C00, SDO1C00},
{0x1C12, OTYPE_ARRAY, 6, 0, acName1C12, SDO1C12},
{0x1C13, OTYPE_ARRAY, 5, 0, acName1C13, SDO1C13},
{0x2000, OTYPE_RECORD, 2, 0, acName2000, SDO2000},
{0x6000, OTYPE_RECORD, 2, 0, acName6000, SDO6000},
{0x6040, OTYPE_VAR, 0, 0, acName6040, SDO6040},
{0x6041, OTYPE_VAR, 0, 0, acName6041, SDO6041},
{0x6060, OTYPE_VAR, 0, 0, acName6060, SDO6060},
{0x6061, OTYPE_VAR, 0, 0, acName6061, SDO6061},
{0x6064, OTYPE_VAR, 0, 0, acName6064, SDO6064},
{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},
{0x1C12, OTYPE_ARRAY, 2, 0, acName1C12, SDO1C12},
{0x1C13, OTYPE_ARRAY, 2, 0, acName1C13, SDO1C13},
{0x6000, OTYPE_VAR, 0, 0, acName6000, SDO6000},
{0x6001, OTYPE_VAR, 0, 0, acName6001, SDO6001},
{0x7000, OTYPE_VAR, 0, 0, acName7000, SDO7000},
{0x7001, OTYPE_VAR, 0, 0, acName7001, SDO7001},
{0xffff, 0xff, 0xff, 0xff, NULL, NULL}
};

View File

@@ -13,36 +13,14 @@ typedef struct
/* Inputs */
struct
{
int32_t ECount;
uint8_t IndexTriggered;
} EncoderOut;
uint16_t ControlWord;
uint8_t OpMode;
int32_t TargetPosition;
int32_t TargetVelocity;
float EncPos;
float EncFrequency;
/* Outputs */
uint16_t StatusWord;
uint8_t OpModeDisplay;
int32_t ActualPosition;
int32_t ActualVelocity;
int32_t ActualTorque;
struct
{
uint8_t IndexEnable;
uint8_t Reset;
} EncoderIn;
int32_t EncPosScale;
uint32_t EncIndexCEnable;
/* Parameters */
struct
{
uint16_t Period;
float Resolution;
} StepperData;
} _Objects;
extern _Objects Obj;

View File

@@ -14,9 +14,10 @@ platform = ststm32
board = genericSTM32F407VGT6
upload_protocol = stlink
debug_tool = stlink
debug_build_flags = -O0 -g -ggdb
debug_build_flags = -O0 -g -ggdb
monitor_port = COM7
monitor_speed = 115200
build_flags = -Wl,--no-warn-rwx-segment
lib_deps =
SPI
lib_deps =
SPI
rlogiacco/CircularBuffer@^1.3.3

View File

@@ -6,44 +6,59 @@ extern "C"
#include "ecat_slv.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 unwrap_encoder(uint16_t in, int64_t *prev);
#include <Stm32F4_Encoder.h>
Encoder EncoderInit;
#include "Stepper.h"
// #include "Stepper.h"
HardwareSerial Serial1(PA10, PA9);
_Objects Obj;
void StepGen(void);
void indexPulse(void);
double PosScaleRes = 1.0;
uint32_t CurPosScale = 1;
uint8_t OldIndexCEnable = 0;
volatile uint8_t IndexEnable = 1;
volatile uint8_t IndexTriggered = 0;
void cb_set_outputs(void) // Master outputs gets here, slave inputs, first operation
{
IndexEnable = Obj.EncoderIn.IndexEnable;
if (!IndexEnable)
IndexTriggered = 0;
if (Obj.EncIndexCEnable && !OldIndexCEnable) // Should only happen first time IndexCEnable is set
{
attachInterrupt(digitalPinToInterrupt(PA2), indexPulse, RISING); // PA2 = Index pulse
}
OldIndexCEnable = Obj.EncIndexCEnable;
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
{
// Obj.EncoderOut.ECount = TIM2->CNT;
Obj.EncoderOut.ECount = unwrap_encoder(TIM2->CNT, &PreviousEncoderCounterValue);
Obj.EncoderOut.IndexTriggered = IndexTriggered;
uint32_t diffT = ESCvar.Time - ESCvar.PrevTime;
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); // Too bad resolution to measure over 1 ms. The length of the circular buffers
Pos.push(CurPos); // tells over how long time the position is measured.
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
}
void indexPulse(void)
{
if (IndexEnable && !IndexTriggered)
{
TIM2->CNT = 0;
IndexTriggered = 1;
}
}
static esc_cfg_t config =
{
.user_arg = NULL,
@@ -52,7 +67,7 @@ static esc_cfg_t config =
.set_defaults_hook = NULL,
.pre_state_change_hook = NULL,
.post_state_change_hook = NULL,
.application_hook = StepGen,
.application_hook = NULL, // StepGen,
.safeoutput_override = NULL,
.pre_object_download_hook = NULL,
.post_object_download_hook = NULL,
@@ -71,14 +86,12 @@ void setup(void)
rcc_config();
// Set starting count value
// EncoderInit.SetCount(Tim2, 0);
EncoderInit.SetCount(Tim2, 0);
// EncoderInit.SetCount(Tim3, 0);
// EncoderInit.SetCount(Tim4, 0);
// EncoderInit.SetCount(Tim8, 0);
attachInterrupt(digitalPinToInterrupt(PA2), indexPulse, RISING); // PA2 = Index pulse
StepperSetup();
// delay(5000); // To give serial port monitor time to receive
// delay(5000); // To give serial port monitor time to receive
Serial1.printf("Before Ecat config\n");
ecat_slv_init(&config);
@@ -110,16 +123,10 @@ int64_t unwrap_encoder(uint16_t in, int64_t *prev)
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.
float StepperResolution = Obj.StepperData.Resolution; // 2.5 pulses/um
int32_t TargetPosition = Obj.TargetPosition; // um
int32_t ActualPosition = 0; // um
int32_t DistanceToGo = TargetPosition - ActualPosition; // um
int32_t PulsesToMake = DistanceToGo * StepperResolution;
int32_t Frequency = PulsesToMake * 1000000 / Period;
// Check if timer done.
detachInterrupt(digitalPinToInterrupt(PA2)); // PA2 = Index pulse;
EncoderInit.SetCount(Tim2, 0);
Pos.clear();
TDelta.clear();
}

View File

@@ -1 +1,3 @@
fp-info-cache
Ethercat-stm32-backup*
*.lck

View File

@@ -64,7 +64,7 @@
39,
40
],
"visible_layers": "002ffe8_00000001",
"visible_layers": "002202a_00000001",
"zone_display_mode": 0
},
"meta": {