Hello, I would like to add an EtherCAT IO device. What should I do

More
04 Aug 2024 03:13 #306894 by feng
# Generated by PNCconf at Sat Sep 10 10:10:56 2016
# If you make changes to this file, they will be
# overwritten when you run PNCconf again

loadrt [KINS]KINEMATICS
#autoconverted  trivkins
loadrt [EMCMOT]EMCMOT servo_period_nsec=[EMCMOT]SERVO_PERIOD num_joints=[KINS]JOINTS
loadusr -W lcec_conf ethercat-conf.xml
loadrt lcec
loadrt cia402 count=4

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 cia402.3.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 cia402.3.write-all       servo-thread

addf lcec.write-all           servo-thread

#*******************
#  AXIS X
#*******************

# --- joint signals for motion

net x-pos-cmd    <= joint.0.motor-pos-cmd
net x-vel-cmd    <= joint.0.vel-cmd
net x-pos-fb     <= joint.0.motor-pos-fb
net x-enable     <= joint.0.amp-enable-out

# --- connect stepper driver to joint

net x-pos-cmd    => cia402.0.pos-cmd
net x-pos-fb     => cia402.0.pos-fb
net x-enable     => cia402.0.enable

# --- ect60 settings

setp cia402.0.csp-mode 1
setp cia402.0.pos-scale 26214.4

# --- from stepper(ethercat) to cia402

net x-statusword      lcec.0.0.cia-statusword  => cia402.0.statusword
net x-opmode-display  lcec.0.0.opmode-display  => cia402.0.opmode-display
net x-drv-act-pos     lcec.0.0.actual-position => cia402.0.drv-actual-position
net x-drv-act-velo    lcec.0.0.actual-velocity => cia402.0.drv-actual-velocity

# --- from cia402 to stepper(ethercat) 

net x-controlword         cia402.0.controlword         => lcec.0.0.cia-controlword
net x-modes-of-operation  cia402.0.opmode              => lcec.0.0.opmode
net x-drv-target-pos      cia402.0.drv-target-position => lcec.0.0.target-position
net x-drv-target-velo     cia402.0.drv-target-velocity => lcec.0.0.target-velocity

#*******************
#  AXIS Y
#*******************

# --- joint signals for motion
net y-pos-cmd    <= joint.1.motor-pos-cmd
net y-vel-cmd    <= joint.1.vel-cmd
net y-pos-fb     <= joint.1.motor-pos-fb
net y-enable     <= joint.1.amp-enable-out

# --- connect stepper driver to the joint

net y-pos-cmd    => cia402.1.pos-cmd
net y-pos-fb     => cia402.1.pos-fb
net y-enable     => cia402.1.enable

# --- ect60 settings

setp cia402.1.csp-mode 1
setp cia402.1.pos-scale 26214.4

# --- from servo(ethercat) to cia402

net y-statusword      lcec.0.1.cia-statusword  => cia402.1.statusword
net y-opmode-display  lcec.0.1.opmode-display  => cia402.1.opmode-display
net y-drv-act-pos     lcec.0.1.actual-position => cia402.1.drv-actual-position
net y-drv-act-velo    lcec.0.1.actual-velocity => cia402.1.drv-actual-velocity

# --- from cia402 to servo(ethercat) 

net y-controlword         cia402.1.controlword         => lcec.0.1.cia-controlword
net y-modes-of-operation  cia402.1.opmode              => lcec.0.1.opmode
net y-drv-target-pos      cia402.1.drv-target-position => lcec.0.1.target-position
net y-drv-target-velo     cia402.1.drv-target-velocity => lcec.0.1.target-velocity


#*******************
#  AXIS z
#*******************

# --- joint signals for motion
net z-pos-cmd    <= joint.2.motor-pos-cmd
net z-vel-cmd    <= joint.2.vel-cmd
net z-pos-fb     <= joint.2.motor-pos-fb
net z-enable     <= joint.2.amp-enable-out

# --- connect stepper driver to the joint

net z-pos-cmd    => cia402.2.pos-cmd
net z-pos-fb     => cia402.2.pos-fb
net z-enable     => cia402.2.enable

# --- ect60 settings

setp cia402.2.csp-mode 1
setp cia402.2.pos-scale 26214.4

# --- from servo(ethercat) to cia402

net z-statusword      lcec.0.2.cia-statusword  => cia402.2.statusword
net z-opmode-display  lcec.0.2.opmode-display  => cia402.2.opmode-display
net z-drv-act-pos     lcec.0.2.actual-position => cia402.2.drv-actual-position
net z-drv-act-velo    lcec.0.2.actual-velocity => cia402.2.drv-actual-velocity

# --- from cia402 to servo(ethercat) 

net z-controlword         cia402.2.controlword         => lcec.0.2.cia-controlword
net z-modes-of-operation  cia402.2.opmode              => lcec.0.2.opmode
net z-drv-target-pos      cia402.2.drv-target-position => lcec.0.2.target-position
net z-drv-target-velo     cia402.2.drv-target-velocity => lcec.0.2.target-velocity


#*******************
#  SPINDLE
#*******************

# --- joint signals for motion

net spindle-speed-cmd spindle.0.speed-out => cia402.3.velocity-cmd
net spindle-speed-fb cia402.3.velocity-fb => spindle.0.speed-in
net spindle-on spindle.0.on => cia402.3.enable

# --- ect60 settings

setp cia402.3.csp-mode 0
setp cia402.3.pos-scale 4000
setp cia402.3.velo-scale 400

# --- from servo(ethercat) to cia402

net s-statusword      lcec.0.3.cia-statusword  => cia402.3.statusword
net s-opmode-display  lcec.0.3.opmode-display  => cia402.3.opmode-display
net s-drv-act-pos     lcec.0.3.actual-position => cia402.3.drv-actual-position
net s-drv-act-velo    lcec.0.3.actual-velocity => cia402.3.drv-actual-velocity

# --- from cia402 to servo(ethercat) 

net s-controlword         cia402.3.controlword         => lcec.0.3.cia-controlword
net s-modes-of-operation  cia402.3.opmode              => lcec.0.3.opmode
net s-drv-target-pos      cia402.3.drv-target-position => lcec.0.3.target-position
net s-drv-target-velo     cia402.3.drv-target-velocity => lcec.0.3.target-velocity


#*********************
#   E-STOP
#*********************

setp iocontrol.0.emc-enable-in 1


loadrt hal_parport cfg="0 in"
addf parport.0.read servo-thread
#addf mux4.0 servo-thread

# Jog Pendant
loadrt encoder num_chan=1
loadrt mux4 count=1
addf encoder.capture-position servo-thread
addf encoder.update-counters servo-thread
addf mux4.0 servo-thread

# If your MPG outputs a quadrature signal per click set x4 to 1
# If your MPG puts out 1 pulse per click set x4 to 0
setp encoder.0.x4-mode 0

# For velocity mode, set to 1
# In velocity mode the axis stops when the dial is stopped
# even if that means the commanded motion is not completed,
# For position mode (the default), set to 0
# In position mode the axis will move exactly jog-scale
# units for each count, regardless of how long that might take,
setp axis.x.jog-vel-mode 0
setp axis.y.jog-vel-mode 0
setp axis.z.jog-vel-mode 0

# This sets the scale that will be used based on the input to the mux4
setp mux4.0.in0 0.1
setp mux4.0.in1 0.01
setp mux4.0.in2 0.001

# The inputs to the mux4 component
net scale1 mux4.0.sel0 <= parport.0.pin-08-in-not
net scale2 mux4.0.sel1 <= parport.0.pin-07-in-not

# The output from the mux4 is sent to each axis jog scale
net mpg-scale <= mux4.0.out
net mpg-scale => axis.x.jog-scale
net mpg-scale => axis.y.jog-scale
net mpg-scale => axis.z.jog-scale

# The MPG inputs
net mpg-a encoder.0.phase-A <= parport.0.pin-13-in
net mpg-b encoder.0.phase-B <= parport.0.pin-10-in

# The Axis select inputs
net mpg-x axis.x.jog-enable <= parport.0.pin-15-in-not
net mpg-y axis.y.jog-enable <= parport.0.pin-11-in
net mpg-z axis.z.jog-enable <= parport.0.pin-14-in

# The encoder output counts to the axis. Only the selected axis will move.
net encoder-counts  <= encoder.0.counts
net encoder-counts => axis.x.jog-counts
net encoder-counts => axis.y.jog-counts
net encoder-counts => axis.z.jog-counts


lite@LinuxCNC:~$ sudo ethercat slaves
0  0:0  OP     +  L7EC-400S(COE)
1  0:1  OP     +  L7EC-400S(COE)
2  0:2  OP     +  L7EC-400S(COE)
3  0:3  PREOP  E  EM32DX-E4


/* Master 0, Slave 3, "EM32DX-E4"
 * Vendor ID:       0x00004321
 * Product code:    0x01100073
 * Revision number: 0x18050210
 */

ec_pdo_entry_info_t slave_3_pdo_entries[] = {
    {0x7000, 0x01, 16}, /* OUT */
    {0x6000, 0x01, 16}, /* IN */
};

ec_pdo_info_t slave_3_pdos[] = {
    {0x1600, 1, slave_3_pdo_entries + 0}, /* RxPDO0-Map */
    {0x1a00, 1, slave_3_pdo_entries + 1}, /* TxPDO1-Map */
};

ec_sync_info_t slave_3_syncs[] = {
    {0, EC_DIR_OUTPUT, 0, NULL, EC_WD_DISABLE},
    {1, EC_DIR_INPUT, 0, NULL, EC_WD_DISABLE},
    {2, EC_DIR_OUTPUT, 1, slave_3_pdos + 0, EC_WD_ENABLE},
    {3, EC_DIR_INPUT, 1, slave_3_pdos + 1, EC_WD_DISABLE},
    {0xff}
 

Please Log in or Create an account to join the conversation.

More
04 Aug 2024 03:36 #306895 by scottlaird
Leadshine has an amazing ability to put out products with multiple names and not document them clearly (at least in English) for months after they start slipping into the channel. So I'm not sure exactly what a EM32DX-E4 is. I can find pictures, and a manual in Chinese (oss.leisai.com/uploadfiles/EM32DX-E4%20%...%8B%E5%86%8CV3_1.pdf) that I *think* says that it's a 16-port in, 16-port out digital I/O board with something somewhat odd about the first 8 digital inputs and 4 digital outputs

Ignoring the "something somewhat odd" part, it looks pretty straightforward, 16 ins packed together at 0x6000 and 16 outs at 0x7000. It'd be pretty straightforward to modify one of the other packed digital I/O board drivers to support this hardware.

github.com/linuxcnc-ethercat/linuxcnc-ethercat/issues/434
The following user(s) said Thank You: DPFlex

Please Log in or Create an account to join the conversation.

More
04 Aug 2024 04:34 #306898 by rodw
It seems very similar to the Rtelligent ECT1616 which was very easy to work out with a generic driver like I did here.
github.com/rodw-au/linuxcnc-cia402/blob/...hercat-conf.xml#L158

It has some PWM functions as well.

Please Log in or Create an account to join the conversation.

More
04 Aug 2024 05:16 #306900 by onceloved
I think you are Chinese. If you are, add me on QQ and I will help you solve it.  QQ:304394405
The following user(s) said Thank You: rodw

Please Log in or Create an account to join the conversation.

Time to create page: 0.090 seconds
Powered by Kunena Forum