Skip to content
DerAndere edited this page Mar 25, 2023 · 110 revisions

Marlin2ForPipetBot firmware

Copyright 2018 - 2023 DerAndere

Marlin2ForPipetBot firmware for multi-axis 3D printers, CNC machines and lab robots

Note: Multi-axis-Marlin firmware was merged into upstream MarlinFirmware/Marlin bugfix-2.1.x in two steps on 5th June 2021 and on 1st April 2022, so support for up to 9 non-extruder axes is part of official MarlinFirmware/Marlin.

Thanks to the extra axes it is now possible to do indexed multi-axis machining and to drive additional tools (pumps, toolchangers or other) with Marlin. Continuous multi-axis machining with Tool Center Point Control (TCPC) is currently only supported by Marlin2ForPipetBot, not by upstream MarlinFirmware/Marlin.

Code from this repository (DerAndere1/Marlin) may contain additional multi-axis feautures, but official Marlin will be more up to date in general and contain less bugs. Use nightly builds of official MarlinFirmware/Marlin, Version "Marlin 2.1 with bug fixes (bugfix-2.1.x)", whenever possible.

Marlin2ForPipetBot is a firmware for multi-axis 3D printers, CNC machines and lab robots (liquid handling robots, "pipetting robots").

Additional documentation can be found on the PipetBot-A8 project page that is part of the website by DerAndere. Issues related to multi-axis support can be reported to DerAndere1 here. If you want to add support for more hardware or optimize compatibility with other software features, please first consider to fork MarlinFirmware/Marlin and contribute directly to upstream MarlinFirmware/Marlin according to their guidelines. If merging your changes into MarlinFirmware/Marlin is not an option, you are welcome to (re)base your changes onto the Marlin2ForPipetBot_dev branch of DerAndere1/Marlin and create pull requests targeting the Marlin2ForPipetBot_dev branch.
Please test this firmware and let us know if it misbehaves in any way.

Volunteers are standing by!

Not for production use. Use with caution!

The following information pertains to upstream MarlinFirmware/Marlin bugfix-2.1.x. Documentation relevant to Marlin2ForPipetBot or other versions can be found in the README file of the respective branch in this repository.

Marlin supports up to nine non-extruder axes plus extruders (XYZABCUVW+E).

Only a subset of the Marlin G-code dialect is supported with more than 3 non-extruder axes :

  • G0, G1, G2, G3, G28, G29 (only if secondary axes stay in neutral position), G90, G91, G92, T0, T1
  • M17, M18, M43, M85, M92, M111, M114 (partially), M201, M202, M203, M206 (partially), M500, M501, M502, M503, M504

Default axis names are:

Joint number Joint ID Default axis name
1 X X
2 Y Y
3 Z Z
4 I A
5 J B
6 K C
7 U U
8 V V
9 W W
E0 E0 E

In the firmware, each axis is mapped to a joint (stepper driver) according to setting *_DRIVER_TYPE and AXISn_NAME. Internally, joints have the identifiers X, Y, Z, I, J, K, U, V, W (in sequence).

G-code syntax

Marlin uses its own dialect of G-code derived from the language defined ANSI/EIA RS-274-D standard and the NIST RS274NGC interpreter - version 3. For G-code syntax supported by upstream MarlinFirmware/Marlin bugfix-2.1.x, see https://github.com/DerAndere1/MarlinDocumentation/tree/9axis_update/_gcode

Example syntax for movement (G-code G1) for a configuration with the following relevant config settings:

#define X_DRIVER_TYPE A4988
#define Y_DRIVER_TYPE A4988
#define Z_DRIVER_TYPE A4988
#define I_DRIVER_TYPE A4988
#define J_DRIVER_TYPE A4988
#define K_DRIVER_TYPE A4988
#define U_DRIVER_TYPE A4988
#define V_DRIVER_TYPE A4988
#define W_DRIVER_TYPE A4988
#define E0_DRIVER_TYPE A4988
//#define E1_DRIVER_TYPE A4988
#define AXIS4_NAME 'A'
#define AXIS4_ROTATES
#define AXIS4_NAME 'B'
#define AXIS5_ROTATES
#define AXIS6_NAME 'C'
#define AXIS6_ROTATES
#define AXIS7_NAME 'U'
//#define AXIS7_ROTATES
#define AXIS8_NAME 'V'
//#define AXIS8_ROTATES
#define AXIS9_NAME 'W'
//#define AXIS9_ROTATES
G1 [Xx.xxxx] [Yy.yyyy] [Zz.zzzz] [Aa.aaaa] [Bb.bbbb] [Cc.cccc] [Uu.uuuu] [Vv.vvvv] [Ww.wwww] [Ee.eeee] [Ff.ffff]

Parameters:

X, Y, Z: Position in the cartesian coordinate system consisting of primary linear axes X, Y and Z. Unit: mm (after G-code G21) or imperial inch (after G-code G20)

A, B, C: Angular position in the pseudo-cartesian coordinate system consisting of rotational axes A, B, and C that are parallel (wrapped around) axes X, Y and Z. Unit: angular degrees

U, V, W: position in the cartesian coordinate system consisting of secondary linear axes U, V and W that are parallel to axes X, Y and Z. Unit: mm (after G-code G21) or imperial inch (after G-code G20)

E: Distance the E stepper should move. Unit: mm (after G-code G21) or imperial inch (after G-code G20)

F: Feedrate. Three modes for feedrate interpretation are possible. By default, feedrate is interpreted as specified by LinuxCNC (successor of NIST RS274NGC interpreter - version 3) in its default state (trivial kinematics, "CANON_XYZ" feed reference mode, G94 Units-Per-Minute mode). The alternative feedrate interpretation modes can be enabled for machines where no distinction between primary axes (XYZ) and secondary axes is possible.

  • default:

    • For motion involving one or more of the X, Y, and Z axes (with or without motion of other axes), the feed rate means length units per minute along the programmed XYZ path, as if the other axes were not moving.
    • For motion of one or more of the secondary linear axes (axis names 'U', 'V', or 'W') with the X, Y , and Z axes not moving (with or without motion of rotational axes), the feed rate means length units per minute along the programmed UVW path (using the usual Euclidean metric in the UVW coordinate system), as if the rotational axes were not moving.
    • For motion of one or more of the rotational axes (axis names 'A', 'B' or 'C') with linear axes not moving, the rate is applied as follows. Let dA, dB, and dC be the angles in degrees through which the A, B, and C axes, respectively, must move. Let D = sqrt((dA)^2 + (dB)^2 + (dC)^2). Conceptually, D is a measure of total angular motion, using the usual Euclidean metric. Let T = sqrt((dA)^2 + (dB)^2 + (dC)^2) / F be the amount of time required to move through D degrees at the current feed rate in degrees per minute. The rotational axes should be moved in coordinated linear motion so that the elapsed time from the start to the end of the motion is T plus any time required for acceleration or deceleration.
  • ARTICULATED_ROBOT_ARM (see below) is for articulated robots, or for compatibility with other firmware (gblHAL, RepRapFirmware and Smoothie). When this option is defined, all axes are used as feed reference. This means that in all cases all axes are moved in coordinated linear motion so that the time (in minutes) required for the move is T = sqrt((dA)^2 + (dB)^2 + (dC)^2 + (dU)^2 + (dV)^2 + (dW)^2) / F plus any time for acceleration or deceleration.

  • FOAMCUTTER_XYUV(see below) is for foam cutters. When this option is defined, all axes are moved in coordinated linear motion so that the time (in minutes) required for the move is T = sqrt(_MIN((dX)^2 + (dY)^2, (dU)^2 + (dV)^2)) / F plus any time for acceleration or deceleration.

Configuration

Configuration is done by editing the file Marlin/Configuration.h. E.g. to enable the opion I_DRIVER_TYPE, change

//#define I_DRIVER_TYPE A4988

to:

#define I_DRIVER_TYPE A4988

Important options are:

ARTICULATED_ROBOT_ARM

Define ARTICULATED_ROBOT_ARM to enable feedrate interpretation mode suitable for articulated robots and for compatibility with other firmware (grblHAL, RepRapFirmware and Smoothie). Leave ARTICULATED_ROBOT_ARM disabled for default behaviour (see section "G-code syntax"). Currently it is recommended to disable AXIS*_ROTATES for all axes and to disable INCH_MODE_SUPPORT for articulated robots. Host software to control a robot arm can be found at https://github.com/MarginallyClever/Robot-Overlord-App (Requires configuration of kinematic parameters in the host software or implementation of inverse kinematics in Marlin).

FOAMCUTTER_XYUV

Define FOAMCUTTER_XYUV to optimize for a hot wire cutter with parallel horizontal axes X, U where the hights of the two wire ends are controlled by parallel axes Y, V. Currently only works with drivers up to (and including) J_DRIVER_TYPE defined. A dummy pin number can be assigned to pins for the unused Z axis. Usually, axis names should be #define AXIS4_NAME 'U', //#define AXIS4_ROTATES, #define AXIS5_NAME 'V', //#define AXIS5_ROTATES. Leave FOAMCUTTER_XYUV disabled for default behaviour (see section "G-code syntax"). Host software and CAM software for 4 axis foam cutters can be found at https://rckeith.co.uk/file-downloads/ and https://www.jedicut.com/en/download/ . Simple python libraries to generate G-code for 4 axis foam cutters can be found at https://github.com/jasonhamilton/hotwing-core and https://github.com/LinuxCNC/simple-gcode-generators/tree/master/airfoil.

X_DRIVER_TYPE

X_DRIVER_TYPE, Y_DRIVER_TYPE, Z_DRIVER_TYPE, I_DRIVER_TYPE, J_DRIVER_TYPE, K_DRIVER_TYPE, U_DRIVER_TYPE, V_DRIVER_TYPE, W_DRIVER_TYPE. Each enabled option in this sequence adds an axis. Each additional axis requires all previous axes in this sequence XYZIJKUVW to be enabled. Each axis also requires corresponding definitions of the following options:

  • I[, J [, K [, U [, V [, W]]]]]_STEP_PIN
  • I[, J [, K [, U [, V [, W]]]]]_ENABLE_PIN
  • I[, J [, K [, U [, V [, W]]]]]_DIR_PIN
  • I[, J [, K [, U [, V [, W]]]]]_STOP_PIN (for available pins, see the pins/pins_YOURMOTHERBOARD.h file for your board)
  • USE_I[, J [, K [, U [, V [, W]]]]][MIN || MAX]_PLUG
  • I[, J [, K [, U [, V [, W]]]]]_ENABLE_ON
  • DISABLE_I[, J [, K [, U [, V [, W]]]]]
  • I[, J [, K [, U [, V [, W]]]]]_MIN_POS
  • I[, J [, K [, U [, V [, W]]]]]_MAX_POS
  • I[, J [, K [, U [, V [, W]]]]]_HOME_DIR
  • possibly DEFAULT_I[, J [, K [, U [, V [, W]]]]]JERK

and definition of the respective values of

  • DEFAULT_AXIS_STEPS_PER_UNIT
  • DEFAULT_MAX_FEEDRATE
  • DEFAULT_MAX_ACCELERATION
  • HOMING_FEEDRATE_MM_M
  • AXIS_RELATIVE_MODES
  • MICROSTEP_MODES
  • MANUAL_FEEDRATE

and possibly also values of

  • HOMING_BUMP_DIVISOR
  • HOMING_BACKOFF_POST_MM
  • BACKLASH_DISTANCE_MM

For bed-leveling, NOZZLE_TO_PROBE_OFFSETS has to be extended with elements of value 0 until the number of elements is equal to number of non-extruder axes.

Allowed values: [A4988, ...]

AXIS4_ROTATES

AXIS4_ROTATES, AXIS5_ROTATES, AXIS6_ROTATES, AXIS7_ROTATES, AXIS8_ROTATES, AXIS9_ROTATES: If enabled, the corresponding axis is a rotational axis for which positions are specified in angular degrees. For moves involving only rotational axes, feedrate is interpreted in angular degrees per minute.

AXIS4_NAME

AXIS4_NAME, AXIS5_NAME, AXIS6_NAME, AXIS7_NAME, AXIS8_NAME, AXIS9_NAME: Axis codes for secondary axes: This defines the axis code that is used in G-code commands to reference a specific axis.

  • 'A' for rotational axis parallel to X (enabling AXIS*_ROTATES for this axis recommended)
  • 'B' for rotational axis parallel to Y (enabling AXIS*_ROTATES for this axis recommended)
  • 'C' for rotational axis parallel to Z (enabling AXIS*_ROTATES for this axis recommended)
  • 'U' for secondary linear axis parallel to X (disabling AXIS*_ROTATES for this axis recommended)
  • 'V' for secondary linear axis parallel to Y (disabling AXIS*_ROTATES for this axis recommended)
  • 'W' for secondary linear axis parallel to Z (disabling AXIS*_ROTATES for this axis recommended)

Note: Internally, each user-facing axis is sequentially mapped to joints ("firmware-internal axes"). Firmware-internal joint identifiers are I (AXIS4), J (AXIS5), K (AXIS6), U (AXIS7), V (AXIS8), W (AXIS9).

Allowed values: ['A', 'B', 'C', 'U', 'V', 'W']

EVENT_GCODE_TOOLCHANGE_TO

EVENT_GCODE_TOOLCHANGE_TO, EVENT_GCODE_TOOLCHANGE_T1: Event Gcodes to be executed when the printer receives toolchange commands T0 or T1, respectively.

Allowed values: a string containing G-code commands seperated by \n, e.g:

#define EVENT_GCODE_TOOLCHANGE_TO "G28 A\nG28 B\nG1 A0 B5 F100"

EVENT_GCODE_TOOLCHANGE_ALWAYS_RUN

When enabled, G-code sequences defined by options EVENT_GCODE_TOOLCHANGE_TO and EVENT_GCODE_TOOLCHANGE_T1 are not only executed when the machine directly receives tool change commands, but also when tool changes that are initiated indirectly by the firmware during execution of other commands (e.g. during homing or bed leveling). Use with caution!

LINEAR_AXES

Deprecated since Marlin 2.1.0. See X_DRIVER_TYPE.

NUM_AXES

Deprecated since Marlin 2.1.0. See X_DRIVER_TYPE.

Building Multi-axis-Marlin firmware

To build Multi-axis-Marlin firmware you'll need PlatformIO. The MarlinFirmware team has posted detailed instructions on Building Marlin with PlatformIO.

The most stable Marlin Firmware with support for up to 6 axes is current MarlinFirmware/Marlin. All contributions that are not specific to pipetting robots should be rebased onto https://github.com/MarlinFirmware/Marlin/tree/bugfix-2.1.x and a pull requests targeting https://github.com/MarlinFirmware/Marlin/tree/bugfix-2.1.x should be prepared.

The different branches in the git repository https://github.com/DerAndere1/Marlin reflect different stages of development:

Supported Configuration options:

Currently the configs by hobiseven, MarginallyClever, HendrikJan-5D and DerAndere are the only ones that were tested. Below is a list of features that were tested at some point and worked individually (although not in all combinations):

  • *_DRIVER_TYPE A4988
  • *_DRIVER_TYPE DRV8825
  • *_DRIVER_TYPE TMC5160
  • *_DRIVER_TYPE TMC2226
  • *_DRIVER_TYPE TMC2209
  • X_DRIVER_TYPE A4988
  • Y_DRIVER_TYPE A4988
  • Z_DRIVER_TYPE A4988
  • I_DRIVER_TYPE A4988
  • J_DRIVER_TYPE A4988
  • K_DRIVER_TYPE A4988
  • U_DRIVER_TYPE A4988
  • V_DRIVER_TYPE A4988
  • W_DRIVER_TYPE A4988
  • EXTRUDERS 0
  • EXTRUDERS 1
  • EXTRUDERS 2
  • DEBUG_LEVELING
  • DEBUG_PINS
  • [dogm display (possibly not all menus work flawlessly with axes I,J,K,U,V,W)]
  • One or two stepper drivers per axis (*_DUAL_STEPPER_DRIVERS)
  • [AUTO_BED_LEVELING_3POINT (bed leveling must be disabled while bed is not oriented horizontally or while tool is not oriented vertically)]
  • [AUTO_BED_LEVELING_LINEAR (bed leveling must be disabled while bed is not oriented horizontally or while tool is not oriented vertically)]

Boards:

  • ANET_10
  • RAMPS_14_EFB
  • MKS Rumba32
  • ALFAWISE_U20 (?)
  • ALFAWISE_U30 (?)
  • Teensy 3.6
  • BTT GTR V1.0 with M5 V1.0 board

Using Multi-axis-Marlin

Multiple syringe pumps, outlets positioned by axes XYZ (Similar to "Multi-Material-Unit" extruder configuration)

Let outlet positioning in space be controlled by axes XYZ. Let pumps be driven by axes U, V, each transfering a different substance. Assume that you want to dispense different amounts of different substances at different feedrates at overlapping timepoints. The G-code generator / CAM software needs capabilty of internal volume tracking. Then one would calculate the moves required for dispensing certain amounts of liquid in the G-code generator. The G-code generator splits the dispension up into individual G1 commands, whenever the number of simultaneously moving axes or the speed of any axis has to change. Lets say you want to dispense in total 110mL liquid from pump U and in total 150 mL of liquid from pump V at different (overlapping) timepoints and with different feedrates. The G-code generator / CAM software has to split this up into the following steps, e.g.:

  1. Dispense 100 mL U over 1 minute (requires speed: U 100mm/min)
  2. Dispense 10 mL U and 20 mL V over 1 minute (requires speeds: U 10 mm/min, V 20 mm/min)
  3. Dispense 30 mL V at same speed (required speed: V 20 mm/min)
  4. Dispense 100 mL V at 200 mL/min (required speed: V 200 mm/min)

For this example the G-code generator / CAM software needs to generate the following G-code script:

M203 U100 ;           set max speed U 100 mm/min
G1 U100 F99999 ;      try to move U at 99999 mm/min (Any high feedrate would work). will be limited by M203 max feedrate setting
M203 U10 V20  ;       set max speed U 10 mm/min, V 20 mm/min
G1 U10 V20 F99999 ;   try to move U, V at 99999 mm/min. will be limited to 10 and 20 mm/min by M203
M295 V20 ;            set max speed U 20 mm/min
G1 V30 F99999 ;       try to move U, V at 99999 mm/min. will be limited to 20 mm/min by M203
M203 V200 ;           set max speed V 200 mm/min
G1 V100 F99999 ;      try to move V at 99999 mm/min. will be limited to 200 mm/min by M203

Credits

Multi-axis support for Marlin firmware is developed by:

  • DerAndere [@DerAndere1] - Germany - Marlin2ForPipetBot Maintainer Donate
  • Garbriel Beraldo [@GabrielBeraldo] - Brasil
  • Olivier Briand [@hobiseven] - France
  • Wolverine [@MohammadSDGHN] - Undisclosed
  • bilsef [@bilsef] - Undisclosed
  • FNeo31 [@FNeo31] - Undisclosed
  • HendrikJan-5D [@HendrikJan-5D] - Undisclosed
  • Paloky [@paloky] - Undisclosed
  • Scott Lahteine [@thinkyhead] - USA

Multi-axis-Marlin firmware is based on Marlin firmware.

The current Marlin dev team consists of:

Scott Lahteine [@thinkyhead] - USA
Roxanne Neufeld [@Roxy-3D] - USA
Bob Kuhn [@Bob-the-Kuhn] - USA
Chris Pepper [@p3p] - UK
João Brazio [@jbrazio] - Portugal
Erik van der Zalm [@ErikZalm] - Netherlands

Contributions:

Author Contact Contribution
DerAndere @DerAndere1 main developer of multi-axis support, idea, initial implementation, added EVENT_GCODE_TOOLCHANGE_T0, EVENT_GCODE_TOOLCHANGE_T1, SAFE_BED_LEVELING_POSITION_X, AXIS4_ROTATES, FOAMCUTTER_XYUV, ARTICULATED_ROBOT_ARM, QUICK_HOME_ALL_NON_Z_AXES, LCD_SHOW_SECONDARY_AXES features, bugfixes
Gabriel Beraldo @GabrielBeraldo hardware debugging, bugfixes yielding first working prototype (make additional axes move, fix EEPROM)
Olivier Briand @hobiseven testing, added experimental compatibility with different configurations, code review, FOAMCUTTER_XYUV feed rate interpretation mode
Wolverine @MohammadSDGHN added experimental compatibility with different configurations (BigTreeTech SKR Pro 1.1, Trinamic TMC drivers, StealthChop, sensorless homing)
bilsef @bilsef testing, code review, bugfixes (fix movement of additional axes, fix types.h, fix EEPROM)
FNeo31 @FNeo31 added experimental drilling cyles (G81, G82, G83)
HendrikJan-5D @HendrikJan-5D testing bed leveling and Trinamic TMC, bugfixes yielding first working 9 axis printer prototype
Paloky @paloky Initial extension of multi-axis support from 6 to 8 axes
Keith @rcKeith Testing of FOAMCUTTER_XYUV and LCD_SHOW_SECONDARY_AXES
Scott Lahteine @thinkyhead code review, refactoring
MarlinFirmware @MarlinFirmware Marlin 3D Printer firmware

Licensing information

/**
 * Multi-axis-Marlin firmware
 * Copyright 2018 - 2023 DerAndere and other Multi-axis-Marlin authors
 *
 * Based on:
 * Marlin 3D Printer Firmware
 * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
 *
 * Based on Sprinter and grbl.
 * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
 *
 * This program is free software: you can redistribute it and/or modify
 * it under the terms of the GNU General Public License as published by
 * the Free Software Foundation, either version 3 of the License, or
 * (at your option) any later version.
 *
 * This program is distributed in the hope that it will be useful,
 * but WITHOUT ANY WARRANTY; without even the implied warranty of
 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
 * GNU General Public License for more details.
 *
 * You should have received a copy of the GNU General Public License
 * along with this program.  If not, see <http://www.gnu.org/licenses/>.
 *
 */