New enable input. Add dc ability. Set only SM2 synchronization. Various to make lathe work
This commit is contained in:
@@ -14,6 +14,7 @@ public:
|
|||||||
volatile uint32_t timerNewCycleTime;
|
volatile uint32_t timerNewCycleTime;
|
||||||
volatile double_t actualPosition;
|
volatile double_t actualPosition;
|
||||||
volatile double_t requestedPosition;
|
volatile double_t requestedPosition;
|
||||||
|
volatile uint8_t enabled;
|
||||||
HardwareTimer *MyTim;
|
HardwareTimer *MyTim;
|
||||||
uint16_t stepsPerMM;
|
uint16_t stepsPerMM;
|
||||||
static uint32_t sync0CycleTime;
|
static uint32_t sync0CycleTime;
|
||||||
@@ -32,6 +33,7 @@ public:
|
|||||||
void handleStepper(void);
|
void handleStepper(void);
|
||||||
void timerCB();
|
void timerCB();
|
||||||
void setScale(int16_t spm);
|
void setScale(int16_t spm);
|
||||||
|
void enable(uint8_t yes);
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
@@ -191,6 +191,40 @@
|
|||||||
</Flags>
|
</Flags>
|
||||||
</SubItem>
|
</SubItem>
|
||||||
</DataType>
|
</DataType>
|
||||||
|
<DataType>
|
||||||
|
<Name>DT1604</Name>
|
||||||
|
<BitSize>144</BitSize>
|
||||||
|
<SubItem>
|
||||||
|
<SubIdx>0</SubIdx>
|
||||||
|
<Name>Max SubIndex</Name>
|
||||||
|
<Type>USINT</Type>
|
||||||
|
<BitSize>8</BitSize>
|
||||||
|
<BitOffs>0</BitOffs>
|
||||||
|
<Flags>
|
||||||
|
<Access>ro</Access>
|
||||||
|
</Flags>
|
||||||
|
</SubItem>
|
||||||
|
<SubItem>
|
||||||
|
<SubIdx>1</SubIdx>
|
||||||
|
<Name>Enable1</Name>
|
||||||
|
<Type>ULINT</Type>
|
||||||
|
<BitSize>64</BitSize>
|
||||||
|
<BitOffs>16</BitOffs>
|
||||||
|
<Flags>
|
||||||
|
<Access>ro</Access>
|
||||||
|
</Flags>
|
||||||
|
</SubItem>
|
||||||
|
<SubItem>
|
||||||
|
<SubIdx>2</SubIdx>
|
||||||
|
<Name>Padding 1</Name>
|
||||||
|
<Type>ULINT</Type>
|
||||||
|
<BitSize>64</BitSize>
|
||||||
|
<BitOffs>80</BitOffs>
|
||||||
|
<Flags>
|
||||||
|
<Access>ro</Access>
|
||||||
|
</Flags>
|
||||||
|
</SubItem>
|
||||||
|
</DataType>
|
||||||
<DataType>
|
<DataType>
|
||||||
<Name>DT1A00</Name>
|
<Name>DT1A00</Name>
|
||||||
<BitSize>80</BitSize>
|
<BitSize>80</BitSize>
|
||||||
@@ -394,15 +428,15 @@
|
|||||||
<DataType>
|
<DataType>
|
||||||
<Name>DT1C12ARR</Name>
|
<Name>DT1C12ARR</Name>
|
||||||
<BaseType>UINT</BaseType>
|
<BaseType>UINT</BaseType>
|
||||||
<BitSize>64</BitSize>
|
<BitSize>80</BitSize>
|
||||||
<ArrayInfo>
|
<ArrayInfo>
|
||||||
<LBound>1</LBound>
|
<LBound>1</LBound>
|
||||||
<Elements>4</Elements>
|
<Elements>5</Elements>
|
||||||
</ArrayInfo>
|
</ArrayInfo>
|
||||||
</DataType>
|
</DataType>
|
||||||
<DataType>
|
<DataType>
|
||||||
<Name>DT1C12</Name>
|
<Name>DT1C12</Name>
|
||||||
<BitSize>80</BitSize>
|
<BitSize>96</BitSize>
|
||||||
<SubItem>
|
<SubItem>
|
||||||
<SubIdx>0</SubIdx>
|
<SubIdx>0</SubIdx>
|
||||||
<Name>Max SubIndex</Name>
|
<Name>Max SubIndex</Name>
|
||||||
@@ -416,7 +450,7 @@
|
|||||||
<SubItem>
|
<SubItem>
|
||||||
<Name>Elements</Name>
|
<Name>Elements</Name>
|
||||||
<Type>DT1C12ARR</Type>
|
<Type>DT1C12ARR</Type>
|
||||||
<BitSize>64</BitSize>
|
<BitSize>80</BitSize>
|
||||||
<BitOffs>16</BitOffs>
|
<BitOffs>16</BitOffs>
|
||||||
<Flags>
|
<Flags>
|
||||||
<Access>ro</Access>
|
<Access>ro</Access>
|
||||||
@@ -613,6 +647,10 @@
|
|||||||
<Name>INT</Name>
|
<Name>INT</Name>
|
||||||
<BitSize>16</BitSize>
|
<BitSize>16</BitSize>
|
||||||
</DataType>
|
</DataType>
|
||||||
|
<DataType>
|
||||||
|
<Name>BOOL</Name>
|
||||||
|
<BitSize>1</BitSize>
|
||||||
|
</DataType>
|
||||||
</DataTypes>
|
</DataTypes>
|
||||||
<Objects>
|
<Objects>
|
||||||
<Object>
|
<Object>
|
||||||
@@ -810,6 +848,35 @@
|
|||||||
<Access>ro</Access>
|
<Access>ro</Access>
|
||||||
</Flags>
|
</Flags>
|
||||||
</Object>
|
</Object>
|
||||||
|
<Object>
|
||||||
|
<Index>#x1604</Index>
|
||||||
|
<Name>Enable1</Name>
|
||||||
|
<Type>DT1604</Type>
|
||||||
|
<BitSize>144</BitSize>
|
||||||
|
<Info>
|
||||||
|
<SubItem>
|
||||||
|
<Name>Max SubIndex</Name>
|
||||||
|
<Info>
|
||||||
|
<DefaultValue>2</DefaultValue>
|
||||||
|
</Info>
|
||||||
|
</SubItem>
|
||||||
|
<SubItem>
|
||||||
|
<Name>Enable1</Name>
|
||||||
|
<Info>
|
||||||
|
<DefaultValue>#x70040001</DefaultValue>
|
||||||
|
</Info>
|
||||||
|
</SubItem>
|
||||||
|
<SubItem>
|
||||||
|
<Name>Padding 1</Name>
|
||||||
|
<Info>
|
||||||
|
<DefaultValue>#x00000007</DefaultValue>
|
||||||
|
</Info>
|
||||||
|
</SubItem>
|
||||||
|
</Info>
|
||||||
|
<Flags>
|
||||||
|
<Access>ro</Access>
|
||||||
|
</Flags>
|
||||||
|
</Object>
|
||||||
<Object>
|
<Object>
|
||||||
<Index>#x1A00</Index>
|
<Index>#x1A00</Index>
|
||||||
<Name>EncPos</Name>
|
<Name>EncPos</Name>
|
||||||
@@ -1016,12 +1083,12 @@
|
|||||||
<Index>#x1C12</Index>
|
<Index>#x1C12</Index>
|
||||||
<Name>Sync Manager 2 PDO Assignment</Name>
|
<Name>Sync Manager 2 PDO Assignment</Name>
|
||||||
<Type>DT1C12</Type>
|
<Type>DT1C12</Type>
|
||||||
<BitSize>80</BitSize>
|
<BitSize>96</BitSize>
|
||||||
<Info>
|
<Info>
|
||||||
<SubItem>
|
<SubItem>
|
||||||
<Name>Max SubIndex</Name>
|
<Name>Max SubIndex</Name>
|
||||||
<Info>
|
<Info>
|
||||||
<DefaultValue>4</DefaultValue>
|
<DefaultValue>5</DefaultValue>
|
||||||
</Info>
|
</Info>
|
||||||
</SubItem>
|
</SubItem>
|
||||||
<SubItem>
|
<SubItem>
|
||||||
@@ -1048,6 +1115,12 @@
|
|||||||
<DefaultValue>#x1603</DefaultValue>
|
<DefaultValue>#x1603</DefaultValue>
|
||||||
</Info>
|
</Info>
|
||||||
</SubItem>
|
</SubItem>
|
||||||
|
<SubItem>
|
||||||
|
<Name>PDO Mapping</Name>
|
||||||
|
<Info>
|
||||||
|
<DefaultValue>#x1604</DefaultValue>
|
||||||
|
</Info>
|
||||||
|
</SubItem>
|
||||||
</Info>
|
</Info>
|
||||||
<Flags>
|
<Flags>
|
||||||
<Access>ro</Access>
|
<Access>ro</Access>
|
||||||
@@ -1307,6 +1380,19 @@
|
|||||||
<Access>ro</Access>
|
<Access>ro</Access>
|
||||||
</Flags>
|
</Flags>
|
||||||
</Object>
|
</Object>
|
||||||
|
<Object>
|
||||||
|
<Index>#x7004</Index>
|
||||||
|
<Name>Enable1</Name>
|
||||||
|
<Type>BOOL</Type>
|
||||||
|
<BitSize>1</BitSize>
|
||||||
|
<Info>
|
||||||
|
<DefaultValue>0</DefaultValue>
|
||||||
|
</Info>
|
||||||
|
<Flags>
|
||||||
|
<Access>ro</Access>
|
||||||
|
<PdoMapping>R</PdoMapping>
|
||||||
|
</Flags>
|
||||||
|
</Object>
|
||||||
</Objects>
|
</Objects>
|
||||||
</Dictionary>
|
</Dictionary>
|
||||||
</Profile>
|
</Profile>
|
||||||
@@ -1375,6 +1461,22 @@
|
|||||||
<DataType>INT</DataType>
|
<DataType>INT</DataType>
|
||||||
</Entry>
|
</Entry>
|
||||||
</RxPdo>
|
</RxPdo>
|
||||||
|
<RxPdo Fixed="true" Mandatory="true" Sm="2">
|
||||||
|
<Index>#x1604</Index>
|
||||||
|
<Name>Enable1</Name>
|
||||||
|
<Entry>
|
||||||
|
<Index>#x7004</Index>
|
||||||
|
<SubIndex>#x0</SubIndex>
|
||||||
|
<BitLen>1</BitLen>
|
||||||
|
<Name>Enable1</Name>
|
||||||
|
<DataType>BOOL</DataType>
|
||||||
|
</Entry>
|
||||||
|
<Entry>
|
||||||
|
<Index>0</Index>
|
||||||
|
<SubIndex>0</SubIndex>
|
||||||
|
<BitLen>7</BitLen>
|
||||||
|
</Entry>
|
||||||
|
</RxPdo>
|
||||||
<TxPdo Fixed="true" Mandatory="true" Sm="3">
|
<TxPdo Fixed="true" Mandatory="true" Sm="3">
|
||||||
<Index>#x1A00</Index>
|
<Index>#x1A00</Index>
|
||||||
<Name>EncPos</Name>
|
<Name>EncPos</Name>
|
||||||
|
|||||||
@@ -33,7 +33,7 @@
|
|||||||
#define SM3_smc 0x20
|
#define SM3_smc 0x20
|
||||||
#define SM3_act 1
|
#define SM3_act 1
|
||||||
|
|
||||||
#define MAX_MAPPINGS_SM2 6
|
#define MAX_MAPPINGS_SM2 8
|
||||||
#define MAX_MAPPINGS_SM3 7
|
#define MAX_MAPPINGS_SM3 7
|
||||||
|
|
||||||
#define MAX_RXPDO_SIZE 512
|
#define MAX_RXPDO_SIZE 512
|
||||||
|
|||||||
@@ -223,6 +223,17 @@
|
|||||||
"rxpdo"
|
"rxpdo"
|
||||||
]
|
]
|
||||||
},
|
},
|
||||||
|
"7004": {
|
||||||
|
"otype": "VAR",
|
||||||
|
"name": "Enable1",
|
||||||
|
"access": "RO",
|
||||||
|
"pdo_mappings": [
|
||||||
|
"rxpdo"
|
||||||
|
],
|
||||||
|
"dtype": "BOOLEAN",
|
||||||
|
"value": "0",
|
||||||
|
"data": "&Obj.Enable1"
|
||||||
|
},
|
||||||
"60664": {
|
"60664": {
|
||||||
"otype": "VAR",
|
"otype": "VAR",
|
||||||
"name": "ActualPosition",
|
"name": "ActualPosition",
|
||||||
|
|||||||
@@ -27,6 +27,10 @@ static const char acName1603[] = "StepGenIn2";
|
|||||||
static const char acName1603_00[] = "Max SubIndex";
|
static const char acName1603_00[] = "Max SubIndex";
|
||||||
static const char acName1603_01[] = "CommandedPosition";
|
static const char acName1603_01[] = "CommandedPosition";
|
||||||
static const char acName1603_02[] = "StepsPerMM";
|
static const char acName1603_02[] = "StepsPerMM";
|
||||||
|
static const char acName1604[] = "Enable1";
|
||||||
|
static const char acName1604_00[] = "Max SubIndex";
|
||||||
|
static const char acName1604_01[] = "Enable1";
|
||||||
|
static const char acName1604_02[] = "Padding 1";
|
||||||
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";
|
||||||
@@ -60,6 +64,7 @@ static const char acName1C12_01[] = "PDO Mapping";
|
|||||||
static const char acName1C12_02[] = "PDO Mapping";
|
static const char acName1C12_02[] = "PDO Mapping";
|
||||||
static const char acName1C12_03[] = "PDO Mapping";
|
static const char acName1C12_03[] = "PDO Mapping";
|
||||||
static const char acName1C12_04[] = "PDO Mapping";
|
static const char acName1C12_04[] = "PDO Mapping";
|
||||||
|
static const char acName1C12_05[] = "PDO Mapping";
|
||||||
static const char acName1C13[] = "Sync Manager 3 PDO Assignment";
|
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";
|
||||||
@@ -90,6 +95,7 @@ static const char acName7003[] = "StepGenIn2";
|
|||||||
static const char acName7003_00[] = "Max SubIndex";
|
static const char acName7003_00[] = "Max SubIndex";
|
||||||
static const char acName7003_01[] = "CommandedPosition";
|
static const char acName7003_01[] = "CommandedPosition";
|
||||||
static const char acName7003_02[] = "StepsPerMM";
|
static const char acName7003_02[] = "StepsPerMM";
|
||||||
|
static const char acName7004[] = "Enable1";
|
||||||
|
|
||||||
const _objd SDO1000[] =
|
const _objd SDO1000[] =
|
||||||
{
|
{
|
||||||
@@ -137,6 +143,12 @@ const _objd SDO1603[] =
|
|||||||
{0x01, DTYPE_UNSIGNED64, 64, ATYPE_RO, acName1603_01, 0x70030140, NULL},
|
{0x01, DTYPE_UNSIGNED64, 64, ATYPE_RO, acName1603_01, 0x70030140, NULL},
|
||||||
{0x02, DTYPE_UNSIGNED64, 64, ATYPE_RO, acName1603_02, 0x70030210, NULL},
|
{0x02, DTYPE_UNSIGNED64, 64, ATYPE_RO, acName1603_02, 0x70030210, NULL},
|
||||||
};
|
};
|
||||||
|
const _objd SDO1604[] =
|
||||||
|
{
|
||||||
|
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1604_00, 2, NULL},
|
||||||
|
{0x01, DTYPE_UNSIGNED64, 64, ATYPE_RO, acName1604_01, 0x70040001, NULL},
|
||||||
|
{0x02, DTYPE_UNSIGNED64, 64, ATYPE_RO, acName1604_02, 0x00000007, NULL},
|
||||||
|
};
|
||||||
const _objd SDO1A00[] =
|
const _objd SDO1A00[] =
|
||||||
{
|
{
|
||||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1A00_00, 1, NULL},
|
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1A00_00, 1, NULL},
|
||||||
@@ -182,11 +194,12 @@ const _objd SDO1C00[] =
|
|||||||
};
|
};
|
||||||
const _objd SDO1C12[] =
|
const _objd SDO1C12[] =
|
||||||
{
|
{
|
||||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1C12_00, 4, NULL},
|
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1C12_00, 5, NULL},
|
||||||
{0x01, DTYPE_UNSIGNED16, 16, ATYPE_RO, acName1C12_01, 0x1600, NULL},
|
{0x01, DTYPE_UNSIGNED16, 16, ATYPE_RO, acName1C12_01, 0x1600, NULL},
|
||||||
{0x02, DTYPE_UNSIGNED16, 16, ATYPE_RO, acName1C12_02, 0x1601, NULL},
|
{0x02, DTYPE_UNSIGNED16, 16, ATYPE_RO, acName1C12_02, 0x1601, NULL},
|
||||||
{0x03, DTYPE_UNSIGNED16, 16, ATYPE_RO, acName1C12_03, 0x1602, NULL},
|
{0x03, DTYPE_UNSIGNED16, 16, ATYPE_RO, acName1C12_03, 0x1602, NULL},
|
||||||
{0x04, DTYPE_UNSIGNED16, 16, ATYPE_RO, acName1C12_04, 0x1603, NULL},
|
{0x04, DTYPE_UNSIGNED16, 16, ATYPE_RO, acName1C12_04, 0x1603, NULL},
|
||||||
|
{0x05, DTYPE_UNSIGNED16, 16, ATYPE_RO, acName1C12_05, 0x1604, NULL},
|
||||||
};
|
};
|
||||||
const _objd SDO1C13[] =
|
const _objd SDO1C13[] =
|
||||||
{
|
{
|
||||||
@@ -249,6 +262,10 @@ const _objd SDO7003[] =
|
|||||||
{0x01, DTYPE_REAL64, 64, ATYPE_RO, acName7003_01, 0, &Obj.StepGenIn2.CommandedPosition},
|
{0x01, DTYPE_REAL64, 64, ATYPE_RO, acName7003_01, 0, &Obj.StepGenIn2.CommandedPosition},
|
||||||
{0x02, DTYPE_INTEGER16, 16, ATYPE_RO, acName7003_02, 0, &Obj.StepGenIn2.StepsPerMM},
|
{0x02, DTYPE_INTEGER16, 16, ATYPE_RO, acName7003_02, 0, &Obj.StepGenIn2.StepsPerMM},
|
||||||
};
|
};
|
||||||
|
const _objd SDO7004[] =
|
||||||
|
{
|
||||||
|
{0x0, DTYPE_BOOLEAN, 1, ATYPE_RO | ATYPE_RXPDO, acName7004, 0, &Obj.Enable1},
|
||||||
|
};
|
||||||
|
|
||||||
const _objectlist SDOobjects[] =
|
const _objectlist SDOobjects[] =
|
||||||
{
|
{
|
||||||
@@ -261,6 +278,7 @@ const _objectlist SDOobjects[] =
|
|||||||
{0x1601, OTYPE_RECORD, 1, 0, acName1601, SDO1601},
|
{0x1601, OTYPE_RECORD, 1, 0, acName1601, SDO1601},
|
||||||
{0x1602, OTYPE_RECORD, 2, 0, acName1602, SDO1602},
|
{0x1602, OTYPE_RECORD, 2, 0, acName1602, SDO1602},
|
||||||
{0x1603, OTYPE_RECORD, 2, 0, acName1603, SDO1603},
|
{0x1603, OTYPE_RECORD, 2, 0, acName1603, SDO1603},
|
||||||
|
{0x1604, OTYPE_RECORD, 2, 0, acName1604, SDO1604},
|
||||||
{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},
|
{0x1A02, OTYPE_RECORD, 1, 0, acName1A02, SDO1A02},
|
||||||
@@ -269,7 +287,7 @@ const _objectlist SDOobjects[] =
|
|||||||
{0x1A05, OTYPE_RECORD, 1, 0, acName1A05, SDO1A05},
|
{0x1A05, OTYPE_RECORD, 1, 0, acName1A05, SDO1A05},
|
||||||
{0x1A06, OTYPE_RECORD, 1, 0, acName1A06, SDO1A06},
|
{0x1A06, OTYPE_RECORD, 1, 0, acName1A06, SDO1A06},
|
||||||
{0x1C00, OTYPE_ARRAY, 4, 0, acName1C00, SDO1C00},
|
{0x1C00, OTYPE_ARRAY, 4, 0, acName1C00, SDO1C00},
|
||||||
{0x1C12, OTYPE_ARRAY, 4, 0, acName1C12, SDO1C12},
|
{0x1C12, OTYPE_ARRAY, 5, 0, acName1C12, SDO1C12},
|
||||||
{0x1C13, OTYPE_ARRAY, 7, 0, acName1C13, SDO1C13},
|
{0x1C13, OTYPE_ARRAY, 7, 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},
|
||||||
@@ -282,5 +300,6 @@ const _objectlist SDOobjects[] =
|
|||||||
{0x7001, OTYPE_VAR, 0, 0, acName7001, SDO7001},
|
{0x7001, OTYPE_VAR, 0, 0, acName7001, SDO7001},
|
||||||
{0x7002, OTYPE_RECORD, 2, 0, acName7002, SDO7002},
|
{0x7002, OTYPE_RECORD, 2, 0, acName7002, SDO7002},
|
||||||
{0x7003, OTYPE_RECORD, 2, 0, acName7003, SDO7003},
|
{0x7003, OTYPE_RECORD, 2, 0, acName7003, SDO7003},
|
||||||
|
{0x7004, OTYPE_VAR, 0, 0, acName7004, SDO7004},
|
||||||
{0xffff, 0xff, 0xff, 0xff, NULL, NULL}
|
{0xffff, 0xff, 0xff, 0xff, NULL, NULL}
|
||||||
};
|
};
|
||||||
|
|||||||
@@ -41,6 +41,7 @@ typedef struct
|
|||||||
double CommandedPosition;
|
double CommandedPosition;
|
||||||
int16_t StepsPerMM;
|
int16_t StepsPerMM;
|
||||||
} StepGenIn2;
|
} StepGenIn2;
|
||||||
|
uint8_t Enable1;
|
||||||
|
|
||||||
} _Objects;
|
} _Objects;
|
||||||
|
|
||||||
|
|||||||
@@ -12,6 +12,7 @@ StepGen::StepGen(TIM_TypeDef *Timer, uint32_t _timerChannel, PinName _stepPin, u
|
|||||||
actualPosition = 0;
|
actualPosition = 0;
|
||||||
requestedPosition = 0;
|
requestedPosition = 0;
|
||||||
stepsPerMM = 0;
|
stepsPerMM = 0;
|
||||||
|
enabled = 0;
|
||||||
|
|
||||||
dirPin = _dirPin;
|
dirPin = _dirPin;
|
||||||
stepPin = _stepPin;
|
stepPin = _stepPin;
|
||||||
@@ -37,8 +38,16 @@ double StepGen::actPos()
|
|||||||
return actualPosition;
|
return actualPosition;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void StepGen::enable(uint8_t yes)
|
||||||
|
{
|
||||||
|
enabled = yes;
|
||||||
|
}
|
||||||
|
|
||||||
void StepGen::handleStepper(void)
|
void StepGen::handleStepper(void)
|
||||||
{
|
{
|
||||||
|
if (!enabled)
|
||||||
|
return;
|
||||||
|
|
||||||
actPos(timerStepPosition / double(stepsPerMM));
|
actPos(timerStepPosition / double(stepsPerMM));
|
||||||
double diffPosition = reqPos() - actPos();
|
double diffPosition = reqPos() - actPos();
|
||||||
|
|
||||||
|
|||||||
@@ -46,8 +46,10 @@ void cb_set_outputs(void) // Master outputs gets here, slave inputs, first opera
|
|||||||
|
|
||||||
Step1.reqPos(Obj.StepGenIn1.CommandedPosition);
|
Step1.reqPos(Obj.StepGenIn1.CommandedPosition);
|
||||||
Step1.setScale(Obj.StepGenIn1.StepsPerMM);
|
Step1.setScale(Obj.StepGenIn1.StepsPerMM);
|
||||||
|
Step1.enable(Obj.Enable1);
|
||||||
Step2.reqPos(Obj.StepGenIn2.CommandedPosition);
|
Step2.reqPos(Obj.StepGenIn2.CommandedPosition);
|
||||||
Step2.setScale(Obj.StepGenIn2.StepsPerMM);
|
Step2.setScale(Obj.StepGenIn2.StepsPerMM);
|
||||||
|
Step2.enable(Obj.Enable1);
|
||||||
}
|
}
|
||||||
|
|
||||||
void handleStepper(void)
|
void handleStepper(void)
|
||||||
@@ -123,9 +125,8 @@ void sync0Handler(void)
|
|||||||
void ESC_interrupt_enable(uint32_t mask)
|
void ESC_interrupt_enable(uint32_t mask)
|
||||||
{
|
{
|
||||||
// Enable interrupt for SYNC0 or SM2 or SM3
|
// Enable interrupt for SYNC0 or SM2 or SM3
|
||||||
uint32_t user_int_mask = ESCREG_ALEVENT_DC_SYNC0 |
|
// uint32_t user_int_mask = ESCREG_ALEVENT_DC_SYNC0 | ESCREG_ALEVENT_SM2 | ESCREG_ALEVENT_SM3;
|
||||||
ESCREG_ALEVENT_SM2 |
|
uint32_t user_int_mask = ESCREG_ALEVENT_SM2; // Only SM2
|
||||||
ESCREG_ALEVENT_SM3;
|
|
||||||
if (mask & user_int_mask)
|
if (mask & user_int_mask)
|
||||||
{
|
{
|
||||||
ESC_ALeventmaskwrite(ESC_ALeventmaskread() | (mask & user_int_mask));
|
ESC_ALeventmaskwrite(ESC_ALeventmaskread() | (mask & user_int_mask));
|
||||||
@@ -144,9 +145,8 @@ void ESC_interrupt_enable(uint32_t mask)
|
|||||||
void ESC_interrupt_disable(uint32_t mask)
|
void ESC_interrupt_disable(uint32_t mask)
|
||||||
{
|
{
|
||||||
// Enable interrupt for SYNC0 or SM2 or SM3
|
// Enable interrupt for SYNC0 or SM2 or SM3
|
||||||
uint32_t user_int_mask = ESCREG_ALEVENT_DC_SYNC0 |
|
// uint32_t user_int_mask = ESCREG_ALEVENT_DC_SYNC0 | ESCREG_ALEVENT_SM2 | ESCREG_ALEVENT_SM3;
|
||||||
ESCREG_ALEVENT_SM2 |
|
uint32_t user_int_mask = ESCREG_ALEVENT_SM2;
|
||||||
ESCREG_ALEVENT_SM3;
|
|
||||||
|
|
||||||
if (mask & user_int_mask)
|
if (mask & user_int_mask)
|
||||||
{
|
{
|
||||||
@@ -160,11 +160,12 @@ void ESC_interrupt_disable(uint32_t mask)
|
|||||||
}
|
}
|
||||||
|
|
||||||
extern "C" uint32_t ESC_SYNC0cycletime(void);
|
extern "C" uint32_t ESC_SYNC0cycletime(void);
|
||||||
|
|
||||||
// Setup of DC
|
// Setup of DC
|
||||||
uint16_t dc_checker(void)
|
uint16_t dc_checker(void)
|
||||||
{
|
{
|
||||||
// Indicate we run DC
|
// Indicate we run DC
|
||||||
ESCvar.dcsync = 0;
|
ESCvar.dcsync = 1;
|
||||||
StepGen::sync0CycleTime = ESC_SYNC0cycletime() / 1000;
|
StepGen::sync0CycleTime = ESC_SYNC0cycletime() / 1000;
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
|||||||
Reference in New Issue
Block a user