wip stepgen
This commit is contained in:
@@ -123,6 +123,30 @@
|
||||
</Flags>
|
||||
</SubItem>
|
||||
</DataType>
|
||||
<DataType>
|
||||
<Name>DT1602</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>CommandedPosition</Name>
|
||||
<Type>UDINT</Type>
|
||||
<BitSize>32</BitSize>
|
||||
<BitOffs>16</BitOffs>
|
||||
<Flags>
|
||||
<Access>ro</Access>
|
||||
</Flags>
|
||||
</SubItem>
|
||||
</DataType>
|
||||
<DataType>
|
||||
<Name>DT1A00</Name>
|
||||
<BitSize>48</BitSize>
|
||||
@@ -243,6 +267,30 @@
|
||||
</Flags>
|
||||
</SubItem>
|
||||
</DataType>
|
||||
<DataType>
|
||||
<Name>DT1A05</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>ActualPosition</Name>
|
||||
<Type>UDINT</Type>
|
||||
<BitSize>32</BitSize>
|
||||
<BitOffs>16</BitOffs>
|
||||
<Flags>
|
||||
<Access>ro</Access>
|
||||
</Flags>
|
||||
</SubItem>
|
||||
</DataType>
|
||||
<DataType>
|
||||
<Name>DT1C00ARR</Name>
|
||||
<BaseType>USINT</BaseType>
|
||||
@@ -278,15 +326,15 @@
|
||||
<DataType>
|
||||
<Name>DT1C12ARR</Name>
|
||||
<BaseType>UINT</BaseType>
|
||||
<BitSize>32</BitSize>
|
||||
<BitSize>48</BitSize>
|
||||
<ArrayInfo>
|
||||
<LBound>1</LBound>
|
||||
<Elements>2</Elements>
|
||||
<Elements>3</Elements>
|
||||
</ArrayInfo>
|
||||
</DataType>
|
||||
<DataType>
|
||||
<Name>DT1C12</Name>
|
||||
<BitSize>48</BitSize>
|
||||
<BitSize>64</BitSize>
|
||||
<SubItem>
|
||||
<SubIdx>0</SubIdx>
|
||||
<Name>Max SubIndex</Name>
|
||||
@@ -300,7 +348,7 @@
|
||||
<SubItem>
|
||||
<Name>Elements</Name>
|
||||
<Type>DT1C12ARR</Type>
|
||||
<BitSize>32</BitSize>
|
||||
<BitSize>48</BitSize>
|
||||
<BitOffs>16</BitOffs>
|
||||
<Flags>
|
||||
<Access>ro</Access>
|
||||
@@ -310,15 +358,15 @@
|
||||
<DataType>
|
||||
<Name>DT1C13ARR</Name>
|
||||
<BaseType>UINT</BaseType>
|
||||
<BitSize>80</BitSize>
|
||||
<BitSize>96</BitSize>
|
||||
<ArrayInfo>
|
||||
<LBound>1</LBound>
|
||||
<Elements>5</Elements>
|
||||
<Elements>6</Elements>
|
||||
</ArrayInfo>
|
||||
</DataType>
|
||||
<DataType>
|
||||
<Name>DT1C13</Name>
|
||||
<BitSize>96</BitSize>
|
||||
<BitSize>112</BitSize>
|
||||
<SubItem>
|
||||
<SubIdx>0</SubIdx>
|
||||
<Name>Max SubIndex</Name>
|
||||
@@ -332,13 +380,63 @@
|
||||
<SubItem>
|
||||
<Name>Elements</Name>
|
||||
<Type>DT1C13ARR</Type>
|
||||
<BitSize>80</BitSize>
|
||||
<BitSize>96</BitSize>
|
||||
<BitOffs>16</BitOffs>
|
||||
<Flags>
|
||||
<Access>ro</Access>
|
||||
</Flags>
|
||||
</SubItem>
|
||||
</DataType>
|
||||
<DataType>
|
||||
<Name>DT6005</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>ActualPosition</Name>
|
||||
<Type>DINT</Type>
|
||||
<BitSize>32</BitSize>
|
||||
<BitOffs>16</BitOffs>
|
||||
<Flags>
|
||||
<Access WriteRestrictions="PreOP">ro</Access>
|
||||
<PdoMapping>T</PdoMapping>
|
||||
</Flags>
|
||||
</SubItem>
|
||||
</DataType>
|
||||
<DataType>
|
||||
<Name>DT7002</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>CommandedPosition</Name>
|
||||
<Type>DINT</Type>
|
||||
<BitSize>32</BitSize>
|
||||
<BitOffs>16</BitOffs>
|
||||
<Flags>
|
||||
<Access WriteRestrictions="PreOP">ro</Access>
|
||||
<PdoMapping>R</PdoMapping>
|
||||
</Flags>
|
||||
</SubItem>
|
||||
</DataType>
|
||||
<DataType>
|
||||
<Name>UDINT</Name>
|
||||
<BitSize>32</BitSize>
|
||||
@@ -506,6 +604,29 @@
|
||||
<Access>ro</Access>
|
||||
</Flags>
|
||||
</Object>
|
||||
<Object>
|
||||
<Index>#x1602</Index>
|
||||
<Name>StepGenIn1</Name>
|
||||
<Type>DT1602</Type>
|
||||
<BitSize>48</BitSize>
|
||||
<Info>
|
||||
<SubItem>
|
||||
<Name>Max SubIndex</Name>
|
||||
<Info>
|
||||
<DefaultValue>1</DefaultValue>
|
||||
</Info>
|
||||
</SubItem>
|
||||
<SubItem>
|
||||
<Name>CommandedPosition</Name>
|
||||
<Info>
|
||||
<DefaultValue>#x70020120</DefaultValue>
|
||||
</Info>
|
||||
</SubItem>
|
||||
</Info>
|
||||
<Flags>
|
||||
<Access>ro</Access>
|
||||
</Flags>
|
||||
</Object>
|
||||
<Object>
|
||||
<Index>#x1A00</Index>
|
||||
<Name>EncPos</Name>
|
||||
@@ -621,6 +742,29 @@
|
||||
<Access>ro</Access>
|
||||
</Flags>
|
||||
</Object>
|
||||
<Object>
|
||||
<Index>#x1A05</Index>
|
||||
<Name>StepgenOut1</Name>
|
||||
<Type>DT1A05</Type>
|
||||
<BitSize>48</BitSize>
|
||||
<Info>
|
||||
<SubItem>
|
||||
<Name>Max SubIndex</Name>
|
||||
<Info>
|
||||
<DefaultValue>1</DefaultValue>
|
||||
</Info>
|
||||
</SubItem>
|
||||
<SubItem>
|
||||
<Name>ActualPosition</Name>
|
||||
<Info>
|
||||
<DefaultValue>#x60050120</DefaultValue>
|
||||
</Info>
|
||||
</SubItem>
|
||||
</Info>
|
||||
<Flags>
|
||||
<Access>ro</Access>
|
||||
</Flags>
|
||||
</Object>
|
||||
<Object>
|
||||
<Index>#x1C00</Index>
|
||||
<Name>Sync Manager Communication Type</Name>
|
||||
@@ -666,12 +810,12 @@
|
||||
<Index>#x1C12</Index>
|
||||
<Name>Sync Manager 2 PDO Assignment</Name>
|
||||
<Type>DT1C12</Type>
|
||||
<BitSize>48</BitSize>
|
||||
<BitSize>64</BitSize>
|
||||
<Info>
|
||||
<SubItem>
|
||||
<Name>Max SubIndex</Name>
|
||||
<Info>
|
||||
<DefaultValue>2</DefaultValue>
|
||||
<DefaultValue>3</DefaultValue>
|
||||
</Info>
|
||||
</SubItem>
|
||||
<SubItem>
|
||||
@@ -686,6 +830,12 @@
|
||||
<DefaultValue>#x1601</DefaultValue>
|
||||
</Info>
|
||||
</SubItem>
|
||||
<SubItem>
|
||||
<Name>PDO Mapping</Name>
|
||||
<Info>
|
||||
<DefaultValue>#x1602</DefaultValue>
|
||||
</Info>
|
||||
</SubItem>
|
||||
</Info>
|
||||
<Flags>
|
||||
<Access>ro</Access>
|
||||
@@ -695,12 +845,12 @@
|
||||
<Index>#x1C13</Index>
|
||||
<Name>Sync Manager 3 PDO Assignment</Name>
|
||||
<Type>DT1C13</Type>
|
||||
<BitSize>96</BitSize>
|
||||
<BitSize>112</BitSize>
|
||||
<Info>
|
||||
<SubItem>
|
||||
<Name>Max SubIndex</Name>
|
||||
<Info>
|
||||
<DefaultValue>5</DefaultValue>
|
||||
<DefaultValue>6</DefaultValue>
|
||||
</Info>
|
||||
</SubItem>
|
||||
<SubItem>
|
||||
@@ -733,6 +883,12 @@
|
||||
<DefaultValue>#x1A04</DefaultValue>
|
||||
</Info>
|
||||
</SubItem>
|
||||
<SubItem>
|
||||
<Name>PDO Mapping</Name>
|
||||
<Info>
|
||||
<DefaultValue>#x1A05</DefaultValue>
|
||||
</Info>
|
||||
</SubItem>
|
||||
</Info>
|
||||
<Flags>
|
||||
<Access>ro</Access>
|
||||
@@ -803,6 +959,29 @@
|
||||
<PdoMapping>T</PdoMapping>
|
||||
</Flags>
|
||||
</Object>
|
||||
<Object>
|
||||
<Index>#x6005</Index>
|
||||
<Name>StepgenOut1</Name>
|
||||
<Type>DT6005</Type>
|
||||
<BitSize>48</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>
|
||||
@@ -829,6 +1008,29 @@
|
||||
<PdoMapping>R</PdoMapping>
|
||||
</Flags>
|
||||
</Object>
|
||||
<Object>
|
||||
<Index>#x7002</Index>
|
||||
<Name>StepGenIn1</Name>
|
||||
<Type>DT7002</Type>
|
||||
<BitSize>48</BitSize>
|
||||
<Info>
|
||||
<SubItem>
|
||||
<Name>Max SubIndex</Name>
|
||||
<Info>
|
||||
<DefaultValue>1</DefaultValue>
|
||||
</Info>
|
||||
</SubItem>
|
||||
<SubItem>
|
||||
<Name>CommandedPosition</Name>
|
||||
<Info>
|
||||
<DefaultValue>0</DefaultValue>
|
||||
</Info>
|
||||
</SubItem>
|
||||
</Info>
|
||||
<Flags>
|
||||
<Access>ro</Access>
|
||||
</Flags>
|
||||
</Object>
|
||||
</Objects>
|
||||
</Dictionary>
|
||||
</Profile>
|
||||
@@ -861,6 +1063,17 @@
|
||||
<DataType>UDINT</DataType>
|
||||
</Entry>
|
||||
</RxPdo>
|
||||
<RxPdo Fixed="true" Mandatory="true" Sm="2">
|
||||
<Index>#x1602</Index>
|
||||
<Name>StepGenIn1</Name>
|
||||
<Entry>
|
||||
<Index>#x7002</Index>
|
||||
<SubIndex>#x1</SubIndex>
|
||||
<BitLen>32</BitLen>
|
||||
<Name>CommandedPosition</Name>
|
||||
<DataType>DINT</DataType>
|
||||
</Entry>
|
||||
</RxPdo>
|
||||
<TxPdo Fixed="true" Mandatory="true" Sm="3">
|
||||
<Index>#x1A00</Index>
|
||||
<Name>EncPos</Name>
|
||||
@@ -916,6 +1129,17 @@
|
||||
<DataType>UDINT</DataType>
|
||||
</Entry>
|
||||
</TxPdo>
|
||||
<TxPdo Fixed="true" Mandatory="true" Sm="3">
|
||||
<Index>#x1A05</Index>
|
||||
<Name>StepgenOut1</Name>
|
||||
<Entry>
|
||||
<Index>#x6005</Index>
|
||||
<SubIndex>#x1</SubIndex>
|
||||
<BitLen>32</BitLen>
|
||||
<Name>ActualPosition</Name>
|
||||
<DataType>DINT</DataType>
|
||||
</Entry>
|
||||
</TxPdo>
|
||||
<Mailbox DataLinkLayer="true">
|
||||
<CoE SdoInfo="true" PdoAssign="false" PdoConfig="false" PdoUpload="true" CompleteAccess="false" />
|
||||
</Mailbox>
|
||||
|
||||
@@ -33,8 +33,8 @@
|
||||
#define SM3_smc 0x20
|
||||
#define SM3_act 1
|
||||
|
||||
#define MAX_MAPPINGS_SM2 2
|
||||
#define MAX_MAPPINGS_SM3 5
|
||||
#define MAX_MAPPINGS_SM2 3
|
||||
#define MAX_MAPPINGS_SM3 6
|
||||
|
||||
#define MAX_RXPDO_SIZE 512
|
||||
#define MAX_TXPDO_SIZE 512
|
||||
|
||||
@@ -104,6 +104,26 @@
|
||||
"dtype": "UNSIGNED32",
|
||||
"value": "0",
|
||||
"data": "&Obj.IndexStatus"
|
||||
},
|
||||
"6005": {
|
||||
"otype": "RECORD",
|
||||
"name": "StepgenOut1",
|
||||
"access": "RO",
|
||||
"items": [
|
||||
{
|
||||
"name": "Max SubIndex"
|
||||
},
|
||||
{
|
||||
"name": "ActualPosition",
|
||||
"dtype": "INTEGER32",
|
||||
"data": "&Obj.StepgenOut1.ActualPosition",
|
||||
"value": "0",
|
||||
"access": "RO"
|
||||
}
|
||||
],
|
||||
"pdo_mappings": [
|
||||
"txpdo"
|
||||
]
|
||||
}
|
||||
},
|
||||
"rxpdo": {
|
||||
@@ -129,6 +149,26 @@
|
||||
"value": "0",
|
||||
"data": "&Obj.IndexLatchEnable"
|
||||
},
|
||||
"7002": {
|
||||
"otype": "RECORD",
|
||||
"name": "StepGenIn1",
|
||||
"access": "RO",
|
||||
"items": [
|
||||
{
|
||||
"name": "Max SubIndex"
|
||||
},
|
||||
{
|
||||
"name": "CommandedPosition",
|
||||
"dtype": "INTEGER32",
|
||||
"data": "&Obj.StepGenIn1.CommandedPosition",
|
||||
"value": "0",
|
||||
"access": "RO"
|
||||
}
|
||||
],
|
||||
"pdo_mappings": [
|
||||
"rxpdo"
|
||||
]
|
||||
},
|
||||
"60664": {
|
||||
"otype": "VAR",
|
||||
"name": "ActualPosition",
|
||||
|
||||
@@ -19,6 +19,9 @@ static const char acName1600_01[] = "EncPosScale";
|
||||
static const char acName1601[] = "IndexLatchEnable";
|
||||
static const char acName1601_00[] = "Max SubIndex";
|
||||
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 acName1A00[] = "EncPos";
|
||||
static const char acName1A00_00[] = "Max SubIndex";
|
||||
static const char acName1A00_01[] = "EncPos";
|
||||
@@ -34,6 +37,9 @@ 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 acName1A05[] = "StepgenOut1";
|
||||
static const char acName1A05_00[] = "Max SubIndex";
|
||||
static const char acName1A05_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";
|
||||
@@ -44,6 +50,7 @@ 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 acName1C13[] = "Sync Manager 3 PDO Assignment";
|
||||
static const char acName1C13_00[] = "Max SubIndex";
|
||||
static const char acName1C13_01[] = "PDO Mapping";
|
||||
@@ -51,13 +58,20 @@ 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 acName1C13_06[] = "PDO Mapping";
|
||||
static const char acName6000[] = "EncPos";
|
||||
static const char acName6001[] = "EncFrequency";
|
||||
static const char acName6002[] = "DiffT";
|
||||
static const char acName6003[] = "IndexByte";
|
||||
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 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";
|
||||
|
||||
const _objd SDO1000[] =
|
||||
{
|
||||
@@ -93,6 +107,11 @@ const _objd SDO1601[] =
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1601_00, 1, 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, 0x70020120, NULL},
|
||||
};
|
||||
const _objd SDO1A00[] =
|
||||
{
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1A00_00, 1, NULL},
|
||||
@@ -118,6 +137,11 @@ 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 SDO1A05[] =
|
||||
{
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1A05_00, 1, NULL},
|
||||
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1A05_01, 0x60050120, NULL},
|
||||
};
|
||||
const _objd SDO1C00[] =
|
||||
{
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1C00_00, 4, NULL},
|
||||
@@ -128,18 +152,20 @@ const _objd SDO1C00[] =
|
||||
};
|
||||
const _objd SDO1C12[] =
|
||||
{
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1C12_00, 2, NULL},
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1C12_00, 3, 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},
|
||||
};
|
||||
const _objd SDO1C13[] =
|
||||
{
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1C13_00, 5, NULL},
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1C13_00, 6, 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},
|
||||
};
|
||||
const _objd SDO6000[] =
|
||||
{
|
||||
@@ -161,6 +187,11 @@ const _objd SDO6004[] =
|
||||
{
|
||||
{0x0, DTYPE_UNSIGNED32, 32, ATYPE_RO | ATYPE_TXPDO, acName6004, 0, &Obj.IndexStatus},
|
||||
};
|
||||
const _objd SDO6005[] =
|
||||
{
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName6005_00, 1, NULL},
|
||||
{0x01, DTYPE_INTEGER32, 32, ATYPE_RO, acName6005_01, 0, &Obj.StepgenOut1.ActualPosition},
|
||||
};
|
||||
const _objd SDO7000[] =
|
||||
{
|
||||
{0x0, DTYPE_INTEGER32, 32, ATYPE_RO | ATYPE_RXPDO, acName7000, 0, &Obj.EncPosScale},
|
||||
@@ -169,6 +200,11 @@ const _objd SDO7001[] =
|
||||
{
|
||||
{0x0, DTYPE_UNSIGNED32, 32, ATYPE_RO | ATYPE_RXPDO, acName7001, 0, &Obj.IndexLatchEnable},
|
||||
};
|
||||
const _objd SDO7002[] =
|
||||
{
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName7002_00, 1, NULL},
|
||||
{0x01, DTYPE_INTEGER32, 32, ATYPE_RO, acName7002_01, 0, &Obj.StepGenIn1.CommandedPosition},
|
||||
};
|
||||
|
||||
const _objectlist SDOobjects[] =
|
||||
{
|
||||
@@ -179,20 +215,24 @@ 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},
|
||||
{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},
|
||||
{0x1C00, OTYPE_ARRAY, 4, 0, acName1C00, SDO1C00},
|
||||
{0x1C12, OTYPE_ARRAY, 2, 0, acName1C12, SDO1C12},
|
||||
{0x1C13, OTYPE_ARRAY, 5, 0, acName1C13, SDO1C13},
|
||||
{0x1C12, OTYPE_ARRAY, 3, 0, acName1C12, SDO1C12},
|
||||
{0x1C13, OTYPE_ARRAY, 6, 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},
|
||||
{0x7000, OTYPE_VAR, 0, 0, acName7000, SDO7000},
|
||||
{0x7001, OTYPE_VAR, 0, 0, acName7001, SDO7001},
|
||||
{0x7002, OTYPE_RECORD, 1, 0, acName7002, SDO7002},
|
||||
{0xffff, 0xff, 0xff, 0xff, NULL, NULL}
|
||||
};
|
||||
|
||||
@@ -18,11 +18,19 @@ typedef struct
|
||||
uint32_t DiffT;
|
||||
uint32_t IndexByte;
|
||||
uint32_t IndexStatus;
|
||||
struct
|
||||
{
|
||||
int32_t ActualPosition;
|
||||
} StepgenOut1;
|
||||
|
||||
/* Outputs */
|
||||
|
||||
int32_t EncPosScale;
|
||||
uint32_t IndexLatchEnable;
|
||||
struct
|
||||
{
|
||||
int32_t CommandedPosition;
|
||||
} StepGenIn1;
|
||||
|
||||
} _Objects;
|
||||
|
||||
|
||||
@@ -71,7 +71,7 @@ void HAL_TIM_MspPostInit(TIM_HandleTypeDef *htim)
|
||||
PE9 ------> TIM1_CH1
|
||||
PA8 ------< TIM1_CH1
|
||||
*/
|
||||
GPIO_InitStruct.Pin = GPIO_PIN_8; // 9;
|
||||
GPIO_InitStruct.Pin = GPIO_PIN_11; // 9;
|
||||
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
|
||||
GPIO_InitStruct.Pull = GPIO_NOPULL;
|
||||
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
|
||||
@@ -97,7 +97,7 @@ void StepperSetup(void)
|
||||
|
||||
// htim1.Instance->ARR = 1;
|
||||
// htim1.Instance->CCR1 = 1;
|
||||
HAL_TIM_PWM_Start(&htim1, TIM_CHANNEL_1);
|
||||
HAL_TIM_PWM_Start(&htim1, TIM_CHANNEL_4);
|
||||
TIM_TypeDef *TIMM = TIM1;
|
||||
|
||||
#define CLOCK_FREQ (168000000-2000000)
|
||||
|
||||
@@ -17,13 +17,11 @@ int64_t unwrap_encoder(uint16_t in, int64_t *prev);
|
||||
Encoder EncoderInit;
|
||||
Encoder *encP = &EncoderInit;
|
||||
|
||||
// #include "Stepper.h"
|
||||
#include "Stepper.h"
|
||||
#define INDEX_PIN PA2
|
||||
HardwareSerial Serial1(PA10, PA9);
|
||||
_Objects Obj;
|
||||
|
||||
volatile uint32_t sync0s = 0;
|
||||
|
||||
void indexPulse(void);
|
||||
double PosScaleRes = 1.0;
|
||||
uint32_t CurPosScale = 1;
|
||||
@@ -32,6 +30,8 @@ volatile uint8_t indexPulseFired = 0;
|
||||
uint32_t nFires = 0;
|
||||
volatile uint8_t pleaseZeroTheCounter = 0;
|
||||
|
||||
uint32_t sync0CycleTime = 0;
|
||||
|
||||
void cb_set_outputs(void) // Master outputs gets here, slave inputs, first operation
|
||||
{
|
||||
if (Obj.IndexLatchEnable && !OldLatchCEnable) // Should only happen first time IndexCEnable is set
|
||||
@@ -57,7 +57,7 @@ void cb_get_inputs(void) // Set Master inputs, slave outputs, last operation
|
||||
nFires++;
|
||||
PreviousEncoderCounterValue = 0;
|
||||
}
|
||||
Obj.DiffT = sync0s;
|
||||
Obj.DiffT = sync0CycleTime;
|
||||
|
||||
int64_t pos = unwrap_encoder(TIM2->CNT, &PreviousEncoderCounterValue);
|
||||
double CurPos = pos * PosScaleRes;
|
||||
@@ -81,7 +81,7 @@ void cb_get_inputs(void) // Set Master inputs, slave outputs, last operation
|
||||
|
||||
void ESC_interrupt_enable(uint32_t mask);
|
||||
void ESC_interrupt_disable(uint32_t mask);
|
||||
uint16_t dc_checker (void);
|
||||
uint16_t dc_checker(void);
|
||||
|
||||
static esc_cfg_t config =
|
||||
{
|
||||
@@ -108,6 +108,7 @@ void setup(void)
|
||||
Serial1.begin(115200);
|
||||
rcc_config();
|
||||
|
||||
StepperSetup();
|
||||
// Set starting count value
|
||||
EncoderInit.SetCount(Tim2, 0);
|
||||
// EncoderInit.SetCount(Tim3, 0);
|
||||
@@ -155,9 +156,27 @@ void indexPulse(void)
|
||||
}
|
||||
}
|
||||
|
||||
void countSync0(void)
|
||||
volatile int32_t actualPosition = 0;
|
||||
volatile int32_t requestedPosition;
|
||||
volatile uint32_t pulsesToGo = 0;
|
||||
volatile byte forwardDirection = 0; // 1 if going forward
|
||||
#define STEPPER_DIR PA12
|
||||
//#define STEPPER_STEP PA11 // Set in StepperSetup
|
||||
|
||||
void sync0Handler(void)
|
||||
{
|
||||
sync0s++;
|
||||
// Update the actual position
|
||||
actualPosition += pulsesToGo;
|
||||
Obj.StepgenOut1.ActualPosition = actualPosition;
|
||||
// Get new end position
|
||||
requestedPosition = Obj.StepGenIn1.CommandedPosition;
|
||||
// Get the diff and the direction
|
||||
pulsesToGo = requestedPosition - actualPosition;
|
||||
forwardDirection = pulsesToGo > 0 ? 1 : 0;
|
||||
// Set direction pin
|
||||
digitalWrite(STEPPER_DIR, forwardDirection); // I think one should really wait a bit when changed
|
||||
// Make the pulses using hardware timer
|
||||
makePulses(sync0CycleTime/1000, pulsesToGo);
|
||||
}
|
||||
|
||||
void ESC_interrupt_enable(uint32_t mask)
|
||||
@@ -170,7 +189,7 @@ void ESC_interrupt_enable(uint32_t mask)
|
||||
{
|
||||
ESC_ALeventmaskwrite(ESC_ALeventmaskread() | (mask & user_int_mask));
|
||||
|
||||
attachInterrupt(digitalPinToInterrupt(PC3), countSync0, RISING);
|
||||
attachInterrupt(digitalPinToInterrupt(PC3), sync0Handler, RISING);
|
||||
|
||||
// Set LAN9252 interrupt pin driver as push-pull active high
|
||||
uint32_t bits = 0x00000111;
|
||||
@@ -200,10 +219,12 @@ void ESC_interrupt_disable(uint32_t mask)
|
||||
}
|
||||
}
|
||||
|
||||
// Setup of DC
|
||||
uint16_t dc_checker (void)
|
||||
extern "C" uint32_t ESC_SYNC0cycletime(void);
|
||||
// Setup of DC
|
||||
uint16_t dc_checker(void)
|
||||
{
|
||||
// Indicate we run DC
|
||||
// Indicate we run DC
|
||||
ESCvar.dcsync = 1;
|
||||
sync0CycleTime = ESC_SYNC0cycletime();
|
||||
return 0;
|
||||
}
|
||||
|
||||
Reference in New Issue
Block a user