Added SDO for basePeriod, PDOs for scale, enable, maxAccel. All got default values in ESI
This commit is contained in:
@@ -92,7 +92,12 @@ public:
|
||||
volatile uint64_t cnt = 0; // Debug counter
|
||||
#undef double
|
||||
StepGen3(void);
|
||||
void updateStepGen(double pos_cmd1, double pos_cmd2, double pos_cmd3, double pos_cmd4, uint32_t servoPeriod);
|
||||
|
||||
void updateStepGen(double pos_cmd1, double pos_cmd2, double pos_cmd3, double pos_cmd4,
|
||||
float pos_scale1, float pos_scale2, float pos_scale3, float pos_scale4,
|
||||
float max_acc1, float max_acc2, float max_acc3, float max_acc4,
|
||||
uint8_t enable1, uint8_t enable2, uint8_t enable3, uint8_t enable4,
|
||||
uint32_t servoPeriod);
|
||||
void makeAllPulses(void);
|
||||
int rtapi_app_main();
|
||||
int export_stepgen(int num, stepgen_t *addr, int step_type, int pos_mode);
|
||||
@@ -130,6 +135,7 @@ private:
|
||||
{2, 3, 3, 4, 4, 4, 4, 4, 4, 5, 5, 5, 5, 0};
|
||||
};
|
||||
|
||||
// Initial values. Please update base_period using SDO, the others using PDOs
|
||||
// For the example 20000 ns => 50 kHz
|
||||
// It may be ok with over 100 kHz, it depends on the overall load. You just need to test.
|
||||
#define BASE_PERIOD 20000
|
||||
|
||||
File diff suppressed because it is too large
Load Diff
@@ -33,8 +33,8 @@
|
||||
#define SM3_smc 0x20
|
||||
#define SM3_act 1
|
||||
|
||||
#define MAX_MAPPINGS_SM2 13
|
||||
#define MAX_MAPPINGS_SM3 14
|
||||
#define MAX_MAPPINGS_SM2 18
|
||||
#define MAX_MAPPINGS_SM3 7
|
||||
|
||||
#define MAX_RXPDO_SIZE 512
|
||||
#define MAX_TXPDO_SIZE 512
|
||||
|
||||
Binary file not shown.
@@ -1,13 +1,13 @@
|
||||
:20000000050603446400000000001A0000004E00AA0A0000AEDCCA000100000001000000B8
|
||||
:20000000050603446400000000001A0000004E00D0D1BED000300000020000000100000060
|
||||
:20002000000000000000000000000000000000000010000200120002040000000000000096
|
||||
:200040000000000000000000000000000000000000000000000000000000000000000000A0
|
||||
:20006000000000000000000000000000000000000000000000000000000000000F00010070
|
||||
:200080000A003000041454484341442052656164657220617835383130300E4D6163686950
|
||||
:2000A0006E65436F6E74726F6C06494D47434259334D6574616C4D7573696E6773204561F9
|
||||
:2000C0007365724341542033303030207465737420706C61736D6120746F72636820726566
|
||||
:2000E000616465721E0010000203010400130000000000000000000011000000000000008
|
||||
:20010000000000000000000028000200010203002900100000100002260001010012000228
|
||||
:20012000220001020016000024000103001A000020000104FFFFFFFFFFFFFFFFFFFFFFFF29
|
||||
:200080000A001F00040B434E4320636F6E74726F6C0E4D616368696E65436F6E74726F6C8F
|
||||
:2000A00006494D474342591A4D6574616C4D7573696E677320456173657243415420333021
|
||||
:2000C00030301E001000020301040013000000000000000000001100000000000000000064
|
||||
:2000E000000000000000280002000102030029001000001000022600010100120002220027
|
||||
:2001000001020016000024000103001A000020000104FFFFFFFFFFFFFFFFFFFFFFFFFFFF6D
|
||||
:20012000FFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFDF
|
||||
:20014000FFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFBF
|
||||
:20016000FFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFF9F
|
||||
:20018000FFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFF7F
|
||||
|
||||
@@ -1,10 +1,10 @@
|
||||
{
|
||||
"form": {
|
||||
"VendorName": "MetalMusings",
|
||||
"VendorID": "0xaaa",
|
||||
"ProductCode": "0xcadcae",
|
||||
"VendorID": "0xd0bed1d0",
|
||||
"ProductCode": "0x3000",
|
||||
"ProfileNo": "5002",
|
||||
"RevisionNumber": "0x001",
|
||||
"RevisionNumber": "0x002",
|
||||
"SerialNumber": "0x001",
|
||||
"HWversion": "0.0.1",
|
||||
"SWversion": "0.0.1",
|
||||
@@ -15,10 +15,10 @@
|
||||
"SM2Offset": "0x1600",
|
||||
"SM3Offset": "0x1A00",
|
||||
"TextGroupType": "MachineControl",
|
||||
"TextGroupName5": "Plasma torch reader",
|
||||
"TextGroupName5": "CNC control",
|
||||
"ImageName": "IMGCBY",
|
||||
"TextDeviceType": "THCAD Reader ax58100",
|
||||
"TextDeviceName": "MetalMusings EaserCAT 3000 test plasma torch reader",
|
||||
"TextDeviceType": "CNC control",
|
||||
"TextDeviceName": "MetalMusings EaserCAT 3000",
|
||||
"Port0Physical": "Y",
|
||||
"Port1Physical": "Y",
|
||||
"Port2Physical": " ",
|
||||
@@ -34,6 +34,15 @@
|
||||
},
|
||||
"od": {
|
||||
"sdo": {
|
||||
"2000": {
|
||||
"otype": "VAR",
|
||||
"name": "BasePeriod",
|
||||
"access": "RW",
|
||||
"dtype": "UNSIGNED32",
|
||||
"value": "20000",
|
||||
"isSDOitem": true,
|
||||
"data": "&Obj.BasePeriod"
|
||||
},
|
||||
"A": {
|
||||
"otype": "RECORD",
|
||||
"name": "Error Settings",
|
||||
@@ -73,60 +82,6 @@
|
||||
"data": "&Obj.Velocity"
|
||||
},
|
||||
"6001": {
|
||||
"otype": "ARRAY",
|
||||
"name": "Inputs",
|
||||
"access": "RO",
|
||||
"items": [
|
||||
{
|
||||
"name": "Max SubIndex"
|
||||
},
|
||||
{
|
||||
"name": "IN1",
|
||||
"data": "&Obj.Inputs[0]",
|
||||
"value": "0"
|
||||
},
|
||||
{
|
||||
"name": "IN2",
|
||||
"value": "0",
|
||||
"data": "&Obj.Inputs[1]"
|
||||
},
|
||||
{
|
||||
"name": "IN3",
|
||||
"value": "0",
|
||||
"data": "&Obj.Inputs[2]"
|
||||
},
|
||||
{
|
||||
"name": "IN4",
|
||||
"value": "0",
|
||||
"data": "&Obj.Inputs[3]"
|
||||
},
|
||||
{
|
||||
"name": "IN5",
|
||||
"value": "0",
|
||||
"data": "&Obj.Inputs[4]"
|
||||
},
|
||||
{
|
||||
"name": "IN6",
|
||||
"value": "0",
|
||||
"data": "&Obj.Inputs[5]"
|
||||
},
|
||||
{
|
||||
"name": "IN7",
|
||||
"value": "0",
|
||||
"data": "&Obj.Inputs[6]"
|
||||
},
|
||||
{
|
||||
"name": "IN8",
|
||||
"value": "0",
|
||||
"data": "&Obj.Inputs[7]"
|
||||
}
|
||||
],
|
||||
"pdo_mappings": [
|
||||
"txpdo"
|
||||
],
|
||||
"dtype": "UNSIGNED8"
|
||||
},
|
||||
"6002": {
|
||||
"otype": "VAR",
|
||||
"name": "Frequency",
|
||||
"access": "RO",
|
||||
@@ -137,6 +92,17 @@
|
||||
"value": "0",
|
||||
"data": "&Obj.Frequency"
|
||||
},
|
||||
"6002": {
|
||||
"otype": "VAR",
|
||||
"name": "Input8",
|
||||
"access": "RO",
|
||||
"pdo_mappings": [
|
||||
"txpdo"
|
||||
],
|
||||
"dtype": "UNSIGNED8",
|
||||
"value": "0",
|
||||
"data": "&Obj.Input8"
|
||||
},
|
||||
"6003": {
|
||||
"otype": "VAR",
|
||||
"name": "ActualPosition1",
|
||||
@@ -191,42 +157,19 @@
|
||||
"rxpdo"
|
||||
],
|
||||
"dtype": "REAL32",
|
||||
"value": "0",
|
||||
"value": "1",
|
||||
"data": "&Obj.Scale"
|
||||
},
|
||||
"7001": {
|
||||
"otype": "ARRAY",
|
||||
"name": "Outputs",
|
||||
"otype": "VAR",
|
||||
"name": "Output4",
|
||||
"access": "RO",
|
||||
"items": [
|
||||
{
|
||||
"name": "Max SubIndex"
|
||||
},
|
||||
{
|
||||
"name": "OUT1",
|
||||
"data": "&Obj.Outputs[0]",
|
||||
"value": "0"
|
||||
},
|
||||
{
|
||||
"name": "OUT2",
|
||||
"value": "0",
|
||||
"data": "&Obj.Outputs[1]"
|
||||
},
|
||||
{
|
||||
"name": "OUT3",
|
||||
"value": "0",
|
||||
"data": "&Obj.Outputs[2]"
|
||||
},
|
||||
{
|
||||
"name": "OUT4",
|
||||
"value": "0",
|
||||
"data": "&Obj.Outputs[3]"
|
||||
}
|
||||
],
|
||||
"pdo_mappings": [
|
||||
"rxpdo"
|
||||
],
|
||||
"dtype": "UNSIGNED8"
|
||||
"dtype": "UNSIGNED8",
|
||||
"value": "0",
|
||||
"data": "&Obj.Output4"
|
||||
},
|
||||
"7002": {
|
||||
"otype": "VAR",
|
||||
@@ -279,8 +222,8 @@
|
||||
"pdo_mappings": [
|
||||
"rxpdo"
|
||||
],
|
||||
"dtype": "INTEGER32",
|
||||
"value": "0",
|
||||
"dtype": "REAL32",
|
||||
"value": "100",
|
||||
"data": "&Obj.StepsPerMM1"
|
||||
},
|
||||
"7007": {
|
||||
@@ -290,8 +233,8 @@
|
||||
"pdo_mappings": [
|
||||
"rxpdo"
|
||||
],
|
||||
"dtype": "INTEGER32",
|
||||
"value": "0",
|
||||
"dtype": "REAL32",
|
||||
"value": "100",
|
||||
"data": "&Obj.StepsPerMM2"
|
||||
},
|
||||
"7008": {
|
||||
@@ -301,8 +244,8 @@
|
||||
"pdo_mappings": [
|
||||
"rxpdo"
|
||||
],
|
||||
"dtype": "INTEGER32",
|
||||
"value": "0",
|
||||
"dtype": "REAL32",
|
||||
"value": "100",
|
||||
"data": "&Obj.StepsPerMM3"
|
||||
},
|
||||
"7009": {
|
||||
@@ -312,10 +255,32 @@
|
||||
"pdo_mappings": [
|
||||
"rxpdo"
|
||||
],
|
||||
"dtype": "INTEGER32",
|
||||
"value": "0",
|
||||
"dtype": "REAL32",
|
||||
"value": "100",
|
||||
"data": "&Obj.StepsPerMM4"
|
||||
},
|
||||
"7010": {
|
||||
"otype": "VAR",
|
||||
"name": "Enable3",
|
||||
"access": "RO",
|
||||
"pdo_mappings": [
|
||||
"rxpdo"
|
||||
],
|
||||
"dtype": "UNSIGNED8",
|
||||
"value": "0",
|
||||
"data": "&Obj.Enable3"
|
||||
},
|
||||
"7011": {
|
||||
"otype": "VAR",
|
||||
"name": "Enable4",
|
||||
"access": "RO",
|
||||
"pdo_mappings": [
|
||||
"rxpdo"
|
||||
],
|
||||
"dtype": "UNSIGNED8",
|
||||
"value": "0",
|
||||
"data": "&Obj.Enable4"
|
||||
},
|
||||
"60664": {
|
||||
"otype": "VAR",
|
||||
"name": "ActualPosition",
|
||||
@@ -325,6 +290,72 @@
|
||||
],
|
||||
"dtype": "INTEGER32",
|
||||
"value": "0"
|
||||
},
|
||||
"700D": {
|
||||
"otype": "VAR",
|
||||
"name": "MaxAcceleration4",
|
||||
"access": "RO",
|
||||
"pdo_mappings": [
|
||||
"rxpdo"
|
||||
],
|
||||
"dtype": "REAL32",
|
||||
"value": "10000",
|
||||
"data": "&Obj.MaxAcceleration4"
|
||||
},
|
||||
"700C": {
|
||||
"otype": "VAR",
|
||||
"name": "MaxAcceleration3",
|
||||
"access": "RO",
|
||||
"pdo_mappings": [
|
||||
"rxpdo"
|
||||
],
|
||||
"dtype": "REAL32",
|
||||
"value": "10000",
|
||||
"data": "&Obj.MaxAcceleration3"
|
||||
},
|
||||
"700E": {
|
||||
"otype": "VAR",
|
||||
"name": "Enable1",
|
||||
"access": "RO",
|
||||
"pdo_mappings": [
|
||||
"rxpdo"
|
||||
],
|
||||
"dtype": "UNSIGNED8",
|
||||
"value": "0",
|
||||
"data": "&Obj.Enable1"
|
||||
},
|
||||
"700F": {
|
||||
"otype": "VAR",
|
||||
"name": "Enable2",
|
||||
"access": "RO",
|
||||
"pdo_mappings": [
|
||||
"rxpdo"
|
||||
],
|
||||
"dtype": "UNSIGNED8",
|
||||
"value": "0",
|
||||
"data": "&Obj.Enable2"
|
||||
},
|
||||
"700A": {
|
||||
"otype": "VAR",
|
||||
"name": "MaxAcceleration1",
|
||||
"access": "RO",
|
||||
"pdo_mappings": [
|
||||
"rxpdo"
|
||||
],
|
||||
"dtype": "REAL32",
|
||||
"value": "10000",
|
||||
"data": "&Obj.MaxAcceleration1"
|
||||
},
|
||||
"700B": {
|
||||
"otype": "VAR",
|
||||
"name": "MaxAcceleration2",
|
||||
"access": "RO",
|
||||
"pdo_mappings": [
|
||||
"rxpdo"
|
||||
],
|
||||
"dtype": "REAL32",
|
||||
"value": "10000",
|
||||
"data": "&Obj.MaxAcceleration2"
|
||||
}
|
||||
}
|
||||
},
|
||||
|
||||
@@ -16,12 +16,9 @@ static const char acName1018_04[] = "Serial Number";
|
||||
static const char acName1600[] = "Scale";
|
||||
static const char acName1600_00[] = "Max SubIndex";
|
||||
static const char acName1600_01[] = "Scale";
|
||||
static const char acName1601[] = "Outputs";
|
||||
static const char acName1601[] = "Output4";
|
||||
static const char acName1601_00[] = "Max SubIndex";
|
||||
static const char acName1601_01[] = "OUT1";
|
||||
static const char acName1601_02[] = "OUT2";
|
||||
static const char acName1601_03[] = "OUT3";
|
||||
static const char acName1601_04[] = "OUT4";
|
||||
static const char acName1601_01[] = "Output4";
|
||||
static const char acName1602[] = "CommandedPosition1";
|
||||
static const char acName1602_00[] = "Max SubIndex";
|
||||
static const char acName1602_01[] = "CommandedPosition1";
|
||||
@@ -46,22 +43,39 @@ static const char acName1608_01[] = "StepsPerMM3";
|
||||
static const char acName1609[] = "StepsPerMM4";
|
||||
static const char acName1609_00[] = "Max SubIndex";
|
||||
static const char acName1609_01[] = "StepsPerMM4";
|
||||
static const char acName160A[] = "MaxAcceleration1";
|
||||
static const char acName160A_00[] = "Max SubIndex";
|
||||
static const char acName160A_01[] = "MaxAcceleration1";
|
||||
static const char acName160B[] = "MaxAcceleration2";
|
||||
static const char acName160B_00[] = "Max SubIndex";
|
||||
static const char acName160B_01[] = "MaxAcceleration2";
|
||||
static const char acName160C[] = "MaxAcceleration3";
|
||||
static const char acName160C_00[] = "Max SubIndex";
|
||||
static const char acName160C_01[] = "MaxAcceleration3";
|
||||
static const char acName160D[] = "MaxAcceleration4";
|
||||
static const char acName160D_00[] = "Max SubIndex";
|
||||
static const char acName160D_01[] = "MaxAcceleration4";
|
||||
static const char acName160E[] = "Enable1";
|
||||
static const char acName160E_00[] = "Max SubIndex";
|
||||
static const char acName160E_01[] = "Enable1";
|
||||
static const char acName160F[] = "Enable2";
|
||||
static const char acName160F_00[] = "Max SubIndex";
|
||||
static const char acName160F_01[] = "Enable2";
|
||||
static const char acName1610[] = "Enable3";
|
||||
static const char acName1610_00[] = "Max SubIndex";
|
||||
static const char acName1610_01[] = "Enable3";
|
||||
static const char acName1611[] = "Enable4";
|
||||
static const char acName1611_00[] = "Max SubIndex";
|
||||
static const char acName1611_01[] = "Enable4";
|
||||
static const char acName1A00[] = "Velocity";
|
||||
static const char acName1A00_00[] = "Max SubIndex";
|
||||
static const char acName1A00_01[] = "Velocity";
|
||||
static const char acName1A01[] = "Inputs";
|
||||
static const char acName1A01[] = "Frequency";
|
||||
static const char acName1A01_00[] = "Max SubIndex";
|
||||
static const char acName1A01_01[] = "IN1";
|
||||
static const char acName1A01_02[] = "IN2";
|
||||
static const char acName1A01_03[] = "IN3";
|
||||
static const char acName1A01_04[] = "IN4";
|
||||
static const char acName1A01_05[] = "IN5";
|
||||
static const char acName1A01_06[] = "IN6";
|
||||
static const char acName1A01_07[] = "IN7";
|
||||
static const char acName1A01_08[] = "IN8";
|
||||
static const char acName1A02[] = "Frequency";
|
||||
static const char acName1A01_01[] = "Frequency";
|
||||
static const char acName1A02[] = "Input8";
|
||||
static const char acName1A02_00[] = "Max SubIndex";
|
||||
static const char acName1A02_01[] = "Frequency";
|
||||
static const char acName1A02_01[] = "Input8";
|
||||
static const char acName1A03[] = "ActualPosition1";
|
||||
static const char acName1A03_00[] = "Max SubIndex";
|
||||
static const char acName1A03_01[] = "ActualPosition1";
|
||||
@@ -92,6 +106,14 @@ static const char acName1C12_07[] = "PDO Mapping";
|
||||
static const char acName1C12_08[] = "PDO Mapping";
|
||||
static const char acName1C12_09[] = "PDO Mapping";
|
||||
static const char acName1C12_0a[] = "PDO Mapping";
|
||||
static const char acName1C12_0b[] = "PDO Mapping";
|
||||
static const char acName1C12_0c[] = "PDO Mapping";
|
||||
static const char acName1C12_0d[] = "PDO Mapping";
|
||||
static const char acName1C12_0e[] = "PDO Mapping";
|
||||
static const char acName1C12_0f[] = "PDO Mapping";
|
||||
static const char acName1C12_010[] = "PDO Mapping";
|
||||
static const char acName1C12_11[] = "PDO Mapping";
|
||||
static const char acName1C12_12[] = "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";
|
||||
@@ -101,29 +123,16 @@ 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 acName2000[] = "BasePeriod";
|
||||
static const char acName6000[] = "Velocity";
|
||||
static const char acName6001[] = "Inputs";
|
||||
static const char acName6001_00[] = "Max SubIndex";
|
||||
static const char acName6001_01[] = "IN1";
|
||||
static const char acName6001_02[] = "IN2";
|
||||
static const char acName6001_03[] = "IN3";
|
||||
static const char acName6001_04[] = "IN4";
|
||||
static const char acName6001_05[] = "IN5";
|
||||
static const char acName6001_06[] = "IN6";
|
||||
static const char acName6001_07[] = "IN7";
|
||||
static const char acName6001_08[] = "IN8";
|
||||
static const char acName6002[] = "Frequency";
|
||||
static const char acName6001[] = "Frequency";
|
||||
static const char acName6002[] = "Input8";
|
||||
static const char acName6003[] = "ActualPosition1";
|
||||
static const char acName6004[] = "ActualPosition2";
|
||||
static const char acName6005[] = "ActualPosition3";
|
||||
static const char acName6006[] = "ActualPosition4";
|
||||
static const char acName7000[] = "Scale";
|
||||
static const char acName7001[] = "Outputs";
|
||||
static const char acName7001_00[] = "Max SubIndex";
|
||||
static const char acName7001_01[] = "OUT1";
|
||||
static const char acName7001_02[] = "OUT2";
|
||||
static const char acName7001_03[] = "OUT3";
|
||||
static const char acName7001_04[] = "OUT4";
|
||||
static const char acName7001[] = "Output4";
|
||||
static const char acName7002[] = "CommandedPosition1";
|
||||
static const char acName7003[] = "CommandedPosition2";
|
||||
static const char acName7004[] = "CommandedPosition3";
|
||||
@@ -132,6 +141,14 @@ static const char acName7006[] = "StepsPerMM1";
|
||||
static const char acName7007[] = "StepsPerMM2";
|
||||
static const char acName7008[] = "StepsPerMM3";
|
||||
static const char acName7009[] = "StepsPerMM4";
|
||||
static const char acName700A[] = "MaxAcceleration1";
|
||||
static const char acName700B[] = "MaxAcceleration2";
|
||||
static const char acName700C[] = "MaxAcceleration3";
|
||||
static const char acName700D[] = "MaxAcceleration4";
|
||||
static const char acName700E[] = "Enable1";
|
||||
static const char acName700F[] = "Enable2";
|
||||
static const char acName7010[] = "Enable3";
|
||||
static const char acName7011[] = "Enable4";
|
||||
|
||||
const _objd SDO1000[] =
|
||||
{
|
||||
@@ -139,7 +156,7 @@ const _objd SDO1000[] =
|
||||
};
|
||||
const _objd SDO1008[] =
|
||||
{
|
||||
{0x0, DTYPE_VISIBLE_STRING, 408, ATYPE_RO, acName1008, 0, "MetalMusings EaserCAT 3000 test plasma torch reader"},
|
||||
{0x0, DTYPE_VISIBLE_STRING, 208, ATYPE_RO, acName1008, 0, "MetalMusings EaserCAT 3000"},
|
||||
};
|
||||
const _objd SDO1009[] =
|
||||
{
|
||||
@@ -152,9 +169,9 @@ 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, 13294766, NULL},
|
||||
{0x03, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1018_03, 1, NULL},
|
||||
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1018_01, 3502166480, NULL},
|
||||
{0x02, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1018_02, 12288, 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[] =
|
||||
@@ -164,11 +181,8 @@ const _objd SDO1600[] =
|
||||
};
|
||||
const _objd SDO1601[] =
|
||||
{
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1601_00, 4, NULL},
|
||||
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1601_01, 0x70010108, NULL},
|
||||
{0x02, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1601_02, 0x70010208, NULL},
|
||||
{0x03, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1601_03, 0x70010308, NULL},
|
||||
{0x04, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1601_04, 0x70010408, NULL},
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1601_00, 1, NULL},
|
||||
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1601_01, 0x70010008, NULL},
|
||||
};
|
||||
const _objd SDO1602[] =
|
||||
{
|
||||
@@ -210,6 +224,46 @@ const _objd SDO1609[] =
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1609_00, 1, NULL},
|
||||
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1609_01, 0x70090020, NULL},
|
||||
};
|
||||
const _objd SDO160A[] =
|
||||
{
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName160A_00, 1, NULL},
|
||||
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName160A_01, 0x700A0020, NULL},
|
||||
};
|
||||
const _objd SDO160B[] =
|
||||
{
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName160B_00, 1, NULL},
|
||||
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName160B_01, 0x700B0020, NULL},
|
||||
};
|
||||
const _objd SDO160C[] =
|
||||
{
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName160C_00, 1, NULL},
|
||||
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName160C_01, 0x700C0020, NULL},
|
||||
};
|
||||
const _objd SDO160D[] =
|
||||
{
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName160D_00, 1, NULL},
|
||||
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName160D_01, 0x700D0020, NULL},
|
||||
};
|
||||
const _objd SDO160E[] =
|
||||
{
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName160E_00, 1, NULL},
|
||||
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName160E_01, 0x700E0008, NULL},
|
||||
};
|
||||
const _objd SDO160F[] =
|
||||
{
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName160F_00, 1, NULL},
|
||||
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName160F_01, 0x700F0008, NULL},
|
||||
};
|
||||
const _objd SDO1610[] =
|
||||
{
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1610_00, 1, NULL},
|
||||
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1610_01, 0x70100008, NULL},
|
||||
};
|
||||
const _objd SDO1611[] =
|
||||
{
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1611_00, 1, NULL},
|
||||
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1611_01, 0x70110008, NULL},
|
||||
};
|
||||
const _objd SDO1A00[] =
|
||||
{
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1A00_00, 1, NULL},
|
||||
@@ -217,20 +271,13 @@ const _objd SDO1A00[] =
|
||||
};
|
||||
const _objd SDO1A01[] =
|
||||
{
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1A01_00, 8, NULL},
|
||||
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1A01_01, 0x60010108, NULL},
|
||||
{0x02, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1A01_02, 0x60010208, NULL},
|
||||
{0x03, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1A01_03, 0x60010308, NULL},
|
||||
{0x04, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1A01_04, 0x60010408, NULL},
|
||||
{0x05, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1A01_05, 0x60010508, NULL},
|
||||
{0x06, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1A01_06, 0x60010608, NULL},
|
||||
{0x07, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1A01_07, 0x60010708, NULL},
|
||||
{0x08, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1A01_08, 0x60010808, NULL},
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1A01_00, 1, 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_UNSIGNED32, 32, ATYPE_RO, acName1A02_01, 0x60020020, NULL},
|
||||
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1A02_01, 0x60020008, NULL},
|
||||
};
|
||||
const _objd SDO1A03[] =
|
||||
{
|
||||
@@ -262,7 +309,7 @@ const _objd SDO1C00[] =
|
||||
};
|
||||
const _objd SDO1C12[] =
|
||||
{
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1C12_00, 10, NULL},
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1C12_00, 18, 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},
|
||||
@@ -273,6 +320,14 @@ const _objd SDO1C12[] =
|
||||
{0x08, DTYPE_UNSIGNED16, 16, ATYPE_RO, acName1C12_08, 0x1607, NULL},
|
||||
{0x09, DTYPE_UNSIGNED16, 16, ATYPE_RO, acName1C12_09, 0x1608, NULL},
|
||||
{0x0a, DTYPE_UNSIGNED16, 16, ATYPE_RO, acName1C12_0a, 0x1609, NULL},
|
||||
{0x0b, DTYPE_UNSIGNED16, 16, ATYPE_RO, acName1C12_0b, 0x160A, NULL},
|
||||
{0x0c, DTYPE_UNSIGNED16, 16, ATYPE_RO, acName1C12_0c, 0x160B, NULL},
|
||||
{0x0d, DTYPE_UNSIGNED16, 16, ATYPE_RO, acName1C12_0d, 0x160C, NULL},
|
||||
{0x0e, DTYPE_UNSIGNED16, 16, ATYPE_RO, acName1C12_0e, 0x160D, NULL},
|
||||
{0x0f, DTYPE_UNSIGNED16, 16, ATYPE_RO, acName1C12_0f, 0x160E, NULL},
|
||||
{0x010, DTYPE_UNSIGNED16, 16, ATYPE_RO, acName1C12_010, 0x160F, NULL},
|
||||
{0x11, DTYPE_UNSIGNED16, 16, ATYPE_RO, acName1C12_11, 0x1610, NULL},
|
||||
{0x12, DTYPE_UNSIGNED16, 16, ATYPE_RO, acName1C12_12, 0x1611, NULL},
|
||||
};
|
||||
const _objd SDO1C13[] =
|
||||
{
|
||||
@@ -285,25 +340,21 @@ const _objd SDO1C13[] =
|
||||
{0x06, DTYPE_UNSIGNED16, 16, ATYPE_RO, acName1C13_06, 0x1A05, NULL},
|
||||
{0x07, DTYPE_UNSIGNED16, 16, ATYPE_RO, acName1C13_07, 0x1A06, NULL},
|
||||
};
|
||||
const _objd SDO2000[] =
|
||||
{
|
||||
{0x0, DTYPE_UNSIGNED32, 32, ATYPE_RW, acName2000, 20000, &Obj.BasePeriod},
|
||||
};
|
||||
const _objd SDO6000[] =
|
||||
{
|
||||
{0x0, DTYPE_REAL32, 32, ATYPE_RO | ATYPE_TXPDO, acName6000, 0x00000000, &Obj.Velocity},
|
||||
};
|
||||
const _objd SDO6001[] =
|
||||
{
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName6001_00, 8, NULL},
|
||||
{0x01, DTYPE_UNSIGNED8, 8, ATYPE_RO | ATYPE_TXPDO, acName6001_01, 0, &Obj.Inputs[0]},
|
||||
{0x02, DTYPE_UNSIGNED8, 8, ATYPE_RO | ATYPE_TXPDO, acName6001_02, 0, &Obj.Inputs[1]},
|
||||
{0x03, DTYPE_UNSIGNED8, 8, ATYPE_RO | ATYPE_TXPDO, acName6001_03, 0, &Obj.Inputs[2]},
|
||||
{0x04, DTYPE_UNSIGNED8, 8, ATYPE_RO | ATYPE_TXPDO, acName6001_04, 0, &Obj.Inputs[3]},
|
||||
{0x05, DTYPE_UNSIGNED8, 8, ATYPE_RO | ATYPE_TXPDO, acName6001_05, 0, &Obj.Inputs[4]},
|
||||
{0x06, DTYPE_UNSIGNED8, 8, ATYPE_RO | ATYPE_TXPDO, acName6001_06, 0, &Obj.Inputs[5]},
|
||||
{0x07, DTYPE_UNSIGNED8, 8, ATYPE_RO | ATYPE_TXPDO, acName6001_07, 0, &Obj.Inputs[6]},
|
||||
{0x08, DTYPE_UNSIGNED8, 8, ATYPE_RO | ATYPE_TXPDO, acName6001_08, 0, &Obj.Inputs[7]},
|
||||
{0x0, DTYPE_REAL32, 32, ATYPE_RO | ATYPE_TXPDO, acName6001, 0x00000000, &Obj.Frequency},
|
||||
};
|
||||
const _objd SDO6002[] =
|
||||
{
|
||||
{0x0, DTYPE_REAL32, 32, ATYPE_RO | ATYPE_TXPDO, acName6002, 0x00000000, &Obj.Frequency},
|
||||
{0x0, DTYPE_UNSIGNED8, 8, ATYPE_RO | ATYPE_TXPDO, acName6002, 0, &Obj.Input8},
|
||||
};
|
||||
const _objd SDO6003[] =
|
||||
{
|
||||
@@ -323,15 +374,11 @@ const _objd SDO6006[] =
|
||||
};
|
||||
const _objd SDO7000[] =
|
||||
{
|
||||
{0x0, DTYPE_REAL32, 32, ATYPE_RO | ATYPE_RXPDO, acName7000, 0x00000000, &Obj.Scale},
|
||||
{0x0, DTYPE_REAL32, 32, ATYPE_RO | ATYPE_RXPDO, acName7000, 0x3f800000, &Obj.Scale},
|
||||
};
|
||||
const _objd SDO7001[] =
|
||||
{
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName7001_00, 4, NULL},
|
||||
{0x01, DTYPE_UNSIGNED8, 8, ATYPE_RO | ATYPE_RXPDO, acName7001_01, 0, &Obj.Outputs[0]},
|
||||
{0x02, DTYPE_UNSIGNED8, 8, ATYPE_RO | ATYPE_RXPDO, acName7001_02, 0, &Obj.Outputs[1]},
|
||||
{0x03, DTYPE_UNSIGNED8, 8, ATYPE_RO | ATYPE_RXPDO, acName7001_03, 0, &Obj.Outputs[2]},
|
||||
{0x04, DTYPE_UNSIGNED8, 8, ATYPE_RO | ATYPE_RXPDO, acName7001_04, 0, &Obj.Outputs[3]},
|
||||
{0x0, DTYPE_UNSIGNED8, 8, ATYPE_RO | ATYPE_RXPDO, acName7001, 0, &Obj.Output4},
|
||||
};
|
||||
const _objd SDO7002[] =
|
||||
{
|
||||
@@ -351,19 +398,51 @@ const _objd SDO7005[] =
|
||||
};
|
||||
const _objd SDO7006[] =
|
||||
{
|
||||
{0x0, DTYPE_INTEGER32, 32, ATYPE_RO | ATYPE_RXPDO, acName7006, 0, &Obj.StepsPerMM1},
|
||||
{0x0, DTYPE_REAL32, 32, ATYPE_RO | ATYPE_RXPDO, acName7006, 0x42c80000, &Obj.StepsPerMM1},
|
||||
};
|
||||
const _objd SDO7007[] =
|
||||
{
|
||||
{0x0, DTYPE_INTEGER32, 32, ATYPE_RO | ATYPE_RXPDO, acName7007, 0, &Obj.StepsPerMM2},
|
||||
{0x0, DTYPE_REAL32, 32, ATYPE_RO | ATYPE_RXPDO, acName7007, 0x42c80000, &Obj.StepsPerMM2},
|
||||
};
|
||||
const _objd SDO7008[] =
|
||||
{
|
||||
{0x0, DTYPE_INTEGER32, 32, ATYPE_RO | ATYPE_RXPDO, acName7008, 0, &Obj.StepsPerMM3},
|
||||
{0x0, DTYPE_REAL32, 32, ATYPE_RO | ATYPE_RXPDO, acName7008, 0x42c80000, &Obj.StepsPerMM3},
|
||||
};
|
||||
const _objd SDO7009[] =
|
||||
{
|
||||
{0x0, DTYPE_INTEGER32, 32, ATYPE_RO | ATYPE_RXPDO, acName7009, 0, &Obj.StepsPerMM4},
|
||||
{0x0, DTYPE_REAL32, 32, ATYPE_RO | ATYPE_RXPDO, acName7009, 0x42c80000, &Obj.StepsPerMM4},
|
||||
};
|
||||
const _objd SDO700A[] =
|
||||
{
|
||||
{0x0, DTYPE_REAL32, 32, ATYPE_RO | ATYPE_RXPDO, acName700A, 0x461c4000, &Obj.MaxAcceleration1},
|
||||
};
|
||||
const _objd SDO700B[] =
|
||||
{
|
||||
{0x0, DTYPE_REAL32, 32, ATYPE_RO | ATYPE_RXPDO, acName700B, 0x461c4000, &Obj.MaxAcceleration2},
|
||||
};
|
||||
const _objd SDO700C[] =
|
||||
{
|
||||
{0x0, DTYPE_REAL32, 32, ATYPE_RO | ATYPE_RXPDO, acName700C, 0x461c4000, &Obj.MaxAcceleration3},
|
||||
};
|
||||
const _objd SDO700D[] =
|
||||
{
|
||||
{0x0, DTYPE_REAL32, 32, ATYPE_RO | ATYPE_RXPDO, acName700D, 0x461c4000, &Obj.MaxAcceleration4},
|
||||
};
|
||||
const _objd SDO700E[] =
|
||||
{
|
||||
{0x0, DTYPE_UNSIGNED8, 8, ATYPE_RO | ATYPE_RXPDO, acName700E, 0, &Obj.Enable1},
|
||||
};
|
||||
const _objd SDO700F[] =
|
||||
{
|
||||
{0x0, DTYPE_UNSIGNED8, 8, ATYPE_RO | ATYPE_RXPDO, acName700F, 0, &Obj.Enable2},
|
||||
};
|
||||
const _objd SDO7010[] =
|
||||
{
|
||||
{0x0, DTYPE_UNSIGNED8, 8, ATYPE_RO | ATYPE_RXPDO, acName7010, 0, &Obj.Enable3},
|
||||
};
|
||||
const _objd SDO7011[] =
|
||||
{
|
||||
{0x0, DTYPE_UNSIGNED8, 8, ATYPE_RO | ATYPE_RXPDO, acName7011, 0, &Obj.Enable4},
|
||||
};
|
||||
|
||||
const _objectlist SDOobjects[] =
|
||||
@@ -374,7 +453,7 @@ const _objectlist SDOobjects[] =
|
||||
{0x100A, OTYPE_VAR, 0, 0, acName100A, SDO100A},
|
||||
{0x1018, OTYPE_RECORD, 4, 0, acName1018, SDO1018},
|
||||
{0x1600, OTYPE_RECORD, 1, 0, acName1600, SDO1600},
|
||||
{0x1601, OTYPE_RECORD, 4, 0, acName1601, SDO1601},
|
||||
{0x1601, OTYPE_RECORD, 1, 0, acName1601, SDO1601},
|
||||
{0x1602, OTYPE_RECORD, 1, 0, acName1602, SDO1602},
|
||||
{0x1603, OTYPE_RECORD, 1, 0, acName1603, SDO1603},
|
||||
{0x1604, OTYPE_RECORD, 1, 0, acName1604, SDO1604},
|
||||
@@ -383,25 +462,34 @@ const _objectlist SDOobjects[] =
|
||||
{0x1607, OTYPE_RECORD, 1, 0, acName1607, SDO1607},
|
||||
{0x1608, OTYPE_RECORD, 1, 0, acName1608, SDO1608},
|
||||
{0x1609, OTYPE_RECORD, 1, 0, acName1609, SDO1609},
|
||||
{0x160A, OTYPE_RECORD, 1, 0, acName160A, SDO160A},
|
||||
{0x160B, OTYPE_RECORD, 1, 0, acName160B, SDO160B},
|
||||
{0x160C, OTYPE_RECORD, 1, 0, acName160C, SDO160C},
|
||||
{0x160D, OTYPE_RECORD, 1, 0, acName160D, SDO160D},
|
||||
{0x160E, OTYPE_RECORD, 1, 0, acName160E, SDO160E},
|
||||
{0x160F, OTYPE_RECORD, 1, 0, acName160F, SDO160F},
|
||||
{0x1610, OTYPE_RECORD, 1, 0, acName1610, SDO1610},
|
||||
{0x1611, OTYPE_RECORD, 1, 0, acName1611, SDO1611},
|
||||
{0x1A00, OTYPE_RECORD, 1, 0, acName1A00, SDO1A00},
|
||||
{0x1A01, OTYPE_RECORD, 8, 0, acName1A01, SDO1A01},
|
||||
{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, 10, 0, acName1C12, SDO1C12},
|
||||
{0x1C12, OTYPE_ARRAY, 18, 0, acName1C12, SDO1C12},
|
||||
{0x1C13, OTYPE_ARRAY, 7, 0, acName1C13, SDO1C13},
|
||||
{0x2000, OTYPE_VAR, 0, 0, acName2000, SDO2000},
|
||||
{0x6000, OTYPE_VAR, 0, 0, acName6000, SDO6000},
|
||||
{0x6001, OTYPE_ARRAY, 8, 0, acName6001, SDO6001},
|
||||
{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_VAR, 0, 0, acName6005, SDO6005},
|
||||
{0x6006, OTYPE_VAR, 0, 0, acName6006, SDO6006},
|
||||
{0x7000, OTYPE_VAR, 0, 0, acName7000, SDO7000},
|
||||
{0x7001, OTYPE_ARRAY, 4, 0, acName7001, SDO7001},
|
||||
{0x7001, OTYPE_VAR, 0, 0, acName7001, SDO7001},
|
||||
{0x7002, OTYPE_VAR, 0, 0, acName7002, SDO7002},
|
||||
{0x7003, OTYPE_VAR, 0, 0, acName7003, SDO7003},
|
||||
{0x7004, OTYPE_VAR, 0, 0, acName7004, SDO7004},
|
||||
@@ -410,5 +498,13 @@ const _objectlist SDOobjects[] =
|
||||
{0x7007, OTYPE_VAR, 0, 0, acName7007, SDO7007},
|
||||
{0x7008, OTYPE_VAR, 0, 0, acName7008, SDO7008},
|
||||
{0x7009, OTYPE_VAR, 0, 0, acName7009, SDO7009},
|
||||
{0x700A, OTYPE_VAR, 0, 0, acName700A, SDO700A},
|
||||
{0x700B, OTYPE_VAR, 0, 0, acName700B, SDO700B},
|
||||
{0x700C, OTYPE_VAR, 0, 0, acName700C, SDO700C},
|
||||
{0x700D, OTYPE_VAR, 0, 0, acName700D, SDO700D},
|
||||
{0x700E, OTYPE_VAR, 0, 0, acName700E, SDO700E},
|
||||
{0x700F, OTYPE_VAR, 0, 0, acName700F, SDO700F},
|
||||
{0x7010, OTYPE_VAR, 0, 0, acName7010, SDO7010},
|
||||
{0x7011, OTYPE_VAR, 0, 0, acName7011, SDO7011},
|
||||
{0xffff, 0xff, 0xff, 0xff, NULL, NULL}
|
||||
};
|
||||
|
||||
@@ -14,8 +14,8 @@ typedef struct
|
||||
/* Inputs */
|
||||
|
||||
float Velocity;
|
||||
uint8_t Inputs[8];
|
||||
float Frequency;
|
||||
uint8_t Input8;
|
||||
float ActualPosition1;
|
||||
float ActualPosition2;
|
||||
float ActualPosition3;
|
||||
@@ -24,16 +24,27 @@ typedef struct
|
||||
/* Outputs */
|
||||
|
||||
float Scale;
|
||||
uint8_t Outputs[4];
|
||||
uint8_t Output4;
|
||||
float CommandedPosition1;
|
||||
float CommandedPosition2;
|
||||
float CommandedPosition3;
|
||||
float CommandedPosition4;
|
||||
int32_t StepsPerMM1;
|
||||
int32_t StepsPerMM2;
|
||||
int32_t StepsPerMM3;
|
||||
int32_t StepsPerMM4;
|
||||
float StepsPerMM1;
|
||||
float StepsPerMM2;
|
||||
float StepsPerMM3;
|
||||
float StepsPerMM4;
|
||||
float MaxAcceleration1;
|
||||
float MaxAcceleration2;
|
||||
float MaxAcceleration3;
|
||||
float MaxAcceleration4;
|
||||
uint8_t Enable1;
|
||||
uint8_t Enable2;
|
||||
uint8_t Enable3;
|
||||
uint8_t Enable4;
|
||||
|
||||
/* Parameters */
|
||||
|
||||
uint32_t BasePeriod;
|
||||
} _Objects;
|
||||
|
||||
extern _Objects Obj;
|
||||
|
||||
@@ -1107,7 +1107,7 @@ StepGen3::StepGen3(void)
|
||||
dirPin[3] = PE4;
|
||||
|
||||
rtapi_app_main();
|
||||
stepgen_array[0].pos_scale = JOINT_1_SCALE;
|
||||
stepgen_array[0].pos_scale = JOINT_1_SCALE; // Can and should be overriden by PDO values
|
||||
stepgen_array[0].maxaccel = JOINT_1_STEPGEN_MAXACCEL;
|
||||
stepgen_array[1].pos_scale = JOINT_2_SCALE;
|
||||
stepgen_array[1].maxaccel = JOINT_2_STEPGEN_MAXACCEL;
|
||||
@@ -1116,17 +1116,27 @@ StepGen3::StepGen3(void)
|
||||
stepgen_array[3].pos_scale = JOINT_4_SCALE;
|
||||
stepgen_array[3].maxaccel = JOINT_4_STEPGEN_MAXACCEL;
|
||||
stepgen_array[0].enable = stepgen_array[1].enable =
|
||||
stepgen_array[2].enable = stepgen_array[3].enable = 1;
|
||||
stepgen_array[2].enable = stepgen_array[3].enable = 0; // Note that they are off by default
|
||||
}
|
||||
|
||||
void StepGen3::updateStepGen(double pos_cmd1, double pos_cmd2,
|
||||
double pos_cmd3, double pos_cmd4,
|
||||
void StepGen3::updateStepGen(double pos_cmd1, double pos_cmd2, double pos_cmd3, double pos_cmd4,
|
||||
float pos_scale1, float pos_scale2, float pos_scale3, float pos_scale4,
|
||||
float max_acc1, float max_acc2, float max_acc3, float max_acc4,
|
||||
uint8_t enable1, uint8_t enable2, uint8_t enable3, uint8_t enable4,
|
||||
uint32_t servoPeriod)
|
||||
{
|
||||
stepgen_array[0].pos_cmd = pos_cmd1;
|
||||
stepgen_array[1].pos_cmd = pos_cmd2;
|
||||
stepgen_array[2].pos_cmd = pos_cmd3;
|
||||
stepgen_array[3].pos_cmd = pos_cmd4;
|
||||
stepgen_array[0].pos_scale = pos_scale1;
|
||||
stepgen_array[1].pos_scale = pos_scale2;
|
||||
stepgen_array[2].pos_scale = pos_scale3;
|
||||
stepgen_array[3].pos_scale = pos_scale4;
|
||||
stepgen_array[0].maxaccel = max_acc1;
|
||||
stepgen_array[1].maxaccel = max_acc2;
|
||||
stepgen_array[2].maxaccel = max_acc3;
|
||||
stepgen_array[3].maxaccel = max_acc4;
|
||||
for (int i = 0; i < num_chan; i++)
|
||||
{
|
||||
stepgen_t *step;
|
||||
|
||||
@@ -17,7 +17,10 @@ HardwareSerial Serial1(PA10, PA9);
|
||||
const byte INPUTS[8] = {PE8, PE9, PE10, PE11, PE12, PE13, PE14, PE15};
|
||||
const byte OUTPUTS[4] = {PC5, PB0, PB1, PE7};
|
||||
const byte THCAD_PIN = PA2; // CAN BE PA0, should be PA0
|
||||
// PA2 is connected to Timer 2, a 32-bit timer
|
||||
#define bitset(byte, nbit) ((byte) |= (1 << (nbit)))
|
||||
#define bitclear(byte, nbit) ((byte) &= ~(1 << (nbit)))
|
||||
#define bitflip(byte, nbit) ((byte) ^= (1 << (nbit)))
|
||||
#define bitcheck(byte, nbit) ((byte) & (1 << (nbit)))
|
||||
|
||||
///// Analog out
|
||||
const byte DAC1_pin = PA4;
|
||||
@@ -28,6 +31,10 @@ StepGen3 *Step = 0;
|
||||
HardwareTimer *baseTimer; // The base period timer
|
||||
uint32_t sync0CycleTime; // nanosecs, often 1000000 ( 1 ms )
|
||||
volatile double posCmd1, posCmd2, posCmd3, posCmd4;
|
||||
volatile float posScale1, posScale2, posScale3, posScale4;
|
||||
volatile float maxAcc1, maxAcc2, maxAcc3, maxAcc4;
|
||||
volatile uint8_t enable1, enable2, enable3, enable4;
|
||||
volatile uint32_t basePeriod;
|
||||
volatile uint16_t basePeriodCnt;
|
||||
volatile uint16_t deltaMakePulsesCnt;
|
||||
volatile uint64_t makePulsesCnt = 0;
|
||||
@@ -73,20 +80,30 @@ void globalInt(void); // ISR for INT line
|
||||
////// EtherCAT routines called regularly, to read data, do stuff and write data
|
||||
void cb_set_outputs(void) // Get Master outputs, slave inputs, first operation
|
||||
{
|
||||
for (int i = 0; i < min(sizeof(Obj.Outputs), sizeof(OUTPUTS)); i++)
|
||||
digitalWrite(OUTPUTS[i], Obj.Outputs[i] == 1 ? HIGH : LOW);
|
||||
for (int i = 0; i < 4; i++)
|
||||
digitalWrite(OUTPUTS[i], bitcheck(Obj.Output4, i) ? HIGH : LOW);
|
||||
// analogWrite(DAC1_pin, Obj.Voltage);
|
||||
//Encoder1.setLatch(Obj.IndexLatchEnable);
|
||||
// Encoder1.setLatch(Obj.IndexLatchEnable);
|
||||
// Encoder1.setScale(2000);
|
||||
|
||||
Step->stepgen_array[0].pos_scale = -Obj.StepsPerMM1; // Scale perhaps changed
|
||||
Step->stepgen_array[1].pos_scale = -Obj.StepsPerMM2;
|
||||
Step->stepgen_array[2].pos_scale = -Obj.StepsPerMM3;
|
||||
Step->stepgen_array[3].pos_scale = -Obj.StepsPerMM4;
|
||||
posCmd1 = Obj.CommandedPosition1; // The position update
|
||||
posCmd2 = Obj.CommandedPosition2;
|
||||
posScale1 = Obj.StepsPerMM1; // Scale perhaps changed
|
||||
posScale2 = Obj.StepsPerMM2;
|
||||
posScale3 = Obj.StepsPerMM3;
|
||||
posScale4 = Obj.StepsPerMM4;
|
||||
posCmd1 = Obj.CommandedPosition1; // The position update, etc
|
||||
posCmd2 = Obj.CommandedPosition2; // Is recognised by the base Time loop
|
||||
posCmd3 = Obj.CommandedPosition3;
|
||||
posCmd4 = Obj.CommandedPosition4;
|
||||
maxAcc1 = Obj.MaxAcceleration1;
|
||||
maxAcc2 = Obj.MaxAcceleration2;
|
||||
maxAcc3 = Obj.MaxAcceleration3;
|
||||
maxAcc4 = Obj.MaxAcceleration4;
|
||||
enable1 = Obj.Enable1;
|
||||
enable2 = Obj.Enable2;
|
||||
enable3 = Obj.Enable3;
|
||||
enable4 = Obj.Enable4;
|
||||
if (Obj.BasePeriod != 0) // Use default value from setup() if not set by SDO.
|
||||
basePeriod = Obj.BasePeriod;
|
||||
}
|
||||
|
||||
void cb_get_inputs(void) // Set Master inputs, slave outputs, last operation
|
||||
@@ -97,8 +114,11 @@ void cb_get_inputs(void) // Set Master inputs, slave outputs, last operation
|
||||
scale = Obj.Scale;
|
||||
Obj.Velocity = scale * sin(ESCvar.Time * 1e-8 * 6.28); // Test
|
||||
|
||||
for (int i = 0; i < min(sizeof(Obj.Inputs), sizeof(INPUTS)); i++)
|
||||
Obj.Inputs[i] = digitalRead(INPUTS[i]) == HIGH ? 1 : 0;
|
||||
for (int i = 0; i < 8; i++)
|
||||
if (digitalRead(INPUTS[i]) == HIGH)
|
||||
bitSet(Obj.Input8, i);
|
||||
else
|
||||
bitClear(Obj.Input8, i);
|
||||
#if 0
|
||||
Obj.IndexStatus = Encoder1.indexHappened();
|
||||
Obj.EncPos = Encoder1.currentPos();
|
||||
@@ -157,12 +177,12 @@ void setup(void)
|
||||
Serial1.begin(115200);
|
||||
delay(1000); // To make terminal window ready
|
||||
|
||||
for (int i = 0; i < min(sizeof(Obj.Outputs), sizeof(OUTPUTS)); i++)
|
||||
for (int i = 0; i < 4; i++)
|
||||
{
|
||||
pinMode(OUTPUTS[i], OUTPUT);
|
||||
digitalWrite(OUTPUTS[i], LOW);
|
||||
}
|
||||
for (int i = 0; i < min(sizeof(Obj.Inputs), sizeof(INPUTS)); i++)
|
||||
for (int i = 0; i < 8; i++)
|
||||
pinMode(INPUTS[i], INPUT);
|
||||
pinMode(DAC1_pin, OUTPUT);
|
||||
analogWrite(DAC1_pin, 0);
|
||||
@@ -177,6 +197,8 @@ void setup(void)
|
||||
pinMode(PE5, OUTPUT); // Step 4
|
||||
pinMode(PE4, OUTPUT); // Dir 4
|
||||
|
||||
basePeriod = BASE_PERIOD; // Random-ish number, but it should work
|
||||
|
||||
baseTimer = new HardwareTimer(TIM11); // The base period timer
|
||||
baseTimer->setOverflow(BASE_PERIOD / 1000, MICROSEC_FORMAT); // Or the line above, This one is uncalibrated
|
||||
baseTimer->attachInterrupt(basePeriodCB);
|
||||
@@ -319,10 +341,14 @@ void Rollover_IT_callback(void)
|
||||
void updateStepperGenerators(void)
|
||||
{
|
||||
baseTimer->pause();
|
||||
Step->updateStepGen(posCmd1, posCmd2, posCmd3, posCmd4, sync0CycleTime); // Update positions
|
||||
Step->makeAllPulses(); // Make first step right here
|
||||
basePeriodCnt = sync0CycleTime / BASE_PERIOD; //
|
||||
baseTimer->refresh(); //
|
||||
Step->updateStepGen(posCmd1, posCmd2, posCmd3, posCmd4,
|
||||
posScale1, posScale2, posScale3, posScale4,
|
||||
maxAcc1, maxAcc2, maxAcc3, maxAcc4,
|
||||
enable1, enable2, enable3, enable4,
|
||||
sync0CycleTime); // Update positions
|
||||
Step->makeAllPulses(); // Make first step right here
|
||||
basePeriodCnt = sync0CycleTime / basePeriod; //
|
||||
baseTimer->refresh(); //
|
||||
baseTimer->resume();
|
||||
// Make the other steps in baseTimer's ISR
|
||||
}
|
||||
|
||||
Reference in New Issue
Block a user