This commit is contained in:
2024-01-29 11:53:24 +01:00
parent 6b6369d952
commit 387fc5e6a8
9 changed files with 477 additions and 461 deletions

203
iocsh/cfg/axis.yaml Normal file
View File

@@ -0,0 +1,203 @@
macros: LIMIT=10000,TYPE=0,DRV_SLAVE=${DRV_SLAVE} # Macros for all below (evaluated before jinja linter)
axis:
id: 1 # Axis id
type: joint # this is for future selection of axis type
# mode: CSV # supported mode, CSV and CSP, defaults CSV
# parameters: 'axisPar' # additional parameters # Additional params to motor record driver
#healthOutput: ec0... # Ethercat entry for health output
# autoMode: # Switch drive modes automaticaly for normal motion and homing (smaract for instance)
# modeSet: ec0.. # Ethercat entry drive mode write (set CSV,CSP,homing)
# modeAct: ec0.. # Ethercat entry drive mode reading (set CSV,CSP,homing)
# modeCmdMotion: 9 # Drive mode value for normal motion (written to axis.drvMode.modeSet when normal motion)
# modeCmdHome: 10 # Drive mode value for when homing (written to axis.drvMode.modeSet when homing)
# features:
# blockCom: false # Block communication to axis
# allowedFunctions:
# homing: true # Allow homing
# constantVelocity: true # Allow constant velocity
# positioning: true # Allow positioning
epics:
name: Axis1 # Axis anme
precision: 3 # Decimal count
description: very important motor axis # Axis description
unit: mm # Unit
# motorRecord:
# enable: true
# description: This is MR
# fieldInit: 'RRES=1.0,RTRY=2,RMOD=1,UEIP=0,RDBD=0.1,URIP=1,RDBL=$(IOC):$(ECMC_MOTOR_NAME)-PosActSim' # Extra config for Motor record
drive:
numerator: 3600 # Fastest speed in engineering units
denominator: 32768 # I/O range for ECMC_EC_ALIAS_DRV_VELO_SET
# type: 0 # Stepper: 0. DS402: 1 (DS402 = servos and advanced stepper drives)
control: ec0.s$(DRV_SLAVE).driveControl01 # Control word ethercat entry
enable: 0 # Enable bit index in control word (not used if DS402)
enabled: 1 # Enabled bit index in status word (not used if DS402)
status: ec0.s$(DRV_SLAVE).driveStatus01 # Status word ethercat entry
setpoint: ec0.s$(DRV_SLAVE).velocitySetpoint01 # Velocity setpoint if CSV. Position setpoint if CSP
# reduceTorque: 2 # Reduce torque bit in drive control word
# reduceTorqueEnable: True # Enable reduce torque functionality
# brake:
# enable: true # Enable brake
# output: ec0... # Ethercat link to brake output
# openDelay: 0 # Brake timing parameter in cycles (default 1kHz)
# closeAhead: 0 # Brake timing parameter in cycles (default 1kHz)
# reset: 1 # Reset (if no drive reset bit then leave empty)
# warning: 2 # Warning (if no drive warning bit then leave empty)
# error: # max 3
# - 3 # Error 0 (if no drive error bit then leave empty)
# - 7 # Error 1 (if no drive error bit then leave empty)
# - 14 # Error 2 (if no drive error bit then leave empty)
encoder:
numerator: 360 # Scaling numerator example 360 deg/rev
denominator: 12800 # Scaling denominator example 4096 ticks per 360 degree
# type: 0 # Type: 0=Incremental, 1=Absolute
bits: 16 # Total bit count of encoder raw data
# absBits: 0 # Absolute bit count (for absolute encoders) always least significant part of 'bits'
# absOffset: 0 # Encoder offset in eng units (for absolute encoders)
# mask: '0xFFF00' # Mask applied to raw encoder value
position: ec0.s$(DRV_SLAVE).positionActual01 # Ethercat entry for actual position input (encoder)
control: ec0.s$(DRV_SLAVE).encoderControl01 # mandatory only if 'reset' is used
status: ec0.s$(DRV_SLAVE).encoderStatus01 # mandatory only if 'warning' or 'error' are used
# ready: 10 # Bit in encoder status word for encoder ready
# source: 0 # 0 = Encoder value from etehrcat hardware, 1 = Encoder value from PLC
# reset: 1 # Reset (optional)
# warning: 2 # Warning (optional)
# error: # max 3 (optional)
# - 5 # Error 0
# - 9 # Error 1
# - 11 # Error 2
# filter:
# velocity:
# size: 100 # Filter size for velocity
# enable: true # enable velocity filter
# position:
# size: 100 # Filter size for encoder value
# enable: true # enable encoder value filter
# latch:
# position: '' # Link to latched value. Used for some homing seqs
# control: 0 # Bit in encoder control word to arm latch. Used for some homing seqs
# status: 0 # Bit in encoder status word for latch triggered status. Used for some homing seqs
# primary: 1 # Use this encoder as primary (for control)
# homing:
# type: 3 # Homing sequence type
# position: -30 # Position to reference encoder to
# velocity:
# to: 10 # Velocity to cam/sensor (used for some homing seqs)
# from: 5 # Velocity from cam/sensor (used for some homing seqs)
# acceleration: 20 # Acceleration during homing
# deceleration: 100 # Deceleration during homing
# refToEncIDAtStartup: 1 # At startup then set the start value of this encoder to actpos of this encoder id
# refAtHome: 1 # If homing is executed then set position of this encoder
# tolToPrim: 0 # If set then this is the max allowed tolerance between prim encoder and this encoder
# postMoveEnable: yes # Enable move after successfull homing
# postMovePosition: 10 # Position to move to after successfull homing
# trigg: ec0.. # Ethercat entry for triggering drive internal homing seq (seq id 26)
# ready: ec0.. # Ethercat entry for readinf drive internal homing seq ready (seq id 26)
controller:
Kp: 1 # Kp proportinal gain
Ki: 0.02 # Ki integral gain
Kd: 0 # Kd derivative gain
# Kff: 1 # Feed forward gain
# deadband:
# tol: 0.01 # Stop control if within this distance from target for the below time
# time: 100
# limits:
# minOutput: -100 # Minimum controller output
# maxOutput: 100 # Maximum controller output
# minIntegral: -100 # Minimum integral output
# maxIntegral: 100 # Maximum integral output
# inner:
# Kp: 0.1 # Kp for when close to target
# Ki: 0.1 # Ki for when close to target
# Kd: 0.1 # Kd for when close to target
# tol: 0.1 # Distance from target for when inner PID params will be used, defaults to atTarget tol
trajectory:
# type: 1 # Default 0 = trapetz, 1 = S-curve (ruckig)
axis:
velocity: 100 # Default velo for axis
acceleration: 100 # Default acc for axis
deceleration: 100 # Default dec for axis
# emergencyDeceleration: 0.05 # Deceleration when axis in error state
jerk: 10 # Default jerk for axis
jog:
velocity: 5 # Default velo fro JOG (motor record)
# modulo:
# range: 360 # Modulo range 0..360
# type: 0 # Modulo type
input:
limit:
forward: ec0.s$(DRV_SLAVE).ONE.0 # Ethercat entry for low limit switch input
# forwardPolarity: 0 # Polarity of forward limit switch
backward: ec0.s$(DRV_SLAVE).ONE.0 # Ethercat entry for high limit switch input
# backwardPolarity: 0 # Polarity of forward limit switch
home: 'ec0.s$(DRV_SLAVE).ONE.0' # Ethercat entry for home switch
# homePolarity: 0 # Polarity of home switch
interlock: 'ec0.s$(DRV_SLAVE).ONE.0' # Ethercat entry for interlock switch input
# interlockPolarity: 0 # Polarity of interlock switch
# homing:
# type: 3 # Homing sequence type
# position: -30 # Position to reference encoder to
# velocity:
# to: 10 # Velocity to cam/sensor (used for some homing seqs)
# from: 5 # Velocity from cam/sensor (used for some homing seqs)
# acc: 20 # Acceleration during homing
# dec: 100 # Deceleration during homing
# refToEncIDAtStartup: 1 # At startup then set the start value of this encoder to actpos of this encoder id
# refAtHome: 1 # If homing is executed then set position of this encoder
# tolToPrim: 0 # If set then this is the max allowed tolerance between prim encoder and this encoder
# postMoveEnable: yes # Enable move after successfull homing
# postMovePosition: 10 # Position to move to after successfull homing
# timeout: 100 # Sequence timeout
softlimits:
enable: false # Enable soft limits
forward: 100 # Soft limit position fwd
forwardEnable: false # Soft limit position fwd enable
backward: -100 # Soft limit position bwd
backwardEnable: false # Soft limit position bwd enable
monitoring:
lag:
enable: true # Enable position lag monitoring (following error)
tolerance: 2 # Allowed tolerance
time: 10 # Allowed time outside tolerance target:
enable: false # Enable at target monitoring (needs to be enabled if using motor record)
tolerance: 0.5 # Allowed tolerance
time: 10 # Filter time inside tolerance to be at target
velocity:
enable: false # Enable velocity monitoring
max: 100 # Allowed max velocity
time:
trajectory: 100 # Time allowed outside max velo before system init halt
drive: 200 # Time allowed outside max velo before system disables drive
# velocityDifference:
# enable: true # Enable velocity diff monitoring (velo set vs velo act)
# max: 100 # Allowed max difference
# time:
# trajectory: 100 # Time allowed outside max diff velo before system init halt
# drive: 200 # Time allowed outside max diff velo before system disables drive
plc:
enable: true # Enable axis plc
externalCommands: true # Allow axis to inputs from PLC
file: ${PLC_PATH}test.plc
code: # Sync code
- "if(static.counter % ${LIMIT} == 0){println('AX PLC: Appended');static.counter:=0;};" # calculate set pos for physical axis
- "if(not(static.plc_code_loaded)) {static.counter:=static.counter+1;};"
- ec0.s$(DRV_SLAVE).ONE > 1; # Enable axis if one of master axes is enabled
- ec0.s$(DRV_SLAVE).ZERO > 1; # calculate set pos for physical axis
# velocity_filter: # Filter used to smother velocity feedforward
# encoder: # Filter plc enc velo
# enable: false # Filter enable
# size: 100 # Filter size
# trajectory: # Filter plc traj velo
# enable: false # Filter enable
# size: 100 # Filter size

204
iocsh/cfg/axis_latch.yaml Normal file
View File

@@ -0,0 +1,204 @@
macros: LIMIT=10000,TYPE=0,DRV_SLAVE=${DRV_SLAVE} # Macros for all below (evaluated before jinja linter)
axis:
id: 1 # Axis id
type: joint # this is for future selection of axis type
# mode: CSV # supported mode, CSV and CSP, defaults CSV
# parameters: 'axisPar' # additional parameters # Additional params to motor record driver
#healthOutput: ec0... # Ethercat entry for health output
# autoMode: # Switch drive modes automaticaly for normal motion and homing (smaract for instance)
# modeSet: ec0.. # Ethercat entry drive mode write (set CSV,CSP,homing)
# modeAct: ec0.. # Ethercat entry drive mode reading (set CSV,CSP,homing)
# modeCmdMotion: 9 # Drive mode value for normal motion (written to axis.drvMode.modeSet when normal motion)
# modeCmdHome: 10 # Drive mode value for when homing (written to axis.drvMode.modeSet when homing)
# features:
# blockCom: false # Block communication to axis
# allowedFunctions:
# homing: true # Allow homing
# constantVelocity: true # Allow constant velocity
# positioning: true # Allow positioning
epics:
name: Axis1 # Axis anme
precision: 3 # Decimal count
description: very important motor axis # Axis description
unit: mm # Unit
# motorRecord:
# enable: true
# description: This is MR
# fieldInit: 'RRES=1.0,RTRY=2,RMOD=1,UEIP=0,RDBD=0.1,URIP=1,RDBL=$(IOC):$(ECMC_MOTOR_NAME)-PosActSim' # Extra config for Motor record
drive:
numerator: 3600 # Fastest speed in engineering units
denominator: 32768 # I/O range for ECMC_EC_ALIAS_DRV_VELO_SET
# type: 0 # Stepper: 0. DS402: 1 (DS402 = servos and advanced stepper drives)
control: ec0.s$(DRV_SLAVE).driveControl01 # Control word ethercat entry
enable: 0 # Enable bit index in control word (not used if DS402)
enabled: 1 # Enabled bit index in status word (not used if DS402)
status: ec0.s$(DRV_SLAVE).driveStatus01 # Status word ethercat entry
setpoint: ec0.s$(DRV_SLAVE).velocitySetpoint01 # Velocity setpoint if CSV. Position setpoint if CSP
# reduceTorque: 2 # Reduce torque bit in drive control word
# reduceTorqueEnable: True # Enable reduce torque functionality
# brake:
# enable: true # Enable brake
# output: ec0... # Ethercat link to brake output
# openDelay: 0 # Brake timing parameter in cycles (default 1kHz)
# closeAhead: 0 # Brake timing parameter in cycles (default 1kHz)
# reset: 1 # Reset (if no drive reset bit then leave empty)
# warning: 2 # Warning (if no drive warning bit then leave empty)
# error: # max 3
# - 3 # Error 0 (if no drive error bit then leave empty)
# - 7 # Error 1 (if no drive error bit then leave empty)
# - 14 # Error 2 (if no drive error bit then leave empty)
encoder:
numerator: 360 # Scaling numerator example 360 deg/rev
denominator: 12800 # Scaling denominator example 4096 ticks per 360 degree
# type: 0 # Type: 0=Incremental, 1=Absolute
bits: 16 # Total bit count of encoder raw data
# absBits: 0 # Absolute bit count (for absolute encoders) always least significant part of 'bits'
# absOffset: 0 # Encoder offset in eng units (for absolute encoders)
# mask: '0xFFF00' # Mask applied to raw encoder value
position: ec0.s$(DRV_SLAVE).positionActual01 # Ethercat entry for actual position input (encoder)
control: ec0.s$(DRV_SLAVE).encoderControl01 # mandatory only if 'reset' is used
status: ec0.s$(DRV_SLAVE).encoderStatus01 # mandatory only if 'warning' or 'error' are used
# ready: 10 # Bit in encoder status word for encoder ready
# source: 0 # 0 = Encoder value from etehrcat hardware, 1 = Encoder value from PLC
# reset: 1 # Reset (optional)
# warning: 2 # Warning (optional)
# error: # max 3 (optional)
# - 5 # Error 0
# - 9 # Error 1
# - 11 # Error 2
# filter:
# velocity:
# size: 100 # Filter size for velocity
# enable: true # enable velocity filter
# position:
# size: 100 # Filter size for encoder value
# enable: true # enable encoder value filter
latch:
position: 'ec0.s$(DRV_SLAVE).encoderLatchPostion01' # Link to latched value. Used for some homing seqs
control: 0 # Bit in encoder control word to arm latch. Used for some homing seqs
status: 0 # Bit in encoder status word for latch triggered status. Used for some homing seqs
primary: 1 # Use this encoder as primary (for control)
homing:
type: 12 # Homing sequence type
position: -30 # Position to reference encoder to
velocity:
to: 10 # Velocity to cam/sensor (used for some homing seqs)
from: 5 # Velocity from cam/sensor (used for some homing seqs)
acceleration: 20 # Acceleration during homing
deceleration: 100 # Deceleration during homing
# refToEncIDAtStartup: 1 # At startup then set the start value of this encoder to actpos of this encoder id
refAtHome: 1 # If homing is executed then set position of this encoder
# tolToPrim: 0 # If set then this is the max allowed tolerance between prim encoder and this encoder
# postMoveEnable: yes # Enable move after successfull homing
# postMovePosition: 10 # Position to move to after successfull homing
# trigg: ec0.. # Ethercat entry for triggering drive internal homing seq (seq id 26)
# ready: ec0.. # Ethercat entry for reading drive internal homing seq ready (seq id 26)
latchCount: 1
controller:
Kp: 1 # Kp proportinal gain
Ki: 0.02 # Ki integral gain
Kd: 0 # Kd derivative gain
# Kff: 1 # Feed forward gain
# deadband:
# tol: 0.01 # Stop control if within this distance from target for the below time
# time: 100
# limits:
# minOutput: -100 # Minimum controller output
# maxOutput: 100 # Maximum controller output
# minIntegral: -100 # Minimum integral output
# maxIntegral: 100 # Maximum integral output
# inner:
# Kp: 0.1 # Kp for when close to target
# Ki: 0.1 # Ki for when close to target
# Kd: 0.1 # Kd for when close to target
# tol: 0.1 # Distance from target for when inner PID params will be used, defaults to atTarget tol
trajectory:
# type: 1 # Default 0 = trapetz, 1 = S-curve (ruckig)
axis:
velocity: 100 # Default velo for axis
acceleration: 100 # Default acc for axis
deceleration: 100 # Default dec for axis
# emergencyDeceleration: 0.05 # Deceleration when axis in error state
jerk: 10 # Default jerk for axis
jog:
velocity: 5 # Default velo fro JOG (motor record)
# modulo:
# range: 360 # Modulo range 0..360
# type: 0 # Modulo type
input:
limit:
forward: ec0.s$(DRV_SLAVE).ONE.0 # Ethercat entry for low limit switch input
# forwardPolarity: 0 # Polarity of forward limit switch
backward: ec0.s$(DRV_SLAVE).ONE.0 # Ethercat entry for high limit switch input
# backwardPolarity: 0 # Polarity of forward limit switch
home: 'ec0.s$(DRV_SLAVE).ONE.0' # Ethercat entry for home switch
# homePolarity: 0 # Polarity of home switch
interlock: 'ec0.s$(DRV_SLAVE).ONE.0' # Ethercat entry for interlock switch input
# interlockPolarity: 0 # Polarity of interlock switch
# homing:
# type: 3 # Homing sequence type
# position: -30 # Position to reference encoder to
# velocity:
# to: 10 # Velocity to cam/sensor (used for some homing seqs)
# from: 5 # Velocity from cam/sensor (used for some homing seqs)
# acc: 20 # Acceleration during homing
# dec: 100 # Deceleration during homing
# refToEncIDAtStartup: 1 # At startup then set the start value of this encoder to actpos of this encoder id
# refAtHome: 1 # If homing is executed then set position of this encoder
# tolToPrim: 0 # If set then this is the max allowed tolerance between prim encoder and this encoder
# postMoveEnable: yes # Enable move after successfull homing
# postMovePosition: 10 # Position to move to after successfull homing
# timeout: 100 # Sequence timeout
softlimits:
enable: false # Enable soft limits
forward: 100 # Soft limit position fwd
forwardEnable: false # Soft limit position fwd enable
backward: -100 # Soft limit position bwd
backwardEnable: false # Soft limit position bwd enable
monitoring:
lag:
enable: true # Enable position lag monitoring (following error)
tolerance: 2 # Allowed tolerance
time: 10 # Allowed time outside tolerance target:
enable: false # Enable at target monitoring (needs to be enabled if using motor record)
tolerance: 0.5 # Allowed tolerance
time: 10 # Filter time inside tolerance to be at target
velocity:
enable: false # Enable velocity monitoring
max: 100 # Allowed max velocity
time:
trajectory: 100 # Time allowed outside max velo before system init halt
drive: 200 # Time allowed outside max velo before system disables drive
# velocityDifference:
# enable: true # Enable velocity diff monitoring (velo set vs velo act)
# max: 100 # Allowed max difference
# time:
# trajectory: 100 # Time allowed outside max diff velo before system init halt
# drive: 200 # Time allowed outside max diff velo before system disables drive
plc:
enable: true # Enable axis plc
externalCommands: true # Allow axis to inputs from PLC
file: ${PLC_PATH}test.plc
code: # Sync code
- "if(static.counter % ${LIMIT} == 0){println('AX PLC: Appended');static.counter:=0;};" # calculate set pos for physical axis
- "if(not(static.plc_code_loaded)) {static.counter:=static.counter+1;};"
- ec0.s$(DRV_SLAVE).ONE > 1; # Enable axis if one of master axes is enabled
- ec0.s$(DRV_SLAVE).ZERO > 1; # calculate set pos for physical axis
# velocity_filter: # Filter used to smother velocity feedforward
# encoder: # Filter plc enc velo
# enable: false # Filter enable
# size: 100 # Filter size
# trajectory: # Filter plc traj velo
# enable: false # Filter enable
# size: 100 # Filter size

52
iocsh/el7031.script Normal file
View File

@@ -0,0 +1,52 @@
##############################################################################
## Example config for el7031
require ecmccfg v9.0.1_RC4,"ECMC_VER=v9.0.1_RC4,ENG_MODE=1"
epicsEnvSet(IOC,c6025a)
# Load components lib
require ecmccomp sandst_a
##############################################################################
## Configure hardware
epicsEnvSet("DRV_SLAVE", "4")
${SCRIPTEXEC} ${ecmccfg_DIR}addSlave.cmd, "SLAVE_ID=$(DRV_SLAVE), HW_DESC=EL7031"
#- Apply motor config with some custom macros
${SCRIPTEXEC} ${ecmccomp_DIR}applyComponent.cmd "COMP=Motor-Generic-2Phase-Stepper,MACROS='I_STDBY_MA=200,I_MAX_MA=1000,R_COIL_MOHM=1700'"
epicsEnvSet("ENC_SLAVE", "14")
${SCRIPTEXEC} ${ecmccfg_DIR}addSlave.cmd, "SLAVE_ID=$(ENC_SLAVE), HW_DESC=EL5042"
#- Apply motor config with some custom macros
${SCRIPTEXEC} ${ecmccomp_DIR}applyComponent.cmd "COMP=Encoder-Generic-BISS-C"
#Apply hardware configuration
ecmcConfigOrDie "Cfg.EcApplyConfig(1)"
##############################################################################
## AXIS 1
#
epicsEnvSet("DEV", "$(IOC)")
epicsEnvSet("PLC_PATH", "/ioc/c6025a/ecmccfg/examples/test/ecmccomp/plc/")
${SCRIPTEXEC} ${ECMC_CONFIG_ROOT}loadYamlAxis.cmd, "FILE=./cfg/axis.yaml,LIMIT=1000,TYPE=0"
##############################################################################
## PLC 1
#
${SCRIPTEXEC} ${ECMC_CONFIG_ROOT}loadYamlPlc.cmd, "FILE=./plc/plc_cfg.yaml,LIMIT=5000,TYPE=1"
##############################################################################
############# Configure diagnostics:
ecmcConfigOrDie "Cfg.EcSetDiagnostics(1)"
ecmcConfigOrDie "Cfg.EcEnablePrintouts(0)"
ecmcConfigOrDie "Cfg.EcSetDomainFailedCyclesLimit(100)"
ecmcConfigOrDie "Cfg.SetDiagAxisIndex(1)"
ecmcConfigOrDie "Cfg.SetDiagAxisFreq(2)"
ecmcConfigOrDie "Cfg.SetDiagAxisEnable(0)"
# go active
$(SCRIPTEXEC) ($(ecmccfg_DIR)setAppMode.cmd)

9
iocsh/plc/plc_cfg.yaml Normal file
View File

@@ -0,0 +1,9 @@
macros: LIMIT=1000,TYPE=1 # Macros to pass to this file (also plc.file)
plc:
id: 1
enable: yes
rateMilliseconds: 1
file: ${PLC_PATH}test.plc
code:
- "if(static.counter % ${LIMIT} == 0){println('PLC: Appended');static.counter:=0;};" # calculate set pos for physical axis
- "if(not(static.plc_code_loaded)) {static.counter:=static.counter+1;};"

9
iocsh/plc/test.plc Normal file
View File

@@ -0,0 +1,9 @@
static.counter:=static.counter+1;
static.plc_code_loaded:=1;
if(static.counter % ${LIMIT} == 0) {
if(${TYPE}=0) {
println('AX PLC: File');
} else {
println('PLC : File');
};
};

View File

@@ -1,345 +0,0 @@
IOC_TEST:m0s001-Drv01-Cmd-RB
IOC_TEST:m0s001-Drv01-Spd-RB
IOC_TEST:m0s001-Enc01-PosAct
IOC_TEST:m0s001-Enc01-LtchPosAct
IOC_TEST:m0s001-Enc01-Cmd-RB
IOC_TEST:m0s001-Enc01-PosCmd-RB
IOC_TEST:Axis1-Vel-RB
IOC_TEST:Axis1-Acc-RB
IOC_TEST:Axis1-EncAct
IOC_TEST:Axis1-CfgSREV-RB
IOC_TEST:Axis1-CfgUREV-RB
IOC_TEST:Axis1-CfgPMIN-RB
IOC_TEST:Axis1-CfgPMAX-RB
IOC_TEST:Axis1-CfgSPDB-RB
IOC_TEST:Axis1-CfgRDBD-RB
IOC_TEST:Axis1-CfgRDBD-Tim-RB
IOC_TEST:Axis1-CfgPOSLAG-RB
IOC_TEST:Axis1-CfgPOSLAG-Tim-RB
IOC_TEST:Axis1-CfgDHLM-RB
IOC_TEST:Axis1-CfgDLLM-RB
IOC_TEST:Axis1-CfgVELO-RB
IOC_TEST:Axis1-CfgVMAX-RB
IOC_TEST:Axis1-CfgJVEL-RB
IOC_TEST:Axis1-CfgACCS-RB
IOC_TEST:Axis1-HomPos-RB
IOC_TEST:Axis1-PosAct
IOC_TEST:Axis1-VelAct
IOC_TEST:Axis1-PosSet
IOC_TEST:Axis1-PosErr
IOC_TEST:Axis1-PLC-Err
IOC_TEST:Plg-Mtn0-SmpHz-RB
IOC_TEST:Plg-Mtn0-BuffSze
IOC_TEST:Plg-Mtn0-ElmCnt
IOC_TEST:MCU-AppMode
IOC_TEST:MCU-ErrId
IOC_TEST:MCU-ThdLatMin
IOC_TEST:MCU-ThdLatMax
IOC_TEST:MCU-ThdPrdMin
IOC_TEST:MCU-ThdPrdMax
IOC_TEST:MCU-ThdExeMin
IOC_TEST:MCU-ThdExeMax
IOC_TEST:MCU-ThdSndMin
IOC_TEST:MCU-ThdSndMax
IOC_TEST:m0s001-Drv01-WrnAlrm
IOC_TEST:m0s001-Drv01-ErrAlrm
IOC_TEST:m0s001-Drv01-StlAlrm
IOC_TEST:m0s001-Drv01-SyncErrAlrm
IOC_TEST:m0s001-Enc01-ExtLtchOK
IOC_TEST:m0s001-Enc01-OpnCrctAlrm
IOC_TEST:m0s001-Enc01-WrnAlrm
IOC_TEST:m0s001-Enc01-SyncErrAlrm
IOC_TEST:m0s001-Online
IOC_TEST:m0s001-Operational
IOC_TEST:m0s001-Alstate-Init
IOC_TEST:m0s001-Alstate-Preop
IOC_TEST:m0s001-Alstate-Safeop
IOC_TEST:m0s001-Alstate-Op
IOC_TEST:m0s002-BO01-RB
IOC_TEST:m0s002-BO02-RB
IOC_TEST:m0s002-BO03-RB
IOC_TEST:m0s002-BO04-RB
IOC_TEST:m0s002-BO05-RB
IOC_TEST:m0s002-BO06-RB
IOC_TEST:m0s002-BO07-RB
IOC_TEST:m0s002-BO08-RB
IOC_TEST:m0s002-BO09-RB
IOC_TEST:m0s002-BO10-RB
IOC_TEST:m0s002-BO11-RB
IOC_TEST:m0s002-BO12-RB
IOC_TEST:m0s002-BO13-RB
IOC_TEST:m0s002-BO14-RB
IOC_TEST:m0s002-BO15-RB
IOC_TEST:m0s002-BO16-RB
IOC_TEST:m0s002-BO01-OvrTmpAlrm
IOC_TEST:m0s002-BO01-OpnLdAlrm
IOC_TEST:m0s002-BO01-OvrCurrAlrm
IOC_TEST:m0s002-BO01-ShrtCircAlrm
IOC_TEST:m0s002-BO02-OvrTmpAlrm
IOC_TEST:m0s002-BO02-OpnLdAlrm
IOC_TEST:m0s002-BO02-OvrCurrAlrm
IOC_TEST:m0s002-BO02-ShrtCircAlrm
IOC_TEST:m0s002-BO03-OvrTmpAlrm
IOC_TEST:m0s002-BO03-OpnLdAlrm
IOC_TEST:m0s002-BO03-OvrCurrAlrm
IOC_TEST:m0s002-BO03-ShrtCircAlrm
IOC_TEST:m0s002-BO04-OvrTmpAlrm
IOC_TEST:m0s002-BO04-OpnLdAlrm
IOC_TEST:m0s002-BO04-OvrCurrAlrm
IOC_TEST:m0s002-BO04-ShrtCircAlrm
IOC_TEST:m0s002-BO05-OvrTmpAlrm
IOC_TEST:m0s002-BO05-OpnLdAlrm
IOC_TEST:m0s002-BO05-OvrCurrAlrm
IOC_TEST:m0s002-BO05-ShrtCircAlrm
IOC_TEST:m0s002-BO06-OvrTmpAlrm
IOC_TEST:m0s002-BO06-OpnLdAlrm
IOC_TEST:m0s002-BO06-OvrCurrAlrm
IOC_TEST:m0s002-BO06-ShrtCircAlrm
IOC_TEST:m0s002-BO07-OvrTmpAlrm
IOC_TEST:m0s002-BO07-OpnLdAlrm
IOC_TEST:m0s002-BO07-OvrCurrAlrm
IOC_TEST:m0s002-BO07-ShrtCircAlrm
IOC_TEST:m0s002-BO08-OvrTmpAlrm
IOC_TEST:m0s002-BO08-OpnLdAlrm
IOC_TEST:m0s002-BO08-OvrCurrAlrm
IOC_TEST:m0s002-BO08-ShrtCircAlrm
IOC_TEST:m0s002-BO09-OvrTmpAlrm
IOC_TEST:m0s002-BO09-OpnLdAlrm
IOC_TEST:m0s002-BO09-OvrCurrAlrm
IOC_TEST:m0s002-BO09-ShrtCircAlrm
IOC_TEST:m0s002-BO10-OvrTmpAlrm
IOC_TEST:m0s002-BO10-OpnLdAlrm
IOC_TEST:m0s002-BO10-OvrCurrAlrm
IOC_TEST:m0s002-BO10-ShrtCircAlrm
IOC_TEST:m0s002-BO11-OvrTmpAlrm
IOC_TEST:m0s002-BO11-OpnLdAlrm
IOC_TEST:m0s002-BO11-OvrCurrAlrm
IOC_TEST:m0s002-BO11-ShrtCircAlrm
IOC_TEST:m0s002-BO12-OvrTmpAlrm
IOC_TEST:m0s002-BO12-OpnLdAlrm
IOC_TEST:m0s002-BO12-OvrCurrAlrm
IOC_TEST:m0s002-BO12-ShrtCircAlrm
IOC_TEST:m0s002-BO13-OvrTmpAlrm
IOC_TEST:m0s002-BO13-OpnLdAlrm
IOC_TEST:m0s002-BO13-OvrCurrAlrm
IOC_TEST:m0s002-BO13-ShrtCircAlrm
IOC_TEST:m0s002-BO14-OvrTmpAlrm
IOC_TEST:m0s002-BO14-OpnLdAlrm
IOC_TEST:m0s002-BO14-OvrCurrAlrm
IOC_TEST:m0s002-BO14-ShrtCircAlrm
IOC_TEST:m0s002-BO15-OvrTmpAlrm
IOC_TEST:m0s002-BO15-OpnLdAlrm
IOC_TEST:m0s002-BO15-OvrCurrAlrm
IOC_TEST:m0s002-BO15-ShrtCircAlrm
IOC_TEST:m0s002-BO16-OvrTmpAlrm
IOC_TEST:m0s002-BO16-OpnLdAlrm
IOC_TEST:m0s002-BO16-OvrCurrAlrm
IOC_TEST:m0s002-BO16-ShrtCircAlrm
IOC_TEST:m0s002-Online
IOC_TEST:m0s002-Operational
IOC_TEST:m0s002-Alstate-Init
IOC_TEST:m0s002-Alstate-Preop
IOC_TEST:m0s002-Alstate-Safeop
IOC_TEST:m0s002-Alstate-Op
IOC_TEST:Axis1-EnaCmd-RB
IOC_TEST:Axis1-EnaAct
IOC_TEST:Axis1-ExeCmd-RB
IOC_TEST:Axis1-Busy
IOC_TEST:Axis1-AtTarget
IOC_TEST:Axis1-Moving
IOC_TEST:Axis1-LimFwd
IOC_TEST:Axis1-LimBwd
IOC_TEST:Axis1-HomeSwitch
IOC_TEST:Axis1-Homed
IOC_TEST:Axis1-InRT
IOC_TEST:Axis1-TrjSrcTyp-RB
IOC_TEST:Axis1-EncSrcTyp-RB
IOC_TEST:Axis1-CmdFrmPLCCmd-RB
IOC_TEST:Axis1-SftLimFwdEna-RB
IOC_TEST:Axis1-SftLimBwdEna-RB
IOC_TEST:Axis1-PLC-EnaCmd-RB
IOC_TEST:Axis1-PLC-FirstScan
IOC_TEST:Axis1-Err
IOC_TEST:Axis1-Wrn
IOC_TEST:MCU-ThdRTPrioOK
IOC_TEST:MCU-ThdMemLocked
IOC_TEST:m0-LinkUp
IOC_TEST:m0-AlStates-Init
IOC_TEST:m0-AlStates-Preop
IOC_TEST:m0-AlStates-Safeop
IOC_TEST:m0-AlStates-Op
IOC_TEST:m0-Dom-RedunActive
IOC_TEST:m0-Dom-WC-Zero
IOC_TEST:m0-Dom-WC-Incomplete
IOC_TEST:m0-Dom-WC-Complete
IOC_TEST:m0-Stat-OK
REQMOD:raspberrypi-10406:exit
REQMOD:raspberrypi-10406:MODULES
REQMOD:raspberrypi-10406:VERSIONS
REQMOD:raspberrypi-10406:MOD_VER
IOC_TEST:Axis1-Arr-Stat
IOC_TEST:Axis1-PLC-Expr-RB
IOC_TEST:Plg-Mtn0-PosAct-Arr
IOC_TEST:Plg-Mtn0-PosSet-Arr
IOC_TEST:Plg-Mtn0-PosErr-Arr
IOC_TEST:Plg-Mtn0-Time-Arr
IOC_TEST:Plg-Mtn0-Ena-Arr
IOC_TEST:Plg-Mtn0-EnaAct-Arr
IOC_TEST:Plg-Mtn0-Bsy-Arr
IOC_TEST:Plg-Mtn0-Exe-Arr
IOC_TEST:Plg-Mtn0-TrjSrc-Arr
IOC_TEST:Plg-Mtn0-EncSrc-Arr
IOC_TEST:Plg-Mtn0-AtTrg-Arr
IOC_TEST:Plg-Mtn0-ErrId-Arr
IOC_TEST:MCU-ErrMsg
IOC_TEST:MCU-Updated
IOC_TEST:m0s001-Enc01-LtchCmd
IOC_TEST:Axis1-MtnCmd
IOC_TEST:Axis1-movVelCmd
IOC_TEST:Axis1-movRelCmd
IOC_TEST:Axis1-movAbsCmd
IOC_TEST:Axis1-movHomCmd
IOC_TEST:Axis1-HomProc-RB
IOC_TEST:Axis1-Type
IOC_TEST:Axis1-DrvType
IOC_TEST:Axis1-TrajType
IOC_TEST:m0s001-One
IOC_TEST:m0s001-Zero
IOC_TEST:m0s002-One
IOC_TEST:m0s002-Zero
IOC_TEST:Axis1-DIR_
IOC_TEST:Axis1-ErrRst
IOC_TEST:Axis1-HomProc
IOC_TEST:Axis1-MtnCmdData
IOC_TEST:Plg-Mtn0-Mde-RB
IOC_TEST:Plg-Mtn0-Cmd-RB
IOC_TEST:m0s001-Stat
IOC_TEST:m0s002-Stat
IOC_TEST:Axis1-MR-ErrId
IOC_TEST:Axis1-CfgRDBD-En-RB
IOC_TEST:Axis1-CfgPOSLAG-En-RB
IOC_TEST:Axis1-CfgDHLM-En-RB
IOC_TEST:Axis1-CfgDLLM-En-RB
IOC_TEST:Axis1-Stat
IOC_TEST:Axis1-ErrId
IOC_TEST:Axis1-WrnId
IOC_TEST:Plg-Mtn0-Stat
IOC_TEST:m0-Stat
IOC_TEST:m0-SlvCntr
IOC_TEST:m0-MemmapCntr
IOC_TEST:m0-DomFailCntrTot
IOC_TEST:m0-EntryCntr
IOC_TEST:m0-Dom-Stat
IOC_TEST:MCU-Cfg-Info
IOC_TEST:MCU-Cfg-Naming
IOC_TEST:MCU-Cfg-Mode
IOC_TEST:MCU-Cfg-PVA
IOC_TEST:Axis1-DbgStrToLOG
IOC_TEST:MCU-Cfg-AX1-Pfx
IOC_TEST:MCU-Cfg-AX1-Nam
IOC_TEST:MCU-Cfg-AX1-PfxNam
IOC_TEST:m0s001-EntryCntr
IOC_TEST:m0s002-EntryCntr
IOC_TEST:Axis1-SeqState
IOC_TEST:Axis1-LastIlock
IOC_TEST:m0-SlvRsp
IOC_TEST:m0-Dom-WC
IOC_TEST:m0s001-Enc01-LtchRst
IOC_TEST:Axis1-Cmd_
REQMOD:raspberrypi-10406:BaseVersion
REQMOD:raspberrypi-10406:require_VER
REQMOD:raspberrypi-10406:ecmccfg_VER
REQMOD:raspberrypi-10406:asyn_VER
REQMOD:raspberrypi-10406:exprtk_VER
REQMOD:raspberrypi-10406:motor_VER
REQMOD:raspberrypi-10406:ruckig_VER
REQMOD:raspberrypi-10406:ecmc_VER
IOC_TEST:m0s001-HWType
IOC_TEST:m0s002-HWType
IOC_TEST:Axis1-MsgTxt
REQMOD:raspberrypi-10406:ecmc_plugin_motion_VER
IOC_TEST:m0s001-Drv01-Stat
IOC_TEST:m0s001-Enc01-Stat
IOC_TEST:m0s001-Stat_
IOC_TEST:m0s002-BO01-Stat
IOC_TEST:m0s002-BO02-Stat
IOC_TEST:m0s002-BO03-Stat
IOC_TEST:m0s002-BO04-Stat
IOC_TEST:m0s002-BO05-Stat
IOC_TEST:m0s002-BO06-Stat
IOC_TEST:m0s002-BO07-Stat
IOC_TEST:m0s002-BO08-Stat
IOC_TEST:m0s002-BO09-Stat
IOC_TEST:m0s002-BO10-Stat
IOC_TEST:m0s002-BO11-Stat
IOC_TEST:m0s002-BO12-Stat
IOC_TEST:m0s002-BO13-Stat
IOC_TEST:m0s002-BO14-Stat
IOC_TEST:m0s002-BO15-Stat
IOC_TEST:m0s002-BO16-Stat
IOC_TEST:m0s002-Stat_
IOC_TEST:Axis1-Stat_
IOC_TEST:ThdRTStat_
IOC_TEST:m0-Stat_
IOC_TEST:m0-Dom-Stat_
IOC_TEST:m0s001-Enc01-LtchAutRst
IOC_TEST:Axis1-MtnCmd_
IOC_TEST:MCU-Cfg-EC-Mst
IOC_TEST:MCU-Cfg-Rate
IOC_TEST:MCU-Cfg-Time
IOC_TEST:MCU-Cfg-PV-Time
IOC_TEST:m0s001-Drv01-Cmd
IOC_TEST:m0s001-Drv01-Spd
IOC_TEST:m0s001-Enc01-Cmd
IOC_TEST:m0s001-Enc01-PosCmd
IOC_TEST:m0s001-NxtObjId
IOC_TEST:MCU-Cfg-EC-FrstObjId
IOC_TEST:m0s002-NxtObjId
IOC_TEST:Axis1-OFF_
IOC_TEST:Axis1-MRES_
IOC_TEST:Axis1-HomPos
IOC_TEST:Axis1-VelToHom
IOC_TEST:Axis1-VelFrmHom
IOC_TEST:Axis1-AccHom
IOC_TEST:Axis1-TgtPosCmd
IOC_TEST:Axis1-TgtVelCmd
IOC_TEST:Axis1-Id
IOC_TEST:MCU-Cfg-AX1-NxtObjId
IOC_TEST:MCU-Cfg-AX-FrstObjId
IOC_TEST:MCU-Cfg-PLG{Index}-NxtObjId
IOC_TEST:MCU-Cfg-PLG-FrstObjId
IOC_TEST:Plg-Mtn0-AxCmd-RB
IOC_TEST:MCU-Cfg-Eng-Mode
IOC_TEST:m0s001-Enc01-LchAutRstSp
IOC_TEST:m0s002-BO01
IOC_TEST:m0s002-BO02
IOC_TEST:m0s002-BO03
IOC_TEST:m0s002-BO04
IOC_TEST:m0s002-BO05
IOC_TEST:m0s002-BO06
IOC_TEST:m0s002-BO07
IOC_TEST:m0s002-BO08
IOC_TEST:m0s002-BO09
IOC_TEST:m0s002-BO10
IOC_TEST:m0s002-BO11
IOC_TEST:m0s002-BO12
IOC_TEST:m0s002-BO13
IOC_TEST:m0s002-BO14
IOC_TEST:m0s002-BO15
IOC_TEST:m0s002-BO16
IOC_TEST:Axis1-EnaCmd
IOC_TEST:Axis1-ExeCmd
IOC_TEST:Axis1-StpCmd
IOC_TEST:Axis1-RstCmd
IOC_TEST:Axis1-EncSrcTyp-Cmd
IOC_TEST:Axis1-TrjSrcTyp-Cmd
IOC_TEST:Axis1-PLC-EnaCmd
IOC_TEST:Axis1-CmdFrmPLCCmd
IOC_TEST:Axis1-SftLimBwdEna
IOC_TEST:Axis1-SftLimFwdEna
IOC_TEST:Plg-Mtn0-EnaCmd-RB
IOC_TEST:Plg-Mtn0-TrgCmd-RB
IOC_TEST:MCU-ErrRst
IOC_TEST:Axis1-MCU1-asyn
IOC_TEST:MCU-Cmd
IOC_TEST:Axis1

View File

@@ -1,62 +0,0 @@
##############################################################################
## Example: Configuraftion for running ecmc motion plugin
##############################################################################
## Initiation:
epicsEnvSet("IOC" ,"$(IOC="IOC_TEST")")
epicsEnvSet("SCRIPTEXEC" ,"$(SCRIPTEXEC="iocshLoad")")
require ecmccfg "9.0.1_RC1"
# run module startup.cmd (only needed at ESS PSI auto call at require)
$(ECMCCFG_INIT="")$(SCRIPTEXEC) ${ecmccfg_DIR}startup.cmd, "IOC=$(IOC),ECMC_VER=v9.0.1_RC1, EC_RATE=500"
##############################################################################
## Configure hardware
epicsEnvSet("ECMC_EC_SLAVE_NUM", "1")
${SCRIPTEXEC} ${ecmccfg_DIR}configureSlave.cmd, "SLAVE_ID=$(ECMC_EC_SLAVE_NUM), HW_DESC=EL7031, CONFIG=-Motor-Trinamic-QMot-QSH4218-41-10-035"
epicsEnvSet("DRV_ID", "${ECMC_EC_SLAVE_NUM}")
${SCRIPTEXEC} ${ecmccfg_DIR}addSlave.cmd, "HW_DESC=EL2819"
epicsEnvSet("DO_ID", "${ECMC_EC_SLAVE_NUM}")
# Configure drv input 1 as drv enable
ecmcConfigOrDie "Cfg.EcAddSdo(${DRV_ID},0x8012,0x32,1,1)"
OK
# Control external drv enable
ecmcConfigOrDie "Cfg.WriteEcEntryIDString(${DO_ID},binaryOutput02,1)"
#Apply hardware configuration
ecmcConfigOrDie "Cfg.EcApplyConfig(1)"
##############################################################################
## AXIS 1
#
epicsEnvSet("DEV", "$(IOC)")
$(SCRIPTEXEC) ($(ecmccfg_DIR)configureAxis.cmd, CONFIG=./cfg/el7031.ax)
##############################################################################
## Load plugin: MOTION
#
epicsEnvSet(ECMC_PLUGIN_CONFIG,"PLUGIN_ID=1,AX=1,BUFF_SIZE=200,DBG=0,ENA=1")
require ecmc_plugin_motion master ${ECMC_PLUGIN_CONFIG}
# below needed at ESS but not PSI:
${SCRIPTEXEC} ${ecmc_plugin_motion_DIR}startup.cmd "${ECMC_PLUGIN_CONFIG}"
##############################################################################
############# Configure diagnostics:
ecmcConfigOrDie "Cfg.EcSetDiagnostics(1)"
ecmcConfigOrDie "Cfg.EcEnablePrintouts(0)"
ecmcConfigOrDie "Cfg.EcSetDomainFailedCyclesLimit(100)"
ecmcConfigOrDie "Cfg.SetDiagAxisIndex(1)"
ecmcConfigOrDie "Cfg.SetDiagAxisFreq(2)"
ecmcConfigOrDie "Cfg.SetDiagAxisEnable(0)"
##############################################################################
############# go active:
$(SCRIPTEXEC) ($(ecmccfg_DIR)setAppMode.cmd)
iocInit
dbl > pvs.log

View File

@@ -1,54 +0,0 @@
##############################################################################
## Example: Configuraftion for running ecmc motion plugin
##############################################################################
## Initiation:
epicsEnvSet("IOC" ,"$(IOC="IOC_TEST")")
epicsEnvSet("ECMCCFG_INIT" ,"") #Only run startup once (auto at PSI, need call at ESS), variable set to "#" in startup.cmd
epicsEnvSet("SCRIPTEXEC" ,"$(SCRIPTEXEC="iocshLoad")")
require ecmccfg "sandst_a_v9.0.1_RC1" "ECMC_VER=v9.0.1_RC1"
##############################################################################
## Configure hardware
epicsEnvSet("ECMC_EC_SLAVE_NUM", "4")
${SCRIPTEXEC} ${ecmccfg_DIR}configureSlave.cmd, "SLAVE_ID=$(ECMC_EC_SLAVE_NUM), HW_DESC=EL7031, CONFIG=-Motor-Trinamic-QMot-QSH4218-41-10-035"
epicsEnvSet("DRV_ID", "${ECMC_EC_SLAVE_NUM}")
${SCRIPTEXEC} ${ecmccfg_DIR}addSlave.cmd, "SLAVE_ID=6,HW_DESC=EL2008"
epicsEnvSet(DO_ID,${ECMC_EC_SLAVE_NUM})
#Apply hardware configuration
ecmcConfigOrDie "Cfg.EcApplyConfig(1)"
##############################################################################
## AXIS 1
#
epicsEnvSet("DEV", "$(IOC)")
$(SCRIPTEXEC) ($(ecmccfg_DIR)configureAxis.cmd, CONFIG=./cfg/el7031.ax)
##############################################################################
## Load plugin: MOTION
#
epicsEnvSet(ECMC_PLUGIN_CONFIG,"PLUGIN_ID=1,AX=1,BUFF_SIZE=200,DBG=0,ENA=1")
require ecmc_plugin_motion sandst_a "${ECMC_PLUGIN_CONFIG}"
# below needed at ESS but not PSI:
#${SCRIPTEXEC} ${ecmc_plugin_motion_DIR}startup.cmd "${ECMC_PLUGIN_CONFIG}"
##############################################################################
############# Configure diagnostics:
ecmcConfigOrDie "Cfg.EcSetDiagnostics(1)"
ecmcConfigOrDie "Cfg.EcEnablePrintouts(0)"
ecmcConfigOrDie "Cfg.EcSetDomainFailedCyclesLimit(100)"
ecmcConfigOrDie "Cfg.SetDiagAxisIndex(1)"
ecmcConfigOrDie "Cfg.SetDiagAxisFreq(2)"
ecmcConfigOrDie "Cfg.SetDiagAxisEnable(0)"
##############################################################################
############# go active:
$(SCRIPTEXEC) ($(ecmccfg_DIR)setAppMode.cmd)
iocInit
dbl > pvs.log