LinuxCNC S-Curve Accelerations
I have done some coding in the past to integrate s-curve : github.com/grotius-cnc/S-curve-motion-planning
This code is working and tested on real hardware but not finished.
When you are at speed and do a second acceleration, that piece of code is not finished.
I could finish the code soon.
At the moment i have a stripped down lcnc version. archive-link
The purpose is to use the hal layer and to use components like linuxcnc-ethercat with qt c++.
The graphical environment is opencascade.
The motion planning is done in c++ and goes into the hal servo threat. A hal stepgen component is the back-end pid controller in rt.
Please Log in or Create an account to join the conversation.
That would probably be the only way to find out, unless someone chimes in and says they're using that feature. But making interpolation the responsibility of kinematics and keeping the feature seems like a better idea!I would guess not. But how would you know? We can change the code and see if anyone sues, I suppose.
If interpolation is done by kinematics (no not "in" kinematics), that would mean kinematics delivers not only joint positions but also velocity and acceleration setpoints (since those come from the interpolator today). It'd be natural to feed the velocity and acceleration setpoints from the planners into kinematics as well, so that trivkins could just feed them through. More complicated kins could either use the interpolator or use some other algorithm, more suitable for the specific kinematics. Or differentiate, of course.I don't think that _in_ the kins is the way to go. But in that area makes sense.
This ties in to something that I keep meaning to try..
Kins is maths. If we calculate kins at "then" "now" and "next" then we know joint velocity and joint accel. Nearly as good is "then-1", "then", "no", ie a 2-deep buffer. In either case we can use kins as numerical differentiation to stay within Joint velocity and accel limits.
Not sure how you would use those values to keep within the joint limits though? Dynamically adjust net_feed_scale? That could be done today if someone writes the code - the datapoints already exist.
Please Log in or Create an account to join the conversation.
Of course this assumes that I've drawn correct conclusions about the purpose of the cubic interpolator; that coord_tp produces a trajectory that is suitable for use without being filtered by the interpolator. That remains to be seen I guess.But making interpolation the responsibility of kinematics and keeping the feature seems like a better idea!
Anyway, first step is to get jerk-limited joint jogging to work, and that doesn't require touching kinematics or interpolation at all. I think I have enough understanding of the code at the moment to get on with that.
Please Log in or Create an account to join the conversation.
We are at a lower level than line or arc segments here, in emc/motion/control.c. Look at the code starting at line 1309, case EMCMOT_MOTION_COORD. If the cubic interpolator needs a new point, tpRunCycle() and tpGetPos() are run on coord_tp to get a new cartesian position command (carte_pos_cmd). This is run through inverse kinematics. The results are assigned to the respective joint's coarse_pos member, and are also fed into the cubic interpolator.
Then as a final step the actual "fine" joint position (joint->pos_cmd) as well as velocity and acceleration commands are gotten from the cubic interpolator.
I haven't looked into the cubic interpolator, but maybe this significantly reduces the cpu load by running the inverse kinematics much more seldom than otherwise needed? It looks like it isn't run at the servo rate after all (unless the interpolator requests a new point every cycle).
After some more code reading: The "traj period" is a parameter to motmod.so. It is set to the servo period if not specified .
This ends up in the interpolator via github.com/LinuxCNC/linuxcnc/blob/master...otion/motion.c#L1019 resp. github.com/LinuxCNC/linuxcnc/blob/master...otion/motion.c#L1050
Ok, so this explains why the output from teleop_tp is run through the interpolator: it allows to run inverse kinematics at a lower rate than the servo thread, during axis jogs, by specifying traj_period_nsec to be larger than servo_period_nsec.
Then a new question arises: is this feature still meaningful today? The only reason to use it that I can see is if inverse kinematics is too slow to fit in a servo period, and then you'd get a realtime delay in the servo thread each time the traj period is reached anyway.
I think in this design, inverse kinematics should always be able fo finish within a servo period. Maybe on a single-core machine with "non-trivial" kinematics you wouldn't have enough CPU time left to update GUI or do other userspace-stuff. I don't think that is of any concern even on older multicore CPUs.
Something off-topic: is it just me or do quotes in the forum really look strange?
Please Log in or Create an account to join the conversation.
- tommylight
- Away
- Moderator
- Posts: 19188
- Thank you received: 6433
Yea, the lettering gets bigger.Something off-topic: is it just me or do quotes in the forum really look strange?
Please Log in or Create an account to join the conversation.
- tommylight
- Away
- Moderator
- Posts: 19188
- Thank you received: 6433
And that keeps happening ....
Yea, the lettering gets bigger.Something off-topic: is it just me or do quotes in the forum really look strange?
Please Log in or Create an account to join the conversation.
Did you clicked twice?
I think in this design, inverse kinematics should always be able fo finish within a servo period.
That can be done for (simple) interpolation algoritmes, like xyz.
For robot's (more complicated kinematics) there are ca 120 iterations preferred each cycle. The approach of designing it for a single servo period would result in a slower to set servo-period.
Then as a argument, the "look ahead" integration stay's important. And the s-curve algoritme must be added to the above mentioned itterations.
Coming day's i hope to finish a s-curve position control with a look ahead buffer in ms.
I hope to construct some kind of dynamic code that can fill up the buffer when the kinematics are easy to solve.
When the buffer is full and kinematics are complex,
the machine is at full load, then it will do a auto slow down to get optimized results if the programmed speed can't be reached.
It's quite a hard job to modify the lcnc code. Respect & Good luck !
Please Log in or Create an account to join the conversation.
- tommylight
- Away
- Moderator
- Posts: 19188
- Thank you received: 6433
Nope ... but i did reply twice as sometimes that causes the letters to go even bigger!Did you clicked twice?
Please Log in or Create an account to join the conversation.
For information.
A example program to calculate (preprocess) a s-curve with visual output.
Without the visual output, it's quite impossible to know if every bit of c++ code is written correctly.
It can deal with :
Waypoints = 3d waypoint buffer ( path points )
Vo = initial velocity (pos or neg)
Ve = velocity at end (pos or neg)
Vel = max velocity (sampled to best fit when vel cannot be reached within path lenght)
Acc = acceleration
github.com/grotius-cnc/S-curve-motion-pl...g/releases/tag/1.0.1
My personal goal is to strip down this example program and compile it to a shared library .so file to use with
a motion planner as preprocess function for path planning.
The code can output x,y,z coordinates for every ms.
But you can also interpolate a x,y,z coordinate at a certain time point.
There are various options.
Please Log in or Create an account to join the conversation.
What is it that we're seeing in the diagrams? I'm guessing the black curve is acceleration? Red/white velocity? But I can't figure out the grey one - if it's position then the start and end slopes seem wrong (horizontal although endpoint velocities are nonzero in the first image). And there's the discontinuity in the slope in the middle.
Also note that you will have to handle initial acceleration that's nonzero too, if it's to be usable for jogging. That should not be necessary for the "coordinated motion" planner though.
Please Log in or Create an account to join the conversation.