I had a bit of time today to try things out.
I did as you suggested and commented out the line which includes the basic_sim.tcl line
This produced a different error - it was unable to add all the servo-thread entries
" HAL : ERROR: thread 'servo-thread' not found "
Looking into basic_sim.tcl I can find no instances of servo-thread.
However, basic_sim.tcl includes another file in line 33 called sim_lib.tcl
sim_lib.tcl has servo-thread appear in a lot of places
So it seems like some version of it is needed if we go the route of recycling one of the sim configs as a starting point
Any ideas on how to solve this one?
As a different possible solution, I created a different XYZ machine using two units of 2CS3E-D507, where the first one handles X and Y and the second handles Z. That way we start out totally away from the possible comlplications from the sim universe and directly go to a machine that only has two real, Ethercat devices,
This seems to load OK, but LinuxCNC starts up with the e-stop engaged and won't let me toggle it off.
The configs I created for this are:
ethercat-conf-xml:
<masters>
<master idx="0" appTimePeriod="1000000" refClockSyncCycles="-1">
<slave idx="0" type="2CS3E-D507">
<!-- <dcConf assignActivate="700" sync0Cycle="*1" sync0Shift="0" sync1Cycle="*1" sync1Shift="0"/> -->
<dcConf assignActivate="300" sync0Cycle="*1" sync0Shift="0"/>
</slave>
<slave idx="1" type="2CS3E-D507">
<!-- <dcConf assignActivate="700" sync0Cycle="*1" sync0Shift="0" sync1Cycle="*1" sync1Shift="0"/> -->
<dcConf assignActivate="300" sync0Cycle="*1" sync0Shift="0"/>
</slave>
</master>
</masters>
machine_xyz.ini:
[EMC]
MACHINE = machine_xyz
VERSION = 1.1
DEBUG=0x00000242
[DISPLAY]
DISPLAY = axis
MAX_LINEAR_VELOCITY = 1
[TASK]
TASK = milltask
CYCLE_TIME = 0.001
[RS274NGC]
# NoneType object has no attribute 'rfind'
PARAMETER_FILE = machine_xyz.var
[EMCIO]
EMCIO = io
CYCLE_TIME = 0.100
[EMCMOT]
EMCMOT = motmod
SERVO_PERIOD = 1000000
[HAL]
# new addition to test Leadshine 2CS3E-D507
HALFILE = 2CS3E_D507xyz.hal
[TRAJ]
COORDINATES = XYZ
LINEAR_UNITS = mm
ANGULAR_UNITS = degree
DEFAULT_LINEAR_VELOCITY = 2.50
MAX_LINEAR_VELOCITY = 25.00
[KINS]
JOINTS = 3
KINEMATICS = trivkins coordinates=XYZ
#*** AXIS_X *******************************
[AXIS_X]
MAX_VELOCITY = 50.0
MAX_ACCELERATION = 750.0
MIN_LIMIT = -300.0
MAX_LIMIT = 300.0
[JOINT_0]
TYPE = LINEAR
HOME = 0.0
MIN_LIMIT = -300.0
MAX_LIMIT = 300.0
MAX_VELOCITY = 25.0
MAX_ACCELERATION = 750.0
#*** AXIS_Y *******************************
[AXIS_Y]
MAX_VELOCITY = 25.0
MAX_ACCELERATION = 750.0
MIN_LIMIT = -300.0
MAX_LIMIT = 300.0
[JOINT_1]
TYPE = LINEAR
HOME = 0.0
MIN_LIMIT = -300.0
MAX_LIMIT = 300.0
MAX_VELOCITY = 25.0
MAX_ACCELERATION = 750.0
#*** AXIS_Z *******************************
[AXIS_Z]
MAX_VELOCITY = 25.0
MAX_ACCELERATION = 750.0
MIN_LIMIT = -300.0
MAX_LIMIT = 300.0
[JOINT_2]
TYPE = LINEAR
HOME = 0.0
MIN_LIMIT = -300.0
MAX_LIMIT = 300.0
MAX_VELOCITY = 25.0
MAX_ACCELERATION = 750.0
2CS3E_D507.hal
loadrt [KINS]KINEMATICS
loadrt [EMCMOT]EMCMOT servo_period_nsec=[EMCMOT]SERVO_PERIOD num_joints=3
loadusr -W lcec_conf ethercat-conf.xml
loadrt lcec
loadrt cia402 count=3
addf lcec.read-all servo-thread
addf cia402.0.read-all servo-thread
addf cia402.1.read-all servo-thread
addf cia402.2.read-all servo-thread
addf motion-command-handler servo-thread
addf motion-controller servo-thread
addf cia402.0.write-all servo-thread
addf cia402.1.write-all servo-thread
addf cia402.2.write-all servo-thread
addf lcec.write-all servo-thread
#*******************
# X axis lcec.0.0 (x) cia402.0 joint.0 Y axis lcec.0.0 cia402.1 joint.1 Z axis lcec.0.1 cia402.1 joint 2
#*******************
setp cia402.0.enable 1
#setp cia402.0.opmode 1
setp cia402.0.csp-mode 1
setp cia402.0.pos-scale 4000
# ethercat to cia402 driver
net x-statusword lcec.0.0.srv-1-cia-statusword => cia402.0.statusword
net x-opmode-display lcec.0.0.srv-1-opmode-display => cia402.0.opmode-display
net x-drv-act-pos lcec.0.0.srv-1-actual-position => cia402.0.drv-actual-position
net x-drv-act-vel lcec.0.0.srv-1-actual-velocity => cia402.0.drv-actual-velocity
# cia402 driver to ethercat
net x-controlword cia402.0.controlword => lcec.0.0.srv-1-cia-controlword
net x-modes-of-operation cia402.0.opmode => lcec.0.0.srv-1-opmode
net x-drv-target-pos cia402.0.drv-target-position => lcec.0.0.srv-1-target-position
#from motion to cia
net x-enable <= joint.0.amp-enable-out => cia402.0.enable
net x-amp-fault => joint.0.amp-fault-in <= cia402.0.drv-fault
net x-pos-cmd <= joint.0.motor-pos-cmd => cia402.0.pos-cmd
net x-pos-fb => joint.0.motor-pos-fb <= cia402.0.pos-fb
## Y axis ##
setp cia402.1.enable 1
#setp cia402.1.opmode 1
setp cia402.1.csp-mode 1
setp cia402.1.pos-scale 4000
# ethercat to cia402 driver
net y-statusword lcec.0.0.srv-2-cia-statusword => cia402.1.statusword
net y-opmode-display lcec.0.0.srv-2-opmode-display => cia402.1.opmode-display
net y-drv-act-pos lcec.0.0.srv-2-actual-position => cia402.1.drv-actual-position
net y-drv-act-vel lcec.0.0.srv-2-actual-velocity => cia402.1.drv-actual-velocity
# cia402 driver to ethercat
net y-controlword cia402.1.controlword => lcec.0.0.srv-2-cia-controlword
net y-modes-of-operation cia402.1.opmode => lcec.0.0.srv-2-opmode
net y-drv-target-pos cia402.1.drv-target-position => lcec.0.0.srv-2-target-position
#from motion to cia
net y-enable <= joint.1.amp-enable-out => cia402.1.enable
net y-amp-fault => joint.1.amp-fault-in <= cia402.1.drv-fault
net y-pos-cmd <= joint.1.motor-pos-cmd => cia402.1.pos-cmd
net y-pos-fb => joint.1.motor-pos-fb <= cia402.1.pos-fb
# homing
#net y-home-request joint.1.request-custom-homing => cia402.1.home
#net y-homing joint.1.is-custom-homing <= cia402.1.stat-homing
#net y-homed joint.1.custom-homing-finished <= cia402.1.stat-homed
## Z axis ##
setp cia402.2.enable 1
#setp cia402.2.opmode 1
setp cia402.2.csp-mode 1
setp cia402.2.pos-scale 4000
# ethercat to cia402 driver
net z-statusword lcec.0.1.srv-1-cia-statusword => cia402.2.statusword
net z-opmode-display lcec.0.1.srv-1-opmode-display => cia402.2.opmode-display
net z-drv-act-pos lcec.0.1.srv-1-actual-position => cia402.2.drv-actual-position
net z-drv-act-vel lcec.0.1.srv-1-actual-velocity => cia402.2.drv-actual-velocity
# cia402 driver to ethercat
net z-controlword cia402.2.controlword => lcec.0.1.srv-1-cia-controlword
net z-modes-of-operation cia402.2.opmode => lcec.0.1.srv-1-opmode
net z-drv-target-pos cia402.2.drv-target-position => lcec.0.1.srv-1-target-position
#from motion to cia
net z-enable <= joint.2.amp-enable-out => cia402.2.enable
net z-amp-fault => joint.2.amp-fault-in <= cia402.2.drv-fault
net z-pos-cmd <= joint.2.motor-pos-cmd => cia402.2.pos-cmd
net z-pos-fb => joint.2.motor-pos-fb <= cia402.2.pos-fb
# homing
#net z-home-request joint.2.request-custom-homing => cia402.2.home
#net z-homing joint.2.is-custom-homing <= cia402.2.stat-homing
#net z-homed joint.2.custom-homing-finished <= cia402.2.stat-homed
Any ideas on how to get this one to start? I tried to make it as basic as possible to avoid anything else distracting things.
To reiterate, it loads correctly and LinuxCNC starts without an error screen popping up, but the e-stop on the top left of the axis interface screen is toggled on when it starts and can't be toggled off.
ethercat slaves shows both 2CS3E-D507 slaves in OP state