Skip to content

Comments

Fix: Runaway in jog velocity mode#3820

Open
hdiethelm wants to merge 1 commit intoLinuxCNC:masterfrom
hdiethelm:fix_axis_jog_runaway
Open

Fix: Runaway in jog velocity mode#3820
hdiethelm wants to merge 1 commit intoLinuxCNC:masterfrom
hdiethelm:fix_axis_jog_runaway

Conversation

@hdiethelm
Copy link

While correcting issues in the xhc-whb04b-6 module (#3810), I found an issue in axis.c.

This can result in a crash, especially in Z axis if you have a tool in the spindle.

Steps to reproduce

  1. Start linuxcnc and load axis_mm sample
  2. Enable and home
  3. Go to MDI and execute G53 G0 X-254 (Negative limit)
  4. Go to Manual Control
  5. Open Halshow and add axis.x.jog-vel-mode / axis.x.jog-scale / axis.x.jog-enable / axis.x.jog-counts
  6. Set axis.x.jog-vel-mode = true / axis.x.jog-scale = 0.12 / axis.x.jog-enable = true
  7. Set axis.x.jog-counts = 1 -> Machine moves to x=-0.914 with full speed

I would expect the machine to move to x=-253.88

This happens on all axis and all limits. For simplicity, I just described X negative.

Analysis

The issue lies in https://github.com/LinuxCNC/linuxcnc/blob/master/src/emc/motion/axis.c

After homing, axis->pos_cmd is 0.0

G53 G0 X-254 moves the machine exactly to one of the limits.

Due to this, update_teleop_with_check returns true and axis->pos_cmd is not updated with the actual position:
https://github.com/LinuxCNC/linuxcnc/blob/master/src/emc/motion/axis.c#L677

When jogging in velocity mode, axis->pos_cmd is used to limit the next set-point:
https://github.com/LinuxCNC/linuxcnc/blob/master/src/emc/motion/axis.c#L421

Now with axis->pos_cmd == 0.0 while the machine is at -254, it moves with full speed to x=-0.914.

This issue exists on any axis when moving with gcode to one of the limits or your home position is at one of the limits and then manually jog in velocity mode to any direction.

I analyzed this with some printf debugging. See:
https://github.com/hdiethelm/linuxcnc-fork/tree/printf-debug

This was changed quite some time ago in:
784db03 control.c line 1312

Suggested fix

  • update_teleop_with_check already sets teleop_tp.curr_pos to the last position before the limit and teleop_tp.curr_vel = 0 if at or over the limit
  • axis->pos_cmd: This is only used for jogging in velocity mode. So this change should be save.
  • axis->teleop_vel_cmd: I think this should also be changed. However, I'm not so deep in the code that I'm sure they will be no side effects.

This fixes the above behavior. I will do some future testing next week in simulation and on my machine, but until now, I did not see any side effects.

@hdiethelm hdiethelm mentioned this pull request Feb 22, 2026
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Labels

None yet

Projects

None yet

Development

Successfully merging this pull request may close these issues.

1 participant