A Software Solution to Eliminate Ringing?
-
@PCR
Its always going to be hybrid.I would make the case that this specific thing (software compensation for position error) is about getting the printer to actually do what you told it to do. If the printer was more rigid, the function would not be needed. Therefore, it falls into the same category as basic things like steps per mm.
And it has applicability for any motion control done with RRF/Duet, not just FFF.Functions like Preload in KISSlicer (not that I have used it), are material specific, not just machine specific. So it has to be in the slicer to work correctly.
And its a function that only works for FFF.@PCR said in A Software Solution to Eliminate Ringing?:
Only a quick thought. I really like the idea of a slicer setting for that.
For what?
If you mean filament diameter, my point was that we could be using a volumetric value, people don't because there's no real advantage to it and we all got into the habit of futzing with the slicer setting to get certain effects... But if most printers had an accurate device for measuring filament diameter as it went into the extruder, it would produce more accurate prints.
Not to a degree that I think most people would notice though. Which is why its not a thing. -
Another update.
Before sharing the python code, I wanted to test it on at least one other printer. This time on a cartesian (CoreXY) printer with CPC linear rails. The printer x-axis is made up of one single 15mm rail with a sole runner block holding the hotend and extruder assembly. The rail itself is very rigid. The weak point is instead the x-axis carrier/runner block that has a bit of yield to its roll axis (resulting in ringing along the y axis).
In getting the calibration done for this printer I learned a number of new things. First, and very importantly there are actually two modes of ringing. The first one is the one we classicality think of as ringing. It occurs after the printer has decelerates down to a full stop and the end effector oscillates. The photo below illustrates this.
The second type of ringing was something I hadn’t considered before. It’s ringing that happens during the acceleration phase. If you look carefully you can see it happening in the simulation in the first figure in https://www.digitalvision.blog/spring-damper-control. The effect may look subtle in that animation, but the result on an actual print is much more substantial. The effect is that the extrusion bead gets stretched and compressed periodically.
The effect of this is what I suspect often prevents getting consistent extrusion when printing at high speeds. The extrusion gets ripped apart in the stretching phase. After correcting for this ringing I’ve been able to print consistently even at 150 mm/s with 10 m/s² accelerations, something that I’ve never managed before.
When observing ringing on a print, you will often see a compound effect of both of these two modes of ringing, with the acceleration ringing from e.g. the x-axis compounding with the post-deceleration ringing from the y-axis. When the two axes have different natural spring frequencies the two axis parameters can be hard to tease apart. For that reason, I came up with the strategy of isolating one axis at a time by setting the acceleration limits of the other axis to a very low value. E.g. 10 m/s² acceleration on the y axis with 0.5 m/s² acceleration on the x.
My final issue with calibrating this printer was that I was unable to find a single setting that eliminated the ringing on both the left and right side of the print. The left side had a ringing frequency of ~52 Hz with the right side closer to 60 Hz. It seems like the ringing had different frequencies when moving in the positive y direction vs the negative. Thinking a bit about this I came up with a model that makes sense. The print head is not perfectly balanced under the axis with the center of gravity being offset to one side. This effectively means that gravity is applying pre-tension on the spring biasing the spring effect towards one direction. To test this hypothesis I implemented an asymmetric spring model and plugging in 52 and 60 Hz respectively for the two axes did the trick.
-
Here's the python test code if anyone wants to give this a shot.
https://github.com/OskarLinde/dynamic-motion
The link contains some preliminary instructions for how to use and calibrate the method. You need at least RRF 2.03 since without the
M566 P1
jerk policy the G-Code doesn't execute reliably. I was able to run this on an unmodified firmware for simple objects, but found that I could increase the discretization points and run more complex objects if I made a minor firmware change: I disabled the motion planner (look_ahead) if the current move speeds were below the current instantaneous velocity change settings. With this, the extrusion issues in the 120 mm/s print went away. Oh, I also implemented pressure advance correction the script since the firmware one doesn't work with the type of G-Code the script outputs.While there are many limitations as described above I'd love to get some testing of this approach: Were you able to get it to work? Were you able to see any improvements in ringing or improvements in print speeds? What type of printer and what calibration values did you land on?
-
Despite the fact my machine is half disassembled, and the fact I recently swapped out extruder motors without much 'calibration' this has been pretty cool to work with. I don't think I have anything workable yet, but still neat to play with. Once I get my machine put back together, hopefully I'll be able able to work through the parameters more methodically.
A quick note - I'm thinking the z_max (in mm) parameter is a bit wonky, initially I did some thin wall prints that were 100mm tall, and could only see variation (both in Craftware for previewing) and in the print for the first 20mm or so - even if I set z_max to 100. When I set it to 20mm (for a 20mm tall print) it also looks like the variation occurs in the first 5-8mm or so.
Ok, testing was done on an IDEX machine (only with T0). Fairly heavy Y gantry that carries the T0 and T1 print heads, plus X and U steppers. A quite large print bed, so I modified the python files to eliminate changes to the Z axis (had some issues during my first few tests). I get some significant defects due to the bed oscillating on layer changes. Some potentially useful information from the config.g
M92 X100.00 Y96.00 Z1280.00 U100.00 E415.00 ; Set steps per mm M566 X1000.00 Y1000.00 Z500.00 U1000.00 E36000.00 ; Set maximum instantaneous speed changes (mm/min) M566 P1 M203 X18000.00 Y18000.00 Z1320.00 U18000.00 E3000.00 ; Set maximum speeds (mm/min M201 X4000.00 Y4000.00 Z450.00 U4000.00 E3000.00 ; Set accelerations (mm/s^2) M906 X1800.00 Y2400.00 Z2400.00 U1800.00 E1960.00:500.00 I30 ; Set motor currents (mA) and motor idle factor in per cent
The unmodified print file: JP_talltestPart2.gcode
Short video of unmodified print - https://www.youtube.com/watch?v=3PDYEEwW7_I
First I ran a print of the above file - shown as "F" in pictures below ("F" for front of build plate haha). Printed with HIPS at somewhat high temperatures, no part cooling, 100mm/s. In the FRONT view, the printhead moves left to right along the X axis. In the Right view, the nozzle moves left to right along the Y axis... etc. DAA, PA, etc, all were turned off for the reference print. The reference print is stacked on top of the modified gcode print. For "Fx" I ran the script targeting x f_n, ranging from 5 to 75 across Z=20 (see note above). Yes, the X axis did a good amount of shaking.
Video - https://www.youtube.com/watch?v=6TJ2uW1rX_E
File - x-5-75.gcodeimport move # EXAMPLE CONFIGURATION, PLEASE EDIT BEFORE USING class motion_parameters: dynamic_model = [ move.spring_damper_parameters(f_n = 0, zeta = 0), # x move.spring_damper_parameters(f_n = 0, zeta = 0), # y #move.asymmetric_spring_damper_parameters(f_n_negative = 52.5, f_n_positive = 56.9, zeta = 0.02), # y move.spring_damper_parameters(f_n = 0, zeta = 0.0), # z move.pressure_advance_parameters(k = 0.00) # e ] max_speed = 300 accel = 12000 jerk = 2000000 non_motion_max_speed = 300 # i.e. extrusion-only moves non_motion_accel = 12000 non_motion_jerk = 2000000 axis_limits = [ move.axis_limits(speed = 300), # x move.axis_limits(speed = 300, accel=500), # y move.axis_limits(speed = 22, accel = 1200, jerk = 1000), # z None, #e ] # adjust a parameter dynamically based on the z height def calibration_adjustment(z): # example value_min = 5 value_max = 75 z_max = 20 # mm value = z / z_max * (value_max - value_min) + value_min #motion_parameters.dynamic_model[0].zeta = value # adjust x zeta #motion_parameters.dynamic_model[1].zeta = value # adjust y zeta motion_parameters.dynamic_model[0].f_n = value # adjust x f_n #motion_parameters.dynamic_model[1].f_n = value # adjust y f_n #motion_parameters.dynamic_model[1].f_n_negative = value # adjust y f_n #motion_parameters.dynamic_model[1].f_n_positive = value # adjust y f_n #motion_parameters.dynamic_model[3].k = value # adjust pressure advance # adjust these to adjust the linear interpolation and coarseness of the generated output # reducing the tolerances will increase the size of the output file (and more likely cause the printer motion planner to choke) class curve_parameters: tolerances = [ 0.002, # x (2µm) 0.002, # y (2µm) 0.050, # z (50µm) 0.100, # e (0.1mm) # low tolerance to prevent pressure advance from adding nodes at the potential detriment of the xy spring-damper control ] min_dt = 1/200 def disable_acceleration_control(): print('M566 P1') # RRF Jerk Policy 1 print('M572 D0 S0') # dis.able pressure advance #print('M201 X100000 Y100000 Z100000 E100000') # disable acceleration print('M201 X100000 Y100000 E100000') # disable acceleration #print('M205 X10000 Y10000 Z10000 E10000') # infinite instantaneous velocity change print('M205 X10000 Y10000 E10000') # infinite instantaneous velocity change def restore_acceleration_control(): print('M201 X4000 Y4000 Z1200 E3000') # reset acceleration #print('M205 X10 Y10 Z10 E10000') # reset instantaneous velocity change print('M205 X10 Y10 E10000') # reset instantaneous velocity change
For the image below, same notes - targeted Y axis. I read your warning on going below 20Hz and promptly ignored it hahahahaha
Video - https://www.youtube.com/watch?v=Yc9EpRiLeGE
y-5-75.gcode
import move # EXAMPLE CONFIGURATION, PLEASE EDIT BEFORE USING class motion_parameters: dynamic_model = [ move.spring_damper_parameters(f_n = 0, zeta = 0), # x move.spring_damper_parameters(f_n = 0, zeta = 0), # y #move.asymmetric_spring_damper_parameters(f_n_negative = 52.5, f_n_positive = 56.9, zeta = 0.02), # y move.spring_damper_parameters(f_n = 0, zeta = 0.0), # z move.pressure_advance_parameters(k = 0.00) # e ] max_speed = 300 accel = 12000 jerk = 2000000 non_motion_max_speed = 300 # i.e. extrusion-only moves non_motion_accel = 12000 non_motion_jerk = 2000000 axis_limits = [ move.axis_limits(speed = 300, accel=500), # x move.axis_limits(speed = 300), # y move.axis_limits(speed = 22, accel = 1200, jerk = 1000), # z None, #e ] # adjust a parameter dynamically based on the z height def calibration_adjustment(z): # example value_min = 5 value_max = 75 z_max = 20 # mm value = z / z_max * (value_max - value_min) + value_min #motion_parameters.dynamic_model[0].zeta = value # adjust x zeta #motion_parameters.dynamic_model[1].zeta = value # adjust y zeta #motion_parameters.dynamic_model[0].f_n = value # adjust x f_n motion_parameters.dynamic_model[1].f_n = value # adjust y f_n #motion_parameters.dynamic_model[1].f_n_negative = value # adjust y f_n #motion_parameters.dynamic_model[1].f_n_positive = value # adjust y f_n #motion_parameters.dynamic_model[3].k = value # adjust pressure advance # adjust these to adjust the linear interpolation and coarseness of the generated output # reducing the tolerances will increase the size of the output file (and more likely cause the printer motion planner to choke) class curve_parameters: tolerances = [ 0.002, # x (2µm) 0.002, # y (2µm) 0.050, # z (50µm) 0.100, # e (0.1mm) # low tolerance to prevent pressure advance from adding nodes at the potential detriment of the xy spring-damper control ] min_dt = 1/200 def disable_acceleration_control(): print('M566 P1') # RRF Jerk Policy 1 print('M572 D0 S0') # dis.able pressure advance #print('M201 X100000 Y100000 Z100000 E100000') # disable acceleration print('M201 X100000 Y100000 E100000') # disable acceleration #print('M205 X10000 Y10000 Z10000 E10000') # infinite instantaneous velocity change print('M205 X10000 Y10000 E10000') # infinite instantaneous velocity change def restore_acceleration_control(): print('M201 X4000 Y4000 Z1200 E3000') # reset acceleration #print('M205 X10 Y10 Z10 E10000') # reset instantaneous velocity change print('M205 X10 Y10 E10000') # reset instantaneous velocity change
Fun to watch and futz with (I did many more prints prior to this), but unfortunately nothing conclusive. What I did do was measure the ringing in the reference print on each side, and then ran the print again only targeting those values (no value hunting). I threw in X=25Hz, and (the reason escapes me now) Y=30Hz. The amplitude of the vibrations are much lower (read: surface is smoother) than the reference print (I also ran a print swapping the X and Y values, where in the inverted prints the results were not as good). Unfortunately the picture doesn't quite paint a clear picture.
Video - https://www.youtube.com/watch?v=P6JSEvgVD6A
File - x-25-y-30.gcodeimport move # EXAMPLE CONFIGURATION, PLEASE EDIT BEFORE USING class motion_parameters: dynamic_model = [ move.spring_damper_parameters(f_n = 25, zeta = 0), # x move.spring_damper_parameters(f_n = 30, zeta = 0), # y #move.asymmetric_spring_damper_parameters(f_n_negative = 52.5, f_n_positive = 56.9, zeta = 0.02), # y move.spring_damper_parameters(f_n = 0, zeta = 0.0), # z move.pressure_advance_parameters(k = 0.00) # e ] max_speed = 300 accel = 12000 jerk = 2000000 non_motion_max_speed = 300 # i.e. extrusion-only moves non_motion_accel = 12000 non_motion_jerk = 2000000 axis_limits = [ move.axis_limits(speed = 300), # x move.axis_limits(speed = 300), # y move.axis_limits(speed = 22, accel = 1200, jerk = 1000), # z None, #e ] # adjust a parameter dynamically based on the z height def calibration_adjustment(z): # example value_min = 5 value_max = 75 z_max = 20 # mm value = z / z_max * (value_max - value_min) + value_min #motion_parameters.dynamic_model[0].zeta = value # adjust x zeta #motion_parameters.dynamic_model[1].zeta = value # adjust y zeta #motion_parameters.dynamic_model[0].f_n = value # adjust x f_n #motion_parameters.dynamic_model[1].f_n = value # adjust y f_n #motion_parameters.dynamic_model[1].f_n_negative = value # adjust y f_n #motion_parameters.dynamic_model[1].f_n_positive = value # adjust y f_n #motion_parameters.dynamic_model[3].k = value # adjust pressure advance # adjust these to adjust the linear interpolation and coarseness of the generated output # reducing the tolerances will increase the size of the output file (and more likely cause the printer motion planner to choke) class curve_parameters: tolerances = [ 0.002, # x (2µm) 0.002, # y (2µm) 0.050, # z (50µm) 0.100, # e (0.1mm) # low tolerance to prevent pressure advance from adding nodes at the potential detriment of the xy spring-damper control ] min_dt = 1/200 def disable_acceleration_control(): print('M566 P1') # RRF Jerk Policy 1 print('M572 D0 S0') # dis.able pressure advance #print('M201 X100000 Y100000 Z100000 E100000') # disable acceleration print('M201 X100000 Y100000 E100000') # disable acceleration #print('M205 X10000 Y10000 Z10000 E10000') # infinite instantaneous velocity change print('M205 X10000 Y10000 E10000') # infinite instantaneous velocity change def restore_acceleration_control(): print('M201 X4000 Y4000 Z1200 E3000') # reset acceleration #print('M205 X10 Y10 Z10 E10000') # reset instantaneous velocity change print('M205 X10 Y10 E10000') # reset instantaneous velocity change
-
@sebkritikel said in A Software Solution to Eliminate Ringing?:
Despite the fact my machine is half disassembled, and the fact I recently swapped out extruder motors without much 'calibration' this has been pretty cool to work with. I don't think I have anything workable yet, but still neat to play with. Once I get my machine put back together, hopefully I'll be able able to work through the parameters more methodically.
Thanks for testing! These are very interesting results.
A quick note - I'm thinking the z_max (in mm) parameter is a bit wonky, initially I did some thin wall prints that were 100mm tall, and could only see variation (both in Craftware for previewing) and in the print for the first 20mm or so - even if I set z_max to 100. When I set it to 20mm (for a 20mm tall print) it also looks like the variation occurs in the first 5-8mm or so.
I don't think the parameter is broken – it's more the consequence to the correction magnitude of increasing f_n. The higher the number the smaller the correction, asymptotically approaching zero. The correction magnitude is proportional one over the square of the f_n number, so at say 50 Hz you will get 4x less correction than at 25 Hz, and at 5 Hz (your lowest number, the correction is 100x higher.
I modified the python files to eliminate changes to the Z axis (had some issues during my first few tests).
I get some significant defects due to the bed oscillating on layer changes. Some potentially useful information from the config.gLooking at your g-code, your slicer is not spiralizing the contour, so I think your modifications are ok. You should be able to achieve the same effect by reducing the accel setting in the z axis limits though.
The unmodified print file: JP_talltestPart2.gcode
Short video of unmodified print - https://www.youtube.com/watch?v=3PDYEEwW7_I
First I ran a print of the above file - shown as "F" in pictures below ("F" for front of build plate haha). Printed with HIPS at somewhat high temperatures, no part cooling, 100mm/s. In the FRONT view, the printhead moves left to right along the X axis. In the Right view, the nozzle moves left to right along the Y axis... etc. DAA, PA, etc, all were turned off for the reference print. The reference print is stacked on top of the modified gcode print. For "Fx" I ran the script targeting x f_n, ranging from 5 to 75 across Z=20 (see note above). Yes, the X axis did a good amount of shaking.
Video - https://www.youtube.com/watch?v=6TJ2uW1rX_E
File - x-5-75.gcodeOn the front view, you definitely see a significant improvement around one third up corresponding to roughly 25~30 Hz. I don't quite understand what's happening on the back side though. I think maybe the lack of cooling keeps the filament from achieving good adherence to the layer below.
axis_limits = [ move.axis_limits(speed = 300), # x move.axis_limits(speed = 300, accel=500), # y move.axis_limits(speed = 22, accel = 1200, jerk = 1000), # z
With such a low jerk value, I'm surprised you have issues with the z axis.
For the image below, same notes - targeted Y axis. I read your warning on going below 20Hz and promptly ignored it hahahahaha
Video - https://www.youtube.com/watch?v=Yc9EpRiLeGE
y-5-75.gcode
You should definitely increase the low end of the range from 5Hz to something higher (15 Hz maybe?). The poor extrusion at the bottom is making reading these quite hard. Another thing that helps is plugging in the ~28 Hz value from the X-axis calibration above here to minimize the cross-talk. That being said, you can definitely see a phase transitioning happening in the range of 25-50 % of the height. I've generally been successful picking the middle point of the phase transition.
Fun to watch and futz with (I did many more prints prior to this), but unfortunately nothing conclusive. What I did do was measure the ringing in the reference print on each side, and then ran the print again only targeting those values (no value hunting). I threw in X=25Hz, and (the reason escapes me now) Y=30Hz. The amplitude of the vibrations are much lower (read: surface is smoother) than the reference print (I also ran a print swapping the X and Y values, where in the inverted prints the results were not as good). Unfortunately the picture doesn't quite paint a clear picture.
I think this is a good start. It always took me a few iterations to get it tuned, you should zoom in on the parameters a bit more (e.g try 20–35 Hz). Zeta can also be critical to calibrate (depending on your printer). It's also possible that doing 12000 mm/s² acceleration is aiming too high and you start hitting non-linear spring behaviors. My CoreXY printer has ringing in the range of 52-60 Hz which is almost exactly 2x of your values. Since that means 4x as much spring compensation I'd not be surprised if you need to back off on the acceleration setting.
The thing about photos of shiny filament is that they amplify the curvature changes over the magnitude – you see similar specularities even after reducing the ringing magnitude by a significant factor. You probably want to get your f_n estimates to within 2–5% or so to start seeing more dramatic improvements.
Finding my most similar silver filament, here an "after" print I made on my CoreXY:
80 mm/s, 10,000 mm/s², 2 km/s³ jerkI didn't have enough filament to finish a "before" shot. This was as far as I got:
(identical printing parameters)Ignore the horizontal lines in the middle of the silver zone – that's when I fed in the gold filament.
-
@DigitalVision does your script support arc moves, i.e. G2/G3 moves? I am asking because I sometimes use ArcWelder as a postprocessor to turn segmented curves back into real curves (mostly to compress the gcode)...
-
@DigitalVision Many thanks for the response! Appreciate all of your comments.
Many thanks for your comments! Great insight all around.
Spiral mode... should have started with that!
Not quite there yet, but narrowing it down some - the after here is taken at f_n X to 21Hz, f_n Y to 30Hz (X picked after running from 19-26, Y a number of times from 15-50).
The Y axis was quite interesting to watch and tune for. When running from 15-100 Hz, you could see the initial set of ripples fan out some, and then a second set begin to develop. Image below is likely from 15-50Hz.
For the iterations above, I dropped accelerations to 8000mm/s^2, and jerk to 1,000,000, but have started dropping each of those lowers. I ran one print at 4000mm/s^2 and something like 80,000 (typo), which naturally took quite long, but looked great.
The acceleration values in my config.g (specifically for X, U, and Y), are not picked for print quality, rather they are derived from stepper motor torque, gantry mass, and any gearing present. Some more investigation and test needed on my end there with respect to acceleration and jerk values.
-
@sebkritikel said in A Software Solution to Eliminate Ringing?:
Spiral mode... should have started with that!
Just be careful with your hack to let the machine do Z acceleration ramping in that case. It breaks the time-critical assumption baked into the constant velocity segments that get output.
I also found that Slic3r generate a tiny extra-move at one of the corners in spiral mode which is not ideal with the script. Maybe Cura does spirals better.
Not quite there yet, but narrowing it down some - the after here is taken at f_n X to 21Hz, f_n Y to 30Hz (X picked after running from 19-26, Y a number of times from 15-50).
I curious how you end up with such low frequencies and what's dominating the X-spring in your system. Are your belts fairly loose? How long is the X travel?
The left/right asymmetry is very interesting. You may be seeing a higher frequency of ringing when the printer is accelerating in the negative Y than positive. I had something similar myself but not at all as extreme, which is why I had to implement the asymmetric spring function. Here are my settings:
dynamic_model = [ move.spring_damper_parameters(f_n = 60.5, zeta = 0), # x move.asymmetric_spring_damper_parameters(f_n_negative = 52.5, f_n_positive = 56.9, zeta = 0.02), # y move.spring_damper_parameters(f_n = 0, zeta = 0.0), # z move.pressure_advance_parameters(k = 0.08) # e ]
The Y axis was quite interesting to watch and tune for. When running from 15-100 Hz, you could see the initial set of ripples fan out some, and then a second set begin to develop. Image below is likely from 15-50Hz.
I found it easiest to calibrate the axes when looking at the acceleration ringing rather than the post-deceleration ringing, and decoupling them required setting a low acceleration (500 in my case) on the other axis.
From your image here it does look like there is possibly a bit of post-deceleration ringing at a low frequency on top (the wavy pattern) that may be creating the interference pattern with a higher frequency acceleration ringing on the bottom. You may need to go even lower/more extreme than 500 mm/s² on the X axis to get a clearer read on Y.
There could also be a non-linear spring response – or you simply need to calibrate zeta. On my delta, I did see a similar phase change pattern, so I picked the middle of the transition zone for f_n and swept zeta from 0-0.5 and picked 0.10. The effect from zeta is much more subtle, but allowed the two phases of the interference pattern to separate when re-running a f_n sweep.
For the iterations above, I dropped accelerations to 8000mm/s^2, and jerk to 1,000,000, but have started dropping each of those lowers. I ran one print at 4000mm/s^2 and something like 80,000 (typo), which naturally took quite long, but looked great.
The acceleration values in my config.g (specifically for X, U, and Y), are not picked for print quality, rather they are derived from stepper motor torque, gantry mass, and any gearing present. Some more investigation and test needed on my end there with respect to acceleration and jerk values.
-
@DigitalVision said in A Software Solution to Eliminate Ringing?:
@sebkritikel said in A Software Solution to Eliminate Ringing?:
Not quite there yet, but narrowing it down some - the after here is taken at f_n X to 21Hz, f_n Y to 30Hz (X picked after running from 19-26, Y a number of times from 15-50).
I curious how you end up with such low frequencies and what's dominating the X-spring in your system. Are your belts fairly loose? How long is the X travel?
A quick theoretical calculation on the timing belt contribution:
From Gates' datasheet, a GT3 2mm pitch, 6mm wide belt has an elongation of 0.1% @ 16.9 N of force. If we assume that the extruder is 500 g and running at 10,000 mm/s² accelerations we get 5 N of force. That would correspond to an elongation of 0.03 % or 0.3 mm/m. For a belt that is is 1 m, this corresponds to a spring constant of k=17000 N/m. The natural frequency is sqrt(k/m)/(2π) = 29.3 Hz. A 500 mm belt would have a natural frequency of 41.5 Hz.
I have a CoreXY so there are two belts pulling the extruder. My shorter x belt length from extruder to the motor pulley is ~300 mm at the center and the longer ~1050 mm.
The long belt will have a spring constant of k=15.9 N/mm and the short one k=55.6 N/mm. Since the two springs work in parallel we can simply add the two spring constants getting k=71.5 N/mm.
Assuming 500g of extruder weight we get f_n = sqrt(71.5 * 1000 / 0.500) / (2*π) = 60.2 Hz. That's remarkably close to the 60.5 Hz number I got from tuning.
-
Just a closing thought on the above. Not entirely surprising it seems the belts have the potential to explain almost all of the spring dynamics on my printer. The belt lengths are a critical parameter though, and they will vary significantly across the print envelope, so a single f_n parameter will probably not work across all of it. Luckily it's very easy to calculate the belt lengths at any given point, so it should be easy to build a simple dynamic model to correct for this.
-
@DigitalVision The X and U axis belts are each 1256mm in total length (GT2, 2mm pitch, 9mm width, through SDP/SI (GT3 was not available in that length at the time of purchasing)), so about 600mm center to center (motor to idler). Unfortunately the shoulder bolts I configured through Misumi for the idlers ended up being equivalent to partially threaded screws instead - I set the thread diameter equal to the shoulder diameter, eliminating the shoulder.... As such the X and U idler stackup is quite loose (to allow the bearings to rotate freely), and the belt tension is fairly low as well. I have plans to correct this in the new year (fingers crossed).
The Y axis belts - GT3, 3mm pitch, 15mm width, total length ~ 1235, 580mm center to center - are significantly tighter, although I have my doubts that they are tightened to spec.
-
Really great work, and a nice overlap with some work I am doing looking at prints (although that is initially focused on pressure advance)
Regarding this:
It seems like the ringing had different frequencies when moving in the positive y direction vs the negative. Thinking a bit about this I came up with a model that makes sense. The print head is not perfectly balanced under the axis with the center of gravity being offset to one side. This effectively means that gravity is applying pre-tension on the spring biasing the spring effect towards one direction. To test this hypothesis I implemented an asymmetric spring model and plugging in 52 and 60 Hz respectively for the two axes did the trick.
Another effect we have seen probably relates to the forces acting on the extruder from the associated cable chains, wires etc, and how the change in different parts of the print area. Depending on how your machine is setup these can either have a large or almost negligible effect.
-
@DigitalVision said in A Software Solution to Eliminate Ringing?:
Assuming 500g of extruder weight we get f_n = sqrt(71.5 * 1000 / 0.500) / (2*π) = 60.2 Hz. That's remarkably close to the 60.5 Hz number I got from tuning.
One thing that's been bugging me about this calculation is that I'm leaving out the counter-spring from the opposing belt. I initially thought that spring force wouldn't matter since that side would be slacking. But would it really?
If we model the belt like a spring like this:
And then add a counter spring and apply some tension to the belt we get the following two forces:
Summing these two, we should expect a net spring function like this:
Note that the slope in the center region is twice that from my calculation above, and only beyond the cutoff point (when it exceeds the pre-tension) will the opposing end of the belt slack. So we should in theory expect a sqrt(2) ≈ 1.41 higher ringing frequency than I calculated. I.e. 85 Hz vs 60 Hz. Since I’m not getting that something is off. I can come up with three hypotheses:
- The acceleration exceeds the belt tension causing the opposing belt to slack. This would mean that we operate in the 1 * k slope regime (as opposed to 2 * k).
- The momentary spring displacement is faster than the wave propagation to the opposing side. I.e. when the end-effector jerks to one side the opposing belt end hasn’t yet realized it and had a chance to relax.
- There is another other (serial) spring in the system reducing the ringing frequency.
So let’s test these:
-
We can model our belt as a vibrating string. Plucking my belt between two idlers 417 mm apart gives a 65 Hz tone. The base frequency for a string is f₁ = sqrt(T/(m/L))/(2*L), T=tension (N), L = length, m = mass. The best value I found for the mass of a 2mm pitch 6mm wide GT3 belt is 7.8 g/m. Plugging these numbers in gives a tension of 26 N. Since this is substantially higher than the 5 N of acceleration force we can reject this hypothesis.
-
The wave propagation speed through a string is sqrt(T/(m/L)), or f₁ * 2L. 65 Hz * 2 * 0.417m = 54.2 m/s. My belt is ~1.4 m end-to-end, so it takes 26 ms for a wave to propagate through it. Since this is substantially longer than even the half-period of ringing (1/60 Hz) / 2 = 8.3 ms I think we have our answer. The opposing belt will not have had time to relax its counter force for more than a full period of the ringing leading to the lower slope characteristic of the spring function.
-
@sebkritikel said in A Software Solution to Eliminate Ringing?:
@DigitalVision The X and U axis belts are each 1256mm in total length (GT2, 2mm pitch, 9mm width, through SDP/SI (GT3 was not available in that length at the time of purchasing)), so about 600mm center to center (motor to idler).
Interesting. Making a lot of assumptions (like the motor is to the right) and modeling the belt-spring characteristics gives:
You can see how you get dramatically different spring "constants" (slopes) depending on the x position, with the position near the motor being substantially stiffer than positions further away.
Even across your 60 mm test print, you should see some 17 % higher x-spring constant on the right side than the left. This translates to an 8 % difference in f_n. I think it's clear that I need to augment the model with a position dependent parameter.
-
@T3P3Tony said in A Software Solution to Eliminate Ringing?:
@DigitalVision
Really great work, and a nice overlap with some work I am doing looking at prints (although that is initially focused on pressure advance)Thanks! Very interested to hear more about the pressure advance explorations.
Another effect we have seen probably relates to the forces acting on the extruder from the associated cable chains, wires etc, and how the change in different parts of the print area. Depending on how your machine is setup these can either have a large or almost negligible effect.
That's an interesting aspect I hadn't thought about in this context. I've certainly seen the cable bundle and/or bowden tube affecting e.g. delta bed leveling in the past.
-
Update...
I was a bit concerned about the idea that wave propagation delay in the belts would be significant enough to affect the spring-damper model as my earlier calculation indicated. I'm happy to conclude that I was wrong. I had calculated the transversal wave propagation velocity when what actually matters is the longitudinal wave propagation velocity (or speed of sound) which is substantially higher. For my GT3 belt, the speed of sound is around 1.5 km/s which means that the force propagation delay over my longest belt segment is <1 ms. We need to make signal changes at close to kHz speeds for this to become relevant. I made a small simulation to convince myself of this, and as long as the belt tension is substantially higher than the maximum acceleration force the belt will behave as a perfect spring. Here’s a great source on theory of longitudinal wave propagation: https://www.mathpages.com/home/kmath569/kmath569.htm
The complication is that the spring "constant' is dependent on the spring length which changes with the position. Luckily we can measure and calculate this correction almost perfectly. Here’s a plot of how the ringing frequency theoretically changes across the print bed for a cartesian and CoreXY printer respectively. We can see how the two-belt CoreXY design balances the effect much better than a single linear-belt (with the stepper on one side) does. The linear belt design has a substantially higher spring stiffness when the print head is close to the stepper than when it’s far away and I think it’s clear that we need a positional parameter even for the CoreXY system.
Both of these functions are of the form sqrt(1/p) where p is a quadratic polynomial. For the cartesian case p(x) has 3 parameters of which one is the relative belt lengths for a given x-coordinate and can be easily measured. If we add other serial springs to the system (like the stepper motors and compliant mechanics) we get another simple additive term. Measuring f_n at two different positions will determine the entire system.
For a CoreXY system it gets a bit more complicated since the belt lengths depend on both x and y. The compounded spring model is also a bit more complicated:
For one axis, we have 5 unknown parameters: stiffness of the x and y belt respectively, the serial spring at the end effector and the two stepper springs. We can probably assume that the two steppers are identical and collapse them to one parameter, but we are still left with 4 parameters. For the other axis, many of these parameters overlap. The steppers and belts are identical with only a difference in the driven mass. The serial spring is also different. So we have a total of 6 parameters across two axes. This means that we need to measure f_n for three points per axis rather than two to determine the parameters for the system.
One more thing. Can we calculate the spring constant from a stepper motor? The electrical field in the motor is effectively a spring, and at a static position the spring constant may at a first order be able to be calculated as the holding torque over one full step. I.e. once you exceed the holding torque the stepper will be closer to the next step 2 steps away than the current one and skip.
My stepper's data sheet claim a holding torque of 0.43 Nm and are rated at 1.684 A. I run them at 85% max current though, so 0.37 Nm. They have a 0.9° step size, 18 tooth pulleys with 2mm pitch belt, so the radius is 5.7 mm. If I calculate correctly, this gives me a spring constant of 710,000 N/m or around 10x higher stiffness than the belts. The impact is still a reduction of f_n of around ~4 Hz though, so not insignificant. I wonder if this linear spring force calculation is valid (especially for micro stepping too) though. There is definitely a reduction in torque at speed too. How significant is that at the speeds we run at?
-
Thank you for the work you are putting into this.
Have you seen the variable ringing effects that change with the belt segment length, or is this just theory?
I have a cartesian printer, and would be interested in verifying whether the ringing is different if the toolhead is at different locations. Do you have any tests in mind that I could perform that would be helpful to show you?
I have a hope that you could be wrong about the variation. A guitar string has a fixed length by having two fixed points. The wave originates as a transverse wave from a plucked string.
On the other hand, a belt system has one fixed point: the motor pulley, with an idler. There is still tension beyond the idler. The wave from motion is more of a longitudinal wave, isn't it? So the idler doesn't exactly perfectly impede the wave. It might damp some of the transverse waves that may be induced, but the longitudinal wave seems like it would be able to "flow" right on past the idler, because the belt itself is what determines the position of the idler.
Again, I'm an idiot so I could be wrong and tell me if you think this is the case. But perhaps the variation of ringing won't be as severe as you imagine. I hope!
-
Thanks for your input @bot!
Have you seen the variable ringing effects that change with the belt segment length, or is this just theory?
No, I've not seen it at all, so it's more of a hypothesis than theory at this point. Would love some help to test it though.
I have a cartesian printer, and would be interested in verifying whether the ringing is different if the toolhead is at different locations. Do you have any tests in mind that I could perform that would be helpful to show you?
That would be great! I'd simply print two hollow test cubes at two different positions on the bed. One close to the stepper, another one far away. Print at settings that excite ringing. Say ≥80mm/s, high acceleration (5000~10,000 mm/s) and compare the ringing frequency. If the model is true there should be a significant difference in ringing frequency at the two sides.
I have a hope that you could be wrong about the variation. A guitar string has a fixed length by having two fixed points. The wave originates as a transverse wave from a plucked string.
On the other hand, a belt system has one fixed point: the motor pulley, with an idler. There is still tension beyond the idler. The wave from motion is more of a longitudinal wave, isn't it? So the idler doesn't exactly perfectly impede the wave. It might dampen some of the transverse waves that may be induced, but the longitudinal wave seems like it would be able to "flow" right on past the idler, because the belt itself is what determines the position of the idler.
Interesting thought. If true, it would dramatically simplify things, although I don't think it's going to be true.
I don't consider the idler at all. I'd consider it as a very weak damper for longitudinal force propagation. The three points on the belt I consider are the two attachment points to the end effector and the motor pulley in between. We operate far below the propagation speed of the longitudinal wave, so I think we can think of the belts as operating in DC mode with the motor pulley applying a tension force on one belt segment and relaxing the force on the other segment. I.e. the only dynamic component that matters is the end effector's inertial movement.Edit: Here's a quick sketch:
-
I also have a feeling you're right. I was just trying to come up with some way that it would be more simple! haha. I will perform some tests like you recommend.
Edit: @DigitalVision With your updated sketch, I understand more clearly how you are thinking of the system.
So if the "short segment" is as long as possible, that is the worst case scenario?
Edit 2: Now that I understand what you mean, and think about it a little bit, it seems obvious that what you are saying is likely true. I have about 8 hours of printing to do before I can do the tests but I will get to it as soon as possible.
-
So if the "short segment" is as long as possible, that is the worst case scenario?
Correct. The belt segments get less compliant the shorter they are. If your belt's total length is 1, when you combine the two belt segments in parallel, the net compliance is proportional to x*(1-x). The maximum for this expression is at x=0.5 – i.e. the middle of the belt.