Test in lathe coming.

This commit is contained in:
Hakan Bastedt
2024-03-03 17:02:04 +01:00
parent cbc45bc80b
commit e8ef618fcc
13 changed files with 472 additions and 671 deletions

File diff suppressed because it is too large Load Diff

View File

@@ -33,7 +33,7 @@
#define SM3_smc 0x20
#define SM3_act 1
#define MAX_MAPPINGS_SM2 6
#define MAX_MAPPINGS_SM2 5
#define MAX_MAPPINGS_SM3 11
#define MAX_RXPDO_SIZE 512

View File

@@ -191,7 +191,7 @@ void APP_setwatchdog (int watchdogcnt)
* write ethercat inputs. Implement watch-dog counter to count-out if we have
* made state change affecting the App.state.
*/
void DIG_process (uint16_t ALEvent, uint8_t flags)
void DIG_process (uint8_t flags)
{
/* Handle watchdog */
if((flags & DIG_PROCESS_WD_FLAG) > 0)
@@ -217,14 +217,14 @@ void DIG_process (uint16_t ALEvent, uint8_t flags)
if ((flags & DIG_PROCESS_OUTPUTS_FLAG) > 0)
{
if(((CC_ATOMIC_GET(ESCvar.App.state) & APPSTATE_OUTPUT) > 0) &&
(ALEvent & ESCREG_ALEVENT_SM2))
(ESCvar.ALevent & ESCREG_ALEVENT_SM2))
{
RXPDO_update();
CC_ATOMIC_SET(watchdog, ESCvar.watchdogcnt);
/* Set outputs */
cb_set_outputs();
}
else if (ALEvent & ESCREG_ALEVENT_SM2)
else if (ESCvar.ALevent & ESCREG_ALEVENT_SM2)
{
RXPDO_update();
}
@@ -339,7 +339,7 @@ void ecat_slv_poll (void)
void ecat_slv (void)
{
ecat_slv_poll();
DIG_process(ESCvar.ALevent, DIG_PROCESS_WD_FLAG | DIG_PROCESS_OUTPUTS_FLAG |
DIG_process(DIG_PROCESS_WD_FLAG | DIG_PROCESS_OUTPUTS_FLAG |
DIG_PROCESS_APP_HOOK_FLAG | DIG_PROCESS_INPUTS_FLAG);
}

View File

@@ -36,7 +36,7 @@ void APP_setwatchdog (int watchdogcnt);
*
* @param[in] flags = User input what to execute
*/
void DIG_process (uint16_t ALEvent, uint8_t flags);
void DIG_process (uint8_t flags);
/**
* Handler for SM change, SM0/1, AL CONTROL and EEPROM events, the application

Binary file not shown.

View File

@@ -1,4 +1,4 @@
:200000008006034C64000000000000000000EC00AA0A0000CCBCBB000200000001000000C1
:2000000080060344640000000000000000001400AA0A0000CCBCBB000200000001000000A1
:20002000000000000000000000000000000000000010000200120002040000000000000096
:200040000000000000000000000000000000000000000000000000000000000000000000A0
:20006000000000000000000000000000000000000000000000000000000000000F00010070

View File

@@ -57,7 +57,7 @@
"pdo_mappings": [
"txpdo"
],
"dtype": "REAL64",
"dtype": "REAL32",
"value": "0",
"data": "&Obj.EncPos"
},
@@ -68,7 +68,7 @@
"pdo_mappings": [
"txpdo"
],
"dtype": "REAL64",
"dtype": "REAL32",
"value": "0",
"data": "&Obj.EncFrequency"
},
@@ -79,7 +79,7 @@
"pdo_mappings": [
"txpdo"
],
"dtype": "UNSIGNED32",
"dtype": "UNSIGNED16",
"value": "0",
"data": "&Obj.DiffT"
},
@@ -106,44 +106,26 @@
"data": "&Obj.IndexStatus"
},
"6005": {
"otype": "RECORD",
"name": "StepGenOut1",
"otype": "VAR",
"name": "ActualPosition1",
"access": "RO",
"items": [
{
"name": "Max SubIndex"
},
{
"name": "ActualPosition",
"dtype": "REAL64",
"data": "&Obj.StepGenOut1.ActualPosition",
"value": "0",
"access": "RO"
}
],
"pdo_mappings": [
"txpdo"
]
],
"dtype": "REAL32",
"value": "0",
"data": "&Obj.ActualPosition1"
},
"6006": {
"otype": "RECORD",
"name": "StepGenOut2",
"otype": "VAR",
"name": "ActualPosition2",
"access": "RO",
"items": [
{
"name": "Max SubIndex"
},
{
"name": "ActualPosition",
"dtype": "REAL64",
"data": "&Obj.StepGenOut2.ActualPosition",
"value": "0",
"access": "RO"
}
],
"pdo_mappings": [
"txpdo"
]
],
"dtype": "REAL32",
"value": "0",
"data": "&Obj.ActualPosition2"
},
"6007": {
"otype": "VAR",
@@ -152,7 +134,7 @@
"pdo_mappings": [
"txpdo"
],
"dtype": "INTEGER32",
"dtype": "INTEGER16",
"value": "0",
"data": "&Obj.D1"
},
@@ -163,7 +145,7 @@
"pdo_mappings": [
"txpdo"
],
"dtype": "INTEGER32",
"dtype": "INTEGER16",
"value": "0",
"data": "&Obj.D2"
},
@@ -174,7 +156,7 @@
"pdo_mappings": [
"txpdo"
],
"dtype": "INTEGER32",
"dtype": "INTEGER16",
"value": "0",
"data": "&Obj.D3"
},
@@ -185,24 +167,13 @@
"pdo_mappings": [
"txpdo"
],
"dtype": "INTEGER32",
"dtype": "INTEGER16",
"value": "0",
"data": "&Obj.D4"
}
},
"rxpdo": {
"7000": {
"otype": "VAR",
"name": "EncPosScale",
"access": "RO",
"pdo_mappings": [
"rxpdo"
],
"dtype": "INTEGER32",
"value": "0",
"data": "&Obj.EncPosScale"
},
"7001": {
"otype": "VAR",
"name": "IndexLatchEnable",
"access": "RO",
@@ -213,59 +184,49 @@
"value": "0",
"data": "&Obj.IndexLatchEnable"
},
"7002": {
"otype": "RECORD",
"name": "StepGenIn1",
"7001": {
"otype": "VAR",
"name": "CommandedPosition1",
"access": "RO",
"items": [
{
"name": "Max SubIndex"
},
{
"name": "CommandedPosition",
"dtype": "REAL64",
"data": "&Obj.StepGenIn1.CommandedPosition",
"value": "0",
"access": "RO"
},
{
"name": "StepsPerMM",
"dtype": "INTEGER16",
"value": "0",
"access": "RO",
"data": "&Obj.StepGenIn1.StepsPerMM"
}
],
"pdo_mappings": [
"rxpdo"
]
],
"dtype": "REAL32",
"value": "0",
"data": "&Obj.CommandedPosition1"
},
"7002": {
"otype": "VAR",
"name": "CommandedPosition2",
"access": "RO",
"pdo_mappings": [
"rxpdo"
],
"dtype": "REAL32",
"value": "0",
"data": "&Obj.CommandedPosition2"
},
"7003": {
"otype": "RECORD",
"name": "StepGenIn2",
"otype": "VAR",
"name": "StepsPerMM1",
"access": "RO",
"items": [
{
"name": "Max SubIndex"
},
{
"name": "CommandedPosition",
"dtype": "REAL64",
"data": "&Obj.StepGenIn2.CommandedPosition",
"value": "0",
"access": "RO"
},
{
"name": "StepsPerMM",
"dtype": "INTEGER16",
"value": "0",
"access": "RO",
"data": "&Obj.StepGenIn2.StepsPerMM"
}
],
"pdo_mappings": [
"rxpdo"
]
],
"dtype": "INTEGER16",
"value": "0",
"data": "&Obj.StepsPerMM1"
},
"7004": {
"otype": "VAR",
"name": "StepsPerMM2",
"access": "RO",
"pdo_mappings": [
"rxpdo"
],
"dtype": "INTEGER16",
"value": "0",
"data": "&Obj.StepsPerMM2"
},
"60664": {
"otype": "VAR",

View File

@@ -13,20 +13,21 @@ static const char acName1018_01[] = "Vendor ID";
static const char acName1018_02[] = "Product Code";
static const char acName1018_03[] = "Revision Number";
static const char acName1018_04[] = "Serial Number";
static const char acName1600[] = "EncPosScale";
static const char acName1600[] = "IndexLatchEnable";
static const char acName1600_00[] = "Max SubIndex";
static const char acName1600_01[] = "EncPosScale";
static const char acName1601[] = "IndexLatchEnable";
static const char acName1600_01[] = "IndexLatchEnable";
static const char acName1601[] = "CommandedPosition1";
static const char acName1601_00[] = "Max SubIndex";
static const char acName1601_01[] = "IndexLatchEnable";
static const char acName1602[] = "StepGenIn1";
static const char acName1601_01[] = "CommandedPosition1";
static const char acName1602[] = "CommandedPosition2";
static const char acName1602_00[] = "Max SubIndex";
static const char acName1602_01[] = "CommandedPosition";
static const char acName1602_02[] = "StepsPerMM";
static const char acName1603[] = "StepGenIn2";
static const char acName1602_01[] = "CommandedPosition2";
static const char acName1603[] = "StepsPerMM1";
static const char acName1603_00[] = "Max SubIndex";
static const char acName1603_01[] = "CommandedPosition";
static const char acName1603_02[] = "StepsPerMM";
static const char acName1603_01[] = "StepsPerMM1";
static const char acName1604[] = "StepsPerMM2";
static const char acName1604_00[] = "Max SubIndex";
static const char acName1604_01[] = "StepsPerMM2";
static const char acName1A00[] = "EncPos";
static const char acName1A00_00[] = "Max SubIndex";
static const char acName1A00_01[] = "EncPos";
@@ -42,12 +43,12 @@ 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[] = "ActualPosition1";
static const char acName1A05_00[] = "Max SubIndex";
static const char acName1A05_01[] = "ActualPosition";
static const char acName1A06[] = "StepGenOut2";
static const char acName1A05_01[] = "ActualPosition1";
static const char acName1A06[] = "ActualPosition2";
static const char acName1A06_00[] = "Max SubIndex";
static const char acName1A06_01[] = "ActualPosition";
static const char acName1A06_01[] = "ActualPosition2";
static const char acName1A07[] = "D1";
static const char acName1A07_00[] = "Max SubIndex";
static const char acName1A07_01[] = "D1";
@@ -72,6 +73,7 @@ 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 acName1C12_05[] = "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";
@@ -90,30 +92,21 @@ 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 acName6006[] = "StepGenOut2";
static const char acName6006_00[] = "Max SubIndex";
static const char acName6006_01[] = "ActualPosition";
static const char acName6005[] = "ActualPosition1";
static const char acName6006[] = "ActualPosition2";
static const char acName6007[] = "D1";
static const char acName6008[] = "D2";
static const char acName6009[] = "D3";
static const char acName600A[] = "D4";
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[] = "StepsPerMM";
static const char acName7003[] = "StepGenIn2";
static const char acName7003_00[] = "Max SubIndex";
static const char acName7003_01[] = "CommandedPosition";
static const char acName7003_02[] = "StepsPerMM";
static const char acName7000[] = "IndexLatchEnable";
static const char acName7001[] = "CommandedPosition1";
static const char acName7002[] = "CommandedPosition2";
static const char acName7003[] = "StepsPerMM1";
static const char acName7004[] = "StepsPerMM2";
const _objd SDO1000[] =
{
{0x0, DTYPE_UNSIGNED64, 64, ATYPE_RO, acName1000, 5001, NULL},
{0x0, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1000, 5001, NULL},
};
const _objd SDO1008[] =
{
@@ -130,87 +123,90 @@ const _objd SDO100A[] =
const _objd SDO1018[] =
{
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1018_00, 4, NULL},
{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},
{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},
};
const _objd SDO1600[] =
{
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1600_00, 1, NULL},
{0x01, DTYPE_UNSIGNED64, 64, ATYPE_RO, acName1600_01, 0x70000020, NULL},
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1600_01, 0x70000020, NULL},
};
const _objd SDO1601[] =
{
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1601_00, 1, NULL},
{0x01, DTYPE_UNSIGNED64, 64, ATYPE_RO, acName1601_01, 0x70010020, NULL},
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1601_01, 0x70010020, NULL},
};
const _objd SDO1602[] =
{
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1602_00, 2, NULL},
{0x01, DTYPE_UNSIGNED64, 64, ATYPE_RO, acName1602_01, 0x70020140, NULL},
{0x02, DTYPE_UNSIGNED64, 64, ATYPE_RO, acName1602_02, 0x70020210, NULL},
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1602_00, 1, NULL},
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1602_01, 0x70020020, NULL},
};
const _objd SDO1603[] =
{
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1603_00, 2, NULL},
{0x01, DTYPE_UNSIGNED64, 64, ATYPE_RO, acName1603_01, 0x70030140, NULL},
{0x02, DTYPE_UNSIGNED64, 64, ATYPE_RO, acName1603_02, 0x70030210, NULL},
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1603_00, 1, NULL},
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1603_01, 0x70030010, NULL},
};
const _objd SDO1604[] =
{
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1604_00, 1, NULL},
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1604_01, 0x70040010, NULL},
};
const _objd SDO1A00[] =
{
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1A00_00, 1, NULL},
{0x01, DTYPE_UNSIGNED64, 64, ATYPE_RO, acName1A00_01, 0x60000040, NULL},
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1A00_01, 0x60000020, NULL},
};
const _objd SDO1A01[] =
{
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1A01_00, 1, NULL},
{0x01, DTYPE_UNSIGNED64, 64, ATYPE_RO, acName1A01_01, 0x60010040, 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_UNSIGNED64, 64, ATYPE_RO, acName1A02_01, 0x60020020, NULL},
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1A02_01, 0x60020010, NULL},
};
const _objd SDO1A03[] =
{
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1A03_00, 1, NULL},
{0x01, DTYPE_UNSIGNED64, 64, ATYPE_RO, acName1A03_01, 0x60030020, 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_UNSIGNED64, 64, ATYPE_RO, acName1A04_01, 0x60040020, 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_UNSIGNED64, 64, ATYPE_RO, acName1A05_01, 0x60050140, NULL},
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1A05_01, 0x60050020, NULL},
};
const _objd SDO1A06[] =
{
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1A06_00, 1, NULL},
{0x01, DTYPE_UNSIGNED64, 64, ATYPE_RO, acName1A06_01, 0x60060140, NULL},
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1A06_01, 0x60060020, NULL},
};
const _objd SDO1A07[] =
{
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1A07_00, 1, NULL},
{0x01, DTYPE_UNSIGNED64, 64, ATYPE_RO, acName1A07_01, 0x60070020, NULL},
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1A07_01, 0x60070010, NULL},
};
const _objd SDO1A08[] =
{
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1A08_00, 1, NULL},
{0x01, DTYPE_UNSIGNED64, 64, ATYPE_RO, acName1A08_01, 0x60080020, NULL},
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1A08_01, 0x60080010, NULL},
};
const _objd SDO1A09[] =
{
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1A09_00, 1, NULL},
{0x01, DTYPE_UNSIGNED64, 64, ATYPE_RO, acName1A09_01, 0x60090020, NULL},
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1A09_01, 0x60090010, NULL},
};
const _objd SDO1A0A[] =
{
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1A0A_00, 1, NULL},
{0x01, DTYPE_UNSIGNED64, 64, ATYPE_RO, acName1A0A_01, 0x600A0020, NULL},
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1A0A_01, 0x600A0010, NULL},
};
const _objd SDO1C00[] =
{
@@ -222,11 +218,12 @@ const _objd SDO1C00[] =
};
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},
{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},
{0x05, DTYPE_UNSIGNED16, 16, ATYPE_RO, acName1C12_05, 0x1604, NULL},
};
const _objd SDO1C13[] =
{
@@ -245,15 +242,15 @@ const _objd SDO1C13[] =
};
const _objd SDO6000[] =
{
{0x0, DTYPE_REAL64, 64, ATYPE_RO | ATYPE_TXPDO, acName6000, 0, &Obj.EncPos},
{0x0, DTYPE_REAL32, 32, ATYPE_RO | ATYPE_TXPDO, acName6000, 0x00000000, &Obj.EncPos},
};
const _objd SDO6001[] =
{
{0x0, DTYPE_REAL64, 64, ATYPE_RO | ATYPE_TXPDO, acName6001, 0, &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},
{0x0, DTYPE_UNSIGNED16, 16, ATYPE_RO | ATYPE_TXPDO, acName6002, 0, &Obj.DiffT},
};
const _objd SDO6003[] =
{
@@ -265,49 +262,47 @@ const _objd SDO6004[] =
};
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},
{0x0, DTYPE_REAL32, 32, ATYPE_RO | ATYPE_TXPDO, acName6005, 0x00000000, &Obj.ActualPosition1},
};
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},
{0x0, DTYPE_REAL32, 32, ATYPE_RO | ATYPE_TXPDO, acName6006, 0x00000000, &Obj.ActualPosition2},
};
const _objd SDO6007[] =
{
{0x0, DTYPE_INTEGER32, 32, ATYPE_RO | ATYPE_TXPDO, acName6007, 0, &Obj.D1},
{0x0, DTYPE_INTEGER16, 16, ATYPE_RO | ATYPE_TXPDO, acName6007, 0, &Obj.D1},
};
const _objd SDO6008[] =
{
{0x0, DTYPE_INTEGER32, 32, ATYPE_RO | ATYPE_TXPDO, acName6008, 0, &Obj.D2},
{0x0, DTYPE_INTEGER16, 16, ATYPE_RO | ATYPE_TXPDO, acName6008, 0, &Obj.D2},
};
const _objd SDO6009[] =
{
{0x0, DTYPE_INTEGER32, 32, ATYPE_RO | ATYPE_TXPDO, acName6009, 0, &Obj.D3},
{0x0, DTYPE_INTEGER16, 16, ATYPE_RO | ATYPE_TXPDO, acName6009, 0, &Obj.D3},
};
const _objd SDO600A[] =
{
{0x0, DTYPE_INTEGER32, 32, ATYPE_RO | ATYPE_TXPDO, acName600A, 0, &Obj.D4},
{0x0, DTYPE_INTEGER16, 16, ATYPE_RO | ATYPE_TXPDO, acName600A, 0, &Obj.D4},
};
const _objd SDO7000[] =
{
{0x0, DTYPE_INTEGER32, 32, ATYPE_RO | ATYPE_RXPDO, acName7000, 0, &Obj.EncPosScale},
{0x0, DTYPE_UNSIGNED32, 32, ATYPE_RO | ATYPE_RXPDO, acName7000, 0, &Obj.IndexLatchEnable},
};
const _objd SDO7001[] =
{
{0x0, DTYPE_UNSIGNED32, 32, ATYPE_RO | ATYPE_RXPDO, acName7001, 0, &Obj.IndexLatchEnable},
{0x0, DTYPE_REAL32, 32, ATYPE_RO | ATYPE_RXPDO, acName7001, 0x00000000, &Obj.CommandedPosition1},
};
const _objd SDO7002[] =
{
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName7002_00, 2, NULL},
{0x01, DTYPE_REAL64, 64, ATYPE_RO, acName7002_01, 0, &Obj.StepGenIn1.CommandedPosition},
{0x02, DTYPE_INTEGER16, 16, ATYPE_RO, acName7002_02, 0, &Obj.StepGenIn1.StepsPerMM},
{0x0, DTYPE_REAL32, 32, ATYPE_RO | ATYPE_RXPDO, acName7002, 0x00000000, &Obj.CommandedPosition2},
};
const _objd SDO7003[] =
{
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName7003_00, 2, NULL},
{0x01, DTYPE_REAL64, 64, ATYPE_RO, acName7003_01, 0, &Obj.StepGenIn2.CommandedPosition},
{0x02, DTYPE_INTEGER16, 16, ATYPE_RO, acName7003_02, 0, &Obj.StepGenIn2.StepsPerMM},
{0x0, DTYPE_INTEGER16, 16, ATYPE_RO | ATYPE_RXPDO, acName7003, 0, &Obj.StepsPerMM1},
};
const _objd SDO7004[] =
{
{0x0, DTYPE_INTEGER16, 16, ATYPE_RO | ATYPE_RXPDO, acName7004, 0, &Obj.StepsPerMM2},
};
const _objectlist SDOobjects[] =
@@ -319,8 +314,9 @@ 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},
{0x1603, OTYPE_RECORD, 2, 0, acName1603, SDO1603},
{0x1602, OTYPE_RECORD, 1, 0, acName1602, SDO1602},
{0x1603, OTYPE_RECORD, 1, 0, acName1603, SDO1603},
{0x1604, OTYPE_RECORD, 1, 0, acName1604, SDO1604},
{0x1A00, OTYPE_RECORD, 1, 0, acName1A00, SDO1A00},
{0x1A01, OTYPE_RECORD, 1, 0, acName1A01, SDO1A01},
{0x1A02, OTYPE_RECORD, 1, 0, acName1A02, SDO1A02},
@@ -333,22 +329,23 @@ const _objectlist SDOobjects[] =
{0x1A09, OTYPE_RECORD, 1, 0, acName1A09, SDO1A09},
{0x1A0A, OTYPE_RECORD, 1, 0, acName1A0A, SDO1A0A},
{0x1C00, OTYPE_ARRAY, 4, 0, acName1C00, SDO1C00},
{0x1C12, OTYPE_ARRAY, 4, 0, acName1C12, SDO1C12},
{0x1C12, OTYPE_ARRAY, 5, 0, acName1C12, SDO1C12},
{0x1C13, OTYPE_ARRAY, 11, 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},
{0x6005, OTYPE_VAR, 0, 0, acName6005, SDO6005},
{0x6006, OTYPE_VAR, 0, 0, acName6006, SDO6006},
{0x6007, OTYPE_VAR, 0, 0, acName6007, SDO6007},
{0x6008, OTYPE_VAR, 0, 0, acName6008, SDO6008},
{0x6009, OTYPE_VAR, 0, 0, acName6009, SDO6009},
{0x600A, OTYPE_VAR, 0, 0, acName600A, SDO600A},
{0x7000, OTYPE_VAR, 0, 0, acName7000, SDO7000},
{0x7001, OTYPE_VAR, 0, 0, acName7001, SDO7001},
{0x7002, OTYPE_RECORD, 2, 0, acName7002, SDO7002},
{0x7003, OTYPE_RECORD, 2, 0, acName7003, SDO7003},
{0x7002, OTYPE_VAR, 0, 0, acName7002, SDO7002},
{0x7003, OTYPE_VAR, 0, 0, acName7003, SDO7003},
{0x7004, OTYPE_VAR, 0, 0, acName7004, SDO7004},
{0xffff, 0xff, 0xff, 0xff, NULL, NULL}
};

View File

@@ -13,38 +13,25 @@ typedef struct
/* Inputs */
double EncPos;
double EncFrequency;
uint32_t DiffT;
float EncPos;
float EncFrequency;
uint16_t DiffT;
uint32_t IndexByte;
uint32_t IndexStatus;
struct
{
double ActualPosition;
} StepGenOut1;
struct
{
double ActualPosition;
} StepGenOut2;
int32_t D1;
int32_t D2;
int32_t D3;
int32_t D4;
float ActualPosition1;
float ActualPosition2;
int16_t D1;
int16_t D2;
int16_t D3;
int16_t D4;
/* Outputs */
int32_t EncPosScale;
uint32_t IndexLatchEnable;
struct
{
double CommandedPosition;
int16_t StepsPerMM;
} StepGenIn1;
struct
{
double CommandedPosition;
int16_t StepsPerMM;
} StepGenIn2;
float CommandedPosition1;
float CommandedPosition2;
int16_t StepsPerMM1;
int16_t StepsPerMM2;
} _Objects;

View File

@@ -39,7 +39,7 @@ uint32_t StepGen2::handleStepper(uint64_t irqTime)
nSteps = commandedStepPosition - initialStepPosition;
if (abs(nSteps) < 1000) // Some small number
if (abs(nSteps) < 2) // Some small number
{
frequency = (abs(nSteps) + 1) / lcncCycleTime;
Tpulses = abs(nSteps) / frequency;
@@ -73,7 +73,7 @@ void StepGen2::startTimerCB()
digitalWrite(dirPin, nSteps > 0 ? HIGH : LOW);
// There will be a short break here for t2 usecs, in the future.
timerPulseSteps = abs(nSteps);
pulseTimer->setMode(pulseTimerChan, TIMER_OUTPUT_COMPARE_PWM2, stepPin);
pulseTimer->setMode(pulseTimerChan, TIMER_OUTPUT_COMPARE_PWM1, stepPin);
pulseTimer->setOverflow(timerFrequency, HERTZ_FORMAT);
pulseTimer->setCaptureCompare(pulseTimerChan, 5, MICROSEC_COMPARE_FORMAT); // 5 usecs
pulseTimer->resume();

View File

@@ -25,27 +25,31 @@ StepGen2 Step(TIM1, 4, PA_11, PA12, pulseTimerCallback, TIM10, startTimerCallbac
void pulseTimerCallback(void) { Step.pulseTimerCB(); }
void startTimerCallback(void) { Step.startTimerCB(); }
CircularBuffer<uint32_t, 200> Tim;
volatile uint64_t irqTime = 0, thenTime = 0;
volatile uint64_t irqTime = 0, thenTime = 0, nowTime = 0;
volatile uint32_t ccnnt = 0;
extend32to64 longTime;
void cb_set_outputs(void) // Master outputs gets here, slave inputs, first operation
{
Encoder1.setLatch(Obj.IndexLatchEnable);
Encoder1.setScale(Obj.EncPosScale);
Encoder1.setScale(500);
// Step2.reqPos(Obj.CommandedPosition2);
// Step2.setScale(Obj.StepsPerMM2);
// Step2.enable(1);
Obj.ActualPosition1 = Obj.CommandedPosition1; // Step1.actPos();
Obj.ActualPosition2 = Obj.CommandedPosition2; // Step2.actPos();
}
volatile uint32_t cmt;
void handleStepper(void)
{
digitalWrite(Step.dirPin, cmt++ % 2);
//digitalWrite(Step.dirPin, cmt++ % 2);
Step.enabled = true;
Step.commandedPosition = Obj.StepGenIn1.CommandedPosition;
Obj.StepGenOut1.ActualPosition = Step.commandedPosition;
Step.stepsPerMM = Obj.StepGenIn1.StepsPerMM;
Step.stepsPerMM = 400;
Step.commandedPosition = Obj.CommandedPosition1;
Step.stepsPerMM = Obj.StepsPerMM1;
Step.handleStepper(irqTime);
Obj.StepGenOut2.ActualPosition = Obj.StepGenIn2.CommandedPosition;
Obj.ActualPosition1 = Obj.CommandedPosition1;
}
void cb_get_inputs(void) // Set Master inputs, slave outputs, last operation
@@ -55,7 +59,7 @@ void cb_get_inputs(void) // Set Master inputs, slave outputs, last operation
Obj.EncFrequency = Encoder1.frequency(ESCvar.Time);
Obj.IndexByte = Encoder1.getIndexState();
uint32_t dTim = longTime.extendTime(micros()) - irqTime; // thenTime; // Debug. Getting jitter over the last 200 milliseconds
uint32_t dTim = nowTime - thenTime; // Debug. Getting jitter over the last 200 milliseconds
Tim.push(dTim);
uint32_t max_Tim = 0, min_Tim = UINT32_MAX;
for (decltype(Tim)::index_t i = 0; i < Tim.size(); i++)
@@ -72,7 +76,7 @@ void cb_get_inputs(void) // Set Master inputs, slave outputs, last operation
Obj.D1 = Step.Tjitter;
Obj.D2 = Step.Tstartf * 1e6;
Obj.D3 = Step.dbg;
Obj.D4 = Obj.D1+Obj.D2-Obj.D3;
Obj.D4 = Obj.D1 + Obj.D2 - Obj.D3;
}
void ESC_interrupt_enable(uint32_t mask);
@@ -114,9 +118,12 @@ void loop(void)
uint32_t dTime;
if (serveIRQ)
{
CC_ATOMIC_SET(ESCvar.ALevent, ESC_ALeventread());
DIG_process(ALEventIRQ, DIG_PROCESS_WD_FLAG | DIG_PROCESS_OUTPUTS_FLAG |
DIG_PROCESS_APP_HOOK_FLAG | DIG_PROCESS_INPUTS_FLAG);
nowTime = micros();
/* Read local time from ESC*/
ESC_read(ESCREG_LOCALTIME, (void *)&ESCvar.Time, sizeof(ESCvar.Time));
ESCvar.Time = etohl(ESCvar.Time);
DIG_process(DIG_PROCESS_WD_FLAG | DIG_PROCESS_OUTPUTS_FLAG |
DIG_PROCESS_APP_HOOK_FLAG | DIG_PROCESS_INPUTS_FLAG);
serveIRQ = 0;
ESCvar.PrevTime = ESCvar.Time;
}
@@ -131,7 +138,6 @@ void sync0Handler(void)
ALEventIRQ = ESC_ALeventread();
serveIRQ = 1;
irqTime = longTime.extendTime(micros());
digitalWrite(Step.dirPin, cnt++ % 2);
}
// Enable SM2 interrupts