Encoder works also for threading cycle. non-optmized.
This commit is contained in:
8
Pcb-1-lan9252/Firmware/.vscode/settings.json
vendored
8
Pcb-1-lan9252/Firmware/.vscode/settings.json
vendored
@@ -2,6 +2,12 @@
|
|||||||
"files.associations": {
|
"files.associations": {
|
||||||
"ecat_slv.h": "c",
|
"ecat_slv.h": "c",
|
||||||
"compare": "cpp",
|
"compare": "cpp",
|
||||||
"*.tpp": "cpp"
|
"*.tpp": "cpp",
|
||||||
|
"*.tcc": "cpp",
|
||||||
|
"deque": "cpp",
|
||||||
|
"string": "cpp",
|
||||||
|
"unordered_map": "cpp",
|
||||||
|
"vector": "cpp",
|
||||||
|
"system_error": "cpp"
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@@ -114,7 +114,7 @@
|
|||||||
</SubItem>
|
</SubItem>
|
||||||
<SubItem>
|
<SubItem>
|
||||||
<SubIdx>1</SubIdx>
|
<SubIdx>1</SubIdx>
|
||||||
<Name>EncIndexCEnable</Name>
|
<Name>IndexLatchEnable</Name>
|
||||||
<Type>UDINT</Type>
|
<Type>UDINT</Type>
|
||||||
<BitSize>32</BitSize>
|
<BitSize>32</BitSize>
|
||||||
<BitOffs>16</BitOffs>
|
<BitOffs>16</BitOffs>
|
||||||
@@ -171,6 +171,78 @@
|
|||||||
</Flags>
|
</Flags>
|
||||||
</SubItem>
|
</SubItem>
|
||||||
</DataType>
|
</DataType>
|
||||||
|
<DataType>
|
||||||
|
<Name>DT1A02</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>DiffT</Name>
|
||||||
|
<Type>UDINT</Type>
|
||||||
|
<BitSize>32</BitSize>
|
||||||
|
<BitOffs>16</BitOffs>
|
||||||
|
<Flags>
|
||||||
|
<Access>ro</Access>
|
||||||
|
</Flags>
|
||||||
|
</SubItem>
|
||||||
|
</DataType>
|
||||||
|
<DataType>
|
||||||
|
<Name>DT1A03</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>IndexByte</Name>
|
||||||
|
<Type>UDINT</Type>
|
||||||
|
<BitSize>32</BitSize>
|
||||||
|
<BitOffs>16</BitOffs>
|
||||||
|
<Flags>
|
||||||
|
<Access>ro</Access>
|
||||||
|
</Flags>
|
||||||
|
</SubItem>
|
||||||
|
</DataType>
|
||||||
|
<DataType>
|
||||||
|
<Name>DT1A04</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>IndexStatus</Name>
|
||||||
|
<Type>UDINT</Type>
|
||||||
|
<BitSize>32</BitSize>
|
||||||
|
<BitOffs>16</BitOffs>
|
||||||
|
<Flags>
|
||||||
|
<Access>ro</Access>
|
||||||
|
</Flags>
|
||||||
|
</SubItem>
|
||||||
|
</DataType>
|
||||||
<DataType>
|
<DataType>
|
||||||
<Name>DT1C00ARR</Name>
|
<Name>DT1C00ARR</Name>
|
||||||
<BaseType>USINT</BaseType>
|
<BaseType>USINT</BaseType>
|
||||||
@@ -238,15 +310,15 @@
|
|||||||
<DataType>
|
<DataType>
|
||||||
<Name>DT1C13ARR</Name>
|
<Name>DT1C13ARR</Name>
|
||||||
<BaseType>UINT</BaseType>
|
<BaseType>UINT</BaseType>
|
||||||
<BitSize>32</BitSize>
|
<BitSize>80</BitSize>
|
||||||
<ArrayInfo>
|
<ArrayInfo>
|
||||||
<LBound>1</LBound>
|
<LBound>1</LBound>
|
||||||
<Elements>2</Elements>
|
<Elements>5</Elements>
|
||||||
</ArrayInfo>
|
</ArrayInfo>
|
||||||
</DataType>
|
</DataType>
|
||||||
<DataType>
|
<DataType>
|
||||||
<Name>DT1C13</Name>
|
<Name>DT1C13</Name>
|
||||||
<BitSize>48</BitSize>
|
<BitSize>96</BitSize>
|
||||||
<SubItem>
|
<SubItem>
|
||||||
<SubIdx>0</SubIdx>
|
<SubIdx>0</SubIdx>
|
||||||
<Name>Max SubIndex</Name>
|
<Name>Max SubIndex</Name>
|
||||||
@@ -260,7 +332,7 @@
|
|||||||
<SubItem>
|
<SubItem>
|
||||||
<Name>Elements</Name>
|
<Name>Elements</Name>
|
||||||
<Type>DT1C13ARR</Type>
|
<Type>DT1C13ARR</Type>
|
||||||
<BitSize>32</BitSize>
|
<BitSize>80</BitSize>
|
||||||
<BitOffs>16</BitOffs>
|
<BitOffs>16</BitOffs>
|
||||||
<Flags>
|
<Flags>
|
||||||
<Access>ro</Access>
|
<Access>ro</Access>
|
||||||
@@ -413,7 +485,7 @@
|
|||||||
</Object>
|
</Object>
|
||||||
<Object>
|
<Object>
|
||||||
<Index>#x1601</Index>
|
<Index>#x1601</Index>
|
||||||
<Name>EncIndexCEnable</Name>
|
<Name>IndexLatchEnable</Name>
|
||||||
<Type>DT1601</Type>
|
<Type>DT1601</Type>
|
||||||
<BitSize>48</BitSize>
|
<BitSize>48</BitSize>
|
||||||
<Info>
|
<Info>
|
||||||
@@ -424,7 +496,7 @@
|
|||||||
</Info>
|
</Info>
|
||||||
</SubItem>
|
</SubItem>
|
||||||
<SubItem>
|
<SubItem>
|
||||||
<Name>EncIndexCEnable</Name>
|
<Name>IndexLatchEnable</Name>
|
||||||
<Info>
|
<Info>
|
||||||
<DefaultValue>#x70010020</DefaultValue>
|
<DefaultValue>#x70010020</DefaultValue>
|
||||||
</Info>
|
</Info>
|
||||||
@@ -480,6 +552,75 @@
|
|||||||
<Access>ro</Access>
|
<Access>ro</Access>
|
||||||
</Flags>
|
</Flags>
|
||||||
</Object>
|
</Object>
|
||||||
|
<Object>
|
||||||
|
<Index>#x1A02</Index>
|
||||||
|
<Name>DiffT</Name>
|
||||||
|
<Type>DT1A02</Type>
|
||||||
|
<BitSize>48</BitSize>
|
||||||
|
<Info>
|
||||||
|
<SubItem>
|
||||||
|
<Name>Max SubIndex</Name>
|
||||||
|
<Info>
|
||||||
|
<DefaultValue>1</DefaultValue>
|
||||||
|
</Info>
|
||||||
|
</SubItem>
|
||||||
|
<SubItem>
|
||||||
|
<Name>DiffT</Name>
|
||||||
|
<Info>
|
||||||
|
<DefaultValue>#x60020020</DefaultValue>
|
||||||
|
</Info>
|
||||||
|
</SubItem>
|
||||||
|
</Info>
|
||||||
|
<Flags>
|
||||||
|
<Access>ro</Access>
|
||||||
|
</Flags>
|
||||||
|
</Object>
|
||||||
|
<Object>
|
||||||
|
<Index>#x1A03</Index>
|
||||||
|
<Name>IndexByte</Name>
|
||||||
|
<Type>DT1A03</Type>
|
||||||
|
<BitSize>48</BitSize>
|
||||||
|
<Info>
|
||||||
|
<SubItem>
|
||||||
|
<Name>Max SubIndex</Name>
|
||||||
|
<Info>
|
||||||
|
<DefaultValue>1</DefaultValue>
|
||||||
|
</Info>
|
||||||
|
</SubItem>
|
||||||
|
<SubItem>
|
||||||
|
<Name>IndexByte</Name>
|
||||||
|
<Info>
|
||||||
|
<DefaultValue>#x60030020</DefaultValue>
|
||||||
|
</Info>
|
||||||
|
</SubItem>
|
||||||
|
</Info>
|
||||||
|
<Flags>
|
||||||
|
<Access>ro</Access>
|
||||||
|
</Flags>
|
||||||
|
</Object>
|
||||||
|
<Object>
|
||||||
|
<Index>#x1A04</Index>
|
||||||
|
<Name>IndexStatus</Name>
|
||||||
|
<Type>DT1A04</Type>
|
||||||
|
<BitSize>48</BitSize>
|
||||||
|
<Info>
|
||||||
|
<SubItem>
|
||||||
|
<Name>Max SubIndex</Name>
|
||||||
|
<Info>
|
||||||
|
<DefaultValue>1</DefaultValue>
|
||||||
|
</Info>
|
||||||
|
</SubItem>
|
||||||
|
<SubItem>
|
||||||
|
<Name>IndexStatus</Name>
|
||||||
|
<Info>
|
||||||
|
<DefaultValue>#x60040020</DefaultValue>
|
||||||
|
</Info>
|
||||||
|
</SubItem>
|
||||||
|
</Info>
|
||||||
|
<Flags>
|
||||||
|
<Access>ro</Access>
|
||||||
|
</Flags>
|
||||||
|
</Object>
|
||||||
<Object>
|
<Object>
|
||||||
<Index>#x1C00</Index>
|
<Index>#x1C00</Index>
|
||||||
<Name>Sync Manager Communication Type</Name>
|
<Name>Sync Manager Communication Type</Name>
|
||||||
@@ -554,12 +695,12 @@
|
|||||||
<Index>#x1C13</Index>
|
<Index>#x1C13</Index>
|
||||||
<Name>Sync Manager 3 PDO Assignment</Name>
|
<Name>Sync Manager 3 PDO Assignment</Name>
|
||||||
<Type>DT1C13</Type>
|
<Type>DT1C13</Type>
|
||||||
<BitSize>48</BitSize>
|
<BitSize>96</BitSize>
|
||||||
<Info>
|
<Info>
|
||||||
<SubItem>
|
<SubItem>
|
||||||
<Name>Max SubIndex</Name>
|
<Name>Max SubIndex</Name>
|
||||||
<Info>
|
<Info>
|
||||||
<DefaultValue>2</DefaultValue>
|
<DefaultValue>5</DefaultValue>
|
||||||
</Info>
|
</Info>
|
||||||
</SubItem>
|
</SubItem>
|
||||||
<SubItem>
|
<SubItem>
|
||||||
@@ -574,6 +715,24 @@
|
|||||||
<DefaultValue>#x1A01</DefaultValue>
|
<DefaultValue>#x1A01</DefaultValue>
|
||||||
</Info>
|
</Info>
|
||||||
</SubItem>
|
</SubItem>
|
||||||
|
<SubItem>
|
||||||
|
<Name>PDO Mapping</Name>
|
||||||
|
<Info>
|
||||||
|
<DefaultValue>#x1A02</DefaultValue>
|
||||||
|
</Info>
|
||||||
|
</SubItem>
|
||||||
|
<SubItem>
|
||||||
|
<Name>PDO Mapping</Name>
|
||||||
|
<Info>
|
||||||
|
<DefaultValue>#x1A03</DefaultValue>
|
||||||
|
</Info>
|
||||||
|
</SubItem>
|
||||||
|
<SubItem>
|
||||||
|
<Name>PDO Mapping</Name>
|
||||||
|
<Info>
|
||||||
|
<DefaultValue>#x1A04</DefaultValue>
|
||||||
|
</Info>
|
||||||
|
</SubItem>
|
||||||
</Info>
|
</Info>
|
||||||
<Flags>
|
<Flags>
|
||||||
<Access>ro</Access>
|
<Access>ro</Access>
|
||||||
@@ -605,6 +764,45 @@
|
|||||||
<PdoMapping>T</PdoMapping>
|
<PdoMapping>T</PdoMapping>
|
||||||
</Flags>
|
</Flags>
|
||||||
</Object>
|
</Object>
|
||||||
|
<Object>
|
||||||
|
<Index>#x6002</Index>
|
||||||
|
<Name>DiffT</Name>
|
||||||
|
<Type>UDINT</Type>
|
||||||
|
<BitSize>32</BitSize>
|
||||||
|
<Info>
|
||||||
|
<DefaultValue>0</DefaultValue>
|
||||||
|
</Info>
|
||||||
|
<Flags>
|
||||||
|
<Access>ro</Access>
|
||||||
|
<PdoMapping>T</PdoMapping>
|
||||||
|
</Flags>
|
||||||
|
</Object>
|
||||||
|
<Object>
|
||||||
|
<Index>#x6003</Index>
|
||||||
|
<Name>IndexByte</Name>
|
||||||
|
<Type>UDINT</Type>
|
||||||
|
<BitSize>32</BitSize>
|
||||||
|
<Info>
|
||||||
|
<DefaultValue>0</DefaultValue>
|
||||||
|
</Info>
|
||||||
|
<Flags>
|
||||||
|
<Access>ro</Access>
|
||||||
|
<PdoMapping>T</PdoMapping>
|
||||||
|
</Flags>
|
||||||
|
</Object>
|
||||||
|
<Object>
|
||||||
|
<Index>#x6004</Index>
|
||||||
|
<Name>IndexStatus</Name>
|
||||||
|
<Type>UDINT</Type>
|
||||||
|
<BitSize>32</BitSize>
|
||||||
|
<Info>
|
||||||
|
<DefaultValue>0</DefaultValue>
|
||||||
|
</Info>
|
||||||
|
<Flags>
|
||||||
|
<Access>ro</Access>
|
||||||
|
<PdoMapping>T</PdoMapping>
|
||||||
|
</Flags>
|
||||||
|
</Object>
|
||||||
<Object>
|
<Object>
|
||||||
<Index>#x7000</Index>
|
<Index>#x7000</Index>
|
||||||
<Name>EncPosScale</Name>
|
<Name>EncPosScale</Name>
|
||||||
@@ -620,7 +818,7 @@
|
|||||||
</Object>
|
</Object>
|
||||||
<Object>
|
<Object>
|
||||||
<Index>#x7001</Index>
|
<Index>#x7001</Index>
|
||||||
<Name>EncIndexCEnable</Name>
|
<Name>IndexLatchEnable</Name>
|
||||||
<Type>UDINT</Type>
|
<Type>UDINT</Type>
|
||||||
<BitSize>32</BitSize>
|
<BitSize>32</BitSize>
|
||||||
<Info>
|
<Info>
|
||||||
@@ -654,12 +852,12 @@
|
|||||||
</RxPdo>
|
</RxPdo>
|
||||||
<RxPdo Fixed="true" Mandatory="true" Sm="2">
|
<RxPdo Fixed="true" Mandatory="true" Sm="2">
|
||||||
<Index>#x1601</Index>
|
<Index>#x1601</Index>
|
||||||
<Name>EncIndexCEnable</Name>
|
<Name>IndexLatchEnable</Name>
|
||||||
<Entry>
|
<Entry>
|
||||||
<Index>#x7001</Index>
|
<Index>#x7001</Index>
|
||||||
<SubIndex>#x0</SubIndex>
|
<SubIndex>#x0</SubIndex>
|
||||||
<BitLen>32</BitLen>
|
<BitLen>32</BitLen>
|
||||||
<Name>EncIndexCEnable</Name>
|
<Name>IndexLatchEnable</Name>
|
||||||
<DataType>UDINT</DataType>
|
<DataType>UDINT</DataType>
|
||||||
</Entry>
|
</Entry>
|
||||||
</RxPdo>
|
</RxPdo>
|
||||||
@@ -685,6 +883,39 @@
|
|||||||
<DataType>REAL</DataType>
|
<DataType>REAL</DataType>
|
||||||
</Entry>
|
</Entry>
|
||||||
</TxPdo>
|
</TxPdo>
|
||||||
|
<TxPdo Fixed="true" Mandatory="true" Sm="3">
|
||||||
|
<Index>#x1A02</Index>
|
||||||
|
<Name>DiffT</Name>
|
||||||
|
<Entry>
|
||||||
|
<Index>#x6002</Index>
|
||||||
|
<SubIndex>#x0</SubIndex>
|
||||||
|
<BitLen>32</BitLen>
|
||||||
|
<Name>DiffT</Name>
|
||||||
|
<DataType>UDINT</DataType>
|
||||||
|
</Entry>
|
||||||
|
</TxPdo>
|
||||||
|
<TxPdo Fixed="true" Mandatory="true" Sm="3">
|
||||||
|
<Index>#x1A03</Index>
|
||||||
|
<Name>IndexByte</Name>
|
||||||
|
<Entry>
|
||||||
|
<Index>#x6003</Index>
|
||||||
|
<SubIndex>#x0</SubIndex>
|
||||||
|
<BitLen>32</BitLen>
|
||||||
|
<Name>IndexByte</Name>
|
||||||
|
<DataType>UDINT</DataType>
|
||||||
|
</Entry>
|
||||||
|
</TxPdo>
|
||||||
|
<TxPdo Fixed="true" Mandatory="true" Sm="3">
|
||||||
|
<Index>#x1A04</Index>
|
||||||
|
<Name>IndexStatus</Name>
|
||||||
|
<Entry>
|
||||||
|
<Index>#x6004</Index>
|
||||||
|
<SubIndex>#x0</SubIndex>
|
||||||
|
<BitLen>32</BitLen>
|
||||||
|
<Name>IndexStatus</Name>
|
||||||
|
<DataType>UDINT</DataType>
|
||||||
|
</Entry>
|
||||||
|
</TxPdo>
|
||||||
<Mailbox DataLinkLayer="true">
|
<Mailbox DataLinkLayer="true">
|
||||||
<CoE SdoInfo="true" PdoAssign="false" PdoConfig="false" PdoUpload="true" CompleteAccess="false" />
|
<CoE SdoInfo="true" PdoAssign="false" PdoConfig="false" PdoUpload="true" CompleteAccess="false" />
|
||||||
</Mailbox>
|
</Mailbox>
|
||||||
|
|||||||
@@ -34,7 +34,7 @@
|
|||||||
#define SM3_act 1
|
#define SM3_act 1
|
||||||
|
|
||||||
#define MAX_MAPPINGS_SM2 2
|
#define MAX_MAPPINGS_SM2 2
|
||||||
#define MAX_MAPPINGS_SM3 2
|
#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
|
||||||
|
|||||||
@@ -71,6 +71,39 @@
|
|||||||
"dtype": "REAL32",
|
"dtype": "REAL32",
|
||||||
"value": "0",
|
"value": "0",
|
||||||
"data": "&Obj.EncFrequency"
|
"data": "&Obj.EncFrequency"
|
||||||
|
},
|
||||||
|
"6002": {
|
||||||
|
"otype": "VAR",
|
||||||
|
"name": "DiffT",
|
||||||
|
"access": "RO",
|
||||||
|
"pdo_mappings": [
|
||||||
|
"txpdo"
|
||||||
|
],
|
||||||
|
"dtype": "UNSIGNED32",
|
||||||
|
"value": "0",
|
||||||
|
"data": "&Obj.DiffT"
|
||||||
|
},
|
||||||
|
"6003": {
|
||||||
|
"otype": "VAR",
|
||||||
|
"name": "IndexByte",
|
||||||
|
"access": "RO",
|
||||||
|
"pdo_mappings": [
|
||||||
|
"txpdo"
|
||||||
|
],
|
||||||
|
"dtype": "UNSIGNED32",
|
||||||
|
"value": "0",
|
||||||
|
"data": "&Obj.IndexByte"
|
||||||
|
},
|
||||||
|
"6004": {
|
||||||
|
"otype": "VAR",
|
||||||
|
"name": "IndexStatus",
|
||||||
|
"access": "RO",
|
||||||
|
"pdo_mappings": [
|
||||||
|
"txpdo"
|
||||||
|
],
|
||||||
|
"dtype": "UNSIGNED32",
|
||||||
|
"value": "0",
|
||||||
|
"data": "&Obj.IndexStatus"
|
||||||
}
|
}
|
||||||
},
|
},
|
||||||
"rxpdo": {
|
"rxpdo": {
|
||||||
@@ -87,14 +120,14 @@
|
|||||||
},
|
},
|
||||||
"7001": {
|
"7001": {
|
||||||
"otype": "VAR",
|
"otype": "VAR",
|
||||||
"name": "EncIndexCEnable",
|
"name": "IndexLatchEnable",
|
||||||
"access": "RO",
|
"access": "RO",
|
||||||
"pdo_mappings": [
|
"pdo_mappings": [
|
||||||
"rxpdo"
|
"rxpdo"
|
||||||
],
|
],
|
||||||
"dtype": "UNSIGNED32",
|
"dtype": "UNSIGNED32",
|
||||||
"value": "0",
|
"value": "0",
|
||||||
"data": "&Obj.EncIndexCEnable"
|
"data": "&Obj.IndexLatchEnable"
|
||||||
},
|
},
|
||||||
"60664": {
|
"60664": {
|
||||||
"otype": "VAR",
|
"otype": "VAR",
|
||||||
|
|||||||
@@ -16,15 +16,24 @@ static const char acName1018_04[] = "Serial Number";
|
|||||||
static const char acName1600[] = "EncPosScale";
|
static const char acName1600[] = "EncPosScale";
|
||||||
static const char acName1600_00[] = "Max SubIndex";
|
static const char acName1600_00[] = "Max SubIndex";
|
||||||
static const char acName1600_01[] = "EncPosScale";
|
static const char acName1600_01[] = "EncPosScale";
|
||||||
static const char acName1601[] = "EncIndexCEnable";
|
static const char acName1601[] = "IndexLatchEnable";
|
||||||
static const char acName1601_00[] = "Max SubIndex";
|
static const char acName1601_00[] = "Max SubIndex";
|
||||||
static const char acName1601_01[] = "EncIndexCEnable";
|
static const char acName1601_01[] = "IndexLatchEnable";
|
||||||
static const char acName1A00[] = "EncPos";
|
static const char acName1A00[] = "EncPos";
|
||||||
static const char acName1A00_00[] = "Max SubIndex";
|
static const char acName1A00_00[] = "Max SubIndex";
|
||||||
static const char acName1A00_01[] = "EncPos";
|
static const char acName1A00_01[] = "EncPos";
|
||||||
static const char acName1A01[] = "EncFrequency";
|
static const char acName1A01[] = "EncFrequency";
|
||||||
static const char acName1A01_00[] = "Max SubIndex";
|
static const char acName1A01_00[] = "Max SubIndex";
|
||||||
static const char acName1A01_01[] = "EncFrequency";
|
static const char acName1A01_01[] = "EncFrequency";
|
||||||
|
static const char acName1A02[] = "DiffT";
|
||||||
|
static const char acName1A02_00[] = "Max SubIndex";
|
||||||
|
static const char acName1A02_01[] = "DiffT";
|
||||||
|
static const char acName1A03[] = "IndexByte";
|
||||||
|
static const char acName1A03_00[] = "Max SubIndex";
|
||||||
|
static const char acName1A03_01[] = "IndexByte";
|
||||||
|
static const char acName1A04[] = "IndexStatus";
|
||||||
|
static const char acName1A04_00[] = "Max SubIndex";
|
||||||
|
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";
|
||||||
@@ -39,10 +48,16 @@ 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";
|
||||||
static const char acName1C13_02[] = "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 acName6000[] = "EncPos";
|
static const char acName6000[] = "EncPos";
|
||||||
static const char acName6001[] = "EncFrequency";
|
static const char acName6001[] = "EncFrequency";
|
||||||
|
static const char acName6002[] = "DiffT";
|
||||||
|
static const char acName6003[] = "IndexByte";
|
||||||
|
static const char acName6004[] = "IndexStatus";
|
||||||
static const char acName7000[] = "EncPosScale";
|
static const char acName7000[] = "EncPosScale";
|
||||||
static const char acName7001[] = "EncIndexCEnable";
|
static const char acName7001[] = "IndexLatchEnable";
|
||||||
|
|
||||||
const _objd SDO1000[] =
|
const _objd SDO1000[] =
|
||||||
{
|
{
|
||||||
@@ -88,6 +103,21 @@ 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, 0x60010020, NULL},
|
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1A01_01, 0x60010020, NULL},
|
||||||
};
|
};
|
||||||
|
const _objd SDO1A02[] =
|
||||||
|
{
|
||||||
|
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1A02_00, 1, NULL},
|
||||||
|
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1A02_01, 0x60020020, NULL},
|
||||||
|
};
|
||||||
|
const _objd SDO1A03[] =
|
||||||
|
{
|
||||||
|
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1A03_00, 1, NULL},
|
||||||
|
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1A03_01, 0x60030020, NULL},
|
||||||
|
};
|
||||||
|
const _objd SDO1A04[] =
|
||||||
|
{
|
||||||
|
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1A04_00, 1, NULL},
|
||||||
|
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1A04_01, 0x60040020, NULL},
|
||||||
|
};
|
||||||
const _objd SDO1C00[] =
|
const _objd SDO1C00[] =
|
||||||
{
|
{
|
||||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1C00_00, 4, NULL},
|
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1C00_00, 4, NULL},
|
||||||
@@ -104,9 +134,12 @@ const _objd SDO1C12[] =
|
|||||||
};
|
};
|
||||||
const _objd SDO1C13[] =
|
const _objd SDO1C13[] =
|
||||||
{
|
{
|
||||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1C13_00, 2, NULL},
|
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1C13_00, 5, NULL},
|
||||||
{0x01, DTYPE_UNSIGNED16, 16, ATYPE_RO, acName1C13_01, 0x1A00, NULL},
|
{0x01, DTYPE_UNSIGNED16, 16, ATYPE_RO, acName1C13_01, 0x1A00, NULL},
|
||||||
{0x02, DTYPE_UNSIGNED16, 16, ATYPE_RO, acName1C13_02, 0x1A01, 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 SDO6000[] =
|
const _objd SDO6000[] =
|
||||||
{
|
{
|
||||||
@@ -116,13 +149,25 @@ const _objd SDO6001[] =
|
|||||||
{
|
{
|
||||||
{0x0, DTYPE_REAL32, 32, ATYPE_RO | ATYPE_TXPDO, acName6001, 0x00000000, &Obj.EncFrequency},
|
{0x0, DTYPE_REAL32, 32, ATYPE_RO | ATYPE_TXPDO, acName6001, 0x00000000, &Obj.EncFrequency},
|
||||||
};
|
};
|
||||||
|
const _objd SDO6002[] =
|
||||||
|
{
|
||||||
|
{0x0, DTYPE_UNSIGNED32, 32, ATYPE_RO | ATYPE_TXPDO, acName6002, 0, &Obj.DiffT},
|
||||||
|
};
|
||||||
|
const _objd SDO6003[] =
|
||||||
|
{
|
||||||
|
{0x0, DTYPE_UNSIGNED32, 32, ATYPE_RO | ATYPE_TXPDO, acName6003, 0, &Obj.IndexByte},
|
||||||
|
};
|
||||||
|
const _objd SDO6004[] =
|
||||||
|
{
|
||||||
|
{0x0, DTYPE_UNSIGNED32, 32, ATYPE_RO | ATYPE_TXPDO, acName6004, 0, &Obj.IndexStatus},
|
||||||
|
};
|
||||||
const _objd SDO7000[] =
|
const _objd SDO7000[] =
|
||||||
{
|
{
|
||||||
{0x0, DTYPE_INTEGER32, 32, ATYPE_RO | ATYPE_RXPDO, acName7000, 0, &Obj.EncPosScale},
|
{0x0, DTYPE_INTEGER32, 32, ATYPE_RO | ATYPE_RXPDO, acName7000, 0, &Obj.EncPosScale},
|
||||||
};
|
};
|
||||||
const _objd SDO7001[] =
|
const _objd SDO7001[] =
|
||||||
{
|
{
|
||||||
{0x0, DTYPE_UNSIGNED32, 32, ATYPE_RO | ATYPE_RXPDO, acName7001, 0, &Obj.EncIndexCEnable},
|
{0x0, DTYPE_UNSIGNED32, 32, ATYPE_RO | ATYPE_RXPDO, acName7001, 0, &Obj.IndexLatchEnable},
|
||||||
};
|
};
|
||||||
|
|
||||||
const _objectlist SDOobjects[] =
|
const _objectlist SDOobjects[] =
|
||||||
@@ -136,11 +181,17 @@ const _objectlist SDOobjects[] =
|
|||||||
{0x1601, OTYPE_RECORD, 1, 0, acName1601, SDO1601},
|
{0x1601, OTYPE_RECORD, 1, 0, acName1601, SDO1601},
|
||||||
{0x1A00, OTYPE_RECORD, 1, 0, acName1A00, SDO1A00},
|
{0x1A00, OTYPE_RECORD, 1, 0, acName1A00, SDO1A00},
|
||||||
{0x1A01, OTYPE_RECORD, 1, 0, acName1A01, SDO1A01},
|
{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},
|
{0x1C00, OTYPE_ARRAY, 4, 0, acName1C00, SDO1C00},
|
||||||
{0x1C12, OTYPE_ARRAY, 2, 0, acName1C12, SDO1C12},
|
{0x1C12, OTYPE_ARRAY, 2, 0, acName1C12, SDO1C12},
|
||||||
{0x1C13, OTYPE_ARRAY, 2, 0, acName1C13, SDO1C13},
|
{0x1C13, OTYPE_ARRAY, 5, 0, acName1C13, SDO1C13},
|
||||||
{0x6000, OTYPE_VAR, 0, 0, acName6000, SDO6000},
|
{0x6000, OTYPE_VAR, 0, 0, acName6000, SDO6000},
|
||||||
{0x6001, OTYPE_VAR, 0, 0, acName6001, SDO6001},
|
{0x6001, OTYPE_VAR, 0, 0, acName6001, SDO6001},
|
||||||
|
{0x6002, OTYPE_VAR, 0, 0, acName6002, SDO6002},
|
||||||
|
{0x6003, OTYPE_VAR, 0, 0, acName6003, SDO6003},
|
||||||
|
{0x6004, OTYPE_VAR, 0, 0, acName6004, SDO6004},
|
||||||
{0x7000, OTYPE_VAR, 0, 0, acName7000, SDO7000},
|
{0x7000, OTYPE_VAR, 0, 0, acName7000, SDO7000},
|
||||||
{0x7001, OTYPE_VAR, 0, 0, acName7001, SDO7001},
|
{0x7001, OTYPE_VAR, 0, 0, acName7001, SDO7001},
|
||||||
{0xffff, 0xff, 0xff, 0xff, NULL, NULL}
|
{0xffff, 0xff, 0xff, 0xff, NULL, NULL}
|
||||||
|
|||||||
@@ -15,11 +15,14 @@ typedef struct
|
|||||||
|
|
||||||
float EncPos;
|
float EncPos;
|
||||||
float EncFrequency;
|
float EncFrequency;
|
||||||
|
uint32_t DiffT;
|
||||||
|
uint32_t IndexByte;
|
||||||
|
uint32_t IndexStatus;
|
||||||
|
|
||||||
/* Outputs */
|
/* Outputs */
|
||||||
|
|
||||||
int32_t EncPosScale;
|
int32_t EncPosScale;
|
||||||
uint32_t EncIndexCEnable;
|
uint32_t IndexLatchEnable;
|
||||||
|
|
||||||
} _Objects;
|
} _Objects;
|
||||||
|
|
||||||
|
|||||||
@@ -15,24 +15,28 @@ 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 indexPulse(void);
|
void indexPulse(void);
|
||||||
double PosScaleRes = 1.0;
|
double PosScaleRes = 1.0;
|
||||||
uint32_t CurPosScale = 1;
|
uint32_t CurPosScale = 1;
|
||||||
uint8_t OldIndexCEnable = 0;
|
uint8_t OldLatchCEnable = 0;
|
||||||
|
volatile uint8_t indexPulseFired = 0;
|
||||||
|
uint32_t nFires = 0;
|
||||||
|
volatile uint8_t pleaseZeroTheCounter=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
|
||||||
{
|
{
|
||||||
if (Obj.EncIndexCEnable && !OldIndexCEnable) // Should only happen first time IndexCEnable is set
|
if (Obj.IndexLatchEnable && !OldLatchCEnable) // Should only happen first time IndexCEnable is set
|
||||||
{
|
{
|
||||||
attachInterrupt(digitalPinToInterrupt(PA2), indexPulse, RISING); // PA2 = Index pulse
|
pleaseZeroTheCounter=1;
|
||||||
}
|
}
|
||||||
OldIndexCEnable = Obj.EncIndexCEnable;
|
OldLatchCEnable = Obj.IndexLatchEnable;
|
||||||
|
|
||||||
if (CurPosScale != Obj.EncPosScale && Obj.EncPosScale != 0)
|
if (CurPosScale != Obj.EncPosScale && Obj.EncPosScale != 0)
|
||||||
{
|
{
|
||||||
@@ -43,6 +47,16 @@ void cb_set_outputs(void) // Master outputs gets here, slave inputs, first opera
|
|||||||
|
|
||||||
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.IndexStatus = 0;
|
||||||
|
if (indexPulseFired)
|
||||||
|
{
|
||||||
|
Obj.IndexStatus = 1;
|
||||||
|
indexPulseFired = 0;
|
||||||
|
nFires++;
|
||||||
|
PreviousEncoderCounterValue = 0;
|
||||||
|
}
|
||||||
|
Obj.DiffT = nFires;
|
||||||
|
|
||||||
int64_t pos = unwrap_encoder(TIM2->CNT, &PreviousEncoderCounterValue);
|
int64_t pos = unwrap_encoder(TIM2->CNT, &PreviousEncoderCounterValue);
|
||||||
double CurPos = pos * PosScaleRes;
|
double CurPos = pos * PosScaleRes;
|
||||||
Obj.EncPos = CurPos;
|
Obj.EncPos = CurPos;
|
||||||
@@ -57,6 +71,19 @@ void cb_get_inputs(void) // Set Master inputs, slave outputs, last operation
|
|||||||
diffPos = fabs(Pos.last() - Pos.first());
|
diffPos = fabs(Pos.last() - Pos.first());
|
||||||
}
|
}
|
||||||
Obj.EncFrequency = diffT != 0 ? diffPos / diffT : 0.0; // Revolutions per second
|
Obj.EncFrequency = diffT != 0 ? diffPos / diffT : 0.0; // Revolutions per second
|
||||||
|
|
||||||
|
Obj.IndexStatus = 0;
|
||||||
|
if (indexPulseFired)
|
||||||
|
{
|
||||||
|
Obj.IndexStatus = 1;
|
||||||
|
indexPulseFired = 0;
|
||||||
|
nFires++;
|
||||||
|
PreviousEncoderCounterValue = 0;
|
||||||
|
}
|
||||||
|
Obj.DiffT = nFires;
|
||||||
|
Obj.IndexByte = digitalRead(INDEX_PIN);
|
||||||
|
if (Obj.IndexByte)
|
||||||
|
Serial1.printf("IS 1\n");
|
||||||
}
|
}
|
||||||
|
|
||||||
static esc_cfg_t config =
|
static esc_cfg_t config =
|
||||||
@@ -81,7 +108,6 @@ 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();
|
||||||
|
|
||||||
@@ -91,11 +117,8 @@ void setup(void)
|
|||||||
// EncoderInit.SetCount(Tim4, 0);
|
// EncoderInit.SetCount(Tim4, 0);
|
||||||
// EncoderInit.SetCount(Tim8, 0);
|
// EncoderInit.SetCount(Tim8, 0);
|
||||||
|
|
||||||
// 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)
|
||||||
@@ -125,8 +148,12 @@ int64_t unwrap_encoder(uint16_t in, int64_t *prev)
|
|||||||
|
|
||||||
void indexPulse(void)
|
void indexPulse(void)
|
||||||
{
|
{
|
||||||
detachInterrupt(digitalPinToInterrupt(PA2)); // PA2 = Index pulse;
|
if (pleaseZeroTheCounter)
|
||||||
EncoderInit.SetCount(Tim2, 0);
|
{
|
||||||
Pos.clear();
|
TIM2->CNT = 0;
|
||||||
TDelta.clear();
|
indexPulseFired = 1;
|
||||||
|
Pos.clear();
|
||||||
|
TDelta.clear();
|
||||||
|
pleaseZeroTheCounter = 0;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
Reference in New Issue
Block a user