Improving Grbl: Cornering Algorithm
Greasing the axle and pumping up the tires… on the metaphoric grbl wheel that is. I had spent some time to really understand the grbl source code these past few weeks, getting knee deep into the intricacies of it. More I had looked at it, the more I became impressed with Simen’s coding efficiency, showing what the little Arduino can do. In short, it can do a lot and still has plenty of room to grow. While grbl is still in development, I decided to take some initiative to help out and solve some problems still existing in the code, i.e. strange cornering behavior, full arc support with acceleration planning, and intermittent strange deceleration issues. As a researcher, I’m pretty much bound to document just about everything, even if it’s pretty insignificant. So here goes on part one.
The Cornering Algorithm: G-code motions involve piecewise linear movements, where each junction between these linear movements immediately turns and continues on to the next linear movement. The problem is that these junctions create problems with real-world CNC machines, since they can’t do these immediate and instantaneous changes in direction. Stepper motors have only a finite amount of torque and the high inertial forces required to make these quick direction changes can cause them to lose steps. The reason why this is so important is that stepper motor-based CNCs are open-loop control and have no feedback on what the motors are doing. A motor driver just knows that it received a step pulse and tries to move the motor. If it misses a step, the controller (grbl) has no idea and will lose its true position, resulting in a ruined part.
Simen had spent some time working on the problem of how to optimally solve for maximum junction speeds, such that to not exceed the maximum allowable acceleration limit of the machine. His approach is based on the euclidean norm of the entry and exit velocity vectors at the junction and limiting the maximum instantaneous change in velocity at the junction: . A good approximation for most applications, only if the
parameter is set correctly for the machine, but not robust for all situations and all machines. In some cases it leads to some strange behavior, like choppy and slow movements through tight curves. In technical terms, Simen’s solution is a linear fit to a nonlinear acceleration problem, but is quite computationally efficient.
To come up with more robust solution of this problem, it needs to be both accurate for all ranges of motion and just as computationally efficient. After some thought, here’s what I came up with: First let’s assume that at a junction of two line segments, we only look at centripetal acceleration to simply things. In other words, we assume the tangential velocity is zero and the velocity through it is constant. At the junction, let’s place a circle with a radius such that both lines are tangent to the circle. The circular segment joining the lines represents the path for constant centripetal acceleration:
. Where the maximum junction velocity
is the fastest speed the CNC can go through the junction without exceeding the CNC’s maximum allowable acceleration
.
This circular segment creates a virtual deviation from the path , which is defined as the distance from the junction to the edge of the circular segment. This
parameter is defined by the user as a setting, which indirectly sets the radius of the circle, and hence limits the junction velocity by the centripetal acceleration. Think of the this as widening a race track. If a race car is driving on a track only as wide as a car, it’ll have to slow down almost to a complete stop to turn corners. If we widen the track a bit, the car can start to use the track to go into the turn. The wider it is, the faster through the corner it can go.
An efficient computation of the circle radius is as follows. If you do the geometry in terms of the known variables, you get: . Re-arranging the equation in terms of circle radius
, you get:
. Theta
is defined as the angle between line segments given by the dot product equation:
. To solve for circle radius, there are two expensive trig functions, acos() and sin(), but these can be completely removed by the trig half angle identity:
. For our applications, this will always be positive.
Now just plug and chug these equations into the centripetal acceleration equation above. You’ll see that there are only two sqrt() computations per junction and absolutely no trig sin() or acos(). To then find the absolute maximum velocity through the junction, just apply: , to guarantee the junction speed never exceeds either the entry or exit speeds at the junction.
This approach is both computationally efficient and accounts for the junction nonlinearities of how sharp the angle is between line segments and how fast the CNC can travel through each junction. Meaning that for right angles or reversing, the computed maximum junction speed is at or near zero. For nearly straight junctions, the computed maximum junction speed is near or at the nominal feedrates, which mean it can fly through the junction without worrying about exceeding the acceleration limits. This has been successfully tested on my machine and by several very helpful users, who have reported that they can crank up the feed speeds of their machines and it runs much smoother through complex paths. Lastly, keep in mind this method is a virtual path deviation that is only used for robustly computing the junction speed and does not actually mean there is a physical path deviation in your CNC machine.
Downloaded src for 0.7 this morning. Reconfigured pins. Compiled via winavr. Uploaded in to my Ardunio. Works brilliant! Thank you so much. Been trying for two weeks to coax an older build to take gcode without locking up. Tried every setting I could find in NcPlot. All I
Hi, I just cloned grbl from the git-repo and changed the device to atmega32. I am facing a few problems:
– mc_dwell(..) in motion_control.c calls _delay_ms(var) but ot seems that this function only accepts constants?
– atmega32 has only one UART so I had to redefine all the UART regs mapping UARTREG0 to UARTREG
– there seems to be a similar problem for the timers in stepper.c
I read about plans for integrating a user interface (with lcd), how much idle time is left?
Nice work! (although I haven’ tested it yet)
Hi! Sorry as of now grbl only supports an atmega 328p and you’ll likely run into problems as you have if you change the processor. It’s likely it won’t run on a 32 without major hacking. The delay compile problem is fixed in the edge version and should be updated in the master when I get time.
As for an LCD, it’s been shelved for now. Time related mostly but it works great with my old Mac laptop so not much motivation to do it until grbl gets all the features that it needs.
Just a self-explaining gift:
http://www.eetimes.com/design/other/4026992/Linear-motor-control-without-the-math-item-1
http://picprog.strongedge.net/step_prof/step-profile.html
Greetings,
Walter
Hi Walter,
Thanks for the links. I’ve read these pages when first starting out on programming Grbl, but the eetimes.com “Linear motor control without the math” has some fundamental problems that the article doesn’t talk about. You have to have the resources to create the step profile and the math required (in particular a divide), doesn’t work for a wide range of stepper setups, then the algorithm has no issues. In other words, this algorithm requires a lot of uninhibited CPU cycles to get up to a high frequency/speed. The Arduino does have enough CPU speed for low frequency rates by itself, but not with g-code parsing and planning. The algorithm also has problems with numerical round-off and works only within a certain range. You really have to tune it to a particular stepper motor.
We’ve put in a lot of work to solve these issues, like lower the CPU overhead to allow for other simultaneous processes to occur, increase maximum frequency/speed without altering performance, working for a very wide range of steppers, and ensure that multi-axis step profiles are executed in sync and exact. I’ve been meaning to write up on this subject for a long time now, but haven’t had the time to do it. Perhaps when v1.0 comes out, I’ll post it.
Do we need Bresenham
The appropriate comment in the listing state’s that the heart of GRBL is Bresenham’s line algorithm. When looking it up I found this link:
http://www.cs.helsinki.fi/group/goa/mallinnus/lines/bresenh.html
It starts with the sentence: “Consider drawing a line on a raster grid where …”, it was right there I nearly stopped reading.
In a 3D-printer we don’t have a raster grid; so wy should we use Bresenham?
To move the printer head along a line not parallel to either the X-axis or the Y-axis, we can just slow down the the speed of one of the motors.
If for example the print head should move in a straight line from (2, 5) to (8, 2) it has to travel 6 units along the X-axis and 3 units along the Y-axis. To accomplish that we just have to reduce the speed of the Y-axis motor with a factor 3/6.
Am I right, or is this a silly thought of a newbe? If so, why?
Jan H. Kila
All stepper-based CNC machines move via integer step counts. The Bresenham algorithm very accurately and efficiently converts floating-point position values to step integer values. Acceleration and real-time motion planning is a lot more complicated that it looks and is still a heavily researched topic today.
Jan, from one newbie to another: A stepper-based CNC machine has a lot in common with a raster grid. I come from a computer graphics background, where raster-grids are bread-and-butter. When I learned that GRBL uses Bresenham’s line algorithm my first thought was how brilliant that was.
Although I understand why using Bresenham’s is smart, I can’t go much further before becoming lost in the code. Sonny is right. It is a lot more complicated than it looks.
Hi, thanks for this documentation!
I have a question regarding ‘delta’.
You say that ‘delta’ is just virtual, but how can you make a sharp corner (or any corner) without a full stop? Doesn’t it require an infinite acceleration?
If so, there must be some rounding of the corner.. isn’t it just the R as in your drawing?
What am I missing?
Thanks,
Ron
A physical machine isn’t infinitely stiff. It has some amount of elasticity. That rounding naturally occurs from the combination of the machine itself flexing from dynamic loads, tool deflection, spindle run-out, stepper motors slightly rotating, etc. This model simply estimates the amount of give, such that the stepper motors don’t lose steps, regardless of speed and angle. In practice, this model works very well on gantry-CNCs and larger milling machines, where you have a non-trivial amount of mass (spindle) you are moving around.
Hi Sonny,
Great post! it’s incredible how simple it is to do quick and accurate calculations if you have the right approach! Thank you for it. And thank you for working on the Grbl project.
I have been working on a collaborative robotic platform that works with series elastic transmission.
In the case of elastic structures limiting Jerk is important to avoid vibrations. I have solved the issue of the jerk with linear acceleration, however the jerk with centripetal acceleration is still to be solved. One approach is to insert 2 half Euler Spirals replacing the arc during the cornering but this means heavy calculations.
Obviously all this runs on 32 bit microprocessors.
I wonder if you have an insight on this.
Thank’s in advance,
Fernando.
Yes, I’ve looked at this problem of adding jerk to the cornering algorithm. This was quite involved to get a solution that would be able to be solved in realtime. It’s operating quite well in some Python simulations. Look for it in a future release.