Two stepgens active pending lathe test
This commit is contained in:
@@ -125,7 +125,7 @@
|
||||
</DataType>
|
||||
<DataType>
|
||||
<Name>DT1602</Name>
|
||||
<BitSize>144</BitSize>
|
||||
<BitSize>80</BitSize>
|
||||
<SubItem>
|
||||
<SubIdx>0</SubIdx>
|
||||
<Name>Max SubIndex</Name>
|
||||
@@ -146,12 +146,26 @@
|
||||
<Access>ro</Access>
|
||||
</Flags>
|
||||
</SubItem>
|
||||
</DataType>
|
||||
<DataType>
|
||||
<Name>DT1603</Name>
|
||||
<BitSize>80</BitSize>
|
||||
<SubItem>
|
||||
<SubIdx>2</SubIdx>
|
||||
<Name>CommandedVelocity</Name>
|
||||
<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>CommandedPosition</Name>
|
||||
<Type>ULINT</Type>
|
||||
<BitSize>64</BitSize>
|
||||
<BitOffs>80</BitOffs>
|
||||
<BitOffs>16</BitOffs>
|
||||
<Flags>
|
||||
<Access>ro</Access>
|
||||
</Flags>
|
||||
@@ -301,6 +315,30 @@
|
||||
</Flags>
|
||||
</SubItem>
|
||||
</DataType>
|
||||
<DataType>
|
||||
<Name>DT1A06</Name>
|
||||
<BitSize>80</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>ActualPosition</Name>
|
||||
<Type>ULINT</Type>
|
||||
<BitSize>64</BitSize>
|
||||
<BitOffs>16</BitOffs>
|
||||
<Flags>
|
||||
<Access>ro</Access>
|
||||
</Flags>
|
||||
</SubItem>
|
||||
</DataType>
|
||||
<DataType>
|
||||
<Name>DT1C00ARR</Name>
|
||||
<BaseType>USINT</BaseType>
|
||||
@@ -336,15 +374,15 @@
|
||||
<DataType>
|
||||
<Name>DT1C12ARR</Name>
|
||||
<BaseType>UINT</BaseType>
|
||||
<BitSize>48</BitSize>
|
||||
<BitSize>64</BitSize>
|
||||
<ArrayInfo>
|
||||
<LBound>1</LBound>
|
||||
<Elements>3</Elements>
|
||||
<Elements>4</Elements>
|
||||
</ArrayInfo>
|
||||
</DataType>
|
||||
<DataType>
|
||||
<Name>DT1C12</Name>
|
||||
<BitSize>64</BitSize>
|
||||
<BitSize>80</BitSize>
|
||||
<SubItem>
|
||||
<SubIdx>0</SubIdx>
|
||||
<Name>Max SubIndex</Name>
|
||||
@@ -358,7 +396,7 @@
|
||||
<SubItem>
|
||||
<Name>Elements</Name>
|
||||
<Type>DT1C12ARR</Type>
|
||||
<BitSize>48</BitSize>
|
||||
<BitSize>64</BitSize>
|
||||
<BitOffs>16</BitOffs>
|
||||
<Flags>
|
||||
<Access>ro</Access>
|
||||
@@ -368,15 +406,15 @@
|
||||
<DataType>
|
||||
<Name>DT1C13ARR</Name>
|
||||
<BaseType>UINT</BaseType>
|
||||
<BitSize>96</BitSize>
|
||||
<BitSize>112</BitSize>
|
||||
<ArrayInfo>
|
||||
<LBound>1</LBound>
|
||||
<Elements>6</Elements>
|
||||
<Elements>7</Elements>
|
||||
</ArrayInfo>
|
||||
</DataType>
|
||||
<DataType>
|
||||
<Name>DT1C13</Name>
|
||||
<BitSize>112</BitSize>
|
||||
<BitSize>128</BitSize>
|
||||
<SubItem>
|
||||
<SubIdx>0</SubIdx>
|
||||
<Name>Max SubIndex</Name>
|
||||
@@ -390,7 +428,7 @@
|
||||
<SubItem>
|
||||
<Name>Elements</Name>
|
||||
<Type>DT1C13ARR</Type>
|
||||
<BitSize>96</BitSize>
|
||||
<BitSize>112</BitSize>
|
||||
<BitOffs>16</BitOffs>
|
||||
<Flags>
|
||||
<Access>ro</Access>
|
||||
@@ -422,9 +460,34 @@
|
||||
</Flags>
|
||||
</SubItem>
|
||||
</DataType>
|
||||
<DataType>
|
||||
<Name>DT6006</Name>
|
||||
<BitSize>80</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>ActualPosition</Name>
|
||||
<Type>LREAL</Type>
|
||||
<BitSize>64</BitSize>
|
||||
<BitOffs>16</BitOffs>
|
||||
<Flags>
|
||||
<Access WriteRestrictions="PreOP">ro</Access>
|
||||
<PdoMapping>T</PdoMapping>
|
||||
</Flags>
|
||||
</SubItem>
|
||||
</DataType>
|
||||
<DataType>
|
||||
<Name>DT7002</Name>
|
||||
<BitSize>144</BitSize>
|
||||
<BitSize>80</BitSize>
|
||||
<SubItem>
|
||||
<SubIdx>0</SubIdx>
|
||||
<Name>Max SubIndex</Name>
|
||||
@@ -446,12 +509,26 @@
|
||||
<PdoMapping>R</PdoMapping>
|
||||
</Flags>
|
||||
</SubItem>
|
||||
</DataType>
|
||||
<DataType>
|
||||
<Name>DT7003</Name>
|
||||
<BitSize>80</BitSize>
|
||||
<SubItem>
|
||||
<SubIdx>2</SubIdx>
|
||||
<Name>CommandedVelocity</Name>
|
||||
<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>CommandedPosition</Name>
|
||||
<Type>LREAL</Type>
|
||||
<BitSize>64</BitSize>
|
||||
<BitOffs>80</BitOffs>
|
||||
<BitOffs>16</BitOffs>
|
||||
<Flags>
|
||||
<Access WriteRestrictions="PreOP">ro</Access>
|
||||
<PdoMapping>R</PdoMapping>
|
||||
@@ -633,12 +710,12 @@
|
||||
<Index>#x1602</Index>
|
||||
<Name>StepGenIn1</Name>
|
||||
<Type>DT1602</Type>
|
||||
<BitSize>144</BitSize>
|
||||
<BitSize>80</BitSize>
|
||||
<Info>
|
||||
<SubItem>
|
||||
<Name>Max SubIndex</Name>
|
||||
<Info>
|
||||
<DefaultValue>2</DefaultValue>
|
||||
<DefaultValue>1</DefaultValue>
|
||||
</Info>
|
||||
</SubItem>
|
||||
<SubItem>
|
||||
@@ -647,10 +724,27 @@
|
||||
<DefaultValue>#x70020140</DefaultValue>
|
||||
</Info>
|
||||
</SubItem>
|
||||
<SubItem>
|
||||
<Name>CommandedVelocity</Name>
|
||||
</Info>
|
||||
<Flags>
|
||||
<Access>ro</Access>
|
||||
</Flags>
|
||||
</Object>
|
||||
<Object>
|
||||
<Index>#x1603</Index>
|
||||
<Name>StepGenIn2</Name>
|
||||
<Type>DT1603</Type>
|
||||
<BitSize>80</BitSize>
|
||||
<Info>
|
||||
<DefaultValue>#x70020240</DefaultValue>
|
||||
<SubItem>
|
||||
<Name>Max SubIndex</Name>
|
||||
<Info>
|
||||
<DefaultValue>1</DefaultValue>
|
||||
</Info>
|
||||
</SubItem>
|
||||
<SubItem>
|
||||
<Name>CommandedPosition</Name>
|
||||
<Info>
|
||||
<DefaultValue>#x70030140</DefaultValue>
|
||||
</Info>
|
||||
</SubItem>
|
||||
</Info>
|
||||
@@ -796,6 +890,29 @@
|
||||
<Access>ro</Access>
|
||||
</Flags>
|
||||
</Object>
|
||||
<Object>
|
||||
<Index>#x1A06</Index>
|
||||
<Name>StepGenOut2</Name>
|
||||
<Type>DT1A06</Type>
|
||||
<BitSize>80</BitSize>
|
||||
<Info>
|
||||
<SubItem>
|
||||
<Name>Max SubIndex</Name>
|
||||
<Info>
|
||||
<DefaultValue>1</DefaultValue>
|
||||
</Info>
|
||||
</SubItem>
|
||||
<SubItem>
|
||||
<Name>ActualPosition</Name>
|
||||
<Info>
|
||||
<DefaultValue>#x60060140</DefaultValue>
|
||||
</Info>
|
||||
</SubItem>
|
||||
</Info>
|
||||
<Flags>
|
||||
<Access>ro</Access>
|
||||
</Flags>
|
||||
</Object>
|
||||
<Object>
|
||||
<Index>#x1C00</Index>
|
||||
<Name>Sync Manager Communication Type</Name>
|
||||
@@ -841,12 +958,12 @@
|
||||
<Index>#x1C12</Index>
|
||||
<Name>Sync Manager 2 PDO Assignment</Name>
|
||||
<Type>DT1C12</Type>
|
||||
<BitSize>64</BitSize>
|
||||
<BitSize>80</BitSize>
|
||||
<Info>
|
||||
<SubItem>
|
||||
<Name>Max SubIndex</Name>
|
||||
<Info>
|
||||
<DefaultValue>3</DefaultValue>
|
||||
<DefaultValue>4</DefaultValue>
|
||||
</Info>
|
||||
</SubItem>
|
||||
<SubItem>
|
||||
@@ -867,6 +984,12 @@
|
||||
<DefaultValue>#x1602</DefaultValue>
|
||||
</Info>
|
||||
</SubItem>
|
||||
<SubItem>
|
||||
<Name>PDO Mapping</Name>
|
||||
<Info>
|
||||
<DefaultValue>#x1603</DefaultValue>
|
||||
</Info>
|
||||
</SubItem>
|
||||
</Info>
|
||||
<Flags>
|
||||
<Access>ro</Access>
|
||||
@@ -876,12 +999,12 @@
|
||||
<Index>#x1C13</Index>
|
||||
<Name>Sync Manager 3 PDO Assignment</Name>
|
||||
<Type>DT1C13</Type>
|
||||
<BitSize>112</BitSize>
|
||||
<BitSize>128</BitSize>
|
||||
<Info>
|
||||
<SubItem>
|
||||
<Name>Max SubIndex</Name>
|
||||
<Info>
|
||||
<DefaultValue>6</DefaultValue>
|
||||
<DefaultValue>7</DefaultValue>
|
||||
</Info>
|
||||
</SubItem>
|
||||
<SubItem>
|
||||
@@ -920,6 +1043,12 @@
|
||||
<DefaultValue>#x1A05</DefaultValue>
|
||||
</Info>
|
||||
</SubItem>
|
||||
<SubItem>
|
||||
<Name>PDO Mapping</Name>
|
||||
<Info>
|
||||
<DefaultValue>#x1A06</DefaultValue>
|
||||
</Info>
|
||||
</SubItem>
|
||||
</Info>
|
||||
<Flags>
|
||||
<Access>ro</Access>
|
||||
@@ -1013,6 +1142,29 @@
|
||||
<Access>ro</Access>
|
||||
</Flags>
|
||||
</Object>
|
||||
<Object>
|
||||
<Index>#x6006</Index>
|
||||
<Name>StepGenOut2</Name>
|
||||
<Type>DT6006</Type>
|
||||
<BitSize>80</BitSize>
|
||||
<Info>
|
||||
<SubItem>
|
||||
<Name>Max SubIndex</Name>
|
||||
<Info>
|
||||
<DefaultValue>1</DefaultValue>
|
||||
</Info>
|
||||
</SubItem>
|
||||
<SubItem>
|
||||
<Name>ActualPosition</Name>
|
||||
<Info>
|
||||
<DefaultValue>0</DefaultValue>
|
||||
</Info>
|
||||
</SubItem>
|
||||
</Info>
|
||||
<Flags>
|
||||
<Access>ro</Access>
|
||||
</Flags>
|
||||
</Object>
|
||||
<Object>
|
||||
<Index>#x7000</Index>
|
||||
<Name>EncPosScale</Name>
|
||||
@@ -1043,12 +1195,12 @@
|
||||
<Index>#x7002</Index>
|
||||
<Name>StepGenIn1</Name>
|
||||
<Type>DT7002</Type>
|
||||
<BitSize>144</BitSize>
|
||||
<BitSize>80</BitSize>
|
||||
<Info>
|
||||
<SubItem>
|
||||
<Name>Max SubIndex</Name>
|
||||
<Info>
|
||||
<DefaultValue>2</DefaultValue>
|
||||
<DefaultValue>1</DefaultValue>
|
||||
</Info>
|
||||
</SubItem>
|
||||
<SubItem>
|
||||
@@ -1057,8 +1209,25 @@
|
||||
<DefaultValue>0</DefaultValue>
|
||||
</Info>
|
||||
</SubItem>
|
||||
</Info>
|
||||
<Flags>
|
||||
<Access>ro</Access>
|
||||
</Flags>
|
||||
</Object>
|
||||
<Object>
|
||||
<Index>#x7003</Index>
|
||||
<Name>StepGenIn2</Name>
|
||||
<Type>DT7003</Type>
|
||||
<BitSize>80</BitSize>
|
||||
<Info>
|
||||
<SubItem>
|
||||
<Name>CommandedVelocity</Name>
|
||||
<Name>Max SubIndex</Name>
|
||||
<Info>
|
||||
<DefaultValue>1</DefaultValue>
|
||||
</Info>
|
||||
</SubItem>
|
||||
<SubItem>
|
||||
<Name>CommandedPosition</Name>
|
||||
<Info>
|
||||
<DefaultValue>0</DefaultValue>
|
||||
</Info>
|
||||
@@ -1110,11 +1279,15 @@
|
||||
<Name>CommandedPosition</Name>
|
||||
<DataType>LREAL</DataType>
|
||||
</Entry>
|
||||
</RxPdo>
|
||||
<RxPdo Fixed="true" Mandatory="true" Sm="2">
|
||||
<Index>#x1603</Index>
|
||||
<Name>StepGenIn2</Name>
|
||||
<Entry>
|
||||
<Index>#x7002</Index>
|
||||
<SubIndex>#x2</SubIndex>
|
||||
<Index>#x7003</Index>
|
||||
<SubIndex>#x1</SubIndex>
|
||||
<BitLen>64</BitLen>
|
||||
<Name>CommandedVelocity</Name>
|
||||
<Name>CommandedPosition</Name>
|
||||
<DataType>LREAL</DataType>
|
||||
</Entry>
|
||||
</RxPdo>
|
||||
@@ -1184,6 +1357,17 @@
|
||||
<DataType>LREAL</DataType>
|
||||
</Entry>
|
||||
</TxPdo>
|
||||
<TxPdo Fixed="true" Mandatory="true" Sm="3">
|
||||
<Index>#x1A06</Index>
|
||||
<Name>StepGenOut2</Name>
|
||||
<Entry>
|
||||
<Index>#x6006</Index>
|
||||
<SubIndex>#x1</SubIndex>
|
||||
<BitLen>64</BitLen>
|
||||
<Name>ActualPosition</Name>
|
||||
<DataType>LREAL</DataType>
|
||||
</Entry>
|
||||
</TxPdo>
|
||||
<Mailbox DataLinkLayer="true">
|
||||
<CoE SdoInfo="true" PdoAssign="false" PdoConfig="false" PdoUpload="true" CompleteAccess="false" />
|
||||
</Mailbox>
|
||||
|
||||
@@ -34,7 +34,7 @@
|
||||
#define SM3_act 1
|
||||
|
||||
#define MAX_MAPPINGS_SM2 4
|
||||
#define MAX_MAPPINGS_SM3 6
|
||||
#define MAX_MAPPINGS_SM3 7
|
||||
|
||||
#define MAX_RXPDO_SIZE 512
|
||||
#define MAX_TXPDO_SIZE 512
|
||||
|
||||
@@ -124,6 +124,26 @@
|
||||
"pdo_mappings": [
|
||||
"txpdo"
|
||||
]
|
||||
},
|
||||
"6006": {
|
||||
"otype": "RECORD",
|
||||
"name": "StepGenOut2",
|
||||
"access": "RO",
|
||||
"items": [
|
||||
{
|
||||
"name": "Max SubIndex"
|
||||
},
|
||||
{
|
||||
"name": "ActualPosition",
|
||||
"dtype": "REAL64",
|
||||
"data": "&Obj.StepGenOut2.ActualPosition",
|
||||
"value": "0",
|
||||
"access": "RO"
|
||||
}
|
||||
],
|
||||
"pdo_mappings": [
|
||||
"txpdo"
|
||||
]
|
||||
}
|
||||
},
|
||||
"rxpdo": {
|
||||
@@ -163,13 +183,26 @@
|
||||
"data": "&Obj.StepGenIn1.CommandedPosition",
|
||||
"value": "0",
|
||||
"access": "RO"
|
||||
}
|
||||
],
|
||||
"pdo_mappings": [
|
||||
"rxpdo"
|
||||
]
|
||||
},
|
||||
"7003": {
|
||||
"otype": "RECORD",
|
||||
"name": "StepGenIn2",
|
||||
"access": "RO",
|
||||
"items": [
|
||||
{
|
||||
"name": "Max SubIndex"
|
||||
},
|
||||
{
|
||||
"name": "CommandedVelocity",
|
||||
"name": "CommandedPosition",
|
||||
"dtype": "REAL64",
|
||||
"data": "&Obj.StepGenIn2.CommandedPosition",
|
||||
"value": "0",
|
||||
"access": "RO",
|
||||
"data": "&Obj.StepGenIn1.CommandedVelocity"
|
||||
"access": "RO"
|
||||
}
|
||||
],
|
||||
"pdo_mappings": [
|
||||
|
||||
@@ -22,7 +22,9 @@ static const char acName1601_01[] = "IndexLatchEnable";
|
||||
static const char acName1602[] = "StepGenIn1";
|
||||
static const char acName1602_00[] = "Max SubIndex";
|
||||
static const char acName1602_01[] = "CommandedPosition";
|
||||
static const char acName1602_02[] = "CommandedVelocity";
|
||||
static const char acName1603[] = "StepGenIn2";
|
||||
static const char acName1603_00[] = "Max SubIndex";
|
||||
static const char acName1603_01[] = "CommandedPosition";
|
||||
static const char acName1A00[] = "EncPos";
|
||||
static const char acName1A00_00[] = "Max SubIndex";
|
||||
static const char acName1A00_01[] = "EncPos";
|
||||
@@ -41,6 +43,9 @@ static const char acName1A04_01[] = "IndexStatus";
|
||||
static const char acName1A05[] = "StepGenOut1";
|
||||
static const char acName1A05_00[] = "Max SubIndex";
|
||||
static const char acName1A05_01[] = "ActualPosition";
|
||||
static const char acName1A06[] = "StepGenOut2";
|
||||
static const char acName1A06_00[] = "Max SubIndex";
|
||||
static const char acName1A06_01[] = "ActualPosition";
|
||||
static const char acName1C00[] = "Sync Manager Communication Type";
|
||||
static const char acName1C00_00[] = "Max SubIndex";
|
||||
static const char acName1C00_01[] = "Communications Type SM0";
|
||||
@@ -52,6 +57,7 @@ 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 acName1C13[] = "Sync Manager 3 PDO Assignment";
|
||||
static const char acName1C13_00[] = "Max SubIndex";
|
||||
static const char acName1C13_01[] = "PDO Mapping";
|
||||
@@ -60,6 +66,7 @@ static const char acName1C13_03[] = "PDO Mapping";
|
||||
static const char acName1C13_04[] = "PDO Mapping";
|
||||
static const char acName1C13_05[] = "PDO Mapping";
|
||||
static const char acName1C13_06[] = "PDO Mapping";
|
||||
static const char acName1C13_07[] = "PDO Mapping";
|
||||
static const char acName6000[] = "EncPos";
|
||||
static const char acName6001[] = "EncFrequency";
|
||||
static const char acName6002[] = "DiffT";
|
||||
@@ -68,12 +75,17 @@ static const char acName6004[] = "IndexStatus";
|
||||
static const char acName6005[] = "StepGenOut1";
|
||||
static const char acName6005_00[] = "Max SubIndex";
|
||||
static const char acName6005_01[] = "ActualPosition";
|
||||
static const char acName6006[] = "StepGenOut2";
|
||||
static const char acName6006_00[] = "Max SubIndex";
|
||||
static const char acName6006_01[] = "ActualPosition";
|
||||
static const char acName7000[] = "EncPosScale";
|
||||
static const char acName7001[] = "IndexLatchEnable";
|
||||
static const char acName7002[] = "StepGenIn1";
|
||||
static const char acName7002_00[] = "Max SubIndex";
|
||||
static const char acName7002_01[] = "CommandedPosition";
|
||||
static const char acName7002_02[] = "CommandedVelocity";
|
||||
static const char acName7003[] = "StepGenIn2";
|
||||
static const char acName7003_00[] = "Max SubIndex";
|
||||
static const char acName7003_01[] = "CommandedPosition";
|
||||
|
||||
const _objd SDO1000[] =
|
||||
{
|
||||
@@ -111,9 +123,13 @@ const _objd SDO1601[] =
|
||||
};
|
||||
const _objd SDO1602[] =
|
||||
{
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1602_00, 2, NULL},
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1602_00, 1, NULL},
|
||||
{0x01, DTYPE_UNSIGNED64, 64, ATYPE_RO, acName1602_01, 0x70020140, NULL},
|
||||
{0x02, DTYPE_UNSIGNED64, 64, ATYPE_RO, acName1602_02, 0x70020240, NULL},
|
||||
};
|
||||
const _objd SDO1603[] =
|
||||
{
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1603_00, 1, NULL},
|
||||
{0x01, DTYPE_UNSIGNED64, 64, ATYPE_RO, acName1603_01, 0x70030140, NULL},
|
||||
};
|
||||
const _objd SDO1A00[] =
|
||||
{
|
||||
@@ -145,6 +161,11 @@ const _objd SDO1A05[] =
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1A05_00, 1, NULL},
|
||||
{0x01, DTYPE_UNSIGNED64, 64, ATYPE_RO, acName1A05_01, 0x60050140, NULL},
|
||||
};
|
||||
const _objd SDO1A06[] =
|
||||
{
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1A06_00, 1, NULL},
|
||||
{0x01, DTYPE_UNSIGNED64, 64, ATYPE_RO, acName1A06_01, 0x60060140, NULL},
|
||||
};
|
||||
const _objd SDO1C00[] =
|
||||
{
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1C00_00, 4, NULL},
|
||||
@@ -155,20 +176,22 @@ const _objd SDO1C00[] =
|
||||
};
|
||||
const _objd SDO1C12[] =
|
||||
{
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1C12_00, 3, NULL},
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1C12_00, 4, 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},
|
||||
};
|
||||
const _objd SDO1C13[] =
|
||||
{
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1C13_00, 6, NULL},
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1C13_00, 7, NULL},
|
||||
{0x01, DTYPE_UNSIGNED16, 16, ATYPE_RO, acName1C13_01, 0x1A00, NULL},
|
||||
{0x02, DTYPE_UNSIGNED16, 16, ATYPE_RO, acName1C13_02, 0x1A01, NULL},
|
||||
{0x03, DTYPE_UNSIGNED16, 16, ATYPE_RO, acName1C13_03, 0x1A02, NULL},
|
||||
{0x04, DTYPE_UNSIGNED16, 16, ATYPE_RO, acName1C13_04, 0x1A03, NULL},
|
||||
{0x05, DTYPE_UNSIGNED16, 16, ATYPE_RO, acName1C13_05, 0x1A04, NULL},
|
||||
{0x06, DTYPE_UNSIGNED16, 16, ATYPE_RO, acName1C13_06, 0x1A05, NULL},
|
||||
{0x07, DTYPE_UNSIGNED16, 16, ATYPE_RO, acName1C13_07, 0x1A06, NULL},
|
||||
};
|
||||
const _objd SDO6000[] =
|
||||
{
|
||||
@@ -195,6 +218,11 @@ const _objd SDO6005[] =
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName6005_00, 1, NULL},
|
||||
{0x01, DTYPE_REAL64, 64, ATYPE_RO, acName6005_01, 0, &Obj.StepGenOut1.ActualPosition},
|
||||
};
|
||||
const _objd SDO6006[] =
|
||||
{
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName6006_00, 1, NULL},
|
||||
{0x01, DTYPE_REAL64, 64, ATYPE_RO, acName6006_01, 0, &Obj.StepGenOut2.ActualPosition},
|
||||
};
|
||||
const _objd SDO7000[] =
|
||||
{
|
||||
{0x0, DTYPE_INTEGER32, 32, ATYPE_RO | ATYPE_RXPDO, acName7000, 0, &Obj.EncPosScale},
|
||||
@@ -205,9 +233,13 @@ const _objd SDO7001[] =
|
||||
};
|
||||
const _objd SDO7002[] =
|
||||
{
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName7002_00, 2, NULL},
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName7002_00, 1, NULL},
|
||||
{0x01, DTYPE_REAL64, 64, ATYPE_RO, acName7002_01, 0, &Obj.StepGenIn1.CommandedPosition},
|
||||
{0x02, DTYPE_REAL64, 64, ATYPE_RO, acName7002_02, 0, &Obj.StepGenIn1.CommandedVelocity},
|
||||
};
|
||||
const _objd SDO7003[] =
|
||||
{
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName7003_00, 1, NULL},
|
||||
{0x01, DTYPE_REAL64, 64, ATYPE_RO, acName7003_01, 0, &Obj.StepGenIn2.CommandedPosition},
|
||||
};
|
||||
|
||||
const _objectlist SDOobjects[] =
|
||||
@@ -219,24 +251,28 @@ 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, 2, 0, acName1602, SDO1602},
|
||||
{0x1602, OTYPE_RECORD, 1, 0, acName1602, SDO1602},
|
||||
{0x1603, OTYPE_RECORD, 1, 0, acName1603, SDO1603},
|
||||
{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},
|
||||
{0x1A05, OTYPE_RECORD, 1, 0, acName1A05, SDO1A05},
|
||||
{0x1A06, OTYPE_RECORD, 1, 0, acName1A06, SDO1A06},
|
||||
{0x1C00, OTYPE_ARRAY, 4, 0, acName1C00, SDO1C00},
|
||||
{0x1C12, OTYPE_ARRAY, 3, 0, acName1C12, SDO1C12},
|
||||
{0x1C13, OTYPE_ARRAY, 6, 0, acName1C13, SDO1C13},
|
||||
{0x1C12, OTYPE_ARRAY, 4, 0, acName1C12, SDO1C12},
|
||||
{0x1C13, OTYPE_ARRAY, 7, 0, acName1C13, SDO1C13},
|
||||
{0x6000, OTYPE_VAR, 0, 0, acName6000, SDO6000},
|
||||
{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},
|
||||
{0x6005, OTYPE_RECORD, 1, 0, acName6005, SDO6005},
|
||||
{0x6006, OTYPE_RECORD, 1, 0, acName6006, SDO6006},
|
||||
{0x7000, OTYPE_VAR, 0, 0, acName7000, SDO7000},
|
||||
{0x7001, OTYPE_VAR, 0, 0, acName7001, SDO7001},
|
||||
{0x7002, OTYPE_RECORD, 2, 0, acName7002, SDO7002},
|
||||
{0x7002, OTYPE_RECORD, 1, 0, acName7002, SDO7002},
|
||||
{0x7003, OTYPE_RECORD, 1, 0, acName7003, SDO7003},
|
||||
{0xffff, 0xff, 0xff, 0xff, NULL, NULL}
|
||||
};
|
||||
|
||||
@@ -22,6 +22,10 @@ typedef struct
|
||||
{
|
||||
double ActualPosition;
|
||||
} StepGenOut1;
|
||||
struct
|
||||
{
|
||||
double ActualPosition;
|
||||
} StepGenOut2;
|
||||
|
||||
/* Outputs */
|
||||
|
||||
@@ -30,8 +34,11 @@ typedef struct
|
||||
struct
|
||||
{
|
||||
double CommandedPosition;
|
||||
double CommandedVelocity;
|
||||
} StepGenIn1;
|
||||
struct
|
||||
{
|
||||
double CommandedPosition;
|
||||
} StepGenIn2;
|
||||
|
||||
} _Objects;
|
||||
|
||||
|
||||
@@ -32,14 +32,12 @@ void timerCallbackStep1(void)
|
||||
{
|
||||
Step1.timerCB();
|
||||
}
|
||||
#if 0
|
||||
void timerCallbackStep2(void);
|
||||
StepGen Step2(TIM8, 4, PC9, PC10, timerCallbackStep2);
|
||||
void timerCallbackStep2(void)
|
||||
{
|
||||
Step2.timerCB();
|
||||
}
|
||||
#endif
|
||||
|
||||
void cb_set_outputs(void) // Master outputs gets here, slave inputs, first operation
|
||||
{
|
||||
@@ -47,11 +45,13 @@ void cb_set_outputs(void) // Master outputs gets here, slave inputs, first opera
|
||||
Encoder1.setScale(Obj.EncPosScale);
|
||||
|
||||
Step1.cmdPos(Obj.StepGenIn1.CommandedPosition);
|
||||
Step2.cmdPos(Obj.StepGenIn2.CommandedPosition);
|
||||
}
|
||||
|
||||
void handleStepper(void)
|
||||
{
|
||||
Step1.handleStepper();
|
||||
Step2.handleStepper();
|
||||
}
|
||||
|
||||
void cb_get_inputs(void) // Set Master inputs, slave outputs, last operation
|
||||
@@ -62,6 +62,7 @@ void cb_get_inputs(void) // Set Master inputs, slave outputs, last operation
|
||||
Obj.IndexByte = Encoder1.getIndexState();
|
||||
|
||||
Obj.StepGenOut1.ActualPosition = Step1.actPos();
|
||||
Obj.StepGenOut2.ActualPosition = Step2.actPos();
|
||||
Obj.DiffT = 10000 * Step1.reqPos(); // Debug
|
||||
}
|
||||
|
||||
@@ -97,7 +98,8 @@ void setup(void)
|
||||
Serial1.begin(115200);
|
||||
rcc_config();
|
||||
|
||||
Step1.setScale(500);
|
||||
Step1.setScale(1250); // 2000 /rev 4 mm/rev x 2.5 gear => 1250 /mm
|
||||
Step2.setScale(500); // 2000 /rev 4 mm/rev => 500 /mm
|
||||
|
||||
ecat_slv_init(&config);
|
||||
}
|
||||
@@ -164,7 +166,6 @@ uint16_t dc_checker(void)
|
||||
{
|
||||
// Indicate we run DC
|
||||
ESCvar.dcsync = 0;
|
||||
//Step1.setCycleTime(ESC_SYNC0cycletime() / 1000); // nsec to usec
|
||||
StepGen::sync0CycleTime = ESC_SYNC0cycletime() / 1000;
|
||||
return 0;
|
||||
}
|
||||
|
||||
Reference in New Issue
Block a user