diff --git a/Firmware/lib/soes/MetalMusings_EaserCAT_2000.xml b/Firmware/lib/soes/MetalMusings_EaserCAT_2000.xml index 6e61434..f3e06b9 100755 --- a/Firmware/lib/soes/MetalMusings_EaserCAT_2000.xml +++ b/Firmware/lib/soes/MetalMusings_EaserCAT_2000.xml @@ -125,7 +125,7 @@ DT1602 - 80 + 144 0 Max SubIndex @@ -146,6 +146,16 @@ ro + + 2 + CommandedVelocity + ULINT + 64 + 80 + + ro + + DT1A00 @@ -414,7 +424,7 @@ DT7002 - 80 + 144 0 Max SubIndex @@ -436,6 +446,17 @@ R + + 2 + CommandedVelocity + LREAL + 64 + 80 + + ro + R + + ULINT @@ -612,12 +633,12 @@ #x1602 StepGenIn1 DT1602 - 80 + 144 Max SubIndex - 1 + 2 @@ -626,6 +647,12 @@ #x70020140 + + CommandedVelocity + + #x70020240 + + ro @@ -1016,12 +1043,12 @@ #x7002 StepGenIn1 DT7002 - 80 + 144 Max SubIndex - 1 + 2 @@ -1030,6 +1057,12 @@ 0 + + CommandedVelocity + + 0 + + ro @@ -1077,6 +1110,13 @@ CommandedPosition LREAL + + #x7002 + #x2 + 64 + CommandedVelocity + LREAL + #x1A00 diff --git a/Firmware/lib/soes/ecat_options.h b/Firmware/lib/soes/ecat_options.h index 20a7dba..29f42a8 100755 --- a/Firmware/lib/soes/ecat_options.h +++ b/Firmware/lib/soes/ecat_options.h @@ -33,7 +33,7 @@ #define SM3_smc 0x20 #define SM3_act 1 -#define MAX_MAPPINGS_SM2 3 +#define MAX_MAPPINGS_SM2 4 #define MAX_MAPPINGS_SM3 6 #define MAX_RXPDO_SIZE 512 diff --git a/Firmware/lib/soes/esi.json b/Firmware/lib/soes/esi.json index d84c06b..1bb3c75 100755 --- a/Firmware/lib/soes/esi.json +++ b/Firmware/lib/soes/esi.json @@ -163,6 +163,13 @@ "data": "&Obj.StepGenIn1.CommandedPosition", "value": "0", "access": "RO" + }, + { + "name": "CommandedVelocity", + "dtype": "REAL64", + "value": "0", + "access": "RO", + "data": "&Obj.StepGenIn1.CommandedVelocity" } ], "pdo_mappings": [ diff --git a/Firmware/lib/soes/objectlist.c b/Firmware/lib/soes/objectlist.c index 88b4215..d3e0869 100755 --- a/Firmware/lib/soes/objectlist.c +++ b/Firmware/lib/soes/objectlist.c @@ -22,6 +22,7 @@ static const char acName1601_01[] = "IndexLatchEnable"; static const char acName1602[] = "StepGenIn1"; static const char acName1602_00[] = "Max SubIndex"; static const char acName1602_01[] = "CommandedPosition"; +static const char acName1602_02[] = "CommandedVelocity"; static const char acName1A00[] = "EncPos"; static const char acName1A00_00[] = "Max SubIndex"; static const char acName1A00_01[] = "EncPos"; @@ -72,6 +73,7 @@ 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[] = "CommandedVelocity"; const _objd SDO1000[] = { @@ -109,8 +111,9 @@ const _objd SDO1601[] = }; const _objd SDO1602[] = { - {0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1602_00, 1, NULL}, + {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, 0x70020240, NULL}, }; const _objd SDO1A00[] = { @@ -202,8 +205,9 @@ const _objd SDO7001[] = }; const _objd SDO7002[] = { - {0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName7002_00, 1, NULL}, + {0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName7002_00, 2, NULL}, {0x01, DTYPE_REAL64, 64, ATYPE_RO, acName7002_01, 0, &Obj.StepGenIn1.CommandedPosition}, + {0x02, DTYPE_REAL64, 64, ATYPE_RO, acName7002_02, 0, &Obj.StepGenIn1.CommandedVelocity}, }; const _objectlist SDOobjects[] = @@ -215,7 +219,7 @@ const _objectlist SDOobjects[] = {0x1018, OTYPE_RECORD, 4, 0, acName1018, SDO1018}, {0x1600, OTYPE_RECORD, 1, 0, acName1600, SDO1600}, {0x1601, OTYPE_RECORD, 1, 0, acName1601, SDO1601}, - {0x1602, OTYPE_RECORD, 1, 0, acName1602, SDO1602}, + {0x1602, OTYPE_RECORD, 2, 0, acName1602, SDO1602}, {0x1A00, OTYPE_RECORD, 1, 0, acName1A00, SDO1A00}, {0x1A01, OTYPE_RECORD, 1, 0, acName1A01, SDO1A01}, {0x1A02, OTYPE_RECORD, 1, 0, acName1A02, SDO1A02}, @@ -233,6 +237,6 @@ const _objectlist SDOobjects[] = {0x6005, OTYPE_RECORD, 1, 0, acName6005, SDO6005}, {0x7000, OTYPE_VAR, 0, 0, acName7000, SDO7000}, {0x7001, OTYPE_VAR, 0, 0, acName7001, SDO7001}, - {0x7002, OTYPE_RECORD, 1, 0, acName7002, SDO7002}, + {0x7002, OTYPE_RECORD, 2, 0, acName7002, SDO7002}, {0xffff, 0xff, 0xff, 0xff, NULL, NULL} }; diff --git a/Firmware/lib/soes/utypes.h b/Firmware/lib/soes/utypes.h index 971c1e8..09b8193 100755 --- a/Firmware/lib/soes/utypes.h +++ b/Firmware/lib/soes/utypes.h @@ -30,6 +30,7 @@ typedef struct struct { double CommandedPosition; + double CommandedVelocity; } StepGenIn1; } _Objects; diff --git a/Firmware/src/main.cpp b/Firmware/src/main.cpp index 2f3846d..e2edede 100755 --- a/Firmware/src/main.cpp +++ b/Firmware/src/main.cpp @@ -35,7 +35,7 @@ volatile uint8_t pleaseZeroTheCounter = 0; HardwareTimer *MyTim; volatile uint32_t stepCount = 0, stepPulses = 0; volatile double_t actualPosition = 0; -volatile double_t requestedPosition; +volatile double_t requestedPosition, requestedVelocity; uint32_t sync0CycleTime = 0; @@ -56,6 +56,7 @@ void cb_set_outputs(void) // Master outputs gets here, slave inputs, first opera PosScaleRes = 1.0 / double(CurPosScale); } requestedPosition = Obj.StepGenIn1.CommandedPosition; + requestedVelocity = Obj.StepGenIn1.CommandedVelocity; } void cb_get_inputs(void) // Set Master inputs, slave outputs, last operation @@ -211,7 +212,7 @@ void sync0Handler(void) void handleStepper(void) { byte forwardDirection = 0; // 1 if going forward - int32_t pulsesToGo = 1000 * (requestedPosition - actualPosition); + int32_t pulsesToGo = 100 * (requestedPosition - actualPosition); if (pulsesToGo != 0) makePulses(900, pulsesToGo); // Make the pulses using hardware timer