This commit is contained in:
2024-09-16 09:31:27 +02:00
parent 6c6d14e0b8
commit 74b291a618
14 changed files with 578 additions and 91 deletions
+1
View File
@@ -0,0 +1 @@
7.0.7
+78
View File
@@ -0,0 +1,78 @@
# https://paulscherrerinstitute.github.io/ecmccfg/manual/axis/axisyaml/
axis:
id: 5
mode: CSV
features:
allowSrcChangeWhenEnabled: true
epics:
name: TRYB
precision: 4
unit: mm
motorRecord:
enable: false
description: "Test Y Bottom"
drive:
numerator: 10 # max velo in EGU/s
denominator: 32768 # MAX_INT for a 16-bit register, always this for this stepper drive!
type: 0
control: ec0.s$(DRV_SLAVE).driveControl01
status: ec0.s$(DRV_SLAVE).driveStatus01
setpoint: ec0.s$(DRV_SLAVE).velocitySetpoint01
encoder:
numerator: 1 # 1egu = 1mm
denominator: 12800 # Number of ticks when motor moves numerator (=1mm): 1 mm / 50 nm = 20000
type: 0 # Type: 0=Incremental, 1=Absolute
bits: 16 # Total bit count of encoder raw data
absBits: 0 # Absolute bit count (for abs enc) always least significant part of 'bits'
absOffset: 0.0000 # Encoder offset in eng units (for absolute encoders)
position: ec0.s$(ENC_SLAVE).positionActual$(ENC_CHANNEL)
controller:
Kp: 10.00
Ki: 0.001
Kd: 0.000
Kff: 1.00
trajectory:
axis:
velocity: 1.0
acceleration: 1.0
deceleration: 1.0
input:
limit:
forward: ec0.s$(DRV_SLAVE).driveStatus01.12 # 1119994 cnts // 55.9997 mm
backward: ec0.s$(DRV_SLAVE).driveStatus01.11 # 98010 cnts // 4.9005 mm
home: ec0.s$(DRV_SLAVE).ONE.0 # unused
interlock: ec0.s$(DRV_SLAVE).ONE.0 # unused
softlimits:
enable: false
backwardEnable: true
forwardEnable: true
forward: 55.8
backward: 5.1
monitoring:
lag:
enable: true
tolerance: 0.05
time: 100
target:
enable: true
tolerance: 0.05
time: 100
velocity:
enable: true
max: 5
time:
trajectory: 100
drive: 200
plc:
enable: true
externalCommands: true
+78
View File
@@ -0,0 +1,78 @@
# https://paulscherrerinstitute.github.io/ecmccfg/manual/axis/axisyaml/
axis:
id: 6
mode: CSV
features:
allowSrcChangeWhenEnabled: true
epics:
name: TRYT
precision: 4
unit: mm
motorRecord:
enable: false
description: "Test Y Top"
drive:
numerator: 10 # max velo in EGU/s
denominator: 32768 # MAX_INT for a 16-bit register, always this for this stepper drive!
type: 0
control: ec0.s$(DRV_SLAVE).driveControl01
status: ec0.s$(DRV_SLAVE).driveStatus01
setpoint: ec0.s$(DRV_SLAVE).velocitySetpoint01
encoder:
numerator: 1 # 1egu = 1mm
denominator: 12800 # Number of ticks when motor moves numerator (=1mm): 1 mm / 50 nm = 20000
type: 0 # Type: 0=Incremental, 1=Absolute
bits: 16 # Total bit count of encoder raw data
absBits: 0 # Absolute bit count (for abs enc) always least significant part of 'bits'
absOffset: 0.0000 # Encoder offset in eng units (for absolute encoders)
position: ec0.s$(ENC_SLAVE).positionActual$(ENC_CHANNEL)
controller:
Kp: 2.000
Ki: 0.001
Kd: 0.000
Kff: 1.00
trajectory:
axis:
velocity: 1.0
acceleration: 1.0
deceleration: 1.0
input:
limit:
forward: ec0.s$(DRV_SLAVE).driveStatus01.12 # 1111969 cnts // 55.5984 mm
backward: ec0.s$(DRV_SLAVE).driveStatus01.11 # 109007 cnts // 5.4504 mm
home: ec0.s$(DRV_SLAVE).ONE.0 # unused
interlock: ec0.s$(DRV_SLAVE).ONE.0 # unused
softlimits:
enable: false
backwardEnable: true
forwardEnable: true
forward: 55.4
backward: 5.7
monitoring:
lag:
enable: true
tolerance: 0.05
time: 100
target:
enable: true
tolerance: 0.05
time: 100
velocity:
enable: true
max: 5
time:
trajectory: 100
drive: 200
plc:
enable: true
externalCommands: true
+8
View File
@@ -0,0 +1,8 @@
####### 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_slit.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"
+64
View File
@@ -0,0 +1,64 @@
axis:
id: ${AX_ID}
type: end effector
epics:
name: CENTERY
precision: 4
unit: mm
motorRecord:
enable: false
description: "Center Y (Virtual)"
encoder:
type: 1
source: 1
numerator: 1
bits: 32
trajectory:
axis:
velocity: 0.5
acceleration: 0.25
jerk: 0.25
input:
limit:
forward: ec0.s0.ONE.0 # unused
backward: ec0.s0.ONE.0 # unused
home: ec0.s0.ONE.0 # unused
interlock: ec0.s0.ONE.0 # unused
softlimits:
enable: false
forwardEnable: true
backwardEnable: true
forward: 52
backward: 8
monitoring:
lag:
enable: yes
tolerance: 0.02
time: 100
target:
enable: yes
tolerance: 0.02
time: 100
velocity:
enable: yes
max: 0.6
time:
trajectory: 100
drive: 100
plc:
enable: true
externalCommands: true
filter:
velocity:
enable: false
size: 10
trajectory:
enable: false
size: 10
+64
View File
@@ -0,0 +1,64 @@
axis:
id: ${AX_ID}
type: end effector
epics:
name: GAPY
precision: 4
unit: mm
motorRecord:
enable: false
description: "Gap Y (Virtual)"
encoder:
type: 1
source: 1
numerator: 1
bits: 32
trajectory:
axis:
velocity: 0.5
acceleration: 0.25
jerk: 0.25
input:
limit:
forward: ec0.s0.ONE.0 # unused
backward: ec0.s0.ONE.0 # unused
home: ec0.s0.ONE.0 # unused
interlock: ec0.s0.ONE.0 # unused
softlimits:
enable: false
forwardEnable: true
backwardEnable: true
forward: 20
backward: -20
monitoring:
lag:
enable: yes
tolerance: 0.02
time: 100
target:
enable: yes
tolerance: 0.02
time: 100
velocity:
enable: yes
max: 0.6
time:
trajectory: 100
drive: 100
plc:
enable: true
externalCommands: true
filter:
velocity:
enable: false
size: 10
trajectory:
enable: false
size: 10
+19
View File
@@ -0,0 +1,19 @@
# 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
```
caqtdm -macro "IOC=c6025a" ecmcMain.ui
```
## TODO
Test with motor record.
+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
+94
View File
@@ -0,0 +1,94 @@
require ecmccfg sandst_a,"ECMC_VER=sandst_a,MODE=NO_MR,ENG_MODE=1,EC_RATE=100"
require ecmccomp
require ecmc_master_slave sandst_a
#- ############################################################################
#- add slaves
#- list of slaves (4 axis test motion box)
# Master0
# 0 0:0 PREOP + EK1100 EtherCAT-Koppler (2A E-Bus)
# 1 0:1 PREOP + EL9227-5500 berstromschutz 24V DC, 2K., max. 10A (Summe), eins
# 2 0:2 PREOP + EL5042 2Ch. BiSS-C Encoder
# 3 0:3 PREOP + EL5042 2Ch. BiSS-C Encoder
# 4 0:4 PREOP + EL3204 4K. Ana. Eingang PT100 (RTD)
# 5 0:5 PREOP + EL2008 8K. Dig. Ausgang 24V, 0.5A
# 6 0:6 PREOP + EL1008 8K. Dig. Eingang 24V, 3ms
# 7 0:7 PREOP + EL7041 1Ch. Stepper motor output stage (50V, 5A)
# 8 0:8 PREOP + EL7041 1Ch. Stepper motor output stage (50V, 5A)
# 9 0:9 PREOP + EL7041 1Ch. Stepper motor output stage (50V, 5A)
# 10 0:10 PREOP + EL7041 1Ch. Stepper motor output stage (50V, 5A)
#
# 0:0 - EK1100 EtherCAT coupler
${SCRIPTEXEC} ${ecmccfg_DIR}addSlave.cmd, "HW_DESC=EK1100"
# 0:1 - EL9227-5500
${SCRIPTEXEC} ${ecmccfg_DIR}addSlave.cmd, "HW_DESC=EL9227-5500"
# 0:2 - EL5042 2Ch BiSS-C Encoder
${SCRIPTEXEC} ${ecmccfg_DIR}addSlave.cmd, "HW_DESC=EL5042"
# 0:3 - EL5042 2Ch BiSS-C Encoder
${SCRIPTEXEC} ${ecmccfg_DIR}addSlave.cmd, "HW_DESC=EL5042"
# 0:4 - EL3204
${SCRIPTEXEC} ${ecmccfg_DIR}addSlave.cmd, "HW_DESC=EL3204"
# 0:5 - EL2008
${SCRIPTEXEC} ${ecmccfg_DIR}addSlave.cmd, "HW_DESC=EL2008"
# 0:6 - EL1008 8K. Dig. Eingang 24V, 3ms
${SCRIPTEXEC} ${ecmccfg_DIR}addSlave.cmd, "HW_DESC=EL1008"
# 0:7 - EL7041 1Ch Stepper
${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,STEPS=400'"
${SCRIPTEXEC} ${ecmccfg_DIR}loadYamlAxis.cmd, "FILE=cfg/axis_ax5_lower.yaml, DRV_SLAVE=${ECMC_EC_SLAVE_NUM}, ENC_SLAVE=${ECMC_EC_SLAVE_NUM}, ENC_CHANNEL=01"
# 0:8 - EL7041 1Ch Stepper
${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,STEPS=400'"
${SCRIPTEXEC} ${ecmccfg_DIR}loadYamlAxis.cmd, "FILE=cfg/axis_ax6_upper.yaml, DRV_SLAVE=${ECMC_EC_SLAVE_NUM}, ENC_SLAVE=${ECMC_EC_SLAVE_NUM}, ENC_CHANNEL=01"
# 0:9 - EL7041 1Ch Stepper
${SCRIPTEXEC} ${ecmccfg_DIR}addSlave.cmd, "HW_DESC=EL7041-0052"
# 0:10 - EL7041 1Ch Stepper
${SCRIPTEXEC} ${ecmccfg_DIR}addSlave.cmd, "HW_DESC=EL7041-0052"
#- #################################################################
#- Virtual axes
${SCRIPTEXEC} ${ecmccfg_DIR}loadYamlAxis.cmd, "FILE=cfg/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}"
#- #############################################################################
#- Y Direction -- Axis groupings in preparation for kinematics PLC
ecmcConfigOrDie "Cfg.AddAxisGroup(realAxesY)"
ecmcConfigOrDie "Cfg.AddAxisToGroupByName(5,realAxesY)"
ecmcConfigOrDie "Cfg.AddAxisToGroupByName(6,realAxesY)"
ecmcConfig "GetAxisGroupIndexByName(realAxesY)"
epicsEnvSet(GRP_ID_RAX,${ECMC_CONFIG_RETURN_VAL=0})
ecmcConfigOrDie "Cfg.AddAxisGroup(virtualAxesY)"
ecmcConfigOrDie "Cfg.AddAxisToGroupByName(12,virtualAxesY)"
ecmcConfigOrDie "Cfg.AddAxisToGroupByName(13,virtualAxesY)"
ecmcConfig "GetAxisGroupIndexByName(virtualAxesY)"
epicsEnvSet(GRP_ID_VAX,${ECMC_CONFIG_RETURN_VAL=0})
#- PLCs with inverse kinematics (note the INC var including dirs to search for include files)
${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_ID_RAX}, GRP_ID_VA=${GRP_ID_VAX}'"
#- #################################################################
#- apply the configuration
${SCRIPTEXEC} ${ecmccfg_DIR}applyConfig.cmd
#- #################################################################
#- go active
${SCRIPTEXEC} ${ecmccfg_DIR}setAppMode.cmd
#- #############################################################################
#- reset all errors
afterInit("ecmcConfigOrDie 'ControllerErrorReset()'")
ecmcConfigOrDie "Cfg.SetDiagAxisEnable(0)"