- Configuring LinuxCNC
- Advanced Configuration
- EtherCAT
- Leadshine 2CS3E-D507 / Cia402 almost working - help please!
Leadshine 2CS3E-D507 / Cia402 almost working - help please!
- jrc
- Away
- New Member
-
Less
More
- Posts: 11
- Thank you received: 1
29 Sep 2025 12:09 - 29 Sep 2025 12:10 #335540
by jrc
Leadshine 2CS3E-D507 / Cia402 almost working - help please! was created by jrc
I am trying to get Leadshine 2CS3E-D507 working to drive two closed-loop steppers to drive the carousel and arm of a toolchanger in simple pp mode.
I think I am very close, but need some help to get over the line.
Scott Laird's driver and the Cia402 component have gotten me to the point where the drive reaches OP state and I can see all the hal pins, but I have not managed to get the steppers to move.
To avoid the complexity of the rest of my machine, I have simply taken one of the sample configs (sim.axis-min), and added two extra joints (joints 3 and 4) for the two closed-loop steppers in the ini file , and added a hal file with what I hope are plausible lcec and cia402 settings. I have then connected the stepper drive to the machine with an Ethernet cable, Linuxcnc starts up OK with no complaints, and ehtercat slaves shows that the 2CS3E-D507 is sitting happily in OP state.
Looking at Machine>Show Hal configuration I can see all the lcec and cia402 pins. Setting setp cia402.0.enable 1 turns on the first joint and the same with cia.1.enable turns on the second one. I can see that this is the case because the LED display shows the corresponding dot. The display shows 88.8. where the dots denote one active axis each.
Reading the position of, say, the first stepper (lcec.0.0.srv-1-actual-position or cia402.0.drv-actual-position ) shows a value of "97", and the other one shows "2". These are arbitrary values corresponding to whatever position the shaft was turned to when powered up.
The corresponding "target position", however, is currently "0", but the drive is not trying to turn from position 97 to 0 at all.
In fact, it seems very determined to hold its current position, so you cannot turn the shaft by hand (which you can easily do when the drive is not enabled). It seems to resist any attempt to move it from its current position of 97
Trying to write a new target position using "setp" fails.
For example, if I try to set it to 700 :
using setp lcec.0.0.srv-1-actual-position 700, it complains that the pin is connected to a signal ( r1-drv-target-pos )
Using setp cia402.0.drv-actual-position 700, it complains " ERROR setting parameter 'cia402.0.drv-actual-position' to '700' pin 'cia402.0.drv-actual-position' is not writable"
The relevant line is the hal file is
net r1-drv-target-pos cia402.0.drv-target-position => lcec.0.0.srv-1-target-position
so I can understand the first complaint (the lcec is taking its input from the signal r1-drv-target-pos, which is getting its value from the cia402.0.drv-target-position pin), but I can't understand the second complaint ( the cia402target position pin not being writable), because one has to be able to tell the drive what the new position target is
Is here a simple fix I am missing, or am I going about this completely the wrong way, and if so, what do I need to change?
Since it's for a tool changer I would like to stick to pp mode rather than csp to simplify things.
I am attaching the .ini and .hal files, which are the only modified ones. All others are as per the normal sim-axis-min sample config in the standard installation.
Many thanks!
I think I am very close, but need some help to get over the line.
Scott Laird's driver and the Cia402 component have gotten me to the point where the drive reaches OP state and I can see all the hal pins, but I have not managed to get the steppers to move.
To avoid the complexity of the rest of my machine, I have simply taken one of the sample configs (sim.axis-min), and added two extra joints (joints 3 and 4) for the two closed-loop steppers in the ini file , and added a hal file with what I hope are plausible lcec and cia402 settings. I have then connected the stepper drive to the machine with an Ethernet cable, Linuxcnc starts up OK with no complaints, and ehtercat slaves shows that the 2CS3E-D507 is sitting happily in OP state.
Looking at Machine>Show Hal configuration I can see all the lcec and cia402 pins. Setting setp cia402.0.enable 1 turns on the first joint and the same with cia.1.enable turns on the second one. I can see that this is the case because the LED display shows the corresponding dot. The display shows 88.8. where the dots denote one active axis each.
Reading the position of, say, the first stepper (lcec.0.0.srv-1-actual-position or cia402.0.drv-actual-position ) shows a value of "97", and the other one shows "2". These are arbitrary values corresponding to whatever position the shaft was turned to when powered up.
The corresponding "target position", however, is currently "0", but the drive is not trying to turn from position 97 to 0 at all.
In fact, it seems very determined to hold its current position, so you cannot turn the shaft by hand (which you can easily do when the drive is not enabled). It seems to resist any attempt to move it from its current position of 97
Trying to write a new target position using "setp" fails.
For example, if I try to set it to 700 :
using setp lcec.0.0.srv-1-actual-position 700, it complains that the pin is connected to a signal ( r1-drv-target-pos )
Using setp cia402.0.drv-actual-position 700, it complains " ERROR setting parameter 'cia402.0.drv-actual-position' to '700' pin 'cia402.0.drv-actual-position' is not writable"
The relevant line is the hal file is
net r1-drv-target-pos cia402.0.drv-target-position => lcec.0.0.srv-1-target-position
so I can understand the first complaint (the lcec is taking its input from the signal r1-drv-target-pos, which is getting its value from the cia402.0.drv-target-position pin), but I can't understand the second complaint ( the cia402target position pin not being writable), because one has to be able to tell the drive what the new position target is
Is here a simple fix I am missing, or am I going about this completely the wrong way, and if so, what do I need to change?
Since it's for a tool changer I would like to stick to pp mode rather than csp to simplify things.
I am attaching the .ini and .hal files, which are the only modified ones. All others are as per the normal sim-axis-min sample config in the standard installation.
Many thanks!
Last edit: 29 Sep 2025 12:10 by jrc. Reason: typo
Please Log in or Create an account to join the conversation.
- Hakan
- Offline
- Platinum Member
-
Less
More
- Posts: 899
- Thank you received: 315
29 Sep 2025 12:25 #335541
by Hakan
Replied by Hakan on topic Leadshine 2CS3E-D507 / Cia402 almost working - help please!
At a quick glance, normally you would need to connect the joints to the cia402 components, see here github.com/dbraun1981/hal-cia402/blob/main/example/cia402.hal
In this case you can try to give a position value to cia402.0.pos-cmd
In this case you can try to give a position value to cia402.0.pos-cmd
Please Log in or Create an account to join the conversation.
- jrc
- Away
- New Member
-
Less
More
- Posts: 11
- Thank you received: 1
30 Sep 2025 08:03 #335608
by jrc
Replied by jrc on topic Leadshine 2CS3E-D507 / Cia402 almost working - help please!
Many thanks for your quick reply.
My hal file looks like this:
The missing part relative to the example you give me from dbraun is:
If I add that into my hal file , LinuxCNC fails to start and complains about being unable to execute certain SDO uploads:
The last item in the list about the motion-command-handler suggests that this is duplicating another one in the standard config. If I comment out the motion-command-handler and motion-controller lines of the dbraun additions., that message goes away but it still crashes on startup with a similar list of SDO complaints and a new one about being unable to add a pin:
@Hakan - Any further suggestions? Am I doing something dumb like omitting some essential pin definition, or ir is possible that the cia402 mappings are somehow not working for a dual-stepper drive for some reason?
@scottlaird - do you have a simple hal file that works for a 2CS3E-D507 and actually gets both closed-loop steppers to move? Ideally in pp mode if possible, but at a push CSP would also work with the risk of more complexity, which is not needed for a toolchanger.
My hal file looks like this:
loadusr -W lcec_conf ethercat-conf.xml
loadrt lcec
loadrt cia402 count=2
addf lcec.read-all servo-thread
addf cia402.0.read-all servo-thread
addf cia402.1.read-all servo-thread
addf cia402.0.write-all servo-thread
addf cia402.1.write-all servo-thread
addf lcec.write-all servo-thread
#*******************
# Right Carousel lcec.0.0 arm (r1) cia402.0 joint.3 platter (r2) cia402.1 joint.4
#*******************
## Carousel arm ##
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 r1-statusword lcec.0.0.srv-1-cia-statusword => cia402.0.statusword
net r1-opmode-display lcec.0.0.srv-1-opmode-display => cia402.0.opmode-display
net r1-drv-act-pos lcec.0.0.srv-1-actual-position => cia402.0.drv-actual-position
net r1-drv-act-vel lcec.0.0.srv-1-actual-velocity => cia402.0.drv-actual-velocity
# cia402 driver to ethercat
net r1-controlword cia402.0.controlword => lcec.0.0.srv-1-cia-controlword
net r1-modes-of-operation cia402.0.opmode => lcec.0.0.srv-1-opmode
net r1-drv-target-pos cia402.0.drv-target-position => lcec.0.0.srv-1-target-position
## Carousel Platter ##
setp cia402.1.enable 1
setp cia402.1.csp-mode 1
setp cia402.1.pos-scale 4000
# ethercat to cia402 driver
net r2-statusword lcec.0.0.srv-2-cia-statusword => cia402.1.statusword
net r2-opmode-display lcec.0.0.srv-2-opmode-display => cia402.1.opmode-display
net r2-drv-act-pos lcec.0.0.srv-2-actual-position => cia402.1.drv-actual-position
net r2-drv-act-vel lcec.0.0.srv-2-actual-velocity => cia402.1.drv-actual-velocity
# cia402 driver to ethercat
net r2-controlword cia402.1.controlword => lcec.0.0.srv-2-cia-controlword
net r2-modes-of-operation cia402.1.opmode => lcec.0.0.srv-2-opmode
net r2-drv-target-pos cia402.1.drv-target-position => lcec.0.0.srv-2-target-position
The missing part relative to the example you give me from dbraun is:
addf motion-command-handler servo-thread
addf motion-controller servo-thread
#from motion to cia
net r1-enable <= joint.3.amp-enable-out => cia402.0.enable
net r1-amp-fault => joint.3.amp-fault-in <= cia402.0.drv-fault
net r1-pos-cmd <= joint.3.motor-pos-cmd => cia402.0.pos-cmd
net r1-pos-fb => joint.3.motor-pos-fb <= cia402.0.pos-fb
net r2-enable <= joint.4.amp-enable-out => cia402.1.enable
net r2-amp-fault => joint.4.amp-fault-in <= cia402.1.drv-fault
net r2-pos-cmd <= joint.4.motor-pos-cmd => cia402.1.pos-cmd
net r2-pos-fb => joint.4.motor-pos-fb <= cia402.1.pos-fb
If I add that into my hal file , LinuxCNC fails to start and complains about being unable to execute certain SDO uploads:
Failed to execute SDO upload: Invalid argument
LCEC: slave 0.1: Failed to execute SDO upload (0x6502:0x00, error -22, abort_code 00000000)
Failed to execute SDO upload: Invalid argument
LCEC: slave 0.1: Failed to execute SDO upload (0x6060:0x00, error -22, abort_code 00000000)
Failed to execute SDO upload: Invalid argument
LCEC: slave 0.1: Failed to execute SDO upload (0x607a:0x00, error -22, abort_code 00000000)
Failed to execute SDO upload: Invalid argument
LCEC: slave 0.1: Failed to execute SDO upload (0x6d02:0x00, error -22, abort_code 00000000)
Failed to execute SDO upload: Invalid argument
LCEC: slave 0.1: Failed to execute SDO upload (0x6860:0x00, error -22, abort_code 00000000)
Failed to execute SDO upload: Invalid argument
LCEC: slave 0.1: Failed to execute SDO upload (0x687a:0x00, error -22, abort_code 00000000)
HAL: ERROR: function 'motion-command-handler' may only be added to one thread
./2CS3E_D507.hal:12: addf failed
The last item in the list about the motion-command-handler suggests that this is duplicating another one in the standard config. If I comment out the motion-command-handler and motion-controller lines of the dbraun additions., that message goes away but it still crashes on startup with a similar list of SDO complaints and a new one about being unable to add a pin:
Failed to execute SDO upload: Invalid argument
LCEC: slave 0.1: Failed to execute SDO upload (0x6502:0x00, error -22, abort_code 00000000)
Failed to execute SDO upload: Invalid argument
LCEC: slave 0.1: Failed to execute SDO upload (0x6060:0x00, error -22, abort_code 00000000)
Failed to execute SDO upload: Invalid argument
LCEC: slave 0.1: Failed to execute SDO upload (0x607a:0x00, error -22, abort_code 00000000)
Failed to execute SDO upload: Invalid argument
LCEC: slave 0.1: Failed to execute SDO upload (0x6d02:0x00, error -22, abort_code 00000000)
Failed to execute SDO upload: Invalid argument
LCEC: slave 0.1: Failed to execute SDO upload (0x6860:0x00, error -22, abort_code 00000000)
Failed to execute SDO upload: Invalid argument
LCEC: slave 0.1: Failed to execute SDO upload (0x687a:0x00, error -22, abort_code 00000000)
./2CS3E_D507.hal:36: Pin 'joint.3.amp-enable-out' does not exist
43420
Stopping realtime threads
Unloading hal components
Note: Using POSIX realtime
@Hakan - Any further suggestions? Am I doing something dumb like omitting some essential pin definition, or ir is possible that the cia402 mappings are somehow not working for a dual-stepper drive for some reason?
@scottlaird - do you have a simple hal file that works for a 2CS3E-D507 and actually gets both closed-loop steppers to move? Ideally in pp mode if possible, but at a push CSP would also work with the risk of more complexity, which is not needed for a toolchanger.
Please Log in or Create an account to join the conversation.
- Hakan
- Offline
- Platinum Member
-
Less
More
- Posts: 899
- Thank you received: 315
30 Sep 2025 09:18 #335611
by Hakan
Replied by Hakan on topic Leadshine 2CS3E-D507 / Cia402 almost working - help please!
You need those two motion-command controller statements, they should go in between the cia402.read-all and write-all as in the example file.
It won't move without those.
It was just an example to show how it is normally done.
You can set the pos-cmd in halshow, try that.
The two drives are distinguished by the variable name srv-2-var srv-1-var etc.
It won't move without those.
It was just an example to show how it is normally done.
You can set the pos-cmd in halshow, try that.
The two drives are distinguished by the variable name srv-2-var srv-1-var etc.
Please Log in or Create an account to join the conversation.
- jrc
- Away
- New Member
-
Less
More
- Posts: 11
- Thank you received: 1
30 Sep 2025 09:54 #335613
by jrc
Replied by jrc on topic Leadshine 2CS3E-D507 / Cia402 almost working - help please!
I added them back in and got the same error : HAL: ERROR: function 'motion-command-handler' may only be added to one thread
I think the simple minimal sim config I use as a starting point probably has those somewhere so it's complaining about duplicates
I think the simple minimal sim config I use as a starting point probably has those somewhere so it's complaining about duplicates
Please Log in or Create an account to join the conversation.
- Hakan
- Offline
- Platinum Member
-
Less
More
- Posts: 899
- Thank you received: 315
30 Sep 2025 13:28 #335617
by Hakan
Replied by Hakan on topic Leadshine 2CS3E-D507 / Cia402 almost working - help please!
Comment out this line in the ini file.Hope it doesn't mean a lot of extra errors but I think it might work.
Then give cia402.0.pos-cmd a value in halshow.
#HALFILE = LIB:basic_sim.tcl
Then give cia402.0.pos-cmd a value in halshow.
Please Log in or Create an account to join the conversation.
- jrc
- Away
- New Member
-
Less
More
- Posts: 11
- Thank you received: 1
30 Sep 2025 23:00 #335645
by jrc
Replied by jrc on topic Leadshine 2CS3E-D507 / Cia402 almost working - help please!
Many thanks! I am away today but will give it a try tomorrow and report back. I might also try making an even simpler test machine configuration with only xy coordinates, trivkins, drive by just one 2CS3E-D507 dual-stepper drive, This should hopefully be easier to debug due to having less confounding variables
Please Log in or Create an account to join the conversation.
- jrc
- Away
- New Member
-
Less
More
- Posts: 11
- Thank you received: 1
02 Oct 2025 10:38 #335700
by jrc
Replied by jrc on topic Leadshine 2CS3E-D507 / Cia402 almost working - help please!
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:
machine_xyz.ini:
2CS3E_D507.hal
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
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
Please Log in or Create an account to join the conversation.
- Hakan
- Offline
- Platinum Member
-
Less
More
- Posts: 899
- Thank you received: 315
02 Oct 2025 11:43 #335708
by Hakan
Replied by Hakan on topic Leadshine 2CS3E-D507 / Cia402 almost working - help please!
From that example/template I linked to before, you needin the hal file.
That should allow it to start I think.
That example/template is a working example. You have a bit different naming due to two motors per drive, but other than that it should work.
net emc-enable => iocontrol.0.emc-enable-in
sets emc-enable 1
That should allow it to start I think.
That example/template is a working example. You have a bit different naming due to two motors per drive, but other than that it should work.
Please Log in or Create an account to join the conversation.
- jrc
- Away
- New Member
-
Less
More
- Posts: 11
- Thank you received: 1
03 Oct 2025 10:19 - 03 Oct 2025 10:21 #335767
by jrc
Replied by jrc on topic Leadshine 2CS3E-D507 / Cia402 almost working - help please!
Many thanks!That got it to work beautifully and I can now easily jog the motors etc., the machine e-stop and machine start buttons on the screen work etc.
Last edit: 03 Oct 2025 10:21 by jrc. Reason: Totally mangled formatting (my fault)
Please Log in or Create an account to join the conversation.
- Configuring LinuxCNC
- Advanced Configuration
- EtherCAT
- Leadshine 2CS3E-D507 / Cia402 almost working - help please!
Time to create page: 0.133 seconds