WIP, non-functional
This commit is contained in:
@@ -52,12 +52,12 @@
|
||||
<option value="INTEGER8">INTEGER8</option>
|
||||
<option value="INTEGER16">INTEGER16</option>
|
||||
<option value="INTEGER32">INTEGER32</option>
|
||||
<option value="INTEGER32">INTEGER64</option>
|
||||
<option value="INTEGER64">INTEGER64</option>
|
||||
<option value="UNSIGNED8">UNSIGNED8</option>
|
||||
<option value="UNSIGNED16">UNSIGNED16</option>
|
||||
<option value="UNSIGNED32">UNSIGNED64</option>
|
||||
<option value="REAL32">REAL32</option>
|
||||
<option value="REAL32">REAL64</option>
|
||||
<option value="REAL64">REAL64</option>
|
||||
<option value="VISIBLE_STRING">VISIBLE STRING</option>
|
||||
</select></td>
|
||||
</tr>
|
||||
|
||||
@@ -23,7 +23,7 @@
|
||||
<DataTypes>
|
||||
<DataType>
|
||||
<Name>DT1018</Name>
|
||||
<BitSize>144</BitSize>
|
||||
<BitSize>272</BitSize>
|
||||
<SubItem>
|
||||
<SubIdx>0</SubIdx>
|
||||
<Name>Max SubIndex</Name>
|
||||
@@ -37,8 +37,8 @@
|
||||
<SubItem>
|
||||
<SubIdx>1</SubIdx>
|
||||
<Name>Vendor ID</Name>
|
||||
<Type>UDINT</Type>
|
||||
<BitSize>32</BitSize>
|
||||
<Type>ULINT</Type>
|
||||
<BitSize>64</BitSize>
|
||||
<BitOffs>16</BitOffs>
|
||||
<Flags>
|
||||
<Access>ro</Access>
|
||||
@@ -47,9 +47,9 @@
|
||||
<SubItem>
|
||||
<SubIdx>2</SubIdx>
|
||||
<Name>Product Code</Name>
|
||||
<Type>UDINT</Type>
|
||||
<BitSize>32</BitSize>
|
||||
<BitOffs>48</BitOffs>
|
||||
<Type>ULINT</Type>
|
||||
<BitSize>64</BitSize>
|
||||
<BitOffs>80</BitOffs>
|
||||
<Flags>
|
||||
<Access>ro</Access>
|
||||
</Flags>
|
||||
@@ -57,9 +57,9 @@
|
||||
<SubItem>
|
||||
<SubIdx>3</SubIdx>
|
||||
<Name>Revision Number</Name>
|
||||
<Type>UDINT</Type>
|
||||
<BitSize>32</BitSize>
|
||||
<BitOffs>80</BitOffs>
|
||||
<Type>ULINT</Type>
|
||||
<BitSize>64</BitSize>
|
||||
<BitOffs>144</BitOffs>
|
||||
<Flags>
|
||||
<Access>ro</Access>
|
||||
</Flags>
|
||||
@@ -67,9 +67,9 @@
|
||||
<SubItem>
|
||||
<SubIdx>4</SubIdx>
|
||||
<Name>Serial Number</Name>
|
||||
<Type>UDINT</Type>
|
||||
<BitSize>32</BitSize>
|
||||
<BitOffs>112</BitOffs>
|
||||
<Type>ULINT</Type>
|
||||
<BitSize>64</BitSize>
|
||||
<BitOffs>208</BitOffs>
|
||||
<Flags>
|
||||
<Access>ro</Access>
|
||||
</Flags>
|
||||
@@ -77,7 +77,7 @@
|
||||
</DataType>
|
||||
<DataType>
|
||||
<Name>DT1600</Name>
|
||||
<BitSize>48</BitSize>
|
||||
<BitSize>80</BitSize>
|
||||
<SubItem>
|
||||
<SubIdx>0</SubIdx>
|
||||
<Name>Max SubIndex</Name>
|
||||
@@ -91,8 +91,8 @@
|
||||
<SubItem>
|
||||
<SubIdx>1</SubIdx>
|
||||
<Name>EncPosScale</Name>
|
||||
<Type>UDINT</Type>
|
||||
<BitSize>32</BitSize>
|
||||
<Type>ULINT</Type>
|
||||
<BitSize>64</BitSize>
|
||||
<BitOffs>16</BitOffs>
|
||||
<Flags>
|
||||
<Access>ro</Access>
|
||||
@@ -101,7 +101,7 @@
|
||||
</DataType>
|
||||
<DataType>
|
||||
<Name>DT1601</Name>
|
||||
<BitSize>48</BitSize>
|
||||
<BitSize>80</BitSize>
|
||||
<SubItem>
|
||||
<SubIdx>0</SubIdx>
|
||||
<Name>Max SubIndex</Name>
|
||||
@@ -115,8 +115,8 @@
|
||||
<SubItem>
|
||||
<SubIdx>1</SubIdx>
|
||||
<Name>IndexLatchEnable</Name>
|
||||
<Type>UDINT</Type>
|
||||
<BitSize>32</BitSize>
|
||||
<Type>ULINT</Type>
|
||||
<BitSize>64</BitSize>
|
||||
<BitOffs>16</BitOffs>
|
||||
<Flags>
|
||||
<Access>ro</Access>
|
||||
@@ -125,7 +125,7 @@
|
||||
</DataType>
|
||||
<DataType>
|
||||
<Name>DT1602</Name>
|
||||
<BitSize>48</BitSize>
|
||||
<BitSize>80</BitSize>
|
||||
<SubItem>
|
||||
<SubIdx>0</SubIdx>
|
||||
<Name>Max SubIndex</Name>
|
||||
@@ -139,8 +139,8 @@
|
||||
<SubItem>
|
||||
<SubIdx>1</SubIdx>
|
||||
<Name>CommandedPosition</Name>
|
||||
<Type>UDINT</Type>
|
||||
<BitSize>32</BitSize>
|
||||
<Type>ULINT</Type>
|
||||
<BitSize>64</BitSize>
|
||||
<BitOffs>16</BitOffs>
|
||||
<Flags>
|
||||
<Access>ro</Access>
|
||||
@@ -149,7 +149,7 @@
|
||||
</DataType>
|
||||
<DataType>
|
||||
<Name>DT1A00</Name>
|
||||
<BitSize>48</BitSize>
|
||||
<BitSize>80</BitSize>
|
||||
<SubItem>
|
||||
<SubIdx>0</SubIdx>
|
||||
<Name>Max SubIndex</Name>
|
||||
@@ -163,8 +163,8 @@
|
||||
<SubItem>
|
||||
<SubIdx>1</SubIdx>
|
||||
<Name>EncPos</Name>
|
||||
<Type>UDINT</Type>
|
||||
<BitSize>32</BitSize>
|
||||
<Type>ULINT</Type>
|
||||
<BitSize>64</BitSize>
|
||||
<BitOffs>16</BitOffs>
|
||||
<Flags>
|
||||
<Access>ro</Access>
|
||||
@@ -173,7 +173,7 @@
|
||||
</DataType>
|
||||
<DataType>
|
||||
<Name>DT1A01</Name>
|
||||
<BitSize>48</BitSize>
|
||||
<BitSize>80</BitSize>
|
||||
<SubItem>
|
||||
<SubIdx>0</SubIdx>
|
||||
<Name>Max SubIndex</Name>
|
||||
@@ -187,8 +187,8 @@
|
||||
<SubItem>
|
||||
<SubIdx>1</SubIdx>
|
||||
<Name>EncFrequency</Name>
|
||||
<Type>UDINT</Type>
|
||||
<BitSize>32</BitSize>
|
||||
<Type>ULINT</Type>
|
||||
<BitSize>64</BitSize>
|
||||
<BitOffs>16</BitOffs>
|
||||
<Flags>
|
||||
<Access>ro</Access>
|
||||
@@ -197,7 +197,7 @@
|
||||
</DataType>
|
||||
<DataType>
|
||||
<Name>DT1A02</Name>
|
||||
<BitSize>48</BitSize>
|
||||
<BitSize>80</BitSize>
|
||||
<SubItem>
|
||||
<SubIdx>0</SubIdx>
|
||||
<Name>Max SubIndex</Name>
|
||||
@@ -211,8 +211,8 @@
|
||||
<SubItem>
|
||||
<SubIdx>1</SubIdx>
|
||||
<Name>DiffT</Name>
|
||||
<Type>UDINT</Type>
|
||||
<BitSize>32</BitSize>
|
||||
<Type>ULINT</Type>
|
||||
<BitSize>64</BitSize>
|
||||
<BitOffs>16</BitOffs>
|
||||
<Flags>
|
||||
<Access>ro</Access>
|
||||
@@ -221,7 +221,7 @@
|
||||
</DataType>
|
||||
<DataType>
|
||||
<Name>DT1A03</Name>
|
||||
<BitSize>48</BitSize>
|
||||
<BitSize>80</BitSize>
|
||||
<SubItem>
|
||||
<SubIdx>0</SubIdx>
|
||||
<Name>Max SubIndex</Name>
|
||||
@@ -235,8 +235,8 @@
|
||||
<SubItem>
|
||||
<SubIdx>1</SubIdx>
|
||||
<Name>IndexByte</Name>
|
||||
<Type>UDINT</Type>
|
||||
<BitSize>32</BitSize>
|
||||
<Type>ULINT</Type>
|
||||
<BitSize>64</BitSize>
|
||||
<BitOffs>16</BitOffs>
|
||||
<Flags>
|
||||
<Access>ro</Access>
|
||||
@@ -245,7 +245,7 @@
|
||||
</DataType>
|
||||
<DataType>
|
||||
<Name>DT1A04</Name>
|
||||
<BitSize>48</BitSize>
|
||||
<BitSize>80</BitSize>
|
||||
<SubItem>
|
||||
<SubIdx>0</SubIdx>
|
||||
<Name>Max SubIndex</Name>
|
||||
@@ -259,8 +259,8 @@
|
||||
<SubItem>
|
||||
<SubIdx>1</SubIdx>
|
||||
<Name>IndexStatus</Name>
|
||||
<Type>UDINT</Type>
|
||||
<BitSize>32</BitSize>
|
||||
<Type>ULINT</Type>
|
||||
<BitSize>64</BitSize>
|
||||
<BitOffs>16</BitOffs>
|
||||
<Flags>
|
||||
<Access>ro</Access>
|
||||
@@ -269,7 +269,7 @@
|
||||
</DataType>
|
||||
<DataType>
|
||||
<Name>DT1A05</Name>
|
||||
<BitSize>48</BitSize>
|
||||
<BitSize>80</BitSize>
|
||||
<SubItem>
|
||||
<SubIdx>0</SubIdx>
|
||||
<Name>Max SubIndex</Name>
|
||||
@@ -283,8 +283,8 @@
|
||||
<SubItem>
|
||||
<SubIdx>1</SubIdx>
|
||||
<Name>ActualPosition</Name>
|
||||
<Type>UDINT</Type>
|
||||
<BitSize>32</BitSize>
|
||||
<Type>ULINT</Type>
|
||||
<BitSize>64</BitSize>
|
||||
<BitOffs>16</BitOffs>
|
||||
<Flags>
|
||||
<Access>ro</Access>
|
||||
@@ -438,8 +438,8 @@
|
||||
</SubItem>
|
||||
</DataType>
|
||||
<DataType>
|
||||
<Name>UDINT</Name>
|
||||
<BitSize>32</BitSize>
|
||||
<Name>ULINT</Name>
|
||||
<BitSize>64</BitSize>
|
||||
</DataType>
|
||||
<DataType>
|
||||
<Name>STRING(26)</Name>
|
||||
@@ -461,6 +461,10 @@
|
||||
<Name>REAL</Name>
|
||||
<BitSize>32</BitSize>
|
||||
</DataType>
|
||||
<DataType>
|
||||
<Name>UDINT</Name>
|
||||
<BitSize>32</BitSize>
|
||||
</DataType>
|
||||
<DataType>
|
||||
<Name>DINT</Name>
|
||||
<BitSize>32</BitSize>
|
||||
@@ -470,8 +474,8 @@
|
||||
<Object>
|
||||
<Index>#x1000</Index>
|
||||
<Name>Device Type</Name>
|
||||
<Type>UDINT</Type>
|
||||
<BitSize>32</BitSize>
|
||||
<Type>ULINT</Type>
|
||||
<BitSize>64</BitSize>
|
||||
<Info>
|
||||
<DefaultValue>5001</DefaultValue>
|
||||
</Info>
|
||||
@@ -521,7 +525,7 @@
|
||||
<Index>#x1018</Index>
|
||||
<Name>Identity Object</Name>
|
||||
<Type>DT1018</Type>
|
||||
<BitSize>144</BitSize>
|
||||
<BitSize>272</BitSize>
|
||||
<Info>
|
||||
<SubItem>
|
||||
<Name>Max SubIndex</Name>
|
||||
@@ -562,7 +566,7 @@
|
||||
<Index>#x1600</Index>
|
||||
<Name>EncPosScale</Name>
|
||||
<Type>DT1600</Type>
|
||||
<BitSize>48</BitSize>
|
||||
<BitSize>80</BitSize>
|
||||
<Info>
|
||||
<SubItem>
|
||||
<Name>Max SubIndex</Name>
|
||||
@@ -585,7 +589,7 @@
|
||||
<Index>#x1601</Index>
|
||||
<Name>IndexLatchEnable</Name>
|
||||
<Type>DT1601</Type>
|
||||
<BitSize>48</BitSize>
|
||||
<BitSize>80</BitSize>
|
||||
<Info>
|
||||
<SubItem>
|
||||
<Name>Max SubIndex</Name>
|
||||
@@ -608,7 +612,7 @@
|
||||
<Index>#x1602</Index>
|
||||
<Name>StepGenIn1</Name>
|
||||
<Type>DT1602</Type>
|
||||
<BitSize>48</BitSize>
|
||||
<BitSize>80</BitSize>
|
||||
<Info>
|
||||
<SubItem>
|
||||
<Name>Max SubIndex</Name>
|
||||
@@ -631,7 +635,7 @@
|
||||
<Index>#x1A00</Index>
|
||||
<Name>EncPos</Name>
|
||||
<Type>DT1A00</Type>
|
||||
<BitSize>48</BitSize>
|
||||
<BitSize>80</BitSize>
|
||||
<Info>
|
||||
<SubItem>
|
||||
<Name>Max SubIndex</Name>
|
||||
@@ -654,7 +658,7 @@
|
||||
<Index>#x1A01</Index>
|
||||
<Name>EncFrequency</Name>
|
||||
<Type>DT1A01</Type>
|
||||
<BitSize>48</BitSize>
|
||||
<BitSize>80</BitSize>
|
||||
<Info>
|
||||
<SubItem>
|
||||
<Name>Max SubIndex</Name>
|
||||
@@ -677,7 +681,7 @@
|
||||
<Index>#x1A02</Index>
|
||||
<Name>DiffT</Name>
|
||||
<Type>DT1A02</Type>
|
||||
<BitSize>48</BitSize>
|
||||
<BitSize>80</BitSize>
|
||||
<Info>
|
||||
<SubItem>
|
||||
<Name>Max SubIndex</Name>
|
||||
@@ -700,7 +704,7 @@
|
||||
<Index>#x1A03</Index>
|
||||
<Name>IndexByte</Name>
|
||||
<Type>DT1A03</Type>
|
||||
<BitSize>48</BitSize>
|
||||
<BitSize>80</BitSize>
|
||||
<Info>
|
||||
<SubItem>
|
||||
<Name>Max SubIndex</Name>
|
||||
@@ -723,7 +727,7 @@
|
||||
<Index>#x1A04</Index>
|
||||
<Name>IndexStatus</Name>
|
||||
<Type>DT1A04</Type>
|
||||
<BitSize>48</BitSize>
|
||||
<BitSize>80</BitSize>
|
||||
<Info>
|
||||
<SubItem>
|
||||
<Name>Max SubIndex</Name>
|
||||
@@ -744,9 +748,9 @@
|
||||
</Object>
|
||||
<Object>
|
||||
<Index>#x1A05</Index>
|
||||
<Name>StepgenOut1</Name>
|
||||
<Name>StepGenOut1</Name>
|
||||
<Type>DT1A05</Type>
|
||||
<BitSize>48</BitSize>
|
||||
<BitSize>80</BitSize>
|
||||
<Info>
|
||||
<SubItem>
|
||||
<Name>Max SubIndex</Name>
|
||||
@@ -961,7 +965,7 @@
|
||||
</Object>
|
||||
<Object>
|
||||
<Index>#x6005</Index>
|
||||
<Name>StepgenOut1</Name>
|
||||
<Name>StepGenOut1</Name>
|
||||
<Type>DT6005</Type>
|
||||
<BitSize>48</BitSize>
|
||||
<Info>
|
||||
@@ -1131,7 +1135,7 @@
|
||||
</TxPdo>
|
||||
<TxPdo Fixed="true" Mandatory="true" Sm="3">
|
||||
<Index>#x1A05</Index>
|
||||
<Name>StepgenOut1</Name>
|
||||
<Name>StepGenOut1</Name>
|
||||
<Entry>
|
||||
<Index>#x6005</Index>
|
||||
<SubIndex>#x1</SubIndex>
|
||||
|
||||
@@ -107,7 +107,7 @@
|
||||
},
|
||||
"6005": {
|
||||
"otype": "RECORD",
|
||||
"name": "StepgenOut1",
|
||||
"name": "StepGenOut1",
|
||||
"access": "RO",
|
||||
"items": [
|
||||
{
|
||||
@@ -116,7 +116,7 @@
|
||||
{
|
||||
"name": "ActualPosition",
|
||||
"dtype": "INTEGER32",
|
||||
"data": "&Obj.StepgenOut1.ActualPosition",
|
||||
"data": "&Obj.StepGenOut1.ActualPosition",
|
||||
"value": "0",
|
||||
"access": "RO"
|
||||
}
|
||||
|
||||
@@ -37,7 +37,7 @@ 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[] = "StepGenOut1";
|
||||
static const char acName1A05_00[] = "Max SubIndex";
|
||||
static const char acName1A05_01[] = "ActualPosition";
|
||||
static const char acName1C00[] = "Sync Manager Communication Type";
|
||||
@@ -64,7 +64,7 @@ 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[] = "StepGenOut1";
|
||||
static const char acName6005_00[] = "Max SubIndex";
|
||||
static const char acName6005_01[] = "ActualPosition";
|
||||
static const char acName7000[] = "EncPosScale";
|
||||
@@ -75,7 +75,7 @@ static const char acName7002_01[] = "CommandedPosition";
|
||||
|
||||
const _objd SDO1000[] =
|
||||
{
|
||||
{0x0, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1000, 5001, NULL},
|
||||
{0x0, DTYPE_UNSIGNED64, 64, ATYPE_RO, acName1000, 5001, NULL},
|
||||
};
|
||||
const _objd SDO1008[] =
|
||||
{
|
||||
@@ -92,55 +92,55 @@ const _objd SDO100A[] =
|
||||
const _objd SDO1018[] =
|
||||
{
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1018_00, 4, NULL},
|
||||
{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},
|
||||
{0x01, DTYPE_UNSIGNED64, 64, ATYPE_RO, acName1018_01, 2730, NULL},
|
||||
{0x02, DTYPE_UNSIGNED64, 64, ATYPE_RO, acName1018_02, 12303564, NULL},
|
||||
{0x03, DTYPE_UNSIGNED64, 64, ATYPE_RO, acName1018_03, 2, NULL},
|
||||
{0x04, DTYPE_UNSIGNED64, 64, 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, 0x70000020, NULL},
|
||||
{0x01, DTYPE_UNSIGNED64, 64, 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, 0x70010020, NULL},
|
||||
{0x01, DTYPE_UNSIGNED64, 64, 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},
|
||||
{0x01, DTYPE_UNSIGNED64, 64, ATYPE_RO, acName1602_01, 0x70020120, NULL},
|
||||
};
|
||||
const _objd SDO1A00[] =
|
||||
{
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1A00_00, 1, NULL},
|
||||
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1A00_01, 0x60000020, NULL},
|
||||
{0x01, DTYPE_UNSIGNED64, 64, 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, 0x60010020, NULL},
|
||||
{0x01, DTYPE_UNSIGNED64, 64, 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},
|
||||
{0x01, DTYPE_UNSIGNED64, 64, 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},
|
||||
{0x01, DTYPE_UNSIGNED64, 64, 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},
|
||||
{0x01, DTYPE_UNSIGNED64, 64, 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},
|
||||
{0x01, DTYPE_UNSIGNED64, 64, ATYPE_RO, acName1A05_01, 0x60050120, NULL},
|
||||
};
|
||||
const _objd SDO1C00[] =
|
||||
{
|
||||
@@ -190,7 +190,7 @@ const _objd SDO6004[] =
|
||||
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},
|
||||
{0x01, DTYPE_INTEGER32, 32, ATYPE_RO, acName6005_01, 0, &Obj.StepGenOut1.ActualPosition},
|
||||
};
|
||||
const _objd SDO7000[] =
|
||||
{
|
||||
|
||||
@@ -21,7 +21,7 @@ typedef struct
|
||||
struct
|
||||
{
|
||||
int32_t ActualPosition;
|
||||
} StepgenOut1;
|
||||
} StepGenOut1;
|
||||
|
||||
/* Outputs */
|
||||
|
||||
|
||||
@@ -86,7 +86,7 @@ uint16_t dc_checker(void);
|
||||
static esc_cfg_t config =
|
||||
{
|
||||
.user_arg = NULL,
|
||||
.use_interrupt = 1,
|
||||
.use_interrupt = 0,
|
||||
.watchdog_cnt = 150,
|
||||
.set_defaults_hook = NULL,
|
||||
.pre_state_change_hook = NULL,
|
||||
@@ -97,10 +97,13 @@ static esc_cfg_t config =
|
||||
.post_object_download_hook = NULL,
|
||||
.rxpdo_override = NULL,
|
||||
.txpdo_override = NULL,
|
||||
.esc_hw_interrupt_enable = ESC_interrupt_enable,
|
||||
.esc_hw_interrupt_disable = ESC_interrupt_disable,
|
||||
//.esc_hw_interrupt_enable = ESC_interrupt_enable,
|
||||
//.esc_hw_interrupt_disable = ESC_interrupt_disable,
|
||||
.esc_hw_interrupt_enable = NULL,
|
||||
.esc_hw_interrupt_disable = NULL,
|
||||
.esc_hw_eep_handler = NULL,
|
||||
.esc_check_dc_handler = dc_checker,
|
||||
// .esc_check_dc_handler = dc_checker,
|
||||
.esc_check_dc_handler = NULL,
|
||||
};
|
||||
|
||||
void setup(void)
|
||||
@@ -161,13 +164,13 @@ 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
|
||||
// #define STEPPER_STEP PA11 // Set in StepperSetup
|
||||
|
||||
void sync0Handler(void)
|
||||
{
|
||||
// Update the actual position
|
||||
actualPosition += pulsesToGo;
|
||||
Obj.StepgenOut1.ActualPosition = actualPosition;
|
||||
Obj.StepGenOut1.ActualPosition = actualPosition;
|
||||
// Get new end position
|
||||
requestedPosition = Obj.StepGenIn1.CommandedPosition;
|
||||
// Get the diff and the direction
|
||||
@@ -176,7 +179,7 @@ void sync0Handler(void)
|
||||
// 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);
|
||||
makePulses(sync0CycleTime / 1000, pulsesToGo);
|
||||
}
|
||||
|
||||
void ESC_interrupt_enable(uint32_t mask)
|
||||
|
||||
Reference in New Issue
Block a user