Prusa MINI Firmware overview
|
Go to the documentation of this file.
31 #include "../inc/MarlinConfig.h"
51 #if ENABLED(HOME_AFTER_DEACTIVATE)
60 constexpr
float slop = 0.0001;
77 #define XY_PROBE_FEEDRATE_MM_S xy_probe_feedrate_mm_s
78 #elif defined(XY_PROBE_SPEED)
79 #define XY_PROBE_FEEDRATE_MM_S MMM_TO_MMS(XY_PROBE_SPEED)
81 #define XY_PROBE_FEEDRATE_MM_S PLANNER_XY_FEEDRATE()
84 #if ENABLED(Z_SAFE_HOMING)
85 constexpr
xy_float_t safe_homing_xy = { Z_SAFE_HOMING_X_POINT, Z_SAFE_HOMING_Y_POINT };
113 #define XYZ_DEFS(T, NAME, OPT) \
114 extern const XYZval<T> NAME##_P; \
115 FORCE_INLINE T NAME(AxisEnum axis) { return pgm_read_any(&NAME##_P[axis]); }
117 XYZ_DEFS(
float, base_min_pos, MIN_POS);
118 XYZ_DEFS(
float, base_max_pos, MAX_POS);
119 XYZ_DEFS(
float, base_home_pos, HOME_POS);
120 XYZ_DEFS(
float, max_length, MAX_LENGTH);
121 XYZ_DEFS(
float, home_bump_mm, HOME_BUMP_MM);
122 XYZ_DEFS(
signed char, home_dir, HOME_DIR);
124 #if HAS_WORKSPACE_OFFSET
127 #define update_workspace_offset(x) NOOP
130 #if HAS_HOTEND_OFFSET
132 void reset_hotend_offsets();
140 #if HAS_SOFTWARE_ENDSTOPS
154 #define apply_motion_limits(V) NOOP
155 #define update_software_endstops(...) NOOP
182 ,
const bool is_fast=
false
193 inline void prepare_internal_fast_move_to_destination(
const feedRate_t &fr_mm_s=0.0f) {
230 #if ENABLED(NO_MOTION_BEFORE_HOMING)
231 #define MOTION_CONDITIONS (IsRunning() && !axis_unhomed_error())
233 #define MOTION_CONDITIONS IsRunning()
245 #if HAS_HOME_OFFSET || HAS_POSITION_SHIFT
249 #if HAS_POSITION_SHIFT
252 #if HAS_HOME_OFFSET && HAS_POSITION_SHIFT
254 #define _WS workspace_offset
255 #elif HAS_HOME_OFFSET
256 #define _WS home_offset
258 #define _WS position_shift
260 #define NATIVE_TO_LOGICAL(POS, AXIS) ((POS) + _WS[AXIS])
261 #define LOGICAL_TO_NATIVE(POS, AXIS) ((POS) - _WS[AXIS])
269 #define NATIVE_TO_LOGICAL(POS, AXIS) (POS)
270 #define LOGICAL_TO_NATIVE(POS, AXIS) (POS)
278 #define LOGICAL_X_POSITION(POS) NATIVE_TO_LOGICAL(POS, X_AXIS)
279 #define LOGICAL_Y_POSITION(POS) NATIVE_TO_LOGICAL(POS, Y_AXIS)
280 #define LOGICAL_Z_POSITION(POS) NATIVE_TO_LOGICAL(POS, Z_AXIS)
281 #define RAW_X_POSITION(POS) LOGICAL_TO_NATIVE(POS, X_AXIS)
282 #define RAW_Y_POSITION(POS) LOGICAL_TO_NATIVE(POS, Y_AXIS)
283 #define RAW_Z_POSITION(POS) LOGICAL_TO_NATIVE(POS, Z_AXIS)
289 #if IS_KINEMATIC // (DELTA or SCARA)
297 return HYPOT2(rx, ry) <=
sq(DELTA_PRINTABLE_RADIUS - inset);
299 const float R2 =
HYPOT2(rx - SCARA_OFFSET_X, ry - SCARA_OFFSET_Y);
302 #
if MIDDLE_DEAD_ZONE_R > 0
303 &&
R2 >=
sq(
float(MIDDLE_DEAD_ZONE_R))
327 #if ENABLED(DUAL_X_CARRIAGE)
364 #if HAS_DUPLICATION_MODE
367 #if ENABLED(MULTI_NOZZLE_DUPLICATION)
368 extern uint8_t duplication_e_mask;
375 #if ENABLED(DUAL_X_CARRIAGE)
377 enum DualXMode :
char {
378 DXC_FULL_CONTROL_MODE,
380 DXC_DUPLICATION_MODE,
384 extern DualXMode dual_x_carriage_mode;
385 extern float inactive_extruder_x_pos,
386 duplicate_extruder_x_offset;
388 extern bool active_extruder_parked;
390 extern int16_t duplicate_extruder_temp_offset;
392 FORCE_INLINE bool dxc_is_duplicating() {
return dual_x_carriage_mode >= DXC_DUPLICATION_MODE; }
394 float x_home_pos(
const int extruder);
398 #elif ENABLED(MULTI_NOZZLE_DUPLICATION)
400 enum DualXMode :
char {
401 DXC_DUPLICATION_MODE = 2
407 void set_home_offset(
const AxisEnum axis,
const float v);
float delta_clip_start_height
#define WITHIN(N, L, H)
Definition: macros.h:195
T z
Definition: types.h:286
static void set_machine_position_mm(const float &a, const float &b, const float &c, const float &e)
Definition: planner.cpp:2721
#define GET_TEXT(MSG)
Definition: multi_language.h:72
void do_blocking_move_to(const float rx, const float ry, const float rz, const feedRate_t &fr_mm_s=0.0f)
Definition: motion.cpp:344
static FORCE_INLINE bool tooColdToExtrude(const uint8_t)
Definition: temperature.h:314
void bilinear_line_to_destination(const feedRate_t &scaled_fr_mm_s, uint16_t x_splits=0xFFFF, uint16_t y_splits=0xFFFF)
#define Y_MIN_POS
Definition: Configuration_A3ides_2209_MINI.h:985
float delta_segments_per_second
#define NOLESS(v, n)
Definition: macros.h:127
#define HOMING_Z_WITH_PROBE
Definition: Conditionals_LCD.h:505
static void report_positions()
Definition: stepper.cpp:2276
#define sq(x)
Definition: wiring_constants.h:83
T z
Definition: types.h:383
static void synchronize()
Definition: planner.cpp:1556
void report_current_position()
Definition: motion.cpp:199
xyz_pos_t max
Definition: motion.h:139
constexpr float L1
Definition: scara.h:33
bool extruder_duplication_enabled
Definition: motion.cpp:876
T x
Definition: types.h:286
#define DEPLOY_PROBE()
Definition: probe.h:60
xyz_pos_t min
Definition: motion.h:139
feedRate_t max_feedrate_mm_s[XYZE_N]
Definition: planner.h:182
#define MSG_ERR_COLD_EXTRUDE_STOP
Definition: language.h:242
constexpr xyz_pos_t probe_offset
Definition: probe.h:58
FI T magnitude() const
Definition: types.h:388
void prepare_move_to_destination()
Definition: motion.cpp:984
#define Z_PROBE_SPEED_FAST
Definition: Configuration_A3ides_2209_MINI.h:868
feedRate_t feedrate_mm_s
Definition: motion.cpp:138
#define Z_MIN_POS
Definition: Configuration_A3ides_2209_MINI.h:986
#define RECIPROCAL(x)
Definition: macros.h:273
void update_software_endstops(const AxisEnum axis)
Definition: motion.cpp:503
#define DEBUG_ECHOLNPGM(...)
Definition: debug_out.h:79
FORCE_INLINE void toNative(xy_pos_t &)
Definition: motion.h:274
FI XYZEval< float > asLogical() const
Definition: types.h:410
bool soft_endstops_enabled
Definition: motion.cpp:486
#define DEBUG_XYZ(...)
Definition: debug_out.h:88
#define UNEAR_ZERO(x)
Definition: macros.h:269
Stepper stepper
Definition: stepper.cpp:82
void remember_feedrate_scaling_off()
Definition: motion.cpp:475
static bool buffer_segment(const float &a, const float &b, const float &c, const float &e, const feedRate_t &fr_mm_s, const uint8_t extruder, const float &millimeters=0.0)
Definition: planner.cpp:2568
#define _MAX(V...)
Definition: macros.h:346
static float get_axis_position_mm(const AxisEnum axis)
Definition: planner.cpp:1526
void do_blocking_move_to_z(const float &rz, const feedRate_t &fr_mm_s)
Definition: motion.cpp:450
static bool leveling_active
Definition: planner.h:276
uint8_t axis_homed
Definition: motion.cpp:91
#define SERIAL_ECHOPAIR(V...)
Definition: serial.h:114
#define MIN_STEPS_PER_SEGMENT
Definition: Configuration_A3ides_2209_MINI_adv.h:1108
void do_blocking_move_to_xy_z(const xy_pos_t &raw, const float &z, const feedRate_t &fr_mm_s)
Definition: motion.cpp:461
#define UBL_SEGMENTED
Definition: Conditionals_post.h:1403
void do_blocking_move_to_xy(const float &rx, const float &ry, const feedRate_t &fr_mm_s)
Definition: motion.cpp:454
void sync_plan_position_e()
Definition: motion.cpp:221
#define Z_HOME_DIR
Definition: Configuration_A3ides_2209_MINI.h:975
static FORCE_INLINE void validate_homing_move()
Definition: endstops.h:144
static FORCE_INLINE void set_z2_lock(const bool state)
Definition: stepper.h:422
#define PGM_P
Definition: pgmspace.h:30
T e
Definition: types.h:383
void set_axis_is_at_home(const AxisEnum axis)
Definition: motion.cpp:1361
I2CPositionEncodersMgr I2CPEM
#define HYPOT2(x, y)
Definition: macros.h:100
#define _MIN(V...)
Definition: macros.h:333
#define max(a, b)
Definition: wiring_constants.h:40
AxisEnum
Definition: types.h:36
static float saved_feedrate_mm_s
Definition: motion.cpp:469
static void line_to_destination_cartesian(const feedRate_t &scaled_fr_mm_s, const uint8_t e)
uint32_t millis(void)
Definition: wiring_time.c:29
feedRate_t get_homing_bump_feedrate(const AxisEnum axis)
Definition: motion.cpp:1076
static void manage_heater() _O2
Definition: temperature.cpp:975
void forward_kinematics_SCARA(const float &a, const float &b)
xy_float_t xy_pos_t
Definition: types.h:159
axis_limits_t soft_endstop
Definition: motion.cpp:489
#define PLANNER_XY_FEEDRATE()
Definition: planner.h:969
#define DEBUG_ECHOLNPAIR(...)
Definition: debug_out.h:82
#define IS_KINEMATIC
Definition: Conditionals_LCD.h:545
#define SERIAL_ECHO_START()
Definition: serial.h:179
#define SERIAL_ECHOLN(x)
Definition: serial.h:72
static void unhomed(const AxisEnum axis)
Definition: I2CPositionEncoder.h:230
void do_blocking_move_to_x(const float &rx, const feedRate_t &fr_mm_s=0.0f)
Definition: motion.cpp:444
void remember_feedrate_and_scaling()
Definition: motion.cpp:471
float feedRate_t
Definition: types.h:80
#define sprintf_P(s,...)
Definition: pgmspace.h:72
FI void set(const T px)
Definition: types.h:290
#define update_workspace_offset(x)
Definition: motion.h:127
bool soft_endstops_enabled
Definition: motion.cpp:486
bool extruder_duplication_enabled
Definition: motion.cpp:876
#define strlen_P(s)
Definition: pgmspace.h:61
abc_float_t delta_endstop_adj
#define F(str)
Definition: UHS_macros.h:164
#define XYZ
Definition: macros.h:27
FORCE_INLINE bool homing_needed()
Definition: motion.h:49
static FORCE_INLINE void unapply_modifiers(xyze_pos_t &pos, bool leveling=false)
Definition: planner.h:520
FORCE_INLINE void set_all_unknown()
Definition: motion.h:47
static FORCE_INLINE bool deploy()
Definition: bltouch.h:72
bool prepare_move_to_destination_cartesian()
Definition: motion.cpp:841
void _internal_move_to_destination(const feedRate_t &fr_mm_s)
Definition: motion.cpp:311
#define X_MIN_POS
Definition: Configuration_A3ides_2209_MINI.h:984
#define NOMORE(v, n)
Definition: macros.h:133
xyze_pos_t destination
Definition: motion.cpp:110
#define Z_MAX_POS
Definition: Configuration_A3ides_2209_MINI.h:989
#define MIN_PROBE_EDGE
Definition: Configuration_A3ides_2209_MINI.h:862
#define ABS(a)
Definition: macros.h:266
#define Z_PROBE_SPEED_SLOW
Definition: Configuration_A3ides_2209_MINI.h:871
FORCE_INLINE bool all_axes_known()
Definition: motion.h:45
#define pgm_read_byte(addr)
Definition: pgmspace.h:95
const feedRate_t homing_feedrate_mm_s[XYZ]
void prepare_internal_move_to_destination(const feedRate_t &fr_mm_s=0.0f)
Definition: motion.h:186
#define FORCE_INLINE
Definition: macros.h:40
#define Y_MAX_POS
Definition: Configuration_A3ides_2209_MINI.h:988
#define SERIAL_ECHO_MSG(S)
Definition: serial.h:183
xyze_pos_t current_position
Definition: motion.cpp:102
int16_t feedrate_percentage
Definition: motion.cpp:139
bool position_is_reachable(const float &rx, const float &ry)
Definition: motion.h:325
#define Z_CLEARANCE_BETWEEN_PROBES
Definition: Configuration_A3ides_2209_MINI.h:893
static FORCE_INLINE bool leveling_active_at_z(const float &)
Definition: planner.h:447
#define HAS_LEVELING
Definition: Conditionals_post.h:1408
void remember_feedrate_and_scaling()
Definition: motion.cpp:471
const feedRate_t homing_feedrate_mm_s[XYZ] PROGMEM
Definition: motion.cpp:142
void set_axis_is_not_at_home(const AxisEnum axis)
Definition: motion.cpp:1425
void line_to_current_position(const feedRate_t &fr_mm_s)
Definition: motion.cpp:285
void set_current_from_steppers_for_axis(const AxisEnum axis)
Definition: motion.cpp:263
#define X_HOME_POS
Definition: Conditionals_post.h:156
void do_blocking_move_to(const float rx, const float ry, const float rz, const feedRate_t &fr_mm_s)
Definition: motion.cpp:344
xyz_pos_t cartes
Definition: motion.cpp:152
void scara_set_axis_is_at_home(const AxisEnum axis)
static void set_directions()
Definition: stepper.cpp:354
void sync_plan_position()
Definition: motion.cpp:216
#define LOOP_XYZ(VAR)
Definition: types.h:60
#define REMEMBER(N, X, V...)
Definition: utility.h:76
#define Y_HOME_POS
Definition: Conditionals_post.h:172
#define DISABLED(V...)
Definition: macros.h:178
void sync_plan_position_e()
Definition: motion.cpp:221
FORCE_INLINE bool position_is_reachable_by_probe(const xy_int_t &pos)
Definition: motion.h:358
#define XYZ_CONSTS(T, NAME, OPT)
Definition: motion.cpp:73
void
Definition: png.h:1083
float probe_min_x()
Definition: probe.h:103
float delta_safe_distance_from_top()
#define XY_PROBE_SPEED
Definition: Configuration_A3ides_2209_MINI.h:865
static void refresh_collector(const float proportion=1.0, const uint8_t t=selected_vtool, float(&c)[MIXING_STEPPERS]=collector)
T x
Definition: types.h:383
xyze_pos_t current_position
Definition: motion.cpp:102
#define pgm_read_float(addr)
Definition: pgmspace.h:109
#define XY_PROBE_FEEDRATE_MM_S
Definition: motion.h:77
static bool buffer_line(const float &rx, const float &ry, const float &rz, const float &e, const feedRate_t &fr_mm_s, const uint8_t extruder, const float millimeters=0.0)
Definition: planner.cpp:2663
feedRate_t feedrate_mm_s
Definition: motion.cpp:138
#define HOMING_FEEDRATE_Z
Definition: Configuration_A3ides_2209_MINI.h:1269
void line_to_current_position(const feedRate_t &fr_mm_s=feedrate_mm_s)
Definition: motion.cpp:285
void do_blocking_move_to_xy(const float &rx, const float &ry, const feedRate_t &fr_mm_s=0.0f)
Definition: motion.cpp:454
#define SERIAL_ECHOLNPAIR(V...)
Definition: serial.h:144
feedRate_t get_homing_bump_feedrate(const AxisEnum axis)
Definition: motion.cpp:1076
list a
Definition: createSpeedLookupTable.py:29
bool relative_mode
Definition: motion.cpp:94
#define HOTEND_LOOP()
Definition: Conditionals_LCD.h:436
void scara_report_positions()
float probe_max_x()
Definition: probe.h:104
#define Z_HOME_BUMP_MM
Definition: Configuration_A3ides_2209_MINI_adv.h:457
static FORCE_INLINE void set_separate_multi_axis(const bool state)
Definition: stepper.h:410
uint8_t axis_known_position
Definition: motion.cpp:91
FI void set(const T px)
Definition: types.h:391
#define SQRT(x)
Definition: macros.h:281
T x
Definition: types.h:185
#define MIXER_STEPPER_LOOP(VAR)
Definition: mixing.h:68
#define DEBUG_POS(...)
Definition: debug_out.h:87
#define ELAPSED(NOW, SOON)
Definition: millis_t.h:29
void do_homing_move(const AxisEnum axis, const float distance, const feedRate_t fr_mm_s=0.0)
Definition: motion.cpp:1232
static float z2_endstop_adj
Definition: endstops.h:51
void get_cartesian_from_steppers()
Definition: motion.cpp:232
float probe_min_y()
Definition: probe.h:105
const uint8_t[]
Definition: 404_html.c:3
bool mirrored_duplication_mode
Definition: motion.cpp:876
float xy_probe_feedrate_mm_s
Definition: motion.cpp:193
bool axis_unhomed_error(uint8_t axis_bits)
Definition: motion.cpp:1054
void update_software_endstops(const AxisEnum axis)
Definition: motion.cpp:503
#define _BV(bit)
Definition: wiring_constants.h:99
#define DEBUG_ECHO(...)
Definition: debug_out.h:75
T y
Definition: types.h:286
static float steps_to_mm[XYZE_N]
Definition: planner.h:254
void restore_feedrate_and_scaling()
Definition: motion.cpp:479
bool axis_unhomed_error(uint8_t axis_bits=0x07)
Definition: motion.cpp:1054
xyze_pos_t destination
Definition: motion.cpp:110
void do_blocking_move_to_x(const float &rx, const feedRate_t &fr_mm_s)
Definition: motion.cpp:444
void homeaxis(const AxisEnum axis)
Definition: motion.cpp:1449
void restore_feedrate_and_scaling()
Definition: motion.cpp:479
FORCE_INLINE feedRate_t homing_feedrate(const AxisEnum a)
Definition: motion.h:93
#define X_MAX_POS
Definition: Configuration_A3ides_2209_MINI.h:987
#define CBI(A, B)
Definition: macros.h:89
#define HAS_HOTEND_OFFSET
Definition: Conditionals_LCD.h:441
constexpr uint8_t xyz_bits
Definition: motion.h:43
constexpr xyz_pos_t hotend_offset[1]
Definition: motion.h:136
static void set_e_position_mm(const float &e)
Definition: planner.cpp:2764
#define MSG_ERR_LONG_EXTRUDE_STOP
Definition: language.h:243
void prepare_move_to_destination()
Definition: motion.cpp:984
void apply_motion_limits(xyz_pos_t &target)
Definition: motion.cpp:589
void do_blocking_move_to_z(const float &rz, const feedRate_t &fr_mm_s=0.0f)
Definition: motion.cpp:450
void set_axis_is_at_home(const AxisEnum axis)
Definition: motion.cpp:1361
xyz_pos_t cartes
Definition: motion.cpp:152
void apply_motion_limits(xyz_pos_t &target)
Definition: motion.cpp:589
#define DEBUGGING(F)
Definition: serial.h:47
void do_blocking_move_to_y(const float &ry, const feedRate_t &fr_mm_s=0.0f)
Definition: motion.cpp:447
void report_current_position()
Definition: motion.cpp:199
unsigned R2
Definition: masstorage.h:306
uint8_t axes_need_homing(uint8_t axis_bits=0x07)
Definition: motion.cpp:1041
int16_t feedrate_percentage
Definition: motion.cpp:139
uint8_t axes_need_homing(uint8_t axis_bits)
Definition: motion.cpp:1041
#define STOW_PROBE()
Definition: probe.h:61
#define DEBUG_ECHOPAIR(...)
Definition: debug_out.h:80
#define TEST(n, b)
Definition: macros.h:81
#define MMM_TO_MMS(MM_M)
Definition: types.h:83
void sync_plan_position()
Definition: motion.cpp:216
static void homed(const AxisEnum axis)
Definition: I2CPositionEncoder.h:225
T y
Definition: types.h:185
#define HOTENDS
Definition: Conditionals_LCD.h:425
void do_blocking_move_to_xy_z(const xy_pos_t &raw, const float &z, const feedRate_t &fr_mm_s=0.0f)
Definition: motion.cpp:461
#define HOMING_FEEDRATE_XY
Definition: Configuration_A3ides_2209_MINI.h:1268
#define HOMING_BUMP_DIVISOR
Definition: Configuration_A3ides_2209_MINI_adv.h:458
void forward_kinematics_DELTA(const float &z1, const float &z2, const float &z3)
FORCE_INLINE float pgm_read_any(const float *p)
Definition: motion.h:110
constexpr float slop
Definition: motion.h:60
void homeaxis(const AxisEnum axis)
Definition: motion.cpp:1449
bool relative_mode
Definition: motion.cpp:94
bool mirrored_duplication_mode
Definition: motion.cpp:876
void serialprintPGM(PGM_P str)
Definition: serial.cpp:35
#define SBI(A, B)
Definition: macros.h:85
const xyze_char_t axis_codes
Definition: types.h:486
static planner_settings_t settings
Definition: planner.h:251
uint8_t axis_homed
Definition: motion.cpp:91
void _internal_move_to_destination(const feedRate_t &fr_mm_s=0.0f)
Definition: motion.cpp:311
static void set_position_mm(const float &rx, const float &ry, const float &rz, const float &e)
Definition: planner.cpp:2741
uint8_t axis_known_position
Definition: motion.cpp:91
void remember_feedrate_scaling_off()
Definition: motion.cpp:475
#define X_HOME_DIR
Definition: Configuration_A3ides_2209_MINI.h:973
#define MMS_SCALED(V)
Definition: types.h:85
void idle()
Definition: Marlin.cpp:629
void get_cartesian_from_steppers()
Definition: motion.cpp:232
axis_limits_t soft_endstop
Definition: motion.cpp:489
FORCE_INLINE void toLogical(xy_pos_t &)
Definition: motion.h:271
#define Z_HOME_POS
Definition: Conditionals_post.h:179
float xy_probe_feedrate_mm_s
Definition: motion.cpp:193
Temperature thermalManager
Definition: temperature.cpp:89
Endstops endstops
Definition: endstops.cpp:51
uint32_t millis_t
Definition: millis_t.h:26
void set_axis_is_not_at_home(const AxisEnum axis)
Definition: motion.cpp:1425
constexpr float L2
Definition: scara.h:33
static FORCE_INLINE uint8_t get_current_vtool()
Definition: mixing.h:111
void do_blocking_move_to_y(const float &ry, const feedRate_t &fr_mm_s)
Definition: motion.cpp:447
#define BUZZ(d, f)
Definition: buzzer.h:126
static void line_to_destination(const feedRate_t &scaled_fr_mm_s, uint8_t x_splits=0xFF, uint8_t y_splits=0xFF)
constexpr uint8_t active_extruder
Definition: motion.h:107
#define XYZ_DEFS(T, NAME, OPT)
Definition: motion.h:113
static FORCE_INLINE void set_z_lock(const bool state)
Definition: stepper.h:421
#define ENABLED(V...)
Definition: macros.h:177
Planner planner
Definition: planner.cpp:111
FORCE_INLINE bool all_axes_homed()
Definition: motion.h:44
T y
Definition: types.h:383
static int16_t saved_feedrate_percentage
Definition: motion.cpp:470
float probe_max_y()
Definition: probe.h:106
static FORCE_INLINE bool stow()
Definition: bltouch.h:73
FORCE_INLINE void set_all_unhomed()
Definition: motion.h:46
#define EXTRUDE_MAXLENGTH
Definition: Configuration_A3ides_2209_MINI.h:524
void set_current_from_steppers_for_axis(const AxisEnum axis)
Definition: motion.cpp:263