10 Commits

Author SHA1 Message Date
sandst_a db80d255de Add PLC desc 2024-10-02 11:11:09 +02:00
sandst_a 2c12d995df Update readme 2024-09-26 16:30:37 +02:00
sandst_a 4a65e3b753 Update readme 2024-09-26 16:29:35 +02:00
sandst_a 1c7e7793eb Update readme 2024-09-26 16:28:43 +02:00
sandst_a fd0f594c08 Add startup file to Makefile 2024-09-26 16:09:01 +02:00
sandst_a 1ccabdf578 Remove version in examples 2024-09-26 16:05:06 +02:00
sandst_a c485498cb7 Update macros to sm 2024-09-26 16:00:27 +02:00
sandst_a 184f01302d use common cfgs for slit example 2024-09-26 15:21:57 +02:00
sandst_a d4bd266180 split examples 2024-09-26 14:44:46 +02:00
sandst_a 96b924debf Add generic scripts for 2..6DoF 2024-09-26 14:37:28 +02:00
24 changed files with 314 additions and 71 deletions
+6
View File
@@ -6,6 +6,12 @@ BUILDCLASSES = Linux
ARCH_FILTER = deb10% ARCH_FILTER = deb10%
EXCLUDE_VERSIONS+=3 7.0.5 7.0.6 EXCLUDE_VERSIONS+=3 7.0.5 7.0.6
SCRIPTS += startup.cmd
SCRIPTS += axis_sm.plc_inc SCRIPTS += axis_sm.plc_inc
SCRIPTS += axis_kin_slit.plc_inc SCRIPTS += axis_kin_slit.plc_inc
SCRIPTS += axis_kin_mirror.plc_inc SCRIPTS += axis_kin_mirror.plc_inc
SCRIPTS += axis_kin_2DoF.plc_inc
SCRIPTS += axis_kin_3DoF.plc_inc
SCRIPTS += axis_kin_4DoF.plc_inc
SCRIPTS += axis_kin_5DoF.plc_inc
SCRIPTS += axis_kin_6DoF.plc_inc
+87 -3
View File
@@ -1,5 +1,89 @@
# ecmc_master_slave # ecmc_master_slave
Standard syncronization scripts for ecmc Standard syncronization scripts for ecmc. The module provides:
* Syncronization scripts
* Generic state machine
## Syncronization scripts
Syncronazation can be done both by defining the forward adn inverse kinematcis as equations or by matrices.
The module implement 5 generic syncronazation scripts based on the matrix approach:
* axis_kin_2DoF.plc_inc : Kinematics for a 2 Dof system (slits)
* axis_kin_3DoF.plc_inc : Kinematics for a 3 Dof system
* axis_kin_4DoF.plc_inc : Kinematics for a 4 Dof system
* axis_kin_5DoF.plc_inc : Kinematics for a 5 Dof system
* axis_kin_6DoF.plc_inc : Kinematics for a 6 Dof system
and 2 dedicated:
* axis_kin_slit.plc_inc : Dedicated script for a slit system based on equations (including interlocks and softlimits)
* axis_kin_mirror.plc_inc : Dedicated script for a 5 DoF mirror system based on matrices
### Generic scripts (axis_kin_\<index\>DoF.plc_inc)
The generic scripts needs a few macros:
* AX_S\<index\> : Axis index for slave axes, index = 1..DoF
* AX_M\<index\> : Axis index for master axes, index = 1..DoF
* FWD\<index\> : Forward kinematics array, index = 1..DoF
* INV\<index\> : Inverse kinematics array, index = 1..DoF
## State machine
The state machine makes sure that master and slaved axes cannot run simultaneous. However, several master axes or several slave axes can run at the same time.
The state machine is implemented in the file axis_sm.plc.inc in this module.
The state machine needs two macros:
* GRP_ID_MA : Group id for master axes (most often virtual axes)
* GRP_ID_SA : Group id for slave axes (most often real axes)
The easiest way to create a group is to just add it in the axis yaml configuration:
```
axis:
id: 5
group: realAxes
```
If the group does not exist, it will be created. The id of the group will be accessible through the environment variable "GRP_\<group_name\>_ID", in this case "GRP_realAxes_ID".
This macro can the be used when loading the PLC-code.
## Using the scripts
The easiest way is to generate a main plc file and then use include to access the kinematic and state machine scripts.
Example for a slit system:
```
/* Forward kinematics to calculate virtual axes from real axes
| CEN | = FWD * | S1_LO |
| GAP | | S2_HI |
Equations:
ax{AX_CEN}.enc.actpos:=(ax{AX_LO}.enc.actpos+ax{AX_HI}.enc.actpos)/2;
ax{AX_GAP}.enc.actpos:=ax{AX_HI}.enc.actpos-ax{AX_LO}.enc.actpos;
*/
var FWD1[2] := {0.5, 0.5};
var FWD2[2] := { -1, 1 };
/* Inverse kinematics to calculate real axes from virtal axes
| S1_LO | = INV * | CEN |
| S2_HI | | GAP |
Equations:
ax{AX_LO}.traj.extsetpos:=ax{AX_CEN}.traj.setpos-ax{AX_GAP}.traj.setpos/2;
ax{AX_HI}.traj.extsetpos:=ax{AX_CEN}.traj.setpos+ax{AX_GAP}.traj.setpos/2;
*/
var INV1[2] := { 1, -0.5};
var INV2[2] := { 1, 0.5};
# Kinematics for slit system.
include "axis_kin_2DoF.plc_inc"
# State machine
include "axis_sm.plc_inc"
```
The main plc file can then be loaded into ecmc with appropriate macros (also not the INC):
```
${SCRIPTEXEC} ${ecmccfg_DIR}loadPLCFile.cmd, "FILE=./cfg/axis_main.plc, PLC_ID=1, INC=.:${ecmc_master_slave_DIR}, PLC_MACROS='PLC_ID=1, AX_M1=12, AX_M2=13, AX_S1=5, AX_S2=6, GRP_ID_SA=${GRP_realAxes_ID}, GRP_ID_MA=${GRP_virtualAxes_ID}'"
```
NOTE: Macros cannot not be used in the include statement. The path to this module needs to set in the INC parameter to loadPLCFile.cmd
## Examples
See examples dir for usage: See examples dir for usage:
* slits * slits (equations, 2DoFs matrix)
* mirror * mirror (matrix)
+13
View File
@@ -0,0 +1,13 @@
#- Slave axes (normally physical/real axes): AX_S1, AX_S2
var SLAVE_AXES[2] := {ax${AX_S1}.enc.actpos, ax${AX_S2}.enc.actpos};
#- Master axes (normally virtual axes): AX_M1, AX_M2
var MASTER_AXES[2] := {ax${AX_M1}.traj.setpos, ax${AX_M2}.traj.setpos};
#- forward kinematics
ax${AX_M1}.enc.actpos := dot(FWD1, SLAVE_AXES);
ax${AX_M2}.enc.actpos := dot(FWD2, SLAVE_AXES);
#- inverse kinematics
ax${AX_S1}.traj.extsetpos := dot(INV1, MASTER_AXES);
ax${AX_S2}.traj.extsetpos := dot(INV2, MASTER_AXES);
+16
View File
@@ -0,0 +1,16 @@
#- Slave axes (normally physical/real axes): AX_S1, AX_S2, AX_S3
var SLAVE_AXES[3] := {ax${AX_S1}.enc.actpos, ax${AX_S2}.enc.actpos, ax${AX_S3}.enc.actpos};
#- Master axes (normally virtual axes): AX_M1, AX_M2, AX_M3
var MASTER_AXES[3] := {ax${AX_M1}.traj.setpos, ax${AX_M2}.traj.setpos, ax${AX_M3}.traj.setpos};
#- forward kinematics
ax${AX_M1}.enc.actpos := dot(FWD1, SLAVE_AXES);
ax${AX_M2}.enc.actpos := dot(FWD2, SLAVE_AXES);
ax${AX_M3}.enc.actpos := dot(FWD3, SLAVE_AXES);
#- inverse kinematics
ax${AX_S1}.traj.extsetpos := dot(INV1, MASTER_AXES);
ax${AX_S2}.traj.extsetpos := dot(INV2, MASTER_AXES);
ax${AX_S3}.traj.extsetpos := dot(INV3, MASTER_AXES);
+18
View File
@@ -0,0 +1,18 @@
#- Slave axes (normally physical/real axes): AX_S1, AX_S2, AX_S3, AX_S4
var SLAVE_AXES[4] := {ax${AX_S1}.enc.actpos, ax${AX_S2}.enc.actpos, ax${AX_S3}.enc.actpos, ax${AX_S4}.enc.actpos};
#- Master axes (normally virtual axes): AX_M1, AX_M2, AX_M3, AX_M4
var MASTER_AXES[4] := {ax${AX_M1}.traj.setpos, ax${AX_M2}.traj.setpos, ax${AX_M3}.traj.setpos, ax${AX_M4}.traj.setpos};
#- forward kinematics
ax${AX_M1}.enc.actpos := dot(FWD1, SLAVE_AXES);
ax${AX_M2}.enc.actpos := dot(FWD2, SLAVE_AXES);
ax${AX_M3}.enc.actpos := dot(FWD3, SLAVE_AXES);
ax${AX_M4}.enc.actpos := dot(FWD4, SLAVE_AXES);
#- inverse kinematics
ax${AX_S1}.traj.extsetpos := dot(INV1, MASTER_AXES);
ax${AX_S2}.traj.extsetpos := dot(INV2, MASTER_AXES);
ax${AX_S3}.traj.extsetpos := dot(INV3, MASTER_AXES);
ax${AX_S4}.traj.extsetpos := dot(INV4, MASTER_AXES);
+20
View File
@@ -0,0 +1,20 @@
#- Slave axes (normally physical/real axes): AX_S1, AX_S2, AX_S3, AX_S4, AX_S5
var SLAVE_AXES[5] := {ax${AX_S1}.enc.actpos, ax${AX_S2}.enc.actpos, ax${AX_S3}.enc.actpos, ax${AX_S4}.enc.actpos, ax${AX_S5}.enc.actpos};
#- Master axes (normally virtual axes): AX_M1, AX_M2, AX_M3, AX_M4, AX_M5
var MASTER_AXES[5] := {ax${AX_M1}.traj.setpos, ax${AX_M2}.traj.setpos, ax${AX_M3}.traj.setpos, ax${AX_M4}.traj.setpos, ax${AX_M5}.traj.setpos};
#- forward kinematics
ax${AX_M1}.enc.actpos := dot(FWD1, SLAVE_AXES);
ax${AX_M2}.enc.actpos := dot(FWD2, SLAVE_AXES);
ax${AX_M3}.enc.actpos := dot(FWD3, SLAVE_AXES);
ax${AX_M4}.enc.actpos := dot(FWD4, SLAVE_AXES);
ax${AX_M5}.enc.actpos := dot(FWD5, SLAVE_AXES);
#- inverse kinematics
ax${AX_S1}.traj.extsetpos := dot(INV1, MASTER_AXES);
ax${AX_S2}.traj.extsetpos := dot(INV2, MASTER_AXES);
ax${AX_S3}.traj.extsetpos := dot(INV3, MASTER_AXES);
ax${AX_S4}.traj.extsetpos := dot(INV4, MASTER_AXES);
ax${AX_S5}.traj.extsetpos := dot(INV5, MASTER_AXES);
+22
View File
@@ -0,0 +1,22 @@
#- Slave axes (normally physical/real axes): AX_S1, AX_S2, AX_S3, AX_S4, AX_S5, AX_S6
var SLAVE_AXES[6] := {ax${AX_S1}.enc.actpos, ax${AX_S2}.enc.actpos, ax${AX_S3}.enc.actpos, ax${AX_S4}.enc.actpos, ax${AX_S5}.enc.actpos, ax${AX_S6}.enc.actpos};
#- Master axes (normally virtual axes): AX_M1, AX_M2, AX_M3, AX_M4, AX_M5, AX_M6
var MASTER_AXES[6] := {ax${AX_M1}.traj.setpos, ax${AX_M2}.traj.setpos, ax${AX_M3}.traj.setpos, ax${AX_M4}.traj.setpos, ax${AX_M5}.traj.setpos, ax${AX_M6}.traj.setpos};
#- forward kinematics
ax${AX_M1}.enc.actpos := dot(FWD1, SLAVE_AXES);
ax${AX_M2}.enc.actpos := dot(FWD2, SLAVE_AXES);
ax${AX_M3}.enc.actpos := dot(FWD3, SLAVE_AXES);
ax${AX_M4}.enc.actpos := dot(FWD4, SLAVE_AXES);
ax${AX_M5}.enc.actpos := dot(FWD5, SLAVE_AXES);
ax${AX_M6}.enc.actpos := dot(FWD6, SLAVE_AXES);
#- inverse kinematics
ax${AX_S1}.traj.extsetpos := dot(INV1, MASTER_AXES);
ax${AX_S2}.traj.extsetpos := dot(INV2, MASTER_AXES);
ax${AX_S3}.traj.extsetpos := dot(INV3, MASTER_AXES);
ax${AX_S4}.traj.extsetpos := dot(INV4, MASTER_AXES);
ax${AX_S5}.traj.extsetpos := dot(INV5, MASTER_AXES);
ax${AX_S6}.traj.extsetpos := dot(INV6, MASTER_AXES);
+1 -1
View File
@@ -16,4 +16,4 @@ ax${AX_Y1}.traj.extsetpos := dot(INV1, VIRT_AXES);
ax${AX_Y2}.traj.extsetpos := dot(INV2, VIRT_AXES); ax${AX_Y2}.traj.extsetpos := dot(INV2, VIRT_AXES);
ax${AX_Y3}.traj.extsetpos := dot(INV3, VIRT_AXES); ax${AX_Y3}.traj.extsetpos := dot(INV3, VIRT_AXES);
ax${AX_X1}.traj.extsetpos := dot(INV4, VIRT_AXES); ax${AX_X1}.traj.extsetpos := dot(INV4, VIRT_AXES);
ax${AX_X2}.traj.extsetpos := dot(INV5, VIRT_AXES); ax${AX_X2}.traj.extsetpos := dot(INV5, VIRT_AXES);
+24 -24
View File
@@ -12,7 +12,7 @@ if ( static.counter<0.105 ) {
if ( static.counter>=0.105) { static.VMState:=0 }; if ( static.counter>=0.105) { static.VMState:=0 };
#- VMs in Internal mode, ready to listen #- VMs in Internal mode, ready to listen
mc_grp_set_traj_src(${GRP_ID_VA},0); mc_grp_set_traj_src(${GRP_ID_MA},0);
}; };
@@ -26,19 +26,19 @@ if ( static.counter<0.105 ) {
if(static.VMState==-1) { if(static.VMState==-1) {
#- Trigg MR sync for all virt axes #- Trigg MR sync for all virt axes
mc_grp_sync_act_set(${GRP_ID_VA},1); mc_grp_sync_act_set(${GRP_ID_MA},1);
#- RM are no longer in motion #- RM are no longer in motion
#- -1 -> 0 #- -1 -> 0
#- Trigger Condition: #- Trigger Condition:
#- - all RM are not busy #- - all RM are not busy
if( mc_grp_get_any_busy(${GRP_ID_RA})==0 ) { if( mc_grp_get_any_busy(${GRP_ID_SA})==0 ) {
#- disable real motors #- disable real motors
mc_grp_set_enable(${GRP_ID_RA},0); mc_grp_set_enable(${GRP_ID_SA},0);
#- VMs in Internal mode, back to ground state #- VMs in Internal mode, back to ground state
mc_grp_set_traj_src(${GRP_ID_VA},0); mc_grp_set_traj_src(${GRP_ID_MA},0);
#- state change #- state change
println('-1 -> 0'); println('-1 -> 0');
@@ -46,8 +46,8 @@ if(static.VMState==-1) {
}; };
#- If RM Motion is occuring, and user commands VM motion: simply disable the VMs to void the command. #- If RM Motion is occuring, and user commands VM motion: simply disable the VMs to void the command.
if( mc_grp_get_any_enabled(${GRP_ID_VA})==1 and mc_grp_get_any_enable(${GRP_ID_VA})==1 ) { if( mc_grp_get_any_enabled(${GRP_ID_MA})==1 and mc_grp_get_any_enable(${GRP_ID_MA})==1 ) {
mc_grp_set_enable(${GRP_ID_VA},0); mc_grp_set_enable(${GRP_ID_MA},0);
}; };
} }
@@ -60,10 +60,10 @@ else if(static.VMState==0) {
#- - all RM are in internal mode #- - all RM are in internal mode
#- - all VM are disabled #- - all VM are disabled
mc_grp_get_any_traj_src_ext(${GRP_ID_RA})==0 mc_grp_get_any_traj_src_ext(${GRP_ID_SA})==0
if( mc_grp_get_any_busy(${GRP_ID_RA})==1 and mc_grp_get_any_traj_src_ext(${GRP_ID_RA})==0 and mc_grp_get_any_enabled(${GRP_ID_VA})==0 ) { if( mc_grp_get_any_busy(${GRP_ID_SA})==1 and mc_grp_get_any_traj_src_ext(${GRP_ID_SA})==0 and mc_grp_get_any_enabled(${GRP_ID_MA})==0 ) {
#- VMs in PLC mode, so no following errors occur #- VMs in PLC mode, so no following errors occur
mc_grp_set_traj_src(${GRP_ID_VA},0); mc_grp_set_traj_src(${GRP_ID_MA},0);
#- state change #- state change
println('0 -> -1'); println('0 -> -1');
@@ -73,29 +73,29 @@ else if(static.VMState==0) {
#- 0 -> 1 #- 0 -> 1
#- Trigger Condition: #- Trigger Condition:
#- - at least 1 VM is enabled #- - at least 1 VM is enabled
else if( mc_grp_get_any_enabled(${GRP_ID_VA})==1 ) { else if( mc_grp_get_any_enabled(${GRP_ID_MA})==1 ) {
#- Exit Condition: all axes are on #- Exit Condition: all axes are on
if( mc_grp_get_enabled(${GRP_ID_RA})==1 and mc_grp_get_enabled(${GRP_ID_VA})==1 and mc_grp_get_any_busy(${GRP_ID_RA})==0 ) { if( mc_grp_get_enabled(${GRP_ID_SA})==1 and mc_grp_get_enabled(${GRP_ID_MA})==1 and mc_grp_get_any_busy(${GRP_ID_SA})==0 ) {
if( mc_grp_get_any_busy(${GRP_ID_VA})==1 ) { if( mc_grp_get_any_busy(${GRP_ID_MA})==1 ) {
mc_grp_set_traj_src(${GRP_ID_RA},1); mc_grp_set_traj_src(${GRP_ID_SA},1);
#- state change #- state change
println('0 -> 1'); println('0 -> 1');
static.VMState:=1; static.VMState:=1;
#- Disable MR sync for all virt axes #- Disable MR sync for all virt axes
mc_grp_sync_act_set(${GRP_ID_VA},0); mc_grp_sync_act_set(${GRP_ID_MA},0);
}; };
} }
#- Actions: If Exit Conditions not met #- Actions: If Exit Conditions not met
else { else {
#- enable motors #- enable motors
mc_grp_set_enable(${GRP_ID_VA},1); mc_grp_set_enable(${GRP_ID_MA},1);
mc_grp_set_enable(${GRP_ID_RA},1); mc_grp_set_enable(${GRP_ID_SA},1);
#- halt real motors #- halt real motors
mc_grp_halt(${GRP_ID_RA}); mc_grp_halt(${GRP_ID_SA});
}; };
}; };
} }
@@ -105,18 +105,18 @@ else if(static.VMState==1) {
#- basically a done test #- basically a done test
#- 1 -> 0 #- 1 -> 0
if( mc_grp_get_any_busy(${GRP_ID_VA})==0 ) { if( mc_grp_get_any_busy(${GRP_ID_MA})==0 ) {
#- disable motors and set source #- disable motors and set source
mc_grp_set_enable(${GRP_ID_VA},0); mc_grp_set_enable(${GRP_ID_MA},0);
mc_grp_set_enable(${GRP_ID_RA},0); mc_grp_set_enable(${GRP_ID_SA},0);
mc_grp_set_traj_src(${GRP_ID_RA},0); mc_grp_set_traj_src(${GRP_ID_SA},0);
#- once VMs are done, RMs need a bit longer to disable #- once VMs are done, RMs need a bit longer to disable
if( mc_grp_get_any_busy(${GRP_ID_RA})==0 ) { if( mc_grp_get_any_busy(${GRP_ID_SA})==0 ) {
#- For some reason, an interlock is raised, but not sure why or what the implications are. It can be cleared this way. #- For some reason, an interlock is raised, but not sure why or what the implications are. It can be cleared this way.
mc_grp_reset_error(${GRP_ID_RA}); mc_grp_reset_error(${GRP_ID_SA});
#- state change #- state change
println('1 -> 0'); println('1 -> 0');
+1 -1
View File
@@ -63,7 +63,7 @@ ${SCRIPTEXEC} ${ECMC_CONFIG_ROOT}loadYamlAxis.cmd, "FILE=cfg/ax10_ROLL.yaml"
${SCRIPTEXEC} ${ECMC_CONFIG_ROOT}loadYamlAxis.cmd, "FILE=cfg/ax11_YAW.yaml" ${SCRIPTEXEC} ${ECMC_CONFIG_ROOT}loadYamlAxis.cmd, "FILE=cfg/ax11_YAW.yaml"
# load the VFM virtual axes PLC # load the VFM virtual axes PLC
${SCRIPTEXEC} ${ECMC_CONFIG_ROOT}loadPLCFile.cmd, "FILE=cfg/VFM.plc,PLC_ID=1,INC=.:${ecmc_master_slave_DIR},PLC_MACROS='PLC_ID=1,AX_Y1=1,AX_Y2=2,AX_Y3=3,AX_X1=4,AX_X2=5,AX_TRX=7,AX_TRY=8,AX_PITCH=9,AX_ROLL=10,AX_YAW=11,GRP_ID_RA=${GRP_VFM_REAL_ID=0},GRP_ID_VA=${GRP_VFM_VIRT_ID=0}'" ${SCRIPTEXEC} ${ECMC_CONFIG_ROOT}loadPLCFile.cmd, "FILE=cfg/VFM.plc,PLC_ID=1,INC=.:${ecmc_master_slave_DIR},PLC_MACROS='PLC_ID=1,AX_Y1=1,AX_Y2=2,AX_Y3=3,AX_X1=4,AX_X2=5,AX_TRX=7,AX_TRY=8,AX_PITCH=9,AX_ROLL=10,AX_YAW=11,GRP_ID_SA=${GRP_VFM_REAL_ID=0},GRP_ID_MA=${GRP_VFM_VIRT_ID=0}'"
#- ############################################################################# #- #############################################################################
#- Temporary test #- Temporary test
@@ -1,16 +1,4 @@
#- Configuration scripts #- Configuration scripts
require ecmccfg,"ENG_MODE=1,EC_RATE=100"
#- Components lib
require ecmccomp
#- Syncronization configs
require ecmc_master_slave
#- Only output errors
asynSetTraceMask(${ECMC_ASYN_PORT}, -1, 0x01)
#- ############################################################################ #- ############################################################################
#- add slaves #- add slaves
#- list of slaves (4 axis test motion box) #- list of slaves (4 axis test motion box)
@@ -52,12 +40,12 @@ ${SCRIPTEXEC} ${ecmccfg_DIR}addSlave.cmd, "HW_DESC=EL1008"
# 0:7 - EL7041 1Ch Stepper # 0:7 - EL7041 1Ch Stepper
${SCRIPTEXEC} ${ecmccfg_DIR}addSlave.cmd, "HW_DESC=EL7041-0052" ${SCRIPTEXEC} ${ecmccfg_DIR}addSlave.cmd, "HW_DESC=EL7041-0052"
${SCRIPTEXEC} ${ecmccomp_DIR}applyComponent.cmd "COMP=Motor-Generic-2Phase-Stepper,MACROS='I_MAX_MA=1000,I_STDBY_MA=500,U_NOM_MV=48000,R_COIL_MOHM=1230'" ${SCRIPTEXEC} ${ecmccomp_DIR}applyComponent.cmd "COMP=Motor-Generic-2Phase-Stepper,MACROS='I_MAX_MA=1000,I_STDBY_MA=500,U_NOM_MV=48000,R_COIL_MOHM=1230'"
${SCRIPTEXEC} ${ecmccfg_DIR}loadYamlAxis.cmd, "FILE=cfg/axis_ax5_LO.yaml, DRV_SLAVE=${ECMC_EC_SLAVE_NUM}, ENC_SLAVE=${ECMC_EC_SLAVE_NUM}, ENC_CHANNEL=01" ${SCRIPTEXEC} ${ecmccfg_DIR}loadYamlAxis.cmd, "FILE=../common/axis_ax5_LO.yaml, DRV_SLAVE=${ECMC_EC_SLAVE_NUM}, ENC_SLAVE=${ECMC_EC_SLAVE_NUM}, ENC_CHANNEL=01"
# 0:8 - EL7041 1Ch Stepper # 0:8 - EL7041 1Ch Stepper
${SCRIPTEXEC} ${ecmccfg_DIR}addSlave.cmd, "HW_DESC=EL7041-0052" ${SCRIPTEXEC} ${ecmccfg_DIR}addSlave.cmd, "HW_DESC=EL7041-0052"
${SCRIPTEXEC} ${ecmccomp_DIR}applyComponent.cmd "COMP=Motor-Generic-2Phase-Stepper,MACROS='I_MAX_MA=1000,I_STDBY_MA=500,U_NOM_MV=48000,R_COIL_MOHM=1230'" ${SCRIPTEXEC} ${ecmccomp_DIR}applyComponent.cmd "COMP=Motor-Generic-2Phase-Stepper,MACROS='I_MAX_MA=1000,I_STDBY_MA=500,U_NOM_MV=48000,R_COIL_MOHM=1230'"
${SCRIPTEXEC} ${ecmccfg_DIR}loadYamlAxis.cmd, "FILE=cfg/axis_ax6_HI.yaml, DRV_SLAVE=${ECMC_EC_SLAVE_NUM}, ENC_SLAVE=${ECMC_EC_SLAVE_NUM}, ENC_CHANNEL=01" ${SCRIPTEXEC} ${ecmccfg_DIR}loadYamlAxis.cmd, "FILE=../common/axis_ax6_HI.yaml, DRV_SLAVE=${ECMC_EC_SLAVE_NUM}, ENC_SLAVE=${ECMC_EC_SLAVE_NUM}, ENC_CHANNEL=01"
# 0:9 - EL7041 1Ch Stepper # 0:9 - EL7041 1Ch Stepper
${SCRIPTEXEC} ${ecmccfg_DIR}addSlave.cmd, "HW_DESC=EL7041-0052" ${SCRIPTEXEC} ${ecmccfg_DIR}addSlave.cmd, "HW_DESC=EL7041-0052"
@@ -67,19 +55,5 @@ ${SCRIPTEXEC} ${ecmccfg_DIR}addSlave.cmd, "HW_DESC=EL7041-0052"
#- ################################################################# #- #################################################################
#- Virtual axes #- Virtual axes
${SCRIPTEXEC} ${ecmccfg_DIR}loadYamlAxis.cmd, "FILE=cfg/axis_vax5_YCEN.yaml, AX_ID=${AX_NUM=12}" ${SCRIPTEXEC} ${ecmccfg_DIR}loadYamlAxis.cmd, "FILE=../common/axis_vax5_YCEN.yaml, AX_ID=${AX_NUM=12}"
${SCRIPTEXEC} ${ecmccfg_DIR}loadYamlAxis.cmd, "FILE=cfg/axis_vax6_YGAP.yaml, AX_ID=${AX_NUM=13}" ${SCRIPTEXEC} ${ecmccfg_DIR}loadYamlAxis.cmd, "FILE=../common/axis_vax6_YGAP.yaml, AX_ID=${AX_NUM=13}"
#- #################################################################
#- PLCs with inverse kinematics (note the INC var including dirs to search for include files)
#- The group ID:s configured in yaml are stored in GRP_<axis.group>_ID
${SCRIPTEXEC} ${ecmccfg_DIR}loadPLCFile.cmd, "FILE=./cfg/axis_main.plc, PLC_ID=1, INC=.:${ecmc_master_slave_DIR}, PLC_MACROS='PLC_ID=1, AX_CEN=12, AX_GAP=13, AX_LO=5, AX_HI=6, GRP_ID_RA=${GRP_realAxes_ID}, GRP_ID_VA=${GRP_virtualAxes_ID}'"
#- #################################################################
#- go active
${SCRIPTEXEC} ${ecmccfg_DIR}applyConfig.cmd
${SCRIPTEXEC} ${ecmccfg_DIR}setAppMode.cmd
#- #############################################################################
#- reset all errors
afterInit("ecmcConfigOrDie 'ControllerErrorReset()'")
-12
View File
@@ -1,15 +1,3 @@
# Test ioc for a slit system
Note: Motor record disabled in this test system
## Changes
1. Use ecmc/ecmccfg version 9.5.4 or newer.
2. Divide statemachine and kinematics into separate include files (add INC param to loadPLCFile.cmd needed)
3. Use extsetpos in kinematics
4. Use new axis group functions in statemachine to make it generic (no direct access to axes in statemachine)
5. Set allow source change when enabled in axis yaml cfg (remove in startup script)
6. Remove encoder.position in virtual axis (not needed anymore)
7. Remove filter cfgs in yaml files
## Panel ## Panel
``` ```
caqtdm -macro "IOC=c6025a" ecmcMain.ui caqtdm -macro "IOC=c6025a" ecmcMain.ui
@@ -0,0 +1,30 @@
#- Configuration scripts
require ecmccfg,"ENG_MODE=1,EC_RATE=100"
#- Components lib
require ecmccomp
#- Syncronization configs
require ecmc_master_slave
#- Only output errors
asynSetTraceMask(${ECMC_ASYN_PORT}, -1, 0x01)
#- #################################################################
# Configure Hardware and Motion
< ../common/cfgHW_and_motion.cmd
#- #################################################################
#- PLCs with inverse kinematics (note the INC var including dirs to search for include files)
#- The group ID:s configured in yaml are stored in GRP_<axis.group>_ID
${SCRIPTEXEC} ${ecmccfg_DIR}loadPLCFile.cmd, "FILE=./cfg/axis_main.plc, PLC_ID=1, INC=.:${ecmc_master_slave_DIR}, PLC_MACROS='PLC_ID=1, AX_CEN=12, AX_GAP=13, AX_LO=5, AX_HI=6, GRP_ID_SA=${GRP_realAxes_ID}, GRP_ID_MA=${GRP_virtualAxes_ID}'"
#- #################################################################
#- go active
${SCRIPTEXEC} ${ecmccfg_DIR}applyConfig.cmd
${SCRIPTEXEC} ${ecmccfg_DIR}setAppMode.cmd
#- #############################################################################
#- reset all errors
afterInit("ecmcConfigOrDie 'ControllerErrorReset()'")
@@ -0,0 +1 @@
7.0.7
@@ -0,0 +1,31 @@
/* Forward kinematics to calculate virtual axes from real axes
| CEN | = FWD * | S1_LO |
| GAP | | S2_HI |
Equations:
ax{AX_CEN}.enc.actpos:=(ax{AX_LO}.enc.actpos+ax{AX_HI}.enc.actpos)/2;
ax{AX_GAP}.enc.actpos:=ax{AX_HI}.enc.actpos-ax{AX_LO}.enc.actpos;
*/
var FWD1[2] := {0.5, 0.5};
var FWD2[2] := { -1, 1 };
/* Inverse kinematics to calculate real axes from virtal axes
| S1_LO | = INV * | CEN |
| S2_HI | | GAP |
Equations:
ax{AX_LO}.traj.extsetpos:=ax{AX_CEN}.traj.setpos-ax{AX_GAP}.traj.setpos/2;
ax{AX_HI}.traj.extsetpos:=ax{AX_CEN}.traj.setpos+ax{AX_GAP}.traj.setpos/2;
*/
var INV1[2] := { 1, -0.5};
var INV2[2] := { 1, 0.5};
####### Kinematics for slit system.
# Macros cannot be used in an include. In order to find files, the loadPLCFile.cmd parameter "INC" defines the dirs that MSI will look for the file)
include "axis_kin_2DoF.plc_inc"
####### State machine
# Macros cannot be used in an include. In order to find files, the loadPLCFile.cmd parameter "INC" defines the dirs that MSI will look for the file)
include "axis_sm.plc_inc"
+11
View File
@@ -0,0 +1,11 @@
# The following lines were generated by "ioc install"
# Generated at: 2024-08-07 16:32:41.171272
epicsEnvSet IOC c6025a
epicsEnvSet ENGINEER sandst_a
< /ioc/startup/startup.script_linux
# ---- ioc/system specific startup script(s)
< startup.script_ecmc
iocInit
@@ -0,0 +1,29 @@
#- Configuration scripts
require ecmccfg sandst_a "ENG_MODE=1,EC_RATE=100"
#- Components lib
require ecmccomp
#- Syncronization configs
require ecmc_master_slave
#- Only output errors
asynSetTraceMask(${ECMC_ASYN_PORT}, -1, 0x01)
#- #################################################################
# Configure Hardware and Motion
< ../common/cfgHW_and_motion.cmd
#- #################################################################
#- PLCs with kinematics (note the INC var including dirs to search for include files)
#- The group ID:s configured in yaml are stored in GRP_<axis.group>_ID
${SCRIPTEXEC} ${ecmccfg_DIR}loadPLCFile.cmd, "FILE=./cfg/axis_main.plc, PLC_ID=1, INC=.:${ecmc_master_slave_DIR}, DESC='Slit Kinematics and Statemachine', PLC_MACROS='PLC_ID=1, AX_M1=12, AX_M2=13, AX_S1=5, AX_S2=6, GRP_ID_SA=${GRP_realAxes_ID}, GRP_ID_MA=${GRP_virtualAxes_ID}'"
#- #################################################################
#- go active
${SCRIPTEXEC} ${ecmccfg_DIR}applyConfig.cmd
${SCRIPTEXEC} ${ecmccfg_DIR}setAppMode.cmd
#- #############################################################################
#- reset all errors
afterInit("ecmcConfigOrDie 'ControllerErrorReset()'")