3D Printing: Penta Axis (PAX) / 5 Axis Printing Option – Draft

Status: inverse kinematics resolved and implemented in the firmware as well

Updates:

  • 2021/07/14: PAX inverse kinematics finally working on firmware level too
  • 2021/05/25: using worm gear with 28BYJ-48 stepper motor to drive tilt rotation
  • 2021/05/14: adding Duet 3 Mini 5+ Setup details (inverse kinematic not yet done in firmware), first motion tests made with 2x NEMA 17 (40mm)
  • 2021/02/28: added animation PAX printing a 4-axis/RTN sliced overhang model
  • 2021/02/17: added two brief animations of inverse kinematics
  • 2021/02/08: inverse kinematics working, printhead mounted on Ashtar K as draft
  • 2021/02/06: machine vs nozzle coordinates, forward/reverse transformation requirements, heatsink fan and part cooler added
  • 2021/02/04: starting with collecting ideas and first drafts

Introduction

After I saw 5- and 6-axis printers at Formnext 2019 and particularly seeing the belt printers able to print 90° overhangs in one direction without support, and then RotBot by ZHAW, a Rotating Tilted Nozzle (RTN) printer, where the 90° overhangs in different directions (given some conditions) can be printed without support – so it was more natural to consider to make the tilting nozzle angle (trot) flexible as well, 0 – 180°.

  • 0°: nozzle looking down, ordinary orientation with Z sliced layers 3D printing
  • 45°: belt printer or rotating tilted nozzle (RTN) printer, printing 90° overhangs in one or more directions *)
  • 90°: printing horizontally outward
  • 135°: printing upward 45°
  • 180°: printing upward entirely

*) Rotating Tilted Nozzle capability printing 90° overhangs depends on location and symmetric alignments, no slicing software yet available.

I chose Micro Swiss clone aka CR10 hotend as printhead as it’s small and compact, and easy to adapt and source.

Flexible Tilting

2 Additional Axes

Tests

Individual tests:

  • NEMA 17 37mm/263g: strong enough, but too heavy, my X gantry rattles and introduces ~ 1 to 2mm errors before swinging in; verdict: unusable
  • NEMA 17 23mm/131g: too weak, can’t hold position Z rotation (A) or tilt (B); verdict: unusable
  • 28BYJ-48 33g: requires ULN2003 or adjustment to drive with stepper driver like A4988; verdict: unusable due the rotation and tilt tolerance; with a more elaborate gearbox might be usable
  • N20 BLDC motor with gearbox & encoder 10g: requires dedicated controller; verdict: <untested>

Different combinations:

  • 2x NEMA 17 37mm/263g (Z rotation (A) + Tilt (B)): strong enough, but too heavy, my X gantry rattles and introduces ~ 1 to 2mm errors before swinging in; verdict: unusable unless entire X gantry/carriage is strengthened
  • 2x NEMA 17 23mm/131g (Z rotation (A) + Tilt (B)): too weak, can’t hold position Z rotation (A) or tilt (B) on PAX 180/90 due PTFE with filament stiffness; verdict: unusable
  • 1x NEMA 17 37mm/263g (Z rotation (A)): strong enough to position with PTFE with filament and cables + 1x 28BYJ-48 (Tilt (B)):
    • direct drive
      • PAX 90 arm (dual hinge): PTFE with filament stiffness prevents 0° tilt, but 15° at minimum: unreliable
      • PAX 180 arm (dual hinge): a bit better, but still problem to reliable position tilt from 0° to 90° and back to 0°: still unreliable
    • worm gear
      • PAX 90 arm (dual hinge): barely works (tilt: -5° to 85°)
      • PAX 180 arm (dual hinge): works so far (tilt: -20° to 170°)

NEMA 17 (23mm & 37mm)

NEMA 17 23mm (131g)

Let’s look at bit closer to the new rotating axes implemented with direct drive NEMA 17 stepper motors:

  • Z rotation (aka Zrot) with
    • NEMA 17 37/40mm/263g long (45Ncm) or
    • NEMA 17 23mm/131g (13Ncm)
  • Tilt rotation (aka Trot) with
    • NEMA 17 20mm/140g (16Ncm) or
    • NEMA 17 23mm/131g (13Ncm)

both provide 1.8° (or optionally 0.9°) resolution per full step, or

  • 8 microsteps (20% force) 0.225° @1.8°step (0.1125° @0.9°step) per microstep
    • Z rotation 9 Ncm (or 2.6Ncm)
    • T rotation 3.2 Ncm
  • 16 microsteps (10% force) 0.1125° @1.8°step (0.0565° @0.9°step) per microstep
    • Z rotation 4.5 Ncm (or 1.3Ncm)
    • T rotation 1.6 Ncm

For now, for sake of simplicity, both axes are in direct drive – if precision requirements dictate a simple reduction gear 1:4 or 1:5 (see below for some more details).

28BYJ-48

28BYJ-48 (33g)

With just 33g weight and easy to source this stepper motor is quite remarkable. With a small modification, the 28BYJ-48 can be driven in bi-polar mode and then connected with the existing stepper drivers.

More in-depth information can be found at Control 28BYJ-48 Stepper Motor with ULN2003 Driver & Arduino.

  • introduces significant margins via the shaft:
    • apprx. 2-3° rotation backlash (last gear of the shaft has 31 tooths, 360° / 31 = 11.6°)
    • apprx. 0.5mm tolerance of the shaft itself, causing at the tip of the shaft > 1mm tolerance or margin
    • possible solutions:
      • add another gearbox in front and introduce more stable (longer) shaft (pros: still light solution, cons: more mechanical complexity)
        • worm gear: works

Even though it’s a low-cost stepper motor and introduces backlash and tolerances to take care of, the lightness of just 33g which is about 12.5% of the NEMA 17 40mm or 25% of NEMA 17 23mm while actually provide sufficient holding torque due the gears.

Duet 3 Mini 5+ config.g changes, using it just the tilt rotation (B):

M906 B200   ; set motor current (mA)
M360 B1 I0  ; turn off microstepping without interpolation
M92 5.66    ; 32 steps / revolution x 63.68395 = 2038 => 2038 / 360 deg => 5.66 steps / deg

The 200mA setting caused the motor to warm up to apprx. 50°C, so likely to reduce the current to 100mA – if a gearbox with a worm is used, likely the reduced current still provides sufficient torque (or alternatively add a small fan to cool the motor). So I went ahead to use a worm gear setup, as direct drive was too weak – for now I use PAX 180 (long arm) to have sufficient space to flex PTFE/filament on top of the printhead.

; 24BYJ-48 
M350 B1 I0
M92 B5.6                                      ; direct drive: 32 steps / revolution x 63.68395 = 2038 => 2038 / 360 deg => 5.66 steps / deg
M92 B90.56                                    ; worm gear: 5.66 steps / deg x 16 = 90.56 steps / degrees

N20 BLDC with gearbox & encoder

Not yet tested.

Taking Advantage of 5 Axis

In 5 axis CNC context there are multiple configurations possible such as table/table, head/head and table/head – as I came from the Rotating Tilted Nozzle (RTN) the extra 2 axis are added to the head, hence head/head configuration.

Tilt rotation 0 .. 180°

The Trot of 0° is the equivalent of ordinary 3D printer with top/down oriented nozzle, the 45° the belt printer or RotBot/RTN, and 90° printing vertical walls with the nozzle perpendicular, and 90-135° printing up-side down – I’m not sure if 135-180° is that useful, perhaps making underlying structures really smooth. For now I keep the tilt rotation from 0° to 180° even though I think I’m going to use 0-135° in real life application when the actual print procedure is developed, planar or non-planar slicing.

Dual Hinge

Mathematics

5 Axis Kinematics

LinuxCNC 5 Axis kinematics describes the notations and provides a starting point and I realized quickly that in CNC context the 5 axis operations is quite thoroughly explored, but much fewer focus on 5 axis additive manufacturing yet (see below at References).

In order to reflect the rotation per axis, the notion A, B and C are adopted, which can be described in OpenSCAD as

translate([X,Y,Z]) rotate([A,B,C]) ...
X,Y,Z (tool coordinate) and I,J,K (tool vector)

Further the CNC notion I, J and K are used as tool vector, the way the nozzle points away. G-code supports natively G1 X Y Z I J K which is machine independent. The machine specific firmware then computes the machine coordinates and rotating angles so the machine tool tip reaches those coordinates with that particular tool vector.

Tool/Nozzle vs Machine Coordinates

Absolute coordinates X, Y, Z of the nozzle tip and angles Zrot, Trot and given the Z rotation arm there is a mapping required to Xm, Ym, Zm with same Zrot, Trot.

The forward transformation in OpenSCAD:

translate([Xm,Ym,Zm]) rotate([0,0,Zrot]) rotate([Trot,0,0]) translate([0,0,-45]) sphere(0.1); // nozzle tip at X, Y, Z with I, J, K
45mm vertical offset of tilt axis to nozzle tip

or expressing it as a list:

  1. at 0, 0, 0 (origin)
  2. translate([Xm,Ym,Zm])
  3. rotate([0,0,Zrot])
  4. rotate([Trot,0,0])
  5. translate([0,0,-45])
  6. at X, Y, Z

The -45 is the 45mm vertical offset of the tilt rotation to the tip of the nozzle.

In OpenSCAD it’s the reverse order, and enumerate matrices (used further below):

  1. at X, Y, Z
  2. translate([0,0,45]) aka M1
  3. rotate([-Trot,0,0]) aka M2
  4. rotate([0,0,-Zrot]) aka M3
  5. translate([ Xm, Ym, Zm ]) aka MR, by inverting matrix the Xm, Ym, Zm can be extracted
  6. at 0, 0, 0 (origin)

Each transformation can be represented by a 4×4 matrix, the sequence of transformations are the multiplication of such, and when multiplying symbolical a single 4×4 matrix will result. When keeping the symbolical notion the inverse transformation can be obtained with one operation and getting Xm, Ym, Zm from X, Y, Z, Zrot, Trot, and that very computation needs to be done in the firmware and controller in order to process X, Y, Z, Zrot, Trot as G1 X.. Y.. Z.. A.. B.. and the internally Xm, Ym, Zm is processed to achieve that tool coordinate; A = Zrot, B = Trot .

G-code

G1 X.. Y.. Z.. A.. B..

Firmware

Zrot = A
Trot = B
Xm, Ym, Zm computed via reverse/inverse transformation on the controller

Numerical Inverse Transformation

Just for sake of confirming the reverse/inverse transformation utilizing m4.scad:

include <m4.scad>

Zrot = 45;
Trot = 45;

M1 =       [ [ 1, 0, 0, 0 ],
             [ 0, 1, 0, 0 ],
             [ 0, 0, 1, 45 ],
             [ 0, 0, 0, 1 ] ];

M2 =       [ [ 1, 0, 0, 0 ],
             [ 0, cos(-Trot), -sin(-Trot), 0 ],
             [ 0, sin(-Trot), cos(-Trot), 0 ],
             [ 0, 0, 0, 1 ] ];

M3 =       [ [ cos(-Zrot), -sin(-Zrot), 0, 0 ],
             [ sin(-Zrot), cos(-Zrot), 0, 0 ],
             [ 0, 0, 1, 0 ],
             [ 0, 0, 0, 1 ] ];

MR = m4inv(M1 * M2 * M3);
// or MR = m4inv(m4tr([0,0,45])*m4rx(-Trot)*m4rz(-Zrot));
echo(MR);

which outputs

ECHO: [[1, 0, 0, 0], [0, 0.707107, -0.707107, 31.8198], [0, 0.707107, 0.707107, -31.8198], [0, 0, 0, 1]]

so MR contains the inverse matrix of the previous transformations, so I can extract the translation vector, the 4th column [ MR[0][3], MR[1][3], MR[2][3] ] or m4trv(MR) to compensate X, Y, Z, Zrot, Trot -> Xm, Ym, Zm:

Testing Inverse Kinematics (IK)

PAX printhead on Ashtar K, inverse kinematics tested: X=150, Y=0, Z=0, Zrot=0..180°, Trot=0..45° (animated)

Perhaps it’s worth to actually calculate symbolical forward and inverse transformation matrix using e.g. Matlab or alike to have transformations in one operation instead multiplying three matrices and inverting it – depending what hardware is used as controller multiplying individual matrices is faster than trying to have a complex single step matrix construct.

Although Marlin firmware supports Delta printer with complex delta inverse kinematics, not sure I can add mine as well, or I have to go with Duet RepRap firmware which seems more suitable (see notes below).

Nozzle Precision from Trot

The 45mm offset of the last rotation massivly contributes to the loss of nozzle position resolution:

s = 2 π * r / 360 = section length per degree

s = π * 45mm / 180 = 0.785mm/° which means:

  • 8 microsteps with 1.8° full step: 0.225°/microstep => 176.7μm/microstep
  • 16 microsteps with 1.8° full step: 0.1125°/microstep => 88.3μm/microstep
  • 8 microsteps with 0.9° full step: 0.1125°/microstep => 88.3μm/microstep
  • 16 microsteps with 0.9° full step: 0.0565°/microstep => 44.4μm/microstep

so the direct drive using the shafts of the NEMA 17 will provide OK resolution, but for anything a bit more serious, a reduction gear might be worth to use.

G-code & Firmware

As I likely will generate machine independent G-code as G1 X Y Z I J K, the slicer stage will likely operate in X, Y, Z and Zrot and Trot as well – so we end up with a data pipeline like this:

  1. Slicer: X, Y, Z, Zrot, Trot
  2. G-code: G1 X Y Z I J K
  3. Firmware: X Y Z I J K => Xm, Ym, Zm and I J K => Zrot, Trot

Alternatively, instead using I J K notion use the G-code A and B as two rotational axes as Duet RepRap Firmware offers G1 X Y Z A B then it’s a bit simpler:

  1. Slicer: X, Y, Z, Zrot=>A, Trot=>B
  2. G-code G1 X Y Z A B
  3. Firmware: X Y Z A B => Xm, Ym, Zm and A=>Zrot, B=>Trot

Reviewing existing slicer/printing software to see which notion is more suitable, and perhaps cover both to stay flexible.

From Xm, Ym, Zm, Zrot, Trot to X, Y, Z

Issues to Resolve

  • Bowden tube- & cable management: properly resolve it, guides etc.
  • Develop the transformation/inverse kinematics X, Y, Z, Zrot, Trot <=> Xm, Ym, Zm, Zrot, Trot as well X, Y, Z, I, J, K <=> Xm, Ym, Zm, Zrot, Trot as required for slicing, and firmware stage, done
  • Calculate the precision of X, Y, Z in relation of Xm, Ym, Zm and Zrot, Trot, whether or how the motor resolution affect axes => getting a grasp how the overall precision of the final setup
  • Direct drive mechanical precision with 8/16 microsteps, repeatability, and heat dissipation from motor (see tweet)
  • Slicer/print software supporting 5 axis nozzle
    • Duet RepRap Firmware: supports ABCD rotational axes
    • Marlin firmware capabilities, as it support Delta printers, inverse kinematics (IK) calculations seem supported well, question is how simple to add my own custom IK as well
    • printing: recognize model features or base design on seams or boundaries, like OPENCASCADE (STEP/IGES support)
    • printing: use vertical slicing as fallback, given no other printing method is suitable
    • explore different print modes like RotBot/RTN
      • recognize rotational objects: print from inside out like with a lath but adding material
      • detect steep overhangs, find proper way to print them
    • collision detection, e.g. tilt rotation becomes available at a certain Z level as below the upside looking nozzle will touch the build plate with the opposite end – the slicing/print software must be aware of the printhead geometry to calculate what’s possible to print and how

Considerations

Pros

  • many new ways to print in (almost) all directions
  • hopefully print 90° and more overhangs without support at all

Cons

  • significant mechanical complexity
    • mechanical limitations arise with new freedom of rotation of printhead
    • collision detection becomes essential which in Z sliced layers is not an issue at all
  • significant software complexity, no current 3D printing software available to take advantage of 5 axis printing

Ashtar K with 5 Axis (PAX) Printhead

Experimental mounting on Ashtar K to see how it looks, including display showing rotations of Zrot (A), Trot (B) too.

Note: the display shows original tool coordinates, whereas the firmware does tool translation aka inverse kinematics as shown in the screenshots with the display readable.

PAX printhead on Ashtar K with virtual Marlin firmware display (animated)

With all the freedom to angle the nozzle, all of the sudden the part cooler air nozzle shape becomes an issue, and has to become narrow as well; and overall geometry of the printhead becomes quite relevant when planning print sequences (collision detection).

PAX can operate in 4-axis mode, e.g. printing a conic sliced (4-axis RTN) overhang model (without support structure) in 4-axis Rotating Tilted Nozzle (RTN) mode (45° titled nozzle):

Ashtar K PAX printing 4-axis/RTN sliced overhang model (animation)

PAX Tilt 180, 135 and 90

The PAX which tilts up to 180° will be referenced further as PAX or PAX 180, the 360° Z rotation is implied then too, as comparison of PAX 90 tilting to 90° only with shorter arm:

As the slicing strategy isn’t determined, it’s not yet clear if tilt 90..180° is required or not. In case only 0..90° is sufficient, the Z rotation arm can be shortened.

As I experimented, I realized an option in between PAX 180 and PAX 90, hence PAX 135, and seemed to compromise between angular range of the tilt and PTFE tube bending.

Printable Parts

Print with 0.4-0.5mm nozzle @ 0.20 – 0.25mm layer height:

  • pax_arm: connects motor A / Zrotation with motor B/tilt
    • pax_arm_90 & pax_arm_90_dualh
    • pax_arm_135 & pax_arm_135_dualh (recommended)
    • pax_arm_180 & pax_arm_180_dualh
  • pax_carriage_mount: holds motor A / Zrotation connects to X carriage
  • pax_printhead: connects motor B with printhead, @ 0.1mm layer height
    • pax_printhead
    • pax_printhead-dualh: for NEMA 17 for tilt
    • pax-printhead_dualh_xl: for 28BYJ-48 direct drive or tilt gearbox (worm gear)
  • pax_tilt_gearbox_28byj48:
    • pax_tilt_gearbox_28byj48: PAX 180
    • pax_tilt_gearbox_28byj48-tilt=true: use with PAX 90/135/190 (recommended)
  • pax_partcooler: connects part cooler fan with printhead
  • pax_fan_nose: part cooler fan nose, @ 0.1mm layer height
  • 28byj_cooler
    • 28byj_cooler-type=single: PAX 90/135
    • 28byj_cooler-type=dual: PAX 90/135/180

Hardware

NEMA 17 23mm Datasheet (17HS4023)

For for my own reference, a few details of stepper motor for Z-rotation (“A” axis) and tilt (“B” axis):

Note: early tests have shown the NEMA 17 23mm “thin” stepper motor has too weak holding torque (without gear reduction) with the stiffness of PTFE/filament and cables for Z rotation (A) and tilt rotation (B) – so I switched back to heavy NEMA 17 40mm “long” stepper motor – but that meant the mounting pieces need to be stronger.

If I find a low-overhead and space efficient gear reduction perhaps the NEMA 17 23mm may still have a chance to be used in this setup.

28BYJ-48 Datasheet

Note: early tests have shown for tilt rotation (B) in direct drive it’s too weak, but with worm gear setup it seems to work, though quite slow, and with just 33g weight it’s quite an advantage in this regard compared to heavy NEMA17.

Duet 3 Mini 5+ & Mini 2 Expansion

Duet 3 Mini 5+ & Expansion Mini 2 provides 7 stepper motors drivers (TMC 2209) with microstep interpolation:

  • Stepper 0: X-axis
  • Stepper 1: Y-axis
  • Stepper 2/3: 2x Z-axis (I could runs 2 Steppers on on the same driver, but since I run quick Z changes, I keep it dedicated driver for each)
  • Stepper 4: E0
  • Stepper 5 (Expansion 0): A (Z rotation)
  • Stepper 6 (Expansion 1): B (tilt rotation)

config.g

; Default config.g template for Duet 3 Mini 5+
; Replace this with a proper configuration file (e.g from https://configtool.reprapfirmware.org)

M575 P1 B57600 S1                             ; Enable UART 

; test network enable
;M552 P192.168.2.14
M552 P10.0.0.100
M552 S1

M550 P"Ashtar K2 PAX"                         ; Name the board/machine

; config drivers -> motors: X, Y, Z(dual), E0, A & B
M584 X0 Y1 Z2:3 E4 
M584 A5 B6 S1

M208 X-10 Y-10 Z0 A-185 B-40 S1               ; Set axis minima
M208 X320 Y320 Z300 A185 B100 S0              ; Set axis maxima

M92 X100 Y100 Z3200 E95                       ; Set axis steps/mm
M92 A9 B9                                     ; Set axis steps/degrees

M350 X16 Y16 Z16 E16 I1                       ; Set 16x microstepping with interpolation
M350 A4 B4 I1                                 ; Set 4/8/16x microstepping with(out) interpolation

M906 X800 Y1000 Z800 E800 A1000 B1000         ; Set motor currents (mA)

M201 X400 Y400 Z15 E1000                      ; Accelerations (mm/s^2)
M201 A800 B800

M203 X10000 Y10000 Z360 E3600                 ; Maximum speeds (mm/min)
M203 A20000 B20000                            ; Maximum speed (mm/min)

M566 X600 Y600 Z30 E20                        ; Maximum jerk speeds (mm/min)
M566 A300 B300

; Define end-stops:
M574 X1 S1 P"io0.in"
M574 Y1 S1 P"io1.in"
M574 Z1 S1 P"io2.in"
;M574 A1 S1 P"io3.in"
;M574 B1 S1 P"io4.in"
M564 H0                       ; Allow (all) axis without homing (required for A/B)

M918 P1                       ; Set 12864 display (doesn't work yet)

M569 P0 S1                    ; Set motor drive P0 (X)
M569 P1 S1                    ; Set motor drive P1 (Y)
M569 P2 S1                    ; Set motor drive P2 (Z1)
M569 P3 S1                    ; Set motor drive P3 (Z2)
M569 P4 S0                    ; Set motor drive P4 (E0)
M569 P5 S0                    ; Set motor drive P5 (A/Zrot)
M569 P6 S0                    ; Set motor drive P6 (B/tilt)

M563 P0 D0 H1 F0       		  ; Define tool 0
G10 P0 X0 Y0 Z0       		  ; Set tool 0 axis offsets
G10 P0 R0 S0                      ; Set initial tool 0 active and standby temperatures to 0C
; M572 D0 S0.06			      ; Set pressure Advance

; Bed Heater
; M308 S0 P"temp0" Y"thermistor" B4725 C7.060000e-8 					; configure sensor 0 as thermistor on pin temp0
; M950 H0 C"out0" Q25 T0                           					; create bed heater output on out0 and map it to sensor 0, PWM frequency: 25Hz
; M307 H0 R0.262 C338.0 D10.52 S1.00 V11.8 B0							; Bed tuning values, enable PID
; M140 H0                                                    			; Bed uses Heater 0
; M143 H0 S120                                               			; Set temperature limit for heater 0 to 120C Bed

; Hotend heater
M308 S1 P"temp1" Y"thermistor" T100000 B4725 C7.060000e-8 					; configure sensor 1 as thermistor on pin temp1
M950 H1 C"out1" T1                           						; create nozzle heater output on out1 and map it to sensor 1
M307 H1 B0 S1.00                             						; disable bang-bang mode for heater  and set PWM limit
M143 H1 S295                                 						; set temperature limit for heater 1 to 295C
M302 S170 R170                                         				; allow extrusion starting from 170°C and retractions already from 170°C

; Part cooling fan
M950 F0 C"out3" Q100          ; Create fan 0 part cooler on pin out3 and set its frequency
M106 P0 S0 H-1                ; Set fan 0 value. Thermostatic control is turned off

; Heatsink cooling fan
M950 F1 C"out4" Q1000		  ; Create fan 1 heatsink fan an pin out4 and set its frequency
M106 P1 T45 S255 H1  	      ; Set fan 1 value. Thermostatic control is turned on > 45C turn on   
;M106 P1 S255 H-1

M302 P1                       ; Allow cold extrusion (for testing)
T0                            ; Set tool 0 (default extruder)

G21                           ; Work in millimetres
G90                           ; Send absolute coordinates...

; pre 3.3 (3.2.x)
G92 A-1 B-1                   ; Make Zrot & Tilt active
G1 A0 B0
; 3.3 or later
;M17 A B

G92 A0 B0
G1 A0 B0 F20000

Endstops:

  • X: io_0 (Pin 2/3)
  • Y: io_1 (Pin 2/3)
  • Z: io_2 (Pin 2/3)
  • [optional] A: io_3 (Pin 2/3)
  • [optional] B: io_4 (Pin 2/3)

Thermistors:

  • temp0: bed
  • temp1: hotend

Heating:

  • out0: bed (max 15A)
  • out1: hotend (max 5A, 60W@12V)

Fans:

  • out3: part cooling fan (Pin 2/4)
  • out4: heatsink fan (Pin 2/4) or 12V: heatsink fan (always on)

So far Duet 3 Mini 5+ with RepRap Firmware V3.2 works well with the first motion tests. It took me an afternoon to configure the board without the web configurator but direct editing config.g on the web-console and reading documentation for each individual G-code configuration as part of getting to know the Duet 3D approach using G-code to configure the entire firmware (except the inverse kinematic).

The inverse kinematic with adjustable offsets comes next.

SKR Pro 1.2

Alternatively the SKR Pro V1.2 also can run Duet 3D RepRap Firmware V3.x

SKR Pro 1.2 provides 6 stepper motors drivers, whereas Z stepper driver provide dual connectors:

  • 1x X-axis
  • 1x Y-axis
  • 2x Z-axis
  • 1x E0
  • 1x A (Z rotation)
  • 1x B (tilt rotation)

In order to be able to set microstepping and motor current via firmware, the driver should operate in UART mode.

Test Setup

Duet 3 Mini 5+ with Expansion Mini 2 with 2x NEMA 17 (40mm) without gear reduction:

Duet Web Console (DWC) for Ashtar K2 with PAX printhead
Test Setup of PAX printhead mounted on Ashtar K (#2) with Duet 3 Mini 5+ (Ethernet)

and first movement with NEMA 17 (40mm) with enhanced carriage mount, manually entered G1 A B motions, a shorter yet stiffer PAX 90 arm (means tilt only 0..90): A=-180..180 and B=0..90:

Closer look:

And alternatively 24-BYJ-48 stepper motor direct drive or with worm gear, with a dual hinge arm:

RepRapFirmware (RRF) vs Marlin 2.x

Duet 3D RepRapFirnware (RRF) natively supports multiple axis, and since RRF V3.2 also treats axis A-D as rotational axis by default. So far Marlin 2.x does not support multiple axis yet, but there is a fork / PR available (reviewed 2021/05/14) which introduces the functionality and be available soon.

RRF Inverse Kinematics (PAXKinematics)

The key element of course is the dedicated inverse kinematics, which I implemented and finally works rudimentary within RRF (2021/07/14), still some small things to take care:

The nozzle tip stays in place, but Zrot and tiltrot is changed; this allows machine independent G-code to be processed.

References

5 Axis

4 Axis

As I progress I will update this blog-post.

That’s it.

3D Printing: Multiple Switching Extrusions (MSE) – Draft

Status: early draft with rotary Z 4 printheads and rotary Y 2 printheads

Updates:

  • 2021/08/01: MSE Z4 printed & mounted
  • 2021/02/09: matured Rotary Y MSE dual with a servo
  • 2021/01/31: added more drafts and formulated Pros and Cons for Rotary Z MSE, post published, with part cooler
  • 2021/01/29: starting with collecting existing solutions and consider my options, Rotary Y (max 2 printheads) and Rotary Z (max. 4 printheads) design started

Introduction

Since I dedicated some time for the IDEX upgrade on all the 4 Ashtar Series: K, C, M and D, I realized one of the main advantages of IDEX is to have the non-active printhead aside and not moving over existing prints and certainly not oozing over it.

There is another way to achieve such, by having multiple printheads mounted on the X carriage and mechanically switch them so only one nozzle actually touches the Z plane to print, all other printheads aside and sealing their nozzle with anti-oozing measure like an underlying metal sheet.

Existing Solutions on Thingiverse

As I like to have my own solution in OpenSCAD source, so let’s dive into the design process:

Multiple Switching Extrusions (MSE)

Design Goals

  • 2, 3 perhaps 4 heads switching, only one printhead/nozzle at Z printing head
    • share one heatsink fan
    • share one part cooler setup and fan
  • simple adjustable calibration of X, Y, Z repeatability
    • ideally interchangable between
      • E3D V6: proven reliability
      • Micro Swiss / CR 10 clone: single screw to set Z distance
  • inactive printheads non-ooze with shield
  • keep it simple, don’t overengineer, keep construction simple and light

Drafts

Rotary Y-Wise

Rotating around the Y axis, suitable for 2 printheads only, as 3 or more printheads use up too much in X space:

Simple design, shared fan is difficult, as I like to go with Micro Swiss as it’s very compact, I likely end up with dedicated heatsink fans as all printheads in use will be heating and the heatsinks require fanned air. The ooze-shields are easy to attach.

  • 132mm / 20°: tall (not good), narrow X space (good)
  • 120mm / 24°: still ok
  • 110mm / 27°: extending X space usage
  • 100mm / 35°: low but extending too much in X

So let’s combine most narrow with a common fan approach, for a compact dual switching printhead/extrusion sacrificing as little X space as possible:

The actual axis of rotation can be moved lower by becoming an arc or swing, which will make the construction more complex, but likely more reliable as the servo cannot be trusted to keep position exact enough – so a spring to keep the swing in either two position, or constant force to push to a left or right limit in dual extrusion setup – for now I use a small SG90 servo to push toward the mechanical stoppers, either left or right hence only usable in dual setup, and using a 1mm wire to connect the swing with the servo.

Rotary Y 3 using too much space

The Rotary Y approach definitely is only suitable for dual extrusion setup, as anything else, as seen on this comparison, uses up too much X space for my consideration.

Addendum: DerM4209 did a design with 6 extruders on full 360° rotary, and as the setup shows, he has plenty X-axis space to dedicate to such.

Let’s explore another idea . . .

Rotary Z-Wise

This design is heavier with NEMA17 motor, and with the focus of more than 2 printheads but 3, or 4 printheads, inspired by the Rotating Tilted Nozzle:

I first went for 9 sided regular polygon, and then switch to 360°/9 angle and only make a connector where the heatsink/printhead is mounted to.

I could tilt the other way and regain some of the Y offset, but the Bowden tube and cable of the printheads would clash with the mount – the same problem arise when I would position the full circle with printheads, it looks nice but doesn’t work with Bowden tubes:

So for the moment I stay with 360°/9 angle and explore further on the details with 4 printheads/extrusions.

Printable Parts

MSE Y2

Not yet.

MSE Z4

  • mse_rotz_mount
  • mse_setup-type=rotaryz,heads_n=4
  • mse_partcooler_mount
  • cr10_hotend_fan_mount_simple (4x)
  • mse_rotz_fannose

Assembly

  • Each hotend is mounted with 2x M3x20 mounting heatsink, and
  • 2x M3x16 mounting the 30mm fan on top.
  • 4x M3 x 8mm used to mount NEMA 17 on top of mse_rtz_mount, and
  • 4x M3x8 to mount it to the X carriage.
  • The part cooler mount is attached with M3x10 with a M3 nut and can be adjusted.

Brief tool changing test:

and guiding the PTFE tubes with a guide:

Ashtar K with Multiple Switching Extrusions (MSE)

Rotary Z with 4 printheads mounted on Ashtar K to see how much space X and Y is sacrificed or otherwise fit with existing design – so far it looks good:

This design is more flexible and extendable, the ooze shields are mounted on the “nose” underneath using metal sheets.

And the Rotary Y with 2 printheads (MSEY2) mounted looks good so far, sacrificing little X space as well:

Issues to Resolve

Rotary Y with Servo

  • mature draft to something actually promising, done with SG90 servo
  • strength to hold angle, likely use servo to constantly push toward a mechanical limit, dual mode: left/right limit, tripple mode some kind of spring the servo has to overcome
    • alternatively using magnets (e.g. 6mm/0.8mm) on anchor and stoppers: pushing anchor without servo or motor, but pushing carriage to X home left and X home right to switch between two states
  • reposition reliability, some kind of spring mechanism, and servo is only used to “jump” to new position
  • mount to X carriage, servo clashes with belt mount, resolved
  • press-fit 625 ZZ bearings based switch axis
    • sufficiently narrow play/margins for printing? tests needed
    • dual bearings still wobbles in Y-axis (when mounted)
    • single bearing doesn’t wobble, more friction when switching

Rotary Z with NEMA 17

  • early draft, untested
    • rotation tested: 40° per tool, e.g. G1 A0, G1 A40 in RepRapFirmware (Duet3D boards)
    • testing holding torque when printing (nozzle running over overextruded parts)
  • mount heatsink fans, done
  • rotary angle calibration at start, position/tool #0 (0 .. heads_n-1) => tool number (e.g. T2)
    • either mechanical homing of the rotation to position/tool #0 or
    • end stop switch to home rotation position
  • ooze shields. mounting for metal sheets prepared & illustrated
    • heat creep toward the “nose”?
    • do ooze shields add to cross-contaminating when changing tools
      • paying attention to details how to bend metal sheets
  • mount to X carriage, done
  • part cooler, will be tricky as, resolved
    • above mount won’t work due Bowden tubes cross through
    • mount via “nose” where the non-ooze metal sheets are mounted, done
  • Marlin firmware tool changing Gcode support with NEMA17 rotating?
  • Bowden tube guides, ensuring smooth rotating of Bowden tubes & wires
    • rings around NEMA 17, in particular around the edges
    • combine tubes & wires above the motor

Considerations

Rotary Y 2

Pros

  • simple mechanical setup incl. ooze shields
  • fast switching of extruders

Cons

  • servo SG90-based: only suitable for dual setup (not extendable to 3 extruders)

Rotary Z 4

Pros

  • fast switching of extruders
  • heavier than a servo, but more reliable holding position
  • simple design, as this design mounts on all of Ashtar Series (K, C, M & D)
  • 2, 3 or 4 printheads/extruders mountable, more flexible than IDEX which only has 2 printheads and requires more modifications

Cons

  • additional moving weight on X axis (NEMA17)
  • loss of build volume in X space ~5-10mm left and right
  • optional loss of build volume in Y space, it can be compensated if printer is used with MSE option only, otherwise some Y space sacrificed as well ~20-30mm
  • ooze shields may contaminate material to rotating nozzles, needs to be tested
  • all nozzles are heated even when not currently selected but will be used during the print
    • some people still print a purge block to purge material from the nozzle newly selected – fast switching material should be ok, long wait between switches may require purging of material – tests needed

Requirements

Rotary Y

  • 1x SG90 servo
  • 2x 625ZZ bearings
  • 1x M5x25 screw
  • 1x M5 nut
  • 50mm x 1mm wire, bend as hinge

Rotary Z

  • 1x rotating motor (NEMA17 20/25/39 mm) with motor driver
  • per additional printhead (given there is a single printhead already installed)
    • an extruder (incl. NEMA17)
    • motor driver on the mainboard
    • printhead (heatsink, heatbreak, heatblock, heat cartridge, nozzle, push fit adapter for bowden)
    • heating driver on the mainboard
    • thermistor input on the mainboard

So for

  • 2 printheads: 2x additional NEMA17 (1x rotating motor + 1x additional extruder), 2x 40W = 80W power
  • 3 printheads: 3x additional NEMA17 (1x rotating motor + 2x additional extruders), 3x 40W = 120W power
  • 4 printheads: 4x additional NEMA17 (1x rotating motor + 3x additional extruders), 4x 40W = 160W power

Obviously you need a mainboard with sufficient heating drivers or (1 digital output and MOSFETs per hotend) and thermistor inputs (ADC), the motor drivers can be added to 2 digital outputs (STEP & DIR) and external motor driver. More detailed informotation will be added later.

Gallery

Very early draft to see how MSE4 looks mounted on Ashtar K, C, D and M:

  • Ashtar K has sufficient space for extruders
  • Ashtar C may have more extruders, not sure where beyond 4 extruders
  • Ashtar D reaches its limits with 4 mounted extruders, unless the controller/display is moved away
  • Ashtar M might not be the best candicate to have a heavier X carriage as it will affect print quality at higher Z positions

I keep updating this blog-post as I progress.

Comparison Dual/Multi Color/Material Extrusions

blue = relevant positive
red = relevant negative

Independent Dual Extrusions (IDEX)

  • complex setup
  • moderate cost
  • non-mixing
  • dual nozzles
  • dual heatblocks
  • dual heatsinks
  • normal retraction
  • no purge block 1)
  • no oozing over print
  • no inactive nozzle traveling
  • reliable 2)

★★★★★

Dual Hotends 2-in-2

  • simple setup
  • low cost
  • non-mixing
  • dual nozzles
  • dual heatblocks
  • dual heatsinks
  • normal retraction
  • no purge block
  • inactive nozzle oozing over prints
  • inactive nozzle travels over print
  • moderate reliability

★★★★★

Chimera 2-in-2

  • simple setup
  • clone: low cost
  • original: high cost
  • non-mixing
  • dual nozzles
  • dual heatblocks
  • single heatsink
  • normal retraction
  • no purge block
  • oozing of inactive material
  • inactive nozzle travels over print
  • moderate reliability

★★★★★

Cyclops 2-in-1

  • simple setup
  • clone: low cost
  • original: high cost
  • mixing
  • single nozzle
  • single heatblock
  • single heatsink
  • normal retraction
  • purge block required
  • no oozing of inactive material
  • clone: unreliable

★★★★ (clone)

Cyclops NF 2-in-1

  • simple setup
  • low cost
  • non-mixing
  • single nozzle
  • single heatblock
  • single heatsink
  • complex retraction
  • no oozing of inactive material
  • moderate reliability

★★★★★

Diamond Hotend 3-in-1

  • complex setup
  • clone: low cost
  • original: high cost
  • mixing
  • single nozzle
  • single heatblock
  • 3 heatsinks
  • tricky retraction
  • purge block required
  • no oozing of inactive material
  • moderate reliability

★★★★★

Multiple Switching Extrusions (MSE) 2-in-2, 3-in-3, 4-in-4

  • moderate complex setup
  • requires additional servo or motor
  • extendable 2, 3, or 4 colors/materials
  • low cost
  • non-mixing
  • multiple nozzles / heatblocks / heatsinks
  • normal retraction
  • no purge block 1)
  • no oozing of inactive material
  • no inactive nozzle touching print
  • reliable 2)

(rating comes later)

Y Splitter x-in-1

  • simple setup
  • extendable 2, 3, or 4 or more colors / materials
  • low cost
  • non-mixing
  • single nozzle
  • single heatblock
  • single heatsink
  • complex retraction
  • purge block required
  • no oozing of inactive material
  • moderate reliability

★★★★★

Tool Changer

  • complex setup
  • extendable to n-colors or materials
  • moderate cost
  • non-mixing
  • multiple nozzles / heatblocks / heatsinks
  • normal retraction
  • no oozing of inactive material
  • no inactive nozzle touching print
  • moderate reliability

(rating comes later)

Footnotes

  1. in theory no purge block, but if ooze shields are shared among switching extrusions (more than 2 extrusions) there may be cross-contamination between colors/materials
  2. the printheads individually are proven to be reliable

Hints:

  • single heatblock = same print temperature
  • dual heatblock = different print temperatures possible
  • dual nozzle = different nozzle sizes possible

That’s it.

3D Printing: Rotating Tilted Nozzle 4th Axis Option – Draft

Status: prototype doing test prints

Updates:

  • 2021/05/31: first prototype photos with dry run
  • 2021/03/13: fallback printing horizontal slices animation added
  • 2021/03/01: added brief animation of simulated print of conic sliced overhang model
  • 2021/02/23: added brief animation (Zrot=-180° .. 180°)
  • 2021/01/31: maturing printhead with heatsink fan and part cooler
  • 2021/01/28: Outside/Inside Cone printing explained with example, Considerations (Pros/Cons) added
  • 2021/01/27: more detailed illustrations and slicing renderings, published as a draft
  • 2021/01/22: adding conic slicing examples
  • 2021/01/21: first version with rotating bowden printhead

I will update this blog-post as I progress or find other people with alike ideas and summarize the findings.

Introduction

RotBot by ZHAW School of Engineering Zurich

RotBot by ZHAW School of Engineering Zurich (2021/01/13), rotating tilted nozzle

As featured on Hackaday January 16, 2021 and other sites, a “Novel 4-Axis 3D Printing Process to Print Overhangs Without Support Material” by ZHAW School of Engineering (Zurich, Switzerland), from the abstract of the paper:

[..] a novel 4-axis FDM printing process with a newly designed printhead, for the printing of overhangs without support structures. With conventional FDM printing, overhangs of more than 45deg–60deg must be supported.

For this novel printing process, the printhead is rotated 45° around a horizontal axis and equipped with a vertical, rotational axis. The printhead no longer follows layers parallel to the build platform, but moves on the surface of a 45deg cone. The printing cone increases in diameter from layer to layer. With this cone-shaped layers, the printable angles increases by 45°, which leads to printable overhangs of up to approximately 100°.

New slicing strategies for this printing process have been developed to slice the parts for the novel printing process. The feasibility of the concept has been prototypically demonstrated. The novel design achieves the advantages of higher speed and quality with lower cost at the same time.

A brief video sequence of printing (YouTube) shows the machine movement. Unfortunately, as of 2021/01 not much more details have been published by ZHAW except a paywalled paper [sigh] which contains useful overview of their research. I contacted ZHAW and Michael Wuethrich mentioned that they are in negotiations with different companies to develop a product (2021/01) and eventually release the details of their slicing approach with pre- and post-processing while using an ordinary slicer.

Update 2021/02/27: I started with a 4-axis conic slicer.

Rotating Tilted Nozzle (RTN) Option

I thought to try my own implementation of this Rotating Titled Nozzle 4 Axis option. The main idea to keep the entire hotend in Bowden style and rotate that around only once (non-continuous) with all wires, that would simplify things greatly:

The challenge is the +/-180° position when the nozzle opening looks forward, where the printhead bowden tube (and all cables) comes most close to the X beam. As a consequence only -180° to +180° rotation is allowed and not multiple revolutions.

It would also mean, once the printhead reaches -180°, and it has to rotate to +180° and decrease from there again to fulfill 360° rotation – whether this is suitable has to be seen, this likely creates a seam there.

The main advantage of this simplified 4 axis approach is to use existing pieces plus just an additional NEMA 17 motor.

Update 2021/01/26: Wuethrich from ZHAW mentioned that they started first also with a full printhead rotating but then switched to the more complex continuous rotating printhead to avoid a seam, have direct drive extruder, faster prints as simpler decision making to change rotation direction and no start/stop of rotation and de/acceleration when reaching -180/+180° position.

Single Revolution with Rotation Shadow

As I pondered on the limits of single rotation approach, there is a range where the bowden tube (and all wires with it) is touching and bending on the X carriage or printhead holder – let’s call it the rotation shadow – ideally it would be zero or slightly sub-zero to have a bit overlap to conceal a possible seam with “ironing” the section (move nozzle over section without extruding).

E3D Volcano

My first attempt is modeling with E3D Volcano hotend like the RotBot by ZHAW:

Micro Swiss / CR 10 Hotend

And as alternative the smaller Micro Swiss / CR 10 printhead which gives significant more space for the bowden tube (and all wires with it) to bend or flex near -180/+180°:

Comparison Volcano vs Micro Swiss

At this point I continue with the Micro Swiss (MS) option, as the smaller heatsink gives me more space to make full 360° turn with -180° to +180° and have ~0° rotation shadow, perhaps even sub-zero as of overlapping.

This particular Swiss Micro clone aka CR10 hotend comes without screws stabilzing the heatblock, and just a small worm-screw fastening the heatbreak on the heatsink, yet make it easy to adjust the overall length, which in this case is desired.

Prototype

Eventually I took the time to print and assemble my Micro Swiss-based Rotating Tilted Nozzle (RTN):

First test run revealed:

  • rotation 170°..180° and -170°..-180° were not reliable with NEMA 17 37mm as skipping steps due the stiffness of PTFE tube with filament – resolvement: increase arm length (away from X carriage down/forward)
    • partially resolved by limiting A to -170°..170°: M208 A-170 S1 and M208 A170 S0 in config.g of Duet 3 Mini 5+ setup
  • micro swiss / CR 10 hotend heatblock socket touches the bed (same height as nozzle), fixed due slight tilt from X carriage due weight, newer design allows angle readjustment
  • single rotation requires refinement by the Slicer4RTN, addressed partially with Slicer4RTN 0.6.0, might require more fine-tuning.

I’m focusing on the hardware-side on the Penta Axis (PAX) 5-Axis printhead and transfer some of the experiences back into the RTN design.

Slicing for Rotating Tilted Nozzle: Conic Slicing

I had to visualize the novel conic slicing approach as mentioned in the article and in the video:

f(Z rot, C height, R) ⟹ X, Y, Z

X = sin(Z rot) * R
Y = -cos(Z rot) * R
Z = C height / sqrt(2)

Z rot = atan2( -Y, X )
R = sqrt( X*X + Y*Y )
C height = Z * sqrt(2)

A single conic slice is covered by Z rot, C height and R, whereas slices are separated by increasing Z offset to C height, forming conic slices on top of each other:

Let’s inspect the motion of a single layer: it’s curved – obviously – in X, Y and Z – this means, the Z axis has way more motion than in cartesian XZ Prusa-Mendel setup where the Z axis only changes once a layer is finished, here with cone-slicing every trace or track all traditional 3 axis are in motion, plus the 4th – the tangent on that conic trace.

Planar vs Conic Layers
Multiple solids sliced planar and in conic manner

See more details on Conic Slicing for Rotating Tilted Nozzle (RTN).

Different Print Modes

The 45° tilted printhead allows three print modes:

  • non-rotation nozzle with planar Z layers (with ordinary slicer), acts like belt-printer in one direction: overhangs in one direction without support
  • rotation nozzle with planar Z layers (requires dedicated slicer), might support near 90° overhangs of a certain length in all X/Y plane directions as well – but needs to be tested
  • rotation nozzle with conic Z layers (requires dedicated slicer or pre- and post-processing while using ordinary slicers)

And by choosing the position of the “axis” of the conic slicing within the model and the cone direction matters then as well:

The last piece with inside and outside looking overhangs requires a switch of nozzle direction, e.g by default the sliced cones are ordered ▲ (outside-in or outside-cones) where outward overhangs work, but for inward overhangs the opposite direction of the nozzle looking outside is required ▼(inside-out or inside-cones), like this piece:

So the slicing software needs to recognize this, and the sliced cones switched either ▼ or ▲ according Z level.

These aspects opens a whole new range of considerations how to orient a piece and where to position the newly introduced slicing axis, and which kind of cones need to laid at which level.

Issues to Resolve

  • Heatsink fan mount: needs to be mounted for both variants, Micro Swiss and E3D Volcano ideally
  • Part cooler:
    • have the part cooler rotate on Z axis as well? yes for now
    • using a flexible pipe to blow air near the nozzle instead

  • Z rotation calibration:
    • alike with X or Y stop, but a trigger rotating from one direction only and then set a angle offset
  • Z rotation motor mount adaptable for different kind of printheads
    • keep it modular
    • ensure the nozzle end is centered (allow simple center calibration)
  • Properly document design and features of Rotating Tilted Nozzle as there isn’t much detail information available
  • 3D printer firmware support
    • Marlin: support for 4th axis?
  • 3D slicing software support

Considerations

Pros

  • conic layers: printing 90° overhangs without support, given some conditions are met:
    • overhangs must be horizontally or vertically rotational symmetric and aligned with the cone axis to switch from outside to inside cone printing or vice-versa (to do: more use cases explored and documented)
  • conic layers: stronger pieces as layers cross X, Y and Z in non-planar manner, mechanical forces distribute further than just planar layers
  • planar layers / rotating nozzle: perhaps close to 90° overhangs (speculative) requires new overhang algorithms in slicer

Cons

  • additional mechanical complexity
    • fine-tuning nozzle center calibration
  • additional slicing software complexity
    • conic layers: more things to consider (preferably recognized by the slicing software):
      • overhangs must be horizontally or vertically rotational symmetric and align with cone axis to take advantage of it (complex compartmentalizing of different cone-direction per overhang and newly introduced seams between those)

Ashtar K with Rotating Tilted Nozzle (RTN)

The additional Y offset is about 20mm, and losing apprx. 50 mm in Z build volume in its current form:

Ashtar K RTN (animated)
Ashtar K RTN printing conic sliced overhang model (animated)

Fallback Print Horizontal Slices

Some parts may not require conic slices, e.g. introducing new unprintable overhangs which in horizontal slices would not exist, so a simple way to print traditional sliced models is by adding a proper rotation angle (e.g. G-code A..) so the nozzle extrudes nicely, something like:

Horizontally sliced 20mm cube printing with enhanced G-code with rtnenhancer

I wrote a small script called rtnenhancer which converts existing G-code to enhanced G-code.

References

See Also

That’s it.

3D Printer: IDEX for Ashtar K, M, D and C (2021/01)

Updates:

  • 2021/01/31: added comparison regarding Multiple Switching Extrusions (MSE)
  • 2021/01/18: added IDEX Features with Pros/Cons, Ashtar Series Genealogy, Comparison Dual Material approaches, and brief Hardware Requirements
  • 2021/01/15: first version with overview side-by-side

Mid of January 2021 (01/12 – 01/14) I added IDEX (Independent Dual Extrusion) option to 4 designs, all still in early draft stage – here as a summary side-by-side:

Ashtar K IDEX has been fairly easy, as I was using an improved “old” design of the X motor mount for the 2nd motor and 2nd belt, and since Ashtar M IDEX is using the same XZ frame, it was a matter of a few minutes to port that option as well.

Ashtar D IDEX with Classic XY belt routing was more tricky as there was little space left to add another motor, so I realized I need to utilize what’s there and take advantage of it – result is a very space saving solution, but it needs to be verified in real life first.

Ashtar C IDEX with Core XY with an additional X motor was easy, I just reused a slightly altered X motor/pulley mount of Ashtar D, so that was done fairly quickly as well, yet the challenge will be the firmware support, as currently (2021/01) only Duet RepRap firmware supports the CoreXYU as my design falls under.

Features of IDEX

Pros:

  • double printing: duplicate or mirror mode
    • double printing volume at same duration
  • two materials with different melting points
  • two colors (non-mixing) with
    • more reliable than dual nozzle setups, as inactive nozzle does not run over existing printed piece often
  • possibly different nozzle sizes
    • dedicated nozzle for infill vs outline

Cons:

  • slightly reduced build-volume in X-axis
  • added complexity

Comparison Dual/Multi Color/Material Extrusions

blue = relevant positive
red = relevant negative

Independent Dual Extrusions (IDEX)

  • complex setup
  • moderate cost
  • non-mixing
  • dual nozzles
  • dual heatblocks
  • dual heatsinks
  • normal retraction
  • no purge block 1)
  • no oozing over print
  • no inactive nozzle traveling
  • reliable 2)

★★★★★

Dual Hotends 2-in-2

  • simple setup
  • low cost
  • non-mixing
  • dual nozzles
  • dual heatblocks
  • dual heatsinks
  • normal retraction
  • no purge block
  • inactive nozzle oozing over prints
  • inactive nozzle travels over print
  • moderate reliability

★★★★★

Chimera 2-in-2

  • simple setup
  • clone: low cost
  • original: high cost
  • non-mixing
  • dual nozzles
  • dual heatblocks
  • single heatsink
  • normal retraction
  • no purge block
  • oozing of inactive material
  • inactive nozzle travels over print
  • moderate reliability

★★★★★

Cyclops 2-in-1

  • simple setup
  • clone: low cost
  • original: high cost
  • mixing
  • single nozzle
  • single heatblock
  • single heatsink
  • normal retraction
  • purge block required
  • no oozing of inactive material
  • clone: unreliable

★★★★ (clone)

Cyclops NF 2-in-1

  • simple setup
  • low cost
  • non-mixing
  • single nozzle
  • single heatblock
  • single heatsink
  • complex retraction
  • no oozing of inactive material
  • moderate reliability

★★★★★

Diamond Hotend 3-in-1

  • complex setup
  • clone: low cost
  • original: high cost
  • mixing
  • single nozzle
  • single heatblock
  • 3 heatsinks
  • tricky retraction
  • purge block required
  • no oozing of inactive material
  • moderate reliability

★★★★★

Multiple Switching Extrusions (MSE) 2-in-2, 3-in-3, 4-in-4

  • moderate complex setup
  • requires additional servo or motor
  • extendable 2, 3, or 4 colors/materials
  • low cost
  • non-mixing
  • multiple nozzles / heatblocks / heatsinks
  • normal retraction
  • no purge block 1)
  • no oozing of inactive material
  • no inactive nozzle touching print
  • reliable 2)

(rating comes later)

Y Splitter x-in-1

  • simple setup
  • extendable 2, 3, or 4 or more colors / materials
  • low cost
  • non-mixing
  • single nozzle
  • single heatblock
  • single heatsink
  • complex retraction
  • purge block required
  • no oozing of inactive material
  • moderate reliability

★★★★★

Tool Changer

  • complex setup
  • extendable to n-colors or materials
  • moderate cost
  • non-mixing
  • multiple nozzles / heatblocks / heatsinks
  • normal retraction
  • no oozing of inactive material
  • no inactive nozzle touching print
  • moderate reliability

(rating comes later)

Footnotes

  1. in theory no purge block, but if ooze shields are shared among switching extrusions (more than 2 extrusions) there may be cross-contamination between colors/materials
  2. the printheads individually are proven to be reliable

Hints:

  • single heatblock = same print temperature
  • dual heatblock = different print temperatures possible
  • dual nozzle = different nozzle sizes possible

Hardware Requirements

  • 1x NEMA 17 42-45Nm with wire, extra stepper motor driver on motherboard
  • 100-110cm long 6mm wide GT2 belt
  • 1x pulley and 1x idler
  • 1x hotend (nozzle, heatblock, heat cartridge, heatbreak, heatsink), extra heating connector on motherboard

That’s it.

3D Printing: Ashtar C IDEX (Independent Dual Extrusion)

Status: just a draft

Updates:

  • 2021/01/14: quick start with a rough draft

Introduction

Well, after the IDEX option designs – still as drafts – worked for Ashtar K (Prusa i3), Ashtar M (Moving Gantry) and Ashtar D (Classic XY), I thought, why not also target Ashtar C (Core XY).

Ashtar D IDEX is definitely a narrow design, so I thought to reuse two parts of it for Ashtar C as well, and hopefully the A and B belts route around – and well, it seems mechanically to work out.

On the firmware part it seems this CoreXY plus additional X motor is called CoreXYU and supported by Duet RepRap firmware – but details need to be researched in more depth. On the first glance the “traditional” CoreXYU setup routes the U belt off the X beam and not place a motor on it as I do, but routes at the end of the frames so the motor is stationary – definitely something also to look at.

Draft

Gallery

Issues to Resolve

  • Firmware supporting CoreXY IDEX:
    • E1: X & Y provided through CoreXY by motors A & B
    • E2: X provided by X motor, Y provided by CoreXY where X=0 remains (both motors A & B have to operate to provide X=0 while Y is moved)
    • Duet RepRap firmware provides CoreXYU support, and it seems it would cover my use case here
    • Marlin firmware as of 2.x does not support CoreXYU yet
  • Moving the X motor – or U motor as in CoreXYU context – off the X beam and route a much longer belt and place the motor stationary like the motors A & B of CoreXY
  • Ooze prevention (same issue as with Ashtar D IDEX)

As I progress I will update this blog-post, and summarize also the developments in the Ashtar C project page.

References

  • CoreXYU: Dual Head for CoreXY, another more complex approach where 3rd motor is also stationary

That’s it.

3D Printing: Ashtar D IDEX (Independent Dual Extrusion)

Status: just a draft

Updates:

  • 2021/01/14: starting the draft, very experimental

Introduction

After just few hours working on IDEX option for Ashtar K and Ashtar M, I thought to try myself on doing IDEX on the very delicate Y carriage on Ashtar D – and after an hour roughly I realized, perhaps it is doable.

The main idea is to reuse the NEMA17 shaft as axis for the idler of the 2nd belt, and use 3mm diameter shaft with 5-10mm length as extension, and stabilize the extension in the idler itself likely the shaft seems long enough by itself – the most space saving option:

If possible, rotate entire X motor mount / carriage and mount it on the other X side.

Draft

I had to color the belts and V modules, as I otherwise get confused while fine-tuning the design within such narrow margins:

  • X1/E1 in green
  • X2/E2 in red

I just love symmetry!
I just love symmetry!

Gallery

Issues to Resolve

  • X motor-mount isn’t fully Y symmetric yet, it’s off by a few mm; needs some further fine-tuning until X2 motor-mount mounting holes align with V module, resolved
  • V module belt mount for X2 needs be adapted, as I can’t mirror it as that “back” mirrored is the “front” side where the printhead is mounted and occupied already, a new piece is required which mounts within the V module
    • dedicated piece ad_xcarriage_beltmount(idex=true) required
  • ooze prevention in rest position: some sort of metal sheet close by where the printhead’s nozzle can rest
  • mature Ashtar D design sufficiently beyond draft stage

As I progress I will update this blog-post, and update the Ashtar D project page as well.

That’s it.

3D Printer: Ashtar K IDEX (Independent Dual Extrusion)


Status
: verified design

Updates:

  • 2021/07/30: design printed and mounted
  • 2021/01/19: improved 2nd X motor mount
  • 2021/01/15: removable/replaceable ooze prevention
  • 2021/01/14: Ashtar M (Moving Gantry – Draft) also with IDEX option now
  • 2021/01/13: ooze prevention at rest position added, mechanical conflict resolved
  • 2021/01/12: starting with a first draft, one mechanical conflict to be resolved

Introduction

I have been pondering on a dual independent X axis upgrade or option for a while, but the other designs of the Ashtar Series I wanted to do first (Ashtar D and Ashtar M) those matured by now (2021/01), so I decided to get back to IDEX upgrade for Ashtar K:

For now I like to keep single 2020 V slot alu extrusion for the X beam where the X carriage rides, and route the 2nd belt above for the 2nd X carriage – and this was a quick solution as earlier version of Ashtar K had the belt routed above the alu profile so I just reused the old pieces again.

“Above routed belt” option with its pieces are weaker and possibly need enforcement improved the strength, so it’s a fast start – just took me 2 hours – but needs definitely some fine-tuning. Alternatively the 2nd belt could be routed at the back of the X carriages, but fastening the 2nd X motor would be challenging.

For now I use the same code base of Ashtar K and introduce IDEX = true flag, and enhance a few existing pieces in parts.scad and optionally add those new pieces when rendering printer-ak.scad.

As I progress with this option or upgrade I update this blog-post.

Draft

Issues to Resolve

  • X carriage #1 belt mount conflicts mechanical with belt 2: redesign xcarriage_beltmount_2020 piece, make it shorted in Z or fasten it inside V module: resolved, shifted 2nd belt a bit Y off, and shorten xcarriage_beltmount_2020(idex=true) by 2mm.
  • “Above routed belt” pieces are weaker: enforcement required, resolved: piece strengthened (2021/01/19):
    • xcarriage_short_hmount_motor_2020 which is the base piece which routes the belt within the 2020, with idex=true option provides idler holder on top
    • X motor #2 is mounted on a x-mirrored version of xcarriage_hmount_motor(20,"left",idex=true) but definitely needs reinforcement, added ooze prevention in case of idex set
  • Nozzle drip prevention:
    • using a piece of sheet metal which the nozzle moves over when in rest position left or right, first attempt done (see below)
    • and/or use purge box with brush to clean nozzle after and before use
    • make extending “nose” detachable/replaceable as it’s expected to break or overheat otherwise entire X motors mount needs replacement, resolved
      • xcarriage_nose-idex-left and xcarriage_nose-idex-right with 10mm wide sheet metal insert
    • how dealing with long resting hot nozzle?
      • drop temperature by 5-10°C in rest position, and heat up when in use again
      • heat creep possible weakening extending printed nose – heat insulation required attaching sheet metal

Gallery

Ashtar M IDEX

And since Ashtar M (Prusa i3 Moving Gantry – Draft) shares much of the Ashtar K design it took me a few mins to add the IDEX upgrade option as well:

References

3D Modeling: Random Snapshots 2020

3D Printer: Ashtar K History 2018-2020

A brief history of “Ashtar K“, my first designed 3D printer I actually built – documented also for my own sake:

AluX: Prusa i3 Clone

It started with AluX (abbreviation of ALU-extrusion eXtendable) early June 2018, which used CTC i3 Pro B / Prusa i3 Clone pieces as the X carriage, X motor mount and X idler all in STL format. I coded the frame parametric using 2040 alu extrusions/profiles and using smooth rods as rails:

I realized then quickly I need to design and code my own pieces, every single piece I need to control and make it parametric if it makes sense, and not rely on existing STL files, as editing meshes of the STL seemed a waste of time but rather design the piece in OpenSCAD right away and derive new variants if necessary from the geometry itself.

Ashtar X & W Series: Riding on Smooth Rods

Mid June 2018, AluX became Ashtar X (abbreviated as AX), and Ashtar W were using 2040 alu extrusions but differently oriented at the base, still using smooth rods as rails:

At this point I got sufficient experience of the parametric approach and it was obvious to use the frame as rails.

Ashtar T Series: Riding Alu Profiles

Beginning of July 2018, with the Ashtar T series I began to use the frame as rails itself, utilizing 2040 alu extrusions, it also started with the parametric V module (due its shape) composed by 2x V-plates, using 3 wheels which ride on the alu extrusion:

With the parametric V modules the X, Y and Z frame beams became rails as well, simplifying the overall construction compared to earlier designs:

The dual Z motors still residing in the front for sake of accessibility, but then I realized I want them in the back and keep the front dedicated to the printhead.

Ashtar K Series: Riding Alu Profiles, Uni-Length Beams

Mid of July 2018 I started the Ashtar K series, I decided to use 2020 alu profiles and focused on the single length of alu profiles, uni-length so I could reuse the beams for other future designs and since all the designs were parametric, it was easy to attain to find an optimum of single length beams and a common build-plate or build-volume:

The 9 beams design turned out too weak when I actually built the printer, so I added two beams back on left and right, and lift up the 9 beam design.

Eventually I decided to use 500mm alu 2020 profiles to achieve ~380x300x360 build volume; Ashtar K #1 used 400×300 build-plate, and Ashtar K #2 300×300 build-plate. Ashtar K #1 was functional in August 2018, and since then became my working horses together with Ashtar K #2, reliably printing.

See more at Ashtar K project page of the current state.

Next Steps

Ashtar Series Genealogy (2018-2020)

After the Ashtar K I did the Ashtar C Core XY cubic frame also with 2020 alu profiles. Late 2020 I started to design Ashtar M, a derivative of Ashtar K but with a moving gantry and static bed, and Ashtar D with Classic XY alike Ashtar C; and also a draft of a parametric enclosure as well to be adaptable to all of my 3D printer designs.

That’s it.

3D Printing: Simple Compact Extruder with 625ZZ Bearing

Updates:

  • 2021/01/01: sufficiently tested, finally published
  • 2018/12/20: starting with write-up

I used some aluminium MK8-based extruders but realized I required my own parametric extruder using 625ZZ bearing and I looked around and found Compact Bowden Extruder by Dominik Scholz which uses 608ZZ and adapted the overall design but coded it from scratch again in OpenSCAD with 625ZZ bearing for the Ashtar Series:

It’s “right handed” by default, but filament can go both directions. The handle is pushed from inside out with a spring, not so elegant, yet it saves space and filament does not have to go through the handle this way, which I prefer.

Bill of Materials (BOM)

  • M5x14 or M5x16: mounting bearing
  • 2x M3x8: mounting base to stepper motor
  • 2x M3x25: mounting handle and spring
  • M3 nut: insert into slot
  • M3 washer (or print it): hold spring
  • 20-25mm long soft spring (ID 3.2-8mm) or alike
  • hubbed gear OD 11mm (MK8)
  • 625ZZ bearing

Recommended further:

  • PTFE OD 4mm, ID 2mm
  • PC4-M6 straight fitting

Building

Software

compact_extruder() takes following parameters, in case you like to recreate the pieces:

  • type:
    • "base": the base attached to the NEMA 17 stepper motor
    • "handle": the push handle with the spring
    • "indicator": small indicator to put on the axis of the stepper motor
  • mount:
    • "none": (default) just attaches to NEMA 17 stepper motor
    • "mount": simple mount (center)
    • "2020": extends flat (lower left version)
  • btd: Bowden tube diameter (default: 0), if 4mm is used, then Bowden PTFE OD 4mm/ID 2mm tube can be inserted on both sides as guides for flexible filament close to the hobbed gear as shown below
  • m5 can be redefined, e.g. 14 then it sinks in

Hardware

I use PC4-M6 push fit connector with PTFE tube 4mm OD / 2mm ID as guides, and began to use it right away on 3x printers for first tests:

Download

https://www.thingiverse.com/thing:3265864

includes STLs and OpenSCAD source code of the module

Applications

Direct Drive Extruder

A small adapter allows to mount the Compact Extruder close to the printhead to use it as Direct Drive Extruder:

I did not test the Direct Drive approach as I prefer the Bowden setup on my printers, but have it ready when needed, e.g. for flexible filament.

References

See Also