weird behavior: homing X messes up Y
- Kieran
- Offline
- Junior Member
-
Less
More
- Posts: 28
- Thank you received: 3
07 Jun 2025 04:01 #329861
by Kieran
weird behavior: homing X messes up Y was created by Kieran
Hey Guys. Im working on my A6 stepperonline servos on the bench currently. I got one axis going. Im trying to get a second axis involved. I got it working and linuxcnc launches without fault. I can jog both axis slowly before homing. I can home joint1 (Y) and still able to slowly jog. once I home X, I can jog it quickly, but cant jog Y at all. and if I fight the Y servo (its holding position), there doesn't appear to be any encoder feedback either once x is homed.
Please Log in or Create an account to join the conversation.
- Kieran
- Offline
- Junior Member
-
Less
More
- Posts: 28
- Thank you received: 3
07 Jun 2025 04:05 #329862
by Kieran
Replied by Kieran on topic weird behavior: homing X messes up Y
Warning: Spoiler!
# custom EtherCAT config
loadrt [KINS]KINEMATICS
loadrt [EMCMOT]EMCMOT servo_period_nsec=[EMCMOT]SERVO_PERIOD num_joints=[KINS]JOINTS
loadusr -W lcec_conf newcat.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 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 lcec.write-all servo-thread
setp iocontrol.0.emc-enable-in 1
#*******************
# AXIS X
#*******************
setp cia402.0.csp-mode 1
setp cia402.0.pos-scale [JOINT_0]PULSES_PER_MM
setp cia402.0.velo-scale [JOINT_0]PULSES_PER_MM
# joint signals for motion
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
# ethercat to cia402 driver
net x-statusword lcec.0.0.status-word => cia402.0.statusword
net x-drv-act-pos lcec.0.0.pos-actual => cia402.0.drv-actual-position
# cia402 driver to ethercat
net x-controlword cia402.0.controlword => lcec.0.0.control-word
net x-drv-target-pos cia402.0.drv-target-position => lcec.0.0.target-position
#*******************
# AXIS Y
#*******************
setp cia402.1.csp-mode 1
setp cia402.1.pos-scale [JOINT_1]PULSES_PER_MM
setp cia402.1.velo-scale [JOINT_1]PULSES_PER_MM
# joint signals for motion
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
# ethercat to cia402 driver
net y-statusword lcec.0.1.status-word => cia402.1.statusword
net y-drv-act-pos lcec.0.1.pos-actual => cia402.1.drv-actual-position
# cia402 driver to ethercat
net y-controlword cia402.1.controlword => lcec.0.1.control-word
net y-drv-target-pos cia402.1.drv-target-position => lcec.0.1.target-position
loadrt [KINS]KINEMATICS
loadrt [EMCMOT]EMCMOT servo_period_nsec=[EMCMOT]SERVO_PERIOD num_joints=[KINS]JOINTS
loadusr -W lcec_conf newcat.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 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 lcec.write-all servo-thread
setp iocontrol.0.emc-enable-in 1
#*******************
# AXIS X
#*******************
setp cia402.0.csp-mode 1
setp cia402.0.pos-scale [JOINT_0]PULSES_PER_MM
setp cia402.0.velo-scale [JOINT_0]PULSES_PER_MM
# joint signals for motion
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
# ethercat to cia402 driver
net x-statusword lcec.0.0.status-word => cia402.0.statusword
net x-drv-act-pos lcec.0.0.pos-actual => cia402.0.drv-actual-position
# cia402 driver to ethercat
net x-controlword cia402.0.controlword => lcec.0.0.control-word
net x-drv-target-pos cia402.0.drv-target-position => lcec.0.0.target-position
#*******************
# AXIS Y
#*******************
setp cia402.1.csp-mode 1
setp cia402.1.pos-scale [JOINT_1]PULSES_PER_MM
setp cia402.1.velo-scale [JOINT_1]PULSES_PER_MM
# joint signals for motion
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
# ethercat to cia402 driver
net y-statusword lcec.0.1.status-word => cia402.1.statusword
net y-drv-act-pos lcec.0.1.pos-actual => cia402.1.drv-actual-position
# cia402 driver to ethercat
net y-controlword cia402.1.controlword => lcec.0.1.control-word
net y-drv-target-pos cia402.1.drv-target-position => lcec.0.1.target-position
Warning: Spoiler!
<masters>
<master idx="0" appTimePeriod="1000000" refClockSyncCycles="1">
<slave idx="0" type="generic" vid="00400000" pid="00000715" configPdos="true" >
<dcConf assignActivate="300" sync0Cycle="*1" sync0Shift="25000"/>
<watchdog divider="2498" intervals="1000"/>
<syncManager idx="2" dir="out">
<pdo idx="1600">
<pdoEntry idx="6040" subIdx="00" bitLen="16" halPin="control-word" halType="u32"/>
<pdoEntry idx="607A" subIdx="00" bitLen="32" halPin="target-position" halType="s32"/>
<pdoEntry idx="60B8" subIdx="00" bitLen="16" halPin="touch-probe-function" halType="u32"/>
</pdo>
</syncManager>
<syncManager idx="3" dir="in">
<pdo idx="1A00">
<pdoEntry idx="6041" subIdx="00" bitLen="16" halPin="status-word" halType="u32"/>
<pdoEntry idx="6064" subIdx="00" bitLen="32" halPin="pos-actual" halType="s32"/>
<pdoEntry idx="60BA" subIdx="00" bitLen="32" halPin="touch-probe-1" halType="s32"/>
<pdoEntry idx="60BC" subIdx="00" bitLen="32" halPin="touch-probe-2" halType="s32"/>
<pdoEntry idx="60B9" subIdx="00" bitLen="16" halPin="touch-probe-status" halType="s32"/>
<pdoEntry idx="603F" subIdx="00" bitLen="16" halPin="fault-code" halType="s32"/>
<pdoEntry idx="60FD" subIdx="00" bitLen="32" halPin="DI-status" halType="u32"/>
<pdoEntry idx="60F4" subIdx="00" bitLen="32" halPin="follow-error" halType="s32"/>
</pdo>
</syncManager>
</slave>
<slave idx="1" type="generic" vid="00400000" pid="00000715" configPdos="true" >
<dcConf assignActivate="300" sync0Cycle="*1" sync0Shift="25000"/>
<watchdog divider="2498" intervals="1000"/>
<syncManager idx="2" dir="out">
<pdo idx="1600">
<pdoEntry idx="6040" subIdx="00" bitLen="16" halPin="control-word" halType="u32"/>
<pdoEntry idx="607A" subIdx="00" bitLen="32" halPin="target-position" halType="s32"/>
<pdoEntry idx="60B8" subIdx="00" bitLen="16" halPin="touch-probe-function" halType="u32"/>
</pdo>
</syncManager>
<syncManager idx="3" dir="in">
<pdo idx="1A00">
<pdoEntry idx="6041" subIdx="00" bitLen="16" halPin="status-word" halType="u32"/>
<pdoEntry idx="6064" subIdx="00" bitLen="32" halPin="pos-actual" halType="s32"/>
<pdoEntry idx="60BA" subIdx="00" bitLen="32" halPin="touch-probe-1" halType="s32"/>
<pdoEntry idx="60BC" subIdx="00" bitLen="32" halPin="touch-probe-2" halType="s32"/>
<pdoEntry idx="60B9" subIdx="00" bitLen="16" halPin="touch-probe-status" halType="s32"/>
<pdoEntry idx="603F" subIdx="00" bitLen="16" halPin="fault-code" halType="s32"/>
<pdoEntry idx="60FD" subIdx="00" bitLen="32" halPin="DI-status" halType="u32"/>
<pdoEntry idx="60F4" subIdx="00" bitLen="32" halPin="follow-error" halType="s32"/>
</pdo>
</syncManager>
</slave>
</master>
</masters>
<master idx="0" appTimePeriod="1000000" refClockSyncCycles="1">
<slave idx="0" type="generic" vid="00400000" pid="00000715" configPdos="true" >
<dcConf assignActivate="300" sync0Cycle="*1" sync0Shift="25000"/>
<watchdog divider="2498" intervals="1000"/>
<syncManager idx="2" dir="out">
<pdo idx="1600">
<pdoEntry idx="6040" subIdx="00" bitLen="16" halPin="control-word" halType="u32"/>
<pdoEntry idx="607A" subIdx="00" bitLen="32" halPin="target-position" halType="s32"/>
<pdoEntry idx="60B8" subIdx="00" bitLen="16" halPin="touch-probe-function" halType="u32"/>
</pdo>
</syncManager>
<syncManager idx="3" dir="in">
<pdo idx="1A00">
<pdoEntry idx="6041" subIdx="00" bitLen="16" halPin="status-word" halType="u32"/>
<pdoEntry idx="6064" subIdx="00" bitLen="32" halPin="pos-actual" halType="s32"/>
<pdoEntry idx="60BA" subIdx="00" bitLen="32" halPin="touch-probe-1" halType="s32"/>
<pdoEntry idx="60BC" subIdx="00" bitLen="32" halPin="touch-probe-2" halType="s32"/>
<pdoEntry idx="60B9" subIdx="00" bitLen="16" halPin="touch-probe-status" halType="s32"/>
<pdoEntry idx="603F" subIdx="00" bitLen="16" halPin="fault-code" halType="s32"/>
<pdoEntry idx="60FD" subIdx="00" bitLen="32" halPin="DI-status" halType="u32"/>
<pdoEntry idx="60F4" subIdx="00" bitLen="32" halPin="follow-error" halType="s32"/>
</pdo>
</syncManager>
</slave>
<slave idx="1" type="generic" vid="00400000" pid="00000715" configPdos="true" >
<dcConf assignActivate="300" sync0Cycle="*1" sync0Shift="25000"/>
<watchdog divider="2498" intervals="1000"/>
<syncManager idx="2" dir="out">
<pdo idx="1600">
<pdoEntry idx="6040" subIdx="00" bitLen="16" halPin="control-word" halType="u32"/>
<pdoEntry idx="607A" subIdx="00" bitLen="32" halPin="target-position" halType="s32"/>
<pdoEntry idx="60B8" subIdx="00" bitLen="16" halPin="touch-probe-function" halType="u32"/>
</pdo>
</syncManager>
<syncManager idx="3" dir="in">
<pdo idx="1A00">
<pdoEntry idx="6041" subIdx="00" bitLen="16" halPin="status-word" halType="u32"/>
<pdoEntry idx="6064" subIdx="00" bitLen="32" halPin="pos-actual" halType="s32"/>
<pdoEntry idx="60BA" subIdx="00" bitLen="32" halPin="touch-probe-1" halType="s32"/>
<pdoEntry idx="60BC" subIdx="00" bitLen="32" halPin="touch-probe-2" halType="s32"/>
<pdoEntry idx="60B9" subIdx="00" bitLen="16" halPin="touch-probe-status" halType="s32"/>
<pdoEntry idx="603F" subIdx="00" bitLen="16" halPin="fault-code" halType="s32"/>
<pdoEntry idx="60FD" subIdx="00" bitLen="32" halPin="DI-status" halType="u32"/>
<pdoEntry idx="60F4" subIdx="00" bitLen="32" halPin="follow-error" halType="s32"/>
</pdo>
</syncManager>
</slave>
</master>
</masters>
Warning: Spoiler!
# Generated by PNCconf at Thu Jan 2 12:17:30 2025
# Using LinuxCNC version: Master (2.9)
# EDITED
[EMC]
MACHINE = LinuxCNC-HAL-SIM-AXIS
DEBUG = 0
VERSION = 1.1
[DISPLAY]
DISPLAY = axis
POSITION_OFFSET = RELATIVE
POSITION_FEEDBACK = ACTUAL
MAX_FEED_OVERRIDE = 2.000000
MAX_SPINDLE_OVERRIDE = 1.000000
MIN_SPINDLE_OVERRIDE = 0.500000
INTRO_GRAPHIC = linuxcnc.gif
INTRO_TIME = 1
PROGRAM_PREFIX = /home/dave/linuxcnc/nc_files
INCREMENTS = 5mm 1mm .1mm 0.01mm .001mm
POSITION_FEEDBACK = ACTUAL
DEFAULT_LINEAR_VELOCITY = 500
MAX_LINEAR_VELOCITY = 250
MIN_LINEAR_VELOCITY = 0.01
DEFAULT_ANGULAR_VELOCITY = 12.000000
MAX_ANGULAR_VELOCITY = 180.000000
MIN_ANGULAR_VELOCITY = 1.666667
EDITOR = geany
GEOMETRY = xyz
CYCLE_TIME = 100
[FILTER]
PROGRAM_EXTENSION = .png,.gif,.jpg Greyscale Depth Image
PROGRAM_EXTENSION = .py Python Script
png = image-to-gcode
gif = image-to-gcode
jpg = image-to-gcode
py = python
[TASK]
TASK = milltask
CYCLE_TIME = 0.010
[RS274NGC]
PARAMETER_FILE = linuxcnc.var
RS274NGC_STARTUP_CODE = G21 G40 G90 G94 G97 G64 P0.001
[EMCMOT]
EMCMOT = motmod
COMM_TIMEOUT = 1.0
SERVO_PERIOD = 1000000
[HAL]
HALUI = halui
#HALFILE = Basic.hal
HALFILE = newcat.hal
#POSTGUI_HALFILE = custom_postgui.hal
#SHUTDOWN = shutdown.hal
[HALUI]
[KINS]
JOINTS = 2
KINEMATICS = trivkins coordinates=X kinstype=BOTH
[TRAJ]
COORDINATES = X
LINEAR_UNITS = mm
ANGULAR_UNITS = degree
DEFAULT_LINEAR_VELOCITY = 8.333
MAX_LINEAR_VELOCITY = 8.333
NO_FORCE_HOMING = 1
[EMCIO]
EMCIO = io
CYCLE_TIME = 0.100
TOOL_TABLE = tool.tbl
#******************************************
[AXIS_X]
MAX_VELOCITY = 250
MAX_ACCELERATION = 3000.0
MIN_LIMIT = -0.001
MAX_LIMIT = 2400.0
[AXIS_Y]
MAX_VELOCITY = 250
MAX_ACCELERATION = 3000.0
MIN_LIMIT = -0.001
MAX_LIMIT = 2400.0
[JOINT_0]
TYPE = LINEAR
HOME = 0.0
FERROR = 500.
MIN_FERROR = 5.
MAX_VELOCITY = 1.0
MAX_ACCELERATION = 30.0
PULSES_PER_MM = 26214
# The values below should be 25% larger than MAX_VELOCITY and MAX_ACCELERATION
# If using BACKLASH compensation STEPGEN_MAXACCEL should be 100% larger.
P = 1000.0
I = 0.0
D = 0.0
FF0 = 0.0
FF1 = 1.0
FF2 = 0.0
BIAS = 0.0
DEADBAND = 0.0
MAX_OUTPUT = 0.0
# these are in nanoseconds
MIN_LIMIT = -0.001
MAX_LIMIT = 2400.0
HOME_OFFSET = 0.0
HOME_SEQUENCE = 1
#******************************************
[JOINT_1]
TYPE = LINEAR
HOME = 0.0
FERROR = 500.
MIN_FERROR = 5.
MAX_VELOCITY = 1.0
MAX_ACCELERATION = 30.0
PULSES_PER_MM = 26214
# The values below should be 25% larger than MAX_VELOCITY and MAX_ACCELERATION
# If using BACKLASH compensation STEPGEN_MAXACCEL should be 100% larger.
P = 1000.0
I = 0.0
D = 0.0
FF0 = 0.0
FF1 = 1.0
FF2 = 0.0
BIAS = 0.0
DEADBAND = 0.0
MAX_OUTPUT = 0.0
# these are in nanoseconds
MIN_LIMIT = -0.001
MAX_LIMIT = 2400.0
HOME_OFFSET = 0.0
HOME_SEQUENCE = 1
#******************************************
# Using LinuxCNC version: Master (2.9)
# EDITED
[EMC]
MACHINE = LinuxCNC-HAL-SIM-AXIS
DEBUG = 0
VERSION = 1.1
[DISPLAY]
DISPLAY = axis
POSITION_OFFSET = RELATIVE
POSITION_FEEDBACK = ACTUAL
MAX_FEED_OVERRIDE = 2.000000
MAX_SPINDLE_OVERRIDE = 1.000000
MIN_SPINDLE_OVERRIDE = 0.500000
INTRO_GRAPHIC = linuxcnc.gif
INTRO_TIME = 1
PROGRAM_PREFIX = /home/dave/linuxcnc/nc_files
INCREMENTS = 5mm 1mm .1mm 0.01mm .001mm
POSITION_FEEDBACK = ACTUAL
DEFAULT_LINEAR_VELOCITY = 500
MAX_LINEAR_VELOCITY = 250
MIN_LINEAR_VELOCITY = 0.01
DEFAULT_ANGULAR_VELOCITY = 12.000000
MAX_ANGULAR_VELOCITY = 180.000000
MIN_ANGULAR_VELOCITY = 1.666667
EDITOR = geany
GEOMETRY = xyz
CYCLE_TIME = 100
[FILTER]
PROGRAM_EXTENSION = .png,.gif,.jpg Greyscale Depth Image
PROGRAM_EXTENSION = .py Python Script
png = image-to-gcode
gif = image-to-gcode
jpg = image-to-gcode
py = python
[TASK]
TASK = milltask
CYCLE_TIME = 0.010
[RS274NGC]
PARAMETER_FILE = linuxcnc.var
RS274NGC_STARTUP_CODE = G21 G40 G90 G94 G97 G64 P0.001
[EMCMOT]
EMCMOT = motmod
COMM_TIMEOUT = 1.0
SERVO_PERIOD = 1000000
[HAL]
HALUI = halui
#HALFILE = Basic.hal
HALFILE = newcat.hal
#POSTGUI_HALFILE = custom_postgui.hal
#SHUTDOWN = shutdown.hal
[HALUI]
[KINS]
JOINTS = 2
KINEMATICS = trivkins coordinates=X kinstype=BOTH
[TRAJ]
COORDINATES = X
LINEAR_UNITS = mm
ANGULAR_UNITS = degree
DEFAULT_LINEAR_VELOCITY = 8.333
MAX_LINEAR_VELOCITY = 8.333
NO_FORCE_HOMING = 1
[EMCIO]
EMCIO = io
CYCLE_TIME = 0.100
TOOL_TABLE = tool.tbl
#******************************************
[AXIS_X]
MAX_VELOCITY = 250
MAX_ACCELERATION = 3000.0
MIN_LIMIT = -0.001
MAX_LIMIT = 2400.0
[AXIS_Y]
MAX_VELOCITY = 250
MAX_ACCELERATION = 3000.0
MIN_LIMIT = -0.001
MAX_LIMIT = 2400.0
[JOINT_0]
TYPE = LINEAR
HOME = 0.0
FERROR = 500.
MIN_FERROR = 5.
MAX_VELOCITY = 1.0
MAX_ACCELERATION = 30.0
PULSES_PER_MM = 26214
# The values below should be 25% larger than MAX_VELOCITY and MAX_ACCELERATION
# If using BACKLASH compensation STEPGEN_MAXACCEL should be 100% larger.
P = 1000.0
I = 0.0
D = 0.0
FF0 = 0.0
FF1 = 1.0
FF2 = 0.0
BIAS = 0.0
DEADBAND = 0.0
MAX_OUTPUT = 0.0
# these are in nanoseconds
MIN_LIMIT = -0.001
MAX_LIMIT = 2400.0
HOME_OFFSET = 0.0
HOME_SEQUENCE = 1
#******************************************
[JOINT_1]
TYPE = LINEAR
HOME = 0.0
FERROR = 500.
MIN_FERROR = 5.
MAX_VELOCITY = 1.0
MAX_ACCELERATION = 30.0
PULSES_PER_MM = 26214
# The values below should be 25% larger than MAX_VELOCITY and MAX_ACCELERATION
# If using BACKLASH compensation STEPGEN_MAXACCEL should be 100% larger.
P = 1000.0
I = 0.0
D = 0.0
FF0 = 0.0
FF1 = 1.0
FF2 = 0.0
BIAS = 0.0
DEADBAND = 0.0
MAX_OUTPUT = 0.0
# these are in nanoseconds
MIN_LIMIT = -0.001
MAX_LIMIT = 2400.0
HOME_OFFSET = 0.0
HOME_SEQUENCE = 1
#******************************************
Please Log in or Create an account to join the conversation.
- Kieran
- Offline
- Junior Member
-
Less
More
- Posts: 28
- Thank you received: 3
07 Jun 2025 04:13 #329863
by Kieran
Replied by Kieran on topic weird behavior: homing X messes up Y
DUH...... I think i fixed it.
COORDINATES = X
changed to
COORDINATES = XY
KINEMATICS = trivkins coordinates=X
changed to
KINEMATICS = trivkins coordinates=XY
oops.
weird how it didnt error out.
COORDINATES = X
changed to
COORDINATES = XY
KINEMATICS = trivkins coordinates=X
changed to
KINEMATICS = trivkins coordinates=XY
oops.
weird how it didnt error out.
Please Log in or Create an account to join the conversation.
- Kieran
- Offline
- Junior Member
-
Less
More
- Posts: 28
- Thank you received: 3
09 Jun 2025 03:44 #329991
by Kieran
Replied by Kieran on topic weird behavior: homing X messes up Y
Ok, more Q's.... Im messing with PDO now. i ran ethercat pdos
heres my working XML snippet
question is, why doesnt it work anymore if i switch from <pdo idx="1600"> to <pdo idx="1701"> for example. why is it using 1600 and 1A00 and working even though "ethercat pdos" spits out 1701 and 1Bo1? I want to use something other than 1600/1A00 because they only have a few PDOs available on my servos. they are "variable PDO" according to the manual. Just trying to understand how this all works.
Warning: Spoiler!
cnc1@CNC1:~$ ethercat pdos
=== Master 0, Slave 0 ===
SM0: PhysAddr 0x1000, DefaultSize 256, ControlRegister 0x26, Enable 1
SM1: PhysAddr 0x1400, DefaultSize 256, ControlRegister 0x22, Enable 1
SM2: PhysAddr 0x1800, DefaultSize 12, ControlRegister 0x64, Enable 1
RxPDO 0x1701 ""
PDO entry 0x6040:00, 16 bit, ""
PDO entry 0x607a:00, 32 bit, ""
PDO entry 0x60b8:00, 16 bit, ""
PDO entry 0x60fe:01, 32 bit, ""
SM3: PhysAddr 0x1c00, DefaultSize 28, ControlRegister 0x20, Enable 1
TxPDO 0x1b01 ""
PDO entry 0x603f:00, 16 bit, ""
PDO entry 0x6041:00, 16 bit, ""
PDO entry 0x6064:00, 32 bit, ""
PDO entry 0x6077:00, 16 bit, ""
PDO entry 0x60f4:00, 32 bit, ""
PDO entry 0x60b9:00, 16 bit, ""
PDO entry 0x60ba:00, 32 bit, ""
PDO entry 0x60bc:00, 32 bit, ""
PDO entry 0x60fd:00, 32 bit, ""
=== Master 0, Slave 0 ===
SM0: PhysAddr 0x1000, DefaultSize 256, ControlRegister 0x26, Enable 1
SM1: PhysAddr 0x1400, DefaultSize 256, ControlRegister 0x22, Enable 1
SM2: PhysAddr 0x1800, DefaultSize 12, ControlRegister 0x64, Enable 1
RxPDO 0x1701 ""
PDO entry 0x6040:00, 16 bit, ""
PDO entry 0x607a:00, 32 bit, ""
PDO entry 0x60b8:00, 16 bit, ""
PDO entry 0x60fe:01, 32 bit, ""
SM3: PhysAddr 0x1c00, DefaultSize 28, ControlRegister 0x20, Enable 1
TxPDO 0x1b01 ""
PDO entry 0x603f:00, 16 bit, ""
PDO entry 0x6041:00, 16 bit, ""
PDO entry 0x6064:00, 32 bit, ""
PDO entry 0x6077:00, 16 bit, ""
PDO entry 0x60f4:00, 32 bit, ""
PDO entry 0x60b9:00, 16 bit, ""
PDO entry 0x60ba:00, 32 bit, ""
PDO entry 0x60bc:00, 32 bit, ""
PDO entry 0x60fd:00, 32 bit, ""
heres my working XML snippet
Warning: Spoiler!
<!-- X axis servo -->
<slave idx="0" type="generic" vid="00400000" pid="00000715" configPdos="true" >
<dcConf assignActivate="300" sync0Cycle="*1" sync0Shift="25000"/>
<watchdog divider="2498" intervals="1000"/>
<syncManager idx="2" dir="out">
<pdo idx="1600">
<pdoEntry idx="6040" subIdx="00" bitLen="16" halPin="control-word" halType="u32"/>
<pdoEntry idx="6060" subIdx="00" bitLen="8" halPin="opmode" halType="s32"/>
<pdoEntry idx="607A" subIdx="00" bitLen="32" halPin="target-position" halType="s32"/>
<pdoEntry idx="60B8" subIdx="00" bitLen="16" halPin="touch-probe-function" halType="u32"/>
</pdo>
</syncManager>
<syncManager idx="3" dir="in">
<pdo idx="1A00">
<pdoEntry idx="6041" subIdx="00" bitLen="16" halPin="status-word" halType="u32"/>
<pdoEntry idx="6064" subIdx="00" bitLen="32" halPin="pos-actual" halType="s32"/>
<pdoEntry idx="60BA" subIdx="00" bitLen="32" halPin="touch-probe-1" halType="s32"/>
<pdoEntry idx="60BC" subIdx="00" bitLen="32" halPin="touch-probe-2" halType="s32"/>
<pdoEntry idx="60B9" subIdx="00" bitLen="16" halPin="touch-probe-status" halType="s32"/>
<pdoEntry idx="603F" subIdx="00" bitLen="16" halPin="fault-code" halType="s32"/>
<pdoEntry idx="60FD" subIdx="00" bitLen="32" halPin="DI-status" halType="u32"/>
<pdoEntry idx="60F4" subIdx="00" bitLen="32" halPin="follow-error" halType="s32"/>
<pdoEntry idx="6077" subIdx="00" bitLen="16" halPin="actual-torque" halType="s32"/>
</pdo>
</syncManager>
</slave>
<slave idx="0" type="generic" vid="00400000" pid="00000715" configPdos="true" >
<dcConf assignActivate="300" sync0Cycle="*1" sync0Shift="25000"/>
<watchdog divider="2498" intervals="1000"/>
<syncManager idx="2" dir="out">
<pdo idx="1600">
<pdoEntry idx="6040" subIdx="00" bitLen="16" halPin="control-word" halType="u32"/>
<pdoEntry idx="6060" subIdx="00" bitLen="8" halPin="opmode" halType="s32"/>
<pdoEntry idx="607A" subIdx="00" bitLen="32" halPin="target-position" halType="s32"/>
<pdoEntry idx="60B8" subIdx="00" bitLen="16" halPin="touch-probe-function" halType="u32"/>
</pdo>
</syncManager>
<syncManager idx="3" dir="in">
<pdo idx="1A00">
<pdoEntry idx="6041" subIdx="00" bitLen="16" halPin="status-word" halType="u32"/>
<pdoEntry idx="6064" subIdx="00" bitLen="32" halPin="pos-actual" halType="s32"/>
<pdoEntry idx="60BA" subIdx="00" bitLen="32" halPin="touch-probe-1" halType="s32"/>
<pdoEntry idx="60BC" subIdx="00" bitLen="32" halPin="touch-probe-2" halType="s32"/>
<pdoEntry idx="60B9" subIdx="00" bitLen="16" halPin="touch-probe-status" halType="s32"/>
<pdoEntry idx="603F" subIdx="00" bitLen="16" halPin="fault-code" halType="s32"/>
<pdoEntry idx="60FD" subIdx="00" bitLen="32" halPin="DI-status" halType="u32"/>
<pdoEntry idx="60F4" subIdx="00" bitLen="32" halPin="follow-error" halType="s32"/>
<pdoEntry idx="6077" subIdx="00" bitLen="16" halPin="actual-torque" halType="s32"/>
</pdo>
</syncManager>
</slave>
question is, why doesnt it work anymore if i switch from <pdo idx="1600"> to <pdo idx="1701"> for example. why is it using 1600 and 1A00 and working even though "ethercat pdos" spits out 1701 and 1Bo1? I want to use something other than 1600/1A00 because they only have a few PDOs available on my servos. they are "variable PDO" according to the manual. Just trying to understand how this all works.
Please Log in or Create an account to join the conversation.
- esmurf
- Offline
- New Member
-
Less
More
- Posts: 16
- Thank you received: 2
09 Jun 2025 12:36 #330012
by esmurf
Replied by esmurf on topic weird behavior: homing X messes up Y
as per manual there is only one variable receive and one variable transmit PDO : 0x1600 and 0x1A00.
Each is limited to 10 entries.
You should see some error messages in /var/log/messages.
If you need more than 10 entries, you can use SDO instead of the 0x1600 PDO.
SDOs can be queried/set with "ethercat upload" or "ethercat download".
SDOs are permanently saved to the servo controller, so this is useful for nonchanging config parameters only.
Each is limited to 10 entries.
You should see some error messages in /var/log/messages.
If you need more than 10 entries, you can use SDO instead of the 0x1600 PDO.
SDOs can be queried/set with "ethercat upload" or "ethercat download".
SDOs are permanently saved to the servo controller, so this is useful for nonchanging config parameters only.
Please Log in or Create an account to join the conversation.
- Kieran
- Offline
- Junior Member
-
Less
More
- Posts: 28
- Thank you received: 3
10 Jun 2025 17:03 #330095
by Kieran
Replied by Kieran on topic weird behavior: homing X messes up Y
ok I guess I need to do more reading on how the PDO works. the servo manual lists other PDOs that aren't listed in the 1600 and 1A00 registers, such as 606C(speed feedback). how would one use these other PDOs? I guess I dont see what fixed PDOs actually do.
Please Log in or Create an account to join the conversation.
- esmurf
- Offline
- New Member
-
Less
More
- Posts: 16
- Thank you received: 2
11 Jun 2025 04:15 #330123
by esmurf
Replied by esmurf on topic weird behavior: homing X messes up Y
You add a new pdoentry for 606C to the 1A00 PDO in your ethercat-conf.xml file. In this entry idx, subidx, bitlen, is from the A6 manual, you chose a name for "halPin".
Inside you hal file you can then use that name. E.g. like lcec.0.X.yourname
In this example 0 is your first ethercat interface, X is the name of your slave. See "halshow" -> Pins ...
Inside you hal file you can then use that name. E.g. like lcec.0.X.yourname
In this example 0 is your first ethercat interface, X is the name of your slave. See "halshow" -> Pins ...
The following user(s) said Thank You: Kieran
Please Log in or Create an account to join the conversation.
Time to create page: 0.082 seconds