Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

issues about emcmotSetCycleTime() #3268

Open
fantacyhuang opened this issue Jan 11, 2025 · 8 comments
Open

issues about emcmotSetCycleTime() #3268

fantacyhuang opened this issue Jan 11, 2025 · 8 comments

Comments

@fantacyhuang
Copy link

fantacyhuang commented Jan 11, 2025

I am a student learning motion control,There are some parts that I believe have issues.
function in motion.c:

void emcmotSetCycleTime(unsigned long nsec )
{
    int servo_mult;
    servo_mult = traj_period_nsec / nsec;
    if(servo_mult < 0) servo_mult = 1;
    setTrajCycleTime(nsec * 1e-9);
    setServoCycleTime(nsec * servo_mult * 1e-9);
}

The trajectory planning cycle should be an integer multiple of the servo cycle. The trajectory cycle is used for coarse interpolation, while the servo cycle uses cubic spline curves for fine interpolation.
The correct function logic, in my opinion, is:

void emcmotSetCycleTime(unsigned long nsec )
{
    int servo_mult;
    servo_mult = traj_period_nsec / nsec;
    if(servo_mult < 0) servo_mult = 1;
    setServoCycleTime(nsec * 1e-9);
    setTrajCycleTime(nsec * servo_mult * 1e-9);
}
@andypugh
Copy link
Collaborator

What you say makes sense, but it seems unlikely that LinuxCNC would have worked at all for so long if this was wrong in a way that mattered.
The function is called in one place:
https://github.com/LinuxCNC/linuxcnc/blob/master/src/emc/motion/control.c#L240
And the function itself then does a second calculation of interpolation_rate:
https://github.com/LinuxCNC/linuxcnc/blob/master/src/emc/motion/motion.c#L1061

So maybe it all works out as it should? Or maybe there really is something wrong, but nobody has ever noticed.

I am travelling all this weekend so can't look much deeper than this, but if you have time to look through what actually happens in detail then that would be useful.

@andypugh
Copy link
Collaborator

Looking at the github "blame" view there may be some clues as to why and when this code was introduced.
163d25e
This mentions a bug SF#2478266
This dates from when LinuxCNC was hosted on Sourceforge, but fortunately is still archived there.
https://sourceforge.net/p/emc/bugs/175/

@fantacyhuang
Copy link
Author

Hello, I apologize for disturbing you on the weekend, but I am really eager to clarify this issue, to the point where it has been troubling me to the extent that I am unable to sleep.
I tried adding some log in the emcmotSetCycleTime() function, attempting to print some important information:

void emcmotSetCycleTime(unsigned long nsec )
{
    int servo_mult;
    servo_mult = traj_period_nsec / nsec;
    if(servo_mult < 0) servo_mult = 1;
    setTrajCycleTime(nsec * 1e-9);
    setServoCycleTime(nsec * servo_mult * 1e-9);

    rtapi_print_msg(RTAPI_MSG_ERR, "after emcmotSetCycleTime() called, servoCycleTime:%f\n", emcmotConfig->servoCycleTime);
    rtapi_print_msg(RTAPI_MSG_ERR, "TP config:\n");
    rtapi_print_msg(RTAPI_MSG_ERR, "\t cycleTime:%f\n", emcmotInternal->coord_tp.cycleTime);
    rtapi_print_msg(RTAPI_MSG_ERR, "cubic config:\n");
    rtapi_print_msg(RTAPI_MSG_ERR, "\t interpolationRate:%d\n", joints[0].cubic.interpolationRate);
    rtapi_print_msg(RTAPI_MSG_ERR, "\t segmentTime:%f\n", joints[0].cubic.segmentTime);
    rtapi_print_msg(RTAPI_MSG_ERR, "\t interpolationIncrement:%f\n", joints[0].cubic.interpolationIncrement);
}

Then, I run linuxcnc/configs/sim/axis/pentapod/pentapod.ini,PERIOD setting is:

[EMCMOT]
EMCMOT =              motmod
COMM_TIMEOUT =          1.0
COMM_WAIT =             0.010
SERVO_PERIOD =               1000000
TRAJ_PERIOD =                10000000

Below is the information printed when starting LinuxCNC:

after emcmotSetCycleTime() called, servoCycleTime:0.001000
TP config:
	 cycleTime:0.001000
cubic config:
	 interpolationRate:1
	 segmentTime:0.001000
	 interpolationIncrement:0.001000

What might be wrong? Although I set TRAJ_PERIOD to be ten times SERVO_PERIOD, the interpolationRate for cubic is still 1. I believe the correct result should be 10.

@andypugh
Copy link
Collaborator

pentakins uses core_sim.hal (via basic_sim.tcl) and that does not set traj_period from the INI.

See also http://linuxcnc.org/docs/stable/html/config/core-components.html#sec:motion

@fantacyhuang
Copy link
Author

fantacyhuang commented Jan 12, 2025

Hello, I used a new ini file and loaded TRAJ_PERIOD in the hal file.
file path: linuxcnc/configs/sim/gmoccapy/6_axis.ini

[EMCMOT]
EMCMOT =              motmod
COMM_TIMEOUT = 1.0
BASE_PERIOD  = 50000
SERVO_PERIOD = 100000
TRAJ_PERIOD  = 1000000

loadrt [EMCMOT]EMCMOT base_period_nsec=[EMCMOT]BASE_PERIOD servo_period_nsec=[EMCMOT]SERVO_PERIOD traj_period_nsec=[EMCMOT]TRAJ_PERIOD num_joints=[KINS]JOINTS
I still printed some log information as follows:

after emcmotSetCycleTime() called, servoCycleTime:0.001000
TP config:
	 cycleTime:0.000100
cubic config:
	 interpolationRate:1
	 segmentTime:0.001000
	 interpolationIncrement:0.001000

I have two points of confusion:

  1. Why is tp.cycleTime ten times smaller than servoCycleTime?
  2. Why is cubic.interpolationRate equal to 1?
    I found a similar question online, but no one answered it.See https://sourceforge.net/p/emc/mailman/message/9754661/

@andypugh
Copy link
Collaborator

Is it possible that the traj period isn't even used?

emcmot runs in the servo thread. I think that to run traj at a slower rate the system would have to simply skip that code on a certain proportion of invocations. (as there isn't a slower thread for traj to be run in).

Is that what actually happens?

@fantacyhuang
Copy link
Author

fantacyhuang commented Jan 17, 2025

Hello, I recently went through the code of the Trajectory Planner module in linuxcnc and studied the relationships between several cycles, including servoCycleTime, trajCycleTime, and cubic.segmentTime.

In lines 1327 to 1387 of the control.c file, we can find some clues.

case EMCMOT_MOTION_COORD:

I think that the role of the TP (Trajectory Planner) is to calculate trajectory points (carte_pos_cmd) in the Cartesian coordinate system under the trajectory planning cycle (trajCycleTime), then convert carte_pos_cmd into joint positions (joint->coarse_pos) through inverse kinematics. To reduce motor vibrations during operation, cubic polynomials (cubic.c) are used for fine interpolation in the joint space, resulting in control commands for each servo cycle (joint->pos_cmd). Therefore, I think the following equations hold:

trajCycleTime = cubic.segmentTime;
trajCycleTime = servoCycleTime * n.

@andypugh
Copy link
Collaborator

andypugh commented Feb 2, 2025

I have been intending to look into this, but haven't found the time.
Did you find anything else out?

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

No branches or pull requests

2 participants