I ran into a problem with the acceleration code. All the acceleration phases work fine but on deceleration I get unnaturally long ends. Basically the motion decelerates and right before it should stop or transition into the next motion it just keeps on moving very slowly.
It’s rather setting dependent but generally seems to occur when the motion settings are pretty smooth. With jerky settings everything seems to be fine.
– using the grbl 0.7 code base
– running at pretty high feed rates, like 2500-20000
– only happens when I lower the acceleration setting to under 1500
评论 (21)
#2 – stefanix 于 2011-07-23
Basically when I set the acceleration to say 500 and the do motions at say at 5000 I get the long slopes at about 1 out of 4 motion ends. It’s pretty much does not seem to matter if I move the head in a rectangle or zig-zag shape. It seems almost any super smooth acceleration settings exhibit this. When I get back to my machine I can see if it is angle dependent or anything.
One consideration: the Lasersaur uses a direct belt drive which basically means that fast head motions are actually rather slow stepper motion compared to a leadscrew drive (I believe roughly a factor of 10 slower). My settings are along the following lines:
$0 = 32.808 (steps/mm x)
$1 = 32.808 (steps/mm y)
$2 = 32.808 (steps/mm z)
$3 = 30 (microseconds step pulse)
$4 = 10000.0 (mm/min default feed rate)
$5 = 20000.0 (mm/min default seek rate)
$6 = 0.100 (mm/arc segment)
$7 = 28 (step port invert mask. binary = 00011100)
$8 = 500.0 (acceleration in mm/sec^2)
$9 = 15.0 (max instant cornering speed change in delta mm/min)
#3 – simen 于 2011-07-24
I don’t have things set up right now and everything in Oslo is really really strange these days, so please bear with me. Could you just try out the edge branch and see if the error persists? I have fixed some things that might be related. If it is fixed in edge I will help you track down the relevant changes.
#4 – simen 于 2011-07-24
Forget it. I see you are quite up to date with the latest edge-patches. It’ll just have to wait a few days until I get the CNC set up for testing. I usually just use serial console and a logic analyzer, but this bug calls for real hardware.
#5 – stefanix 于 2011-07-27
I spend today in the shop trying to get an understanding of this issue. It is not so random after all. I made the following interesting observations:
The long slopes seem to be related to the anti-jerk code. When I set the $9 setting super high (basically saying, I don’t want corner jerk to be limited) I do not get any long slopes.
But, at all the corners where I had long slopes I get an unusually jerky speed changes. My head moves generally smooth but for some corners the accel/decel code seems to fail. Here is an example:
G0 X60 Y120 F20000
G1 X40 Y100
G0 X20 Y120
(here I get almost no accel/decel)
G1 X100 Y40 F3000
G0 X0 Y0
I have the suspicion the closer the corner is to 180deg and the more speed diff you have the more likely is that the accel/decel code produces something jerky.
My Grbl settings are:
$8 = 500.000 (acceleration in mm/sec^2)
$9 = 1000.000 (max instant cornering speed change in delta mm/min)
#6 – simen 于 2011-07-30
Please be patient. I still haven’t had time to run tests in my shop.
#7 – simen 于 2011-08-02
I think I know the cause of this behavior:
I added a finalrate field to blocks in order to know exactly when to stop decelerating. Because of unavoidable rounding issues the minimum speed may be reached a bit early, but because the deceleration is capped at finalrate that is fine in most cases – except if the final rate is very low, which it would regularly get if you have restrictive jerk limit, very high feed rate. A hack to verify this hypothesis is to set a lower rate limit when decelerating in trapezoid_tick in stepper.c. I am working from my phone right now, and it might still be some days until I can actually verify it.
A permanent fix is to make sure rounding errors always lead to final speed being reached a moment too late rather than early.
#8 – chamnit 于 2011-09-17
I’ve had some time to look into this problem. I have been experiencing the same issues at the end of deceleration and sometimes a weird motor stall would occur at the end of acceleration ramps. It seems to be very dependent on the acceleration setting, accelerationticksper_second, feedrate and the length of the planned line.
Simen, I did some testing and set the lower rate limit with not much success. After looking at the code and doing some testing, I now think this is coming from the differences between the estimateaccelerationdistance function and how grbl performs the acceleration ramps. The estimateaccelerationdistance is based on an exact integration of the constant acceleration equation of motion, but grbl does a discrete de/ac-celeration by the accelerationtickspersecond, a numerical integration. In other words, grbl can decelerate to the minimum speed too soon and hit the finalrate several steps before it should, because of the numerical integration trucation error. Round-off issues with ratedelta likely contribute, as well, but I think this depends on the situation. I’m looking to the math to see if there is an efficient way to compute a more accurate estimateacceleration_distance or some other way to account for this phenomenon simply and efficiently.
As for a stop-gap, I’ve had some success by tweaking the acceleration setting and the accelerationticksper_second parameter in the config.h (+/- 5) to shift the numerical error around so stalling problems don’t show up on my machine for the duration of a program.
#9 – chamnit 于 2011-09-18
Last night I had a chance to verify my theory. If I crank up the acceleration steps per second in the config.h file, the long slope problem steadily gets smaller and smaller. On my fork, I got it up to about 120L and the long slope problem was completely gone. Everywhere. Running at 360L made everything extremely smooth. Along with this, lowering the max accelerate should also reduce this problem too by creating a longer de/ac-eceleration, which lets grbl dg more discrete rate adjustments over it, making a more accurate with the exact solution.
#10 – aldenhart 于 2011-09-18
I just spent a bunch of time on this problem and came up with 2 functions to deal with the question. I’ve done this for constant jerk (not acceleration), so the results are probably more than you need for your immediate problem – but changing out the jerk for acceleration should actually make the equations simpler and less costly to compute. The functions are: gettargetvelocity() – which returns the achievable target velocity (Vt) given the starting velocity (Vi), the length of the move or ramp segment (L), and the max jerk (Jm). The other function is gettargetlength(), which returns the achievable length given the initial velocity (Vi), the target velocity (Vt), and the the max jerk (Jm). The equations are:
Vt = (sqrt(L)(L/sqrt(1/Jm))^(1/6)+(1/Jm)^(1/4)Vi)/(1/Jm)^(1/4)
L = abs(Vt-Vi)^(3/2) / sqrt(Jm)
I can post more details about the derivations if you think this would be of use in figuring out the accel cases.
#11 – pauljay 于 2011-09-20
I got same long slope at the end of decel. I watched it with Osciloscope. But it doesn’t happen always. When trail length is long, it happens. Is there anyone who fixed this ?
#12 – chamnit 于 2011-09-20
I’m working on it now. There seems to be multiple causes to this problem. Round-off error from integer math in the stepper rate conversions, numerical drift from too many discrete blocks in longer accelerations or not enough in shorter accelerations, the stepper curve following method, and truncation error from differences in numerical and exact integration of the accelerations. I’ve been able to already fix some of the more significant problems, but it may take me a while to make sure I have something that is solid for the rest. It will likely be posted on my fork probably in a few days.
#13 – pauljay 于 2011-09-21
Dear Sonny,
It’s good to hear from you fixing the bug now.
I have been testing grbl since last year. My major concern is to port GRBL
into ATXmega.
In the mean time, I have been using grbl also for testing my stepper driver.
I have achieved 38KHz step frequency maximum in grbl.
I had wanted to have 100KHz step frequency for high resolution microstep
driver.
But recently I found out the decelleration problem.
I don’t know why i couldn’t find it before.
I have a plan to make desktop manufacturing machines.
So I am currently designing a motion controller as well as step motor driver
with my team.
I have exchanged some ideas with Simen from last year.
I’ve made small PC application to send G-code to GRBL. I am using it for
myself only because the code is not smart.
It’s .net framework base on Windows OS only.
I hope you fix it and release it soon.
I appreciate your work.
Regards,
Paul J
On Wed, Sep 21, 2011 at 8:58 AM, Sonny Jeon < reply@reply.github.com>wrote:
> I’m working on it now. There seems to be multiple causes to this problem.
> Round-off error from integer math in the stepper rate conversions, numerical
> drift from too many discrete blocks in longer accelerations or not enough in
> shorter accelerations, the stepper curve following method, and truncation
> error from differences in numerical and exact integration of the
> accelerations. I’ve been able to already fix some of the more significant
> problems, but it may take me a while to make sure I have something that is
> solid for the rest. It will likely be posted on my fork probably in a few
> days.
>
> ##
>
> Reply to this email directly or view it on GitHub:
> https://github.com/simen/grbl/issues/35#issuecomment-2151262
#14 – aldenhart 于 2011-09-21
Paul, I have actually “ported” grbl to the xmega. But it’s more of a branch than a port. It’s morphed into a different code base for the TInyG project. You can get it on the Synthetos/TinyG github. The CNC code may or may not be of interest to you, but In any event, there is a lot of xmega specific code you may want. Startup, clock setting, interrupt handling, getting past the EEPROM/FLASH errata, etc. There is also a boot loader for the Xmegas written by Alex Forencich called xboot that we’ve implemented, but it’s not in the repo. Here’s a link for that: https://www.synthetos.com/blog/avr-xboot-on-tinyg/. Let me know if you are interested in any further details.
#15 – pauljay 于 2011-09-22
Thank you so much for your TinyG information. I have bought Boston Android
board. It doesn’t have JTAG pin. As soon as I put the JTAG pin on it, I
would like to run your TinyG code.
Do I need to install xboot to run TinyG ?
Or can I use other bootloader ?
I am not a professional to AVR programming.
Regards,
Paul J
On Wed, Sep 21, 2011 at 7:11 PM, Alden Hart < reply@reply.github.com>wrote:
> Paul, I have actually “ported” grbl to the xmega. But it’s more of a branch
> than a port. It’s morphed into a different code base for the TInyG project.
> You can get it on the Synthetos/TinyG github. The CNC code may or may not be
> of interest to you, but In any event, there is a lot of xmega specific code
> you may want. Startup, clock setting, interrupt handling, getting past the
> EEPROM/FLASH errata, etc. There is also a boot loader for the Xmegas written
> by Alex Forencich called xboot that we’ve implemented, but it’s not in the
> repo. Here’s a link for that:
> https://www.synthetos.com/blog/avr-xboot-on-tinyg/. Let me know if you
> are interested in any further details.
>
> ##
>
> Reply to this email directly or view it on GitHub:
> https://github.com/simen/grbl/issues/35#issuecomment-2154415
#16 – aldenhart 于 2011-09-22
Paul,
I actually prefer the Atmel AVRISP mkII programmer which supports the SPI protocol the xmegas require. The programmer is $35 and available from Mouser electronics, among others. I put xboot on there which is fine for occasional update, but the HW programmer is more reliable if you are doing a lot of flashing – which you will be if you are developing. I drive the AVR from Atmel AVRstudio4, but there are other, non-windows options as well. I’m not happy with the reliability of the AVRStudio5 beta yet.
Alden
On Sep 21, 2011, at 9:20 PM, pauljay wrote:
> Thank you so much for your TinyG information. I have bought Boston Android
> board. It doesn’t have JTAG pin. As soon as I put the JTAG pin on it, I
> would like to run your TinyG code.
> Do I need to install xboot to run TinyG ?
> Or can I use other bootloader ?
> I am not a professional to AVR programming.
>
> Regards,
>
> Paul J
>
> On Wed, Sep 21, 2011 at 7:11 PM, Alden Hart <
> reply@reply.github.com>wrote:
>
> > Paul, I have actually “ported” grbl to the xmega. But it’s more of a branch
> > than a port. It’s morphed into a different code base for the TInyG project.
> > You can get it on the Synthetos/TinyG github. The CNC code may or may not be
> > of interest to you, but In any event, there is a lot of xmega specific code
> > you may want. Startup, clock setting, interrupt handling, getting past the
> > EEPROM/FLASH errata, etc. There is also a boot loader for the Xmegas written
> > by Alex Forencich called xboot that we’ve implemented, but it’s not in the
> > repo. Here’s a link for that:
> > https://www.synthetos.com/blog/avr-xboot-on-tinyg/. Let me know if you
> > are interested in any further details.
> >
> > ##
> >
> > Reply to this email directly or view it on GitHub:
> > https://github.com/simen/grbl/issues/35#issuecomment-2154415
>
> ##
>
> Reply to this email directly or view it on GitHub:
> https://github.com/simen/grbl/issues/35#issuecomment-2162984
#17 – pauljay 于 2011-09-23
I have tested Chamnit grbl code and found out it works fine. No decel problem so far.
thanks for Chamnit work.
My configuration is as follows.
$0 = 200.000 (steps/mm x)
$1 = 200.000 (steps/mm y)
$2 = 200.000 (steps/mm z)
$3 = 10 (microseconds step pulse)
$4 = 500.000 (mm/min default feed rate)
$5 = 6000.000 (mm/min default seek rate)
$6 = 0.100 (mm/arc segment)
$7 = 1 (step port invert mask. binary = 1)
$8 = 100.000 (acceleration in mm/sec^2)
$9 = 0.050 (junction deviation for cornering in mm)
‘$x=value’ to set parameter or just ‘$’ to dump current settings
The step frequency as a result is 20KHz. I am using 10 microstep driver and ball screw pitch is 10mm.
The machine advances in 100mm/sec.
I am using IM483 step drivers.
#18 – chamnit 于 2011-09-23
Thanks for posting your results!
A while back I had posted a bugfix to correct how entry and exit
factors create unequal junction speeds on the same junction. Maybe
this could have got the main issue people are seeing with this, but
perhaps I’m seeing some minor residuals of some other problem on my
machine. Let me know if you run into any issues! I really want to try
to nail this thing down. Also did you increase the acceleration ticks
per second parameter in the config.h file?
Sonny
On Sep 22, 2011, at 8:35 PM, pauljay
reply@reply.github.com
wrote:
> I have tested Chamnit grbl code and found out it works fine. No decel problem so far.
> thanks for Chamnit work.
>
> My configuration is as follows.
>
> $0 = 200.000 (steps/mm x)
> $1 = 200.000 (steps/mm y)
> $2 = 200.000 (steps/mm z)
> $3 = 10 (microseconds step pulse)
> $4 = 500.000 (mm/min default feed rate)
> $5 = 6000.000 (mm/min default seek rate)
> $6 = 0.100 (mm/arc segment)
> $7 = 1 (step port invert mask. binary = 1)
> $8 = 100.000 (acceleration in mm/sec^2)
> $9 = 0.050 (junction deviation for cornering in mm)
> ‘$x=value’ to set parameter or just ‘$’ to dump current settings
>
> The step frequency as a result is 20KHz. I am using 10 microstep driver and ball screw pitch is 10mm.
> The machine advances in 100mm/sec.
> I am using IM483 step drivers.
>
> ##
>
> Reply to this email directly or view it on GitHub:
> https://github.com/simen/grbl/issues/35#issuecomment-2174737
#19 – chamnit 于 2011-09-23
OK. I have tracked down the main issue causing this problem. It’s in the stepper.c and it has to do with how and when the de/ac-celerations are done. To fix it, I applied the midpoint rule for curve approximation (or timed it the start of the velocity changes a little differently) and made sure the stepper interrupt would alway stop and start the accelerations and decelerations exactly on time. Tested it on my mill and worked fantastic.
The other stop-gap solution with increasing the ACCELERATIONSTEPSPER_SECOND in the config.h still applies, especially for people running very high accelerations and feedrates.
Expect the code to be post sometime this weekend on my fork.
#20 – aldenhart 于 2011-09-23
Great. I’ll give it a run on the Zen when you post it.
On Sep 23, 2011, at 6:25 PM, Sonny Jeon wrote:
> OK. I have tracked down the main issue causing this problem. It’s in the stepper.c and it has to do with how and when the de/ac-celerations are done. To fix it, I applied the midpoint rule for curve approximation (or timed it the start of the velocity changes a little differently) and made sure the stepper interrupt would alway stop and start the accelerations and decelerations exactly on time. Tested it on my mill and worked fantastic.
>
> The other stop-gap solution with increasing the ACCELERATIONSTEPSPER_SECOND in the config.h still applies, especially for people running very high accelerations and feedrates.
>
> Expect the code to be post sometime this weekend on my fork.
>
> ##
>
> Reply to this email directly or view it on GitHub:
> https://github.com/simen/grbl/issues/35#issuecomment-2183472
#21 – chamnit 于 2011-09-24
Ran a lot of test cases on my machine last night, and it all worked great! The code is now posted on my fork. Let me know if any of you run into any issues, as I’ll make sure to work on it more if it doesn’t fix the problem for some reason. Also, let me know if it works well for you too!
#1 – simen 于 2011-07-22
I’ll look into it asap. Just to speed things along could you post some g-code that exposes the problem? I have applied some changes to avoid that kind of errors lately.