Merge remote-tracking branch 'upstream/bugfix-1.1.x' into release_113

This commit is contained in:
Scott Lahteine 2017-06-04 12:38:19 -05:00
commit 87b591bf53
89 changed files with 4066 additions and 521 deletions

View File

@ -101,12 +101,15 @@
#if ENABLED(ULTIMAKERCONTROLLER) \
|| ENABLED(REPRAP_DISCOUNT_SMART_CONTROLLER) \
|| ENABLED(G3D_PANEL) \
|| ENABLED(RIGIDBOT_PANEL) \
|| ENABLED(REPRAPWORLD_KEYPAD)
|| ENABLED(RIGIDBOT_PANEL)
#define ULTIPANEL
#define NEWPANEL
#endif
#if ENABLED(REPRAPWORLD_KEYPAD)
#define NEWPANEL
#endif
#if ENABLED(RA_CONTROL_PANEL)
#define LCD_I2C_TYPE_PCA8574
#define LCD_I2C_ADDRESS 0x27 // I2C Address of the port expander

View File

@ -847,4 +847,9 @@
// Add commands that need sub-codes to this list
#define USE_GCODE_SUBCODES ENABLED(G38_PROBE_TARGET)
// MESH_BED_LEVELING overrides PROBE_MANUALLY
#if ENABLED(MESH_BED_LEVELING)
#undef PROBE_MANUALLY
#endif
#endif // CONDITIONALS_POST_H

View File

@ -312,6 +312,7 @@
#define K1 0.95 //smoothing factor within the PID
// If you are using a pre-configured hotend then you can use one of the value sets by uncommenting it
// Ultimaker
#define DEFAULT_Kp 22.2
#define DEFAULT_Ki 1.08
@ -1154,7 +1155,7 @@
* - Click the controller to view the LCD menu
* - The LCD will display Japanese, Western, or Cyrillic text
*
* See https: *github.com/MarlinFirmware/Marlin/wiki/LCD-Language
* See https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
*
* :['JAPANESE', 'WESTERN', 'CYRILLIC']
*/

View File

@ -220,12 +220,18 @@
#define EXTRUDER_AUTO_FAN_TEMPERATURE 50
#define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed
// Define a pin to turn case light on/off
//#define CASE_LIGHT_PIN 4
#if PIN_EXISTS(CASE_LIGHT)
#define INVERT_CASE_LIGHT false // Set to true if HIGH is the OFF state (active low)
//#define CASE_LIGHT_DEFAULT_ON // Uncomment to set default state to on
//#define MENU_ITEM_CASE_LIGHT // Uncomment to have a Case Light On / Off entry in main menu
/**
* M355 Case Light on-off / brightness
*/
//#define CASE_LIGHT_ENABLE
#if ENABLED(CASE_LIGHT_ENABLE)
#define CASE_LIGHT_PIN 4 // can be defined here or in the pins_XXX.h file for your board
// pins_XXX.h file overrides this one
#define INVERT_CASE_LIGHT false // set to true if case light is ON when pin is at 0
#define CASE_LIGHT_DEFAULT_ON true // set default power up state to on or off
#define CASE_LIGHT_DEFAULT_BRIGHTNESS 105 // set power up brightness 0-255 ( only used if on PWM
// and if CASE_LIGHT_DEFAULT is set to on
//#define MENU_ITEM_CASE_LIGHT // Uncomment to have a Case Light entry in main menu
#endif
//===========================================================================
@ -1023,7 +1029,7 @@
*/
#define TMC2130_ADV() { }
#endif // ENABLED(HAVE_TMC2130)
#endif // HAVE_TMC2130
// @section L6470

View File

@ -718,7 +718,7 @@
/**
* Wait until all parameters are verified before altering the state!
*/
state.active = !parser.seen('D');
set_bed_leveling_enabled(!parser.seen('D'));
return UBL_OK;
}
@ -734,7 +734,7 @@
* wait for them to get up to temperature.
*/
bool unified_bed_leveling::turn_on_heaters() {
millis_t next;
millis_t next = millis() + 5000UL;
#if HAS_TEMP_BED
#if ENABLED(ULTRA_LCD)
if (g26_bed_temp > 25) {
@ -743,7 +743,6 @@
#endif
has_control_of_lcd_panel = true;
thermalManager.setTargetBed(g26_bed_temp);
next = millis() + 5000UL;
while (abs(thermalManager.degBed() - g26_bed_temp) > 3) {
if (ubl_lcd_clicked()) return exit_from_g26();
if (PENDING(millis(), next)) {

View File

@ -35,6 +35,10 @@
#include "MarlinConfig.h"
#ifdef DEBUG_GCODE_PARSER
#include "gcode.h"
#endif
#include "enum.h"
#include "types.h"
#include "fastio.h"

View File

@ -176,7 +176,7 @@
* M304 - Set bed PID parameters P I and D. (Requires PIDTEMPBED)
* M350 - Set microstepping mode. (Requires digital microstepping pins.)
* M351 - Toggle MS1 MS2 pins directly. (Requires digital microstepping pins.)
* M355 - Turn the Case Light on/off and set its brightness. (Requires CASE_LIGHT_PIN)
* M355 - Set Case Light on/off and set brightness. (Requires CASE_LIGHT_PIN)
* M380 - Activate solenoid on active extruder. (Requires EXT_SOLENOID)
* M381 - Disable all solenoids. (Requires EXT_SOLENOID)
* M400 - Finish all moves.
@ -566,16 +566,6 @@ static uint8_t target_extruder;
;
#endif
#if HAS_CASE_LIGHT
bool case_light_on =
#if ENABLED(CASE_LIGHT_DEFAULT_ON)
true
#else
false
#endif
;
#endif
#if ENABLED(DELTA)
float delta[ABC],
@ -709,7 +699,8 @@ void set_current_from_steppers_for_axis(const AxisEnum axis);
#endif
void tool_change(const uint8_t tmp_extruder, const float fr_mm_s=0.0, bool no_move=false);
static void report_current_position();
void report_current_position();
void report_current_position_detail();
#if ENABLED(DEBUG_LEVELING_FEATURE)
void print_xyz(const char* prefix, const char* suffix, const float x, const float y, const float z) {
@ -720,7 +711,8 @@ static void report_current_position();
SERIAL_ECHOPAIR(", ", z);
SERIAL_CHAR(')');
suffix ? serialprintPGM(suffix) : SERIAL_EOL;
if (suffix) {serialprintPGM(suffix);} //won't compile for Teensy with the previous construction
else SERIAL_EOL;
}
void print_xyz(const char* prefix, const char* suffix, const float xyz[]) {
@ -1545,14 +1537,21 @@ inline void set_destination_to_current() { COPY(destination, current_position);
if (DEBUGGING(LEVELING)) DEBUG_POS("prepare_uninterpolated_move_to_destination", destination);
#endif
if ( current_position[X_AXIS] == destination[X_AXIS]
&& current_position[Y_AXIS] == destination[Y_AXIS]
&& current_position[Z_AXIS] == destination[Z_AXIS]
&& current_position[E_AXIS] == destination[E_AXIS]
) return;
refresh_cmd_timeout();
planner.buffer_line_kinematic(destination, MMS_SCALED(fr_mm_s ? fr_mm_s : feedrate_mm_s), active_extruder);
#if UBL_DELTA
// ubl segmented line will do z-only moves in single segment
ubl.prepare_segmented_line_to(destination, MMS_SCALED(fr_mm_s ? fr_mm_s : feedrate_mm_s));
#else
if ( current_position[X_AXIS] == destination[X_AXIS]
&& current_position[Y_AXIS] == destination[Y_AXIS]
&& current_position[Z_AXIS] == destination[Z_AXIS]
&& current_position[E_AXIS] == destination[E_AXIS]
) return;
planner.buffer_line_kinematic(destination, MMS_SCALED(fr_mm_s ? fr_mm_s : feedrate_mm_s), active_extruder);
#endif
set_current_to_destination();
}
#endif // IS_KINEMATIC
@ -2354,18 +2353,21 @@ static void clean_up_after_endstop_or_probe_move() {
if (enabling) planner.unapply_leveling(current_position);
#elif ENABLED(AUTO_BED_LEVELING_UBL)
#if PLANNER_LEVELING
if (!enable) // leveling from on to off
if (ubl.state.active) { // leveling from on to off
// change unleveled current_position to physical current_position without moving steppers.
planner.apply_leveling(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS]);
else
ubl.state.active = false; // disable only AFTER calling apply_leveling
}
else { // leveling from off to on
ubl.state.active = true; // enable BEFORE calling unapply_leveling, otherwise ignored
// change physical current_position to unleveled current_position without moving steppers.
planner.unapply_leveling(current_position);
}
#else
ubl.state.active = enable; // just flip the bit, current_position will be wrong until next move.
#endif
ubl.state.active = enable;
#else // ABL
#if ENABLED(AUTO_BED_LEVELING_BILINEAR)
@ -2374,8 +2376,12 @@ static void clean_up_after_endstop_or_probe_move() {
(void)bilinear_z_offset(reset);
#endif
// Enable or disable leveling compensation in the planner
planner.abl_enabled = enable;
if (!enable)
// When disabling just get the current position from the steppers.
// This will yield the smallest error when first converted back to steps.
set_current_from_steppers_for_axis(
#if ABL_PLANAR
ALL_AXES
@ -2384,26 +2390,44 @@ static void clean_up_after_endstop_or_probe_move() {
#endif
);
else
// When enabling, remove compensation from the current position,
// so compensation will give the right stepper counts.
planner.unapply_leveling(current_position);
#endif
#endif // ABL
}
}
#if ENABLED(ENABLE_LEVELING_FADE_HEIGHT)
void set_z_fade_height(const float zfh) {
planner.z_fade_height = zfh;
planner.inverse_z_fade_height = RECIPROCAL(zfh);
if (leveling_is_active())
set_current_from_steppers_for_axis(
#if ABL_PLANAR
ALL_AXES
#else
Z_AXIS
#endif
);
const bool level_active = leveling_is_active();
#if ENABLED(AUTO_BED_LEVELING_UBL)
if (level_active)
set_bed_leveling_enabled(false); // turn off before changing fade height for proper apply/unapply leveling to maintain current_position
planner.z_fade_height = zfh;
planner.inverse_z_fade_height = RECIPROCAL(zfh);
if (level_active)
set_bed_leveling_enabled(true); // turn back on after changing fade height
#else
planner.z_fade_height = zfh;
planner.inverse_z_fade_height = RECIPROCAL(zfh);
if (level_active) {
set_current_from_steppers_for_axis(
#if ABL_PLANAR
ALL_AXES
#else
Z_AXIS
#endif
);
}
#endif
}
#endif // LEVELING_FADE_HEIGHT
@ -3665,6 +3689,7 @@ inline void gcode_G28(const bool always_home_all) {
#if ENABLED(DELTA)
home_delta();
UNUSED(always_home_all);
#else // NOT DELTA
@ -4178,19 +4203,19 @@ void home_all_axes() { gcode_G28(true); }
ABL_VAR int left_probe_bed_position, right_probe_bed_position, front_probe_bed_position, back_probe_bed_position;
ABL_VAR float xGridSpacing, yGridSpacing;
#if ABL_PLANAR
#if ENABLED(AUTO_BED_LEVELING_LINEAR)
ABL_VAR uint8_t abl_grid_points_x = GRID_MAX_POINTS_X,
abl_grid_points_y = GRID_MAX_POINTS_Y;
ABL_VAR bool do_topography_map;
#else // 3-point
#else // Bilinear
uint8_t constexpr abl_grid_points_x = GRID_MAX_POINTS_X,
abl_grid_points_y = GRID_MAX_POINTS_Y;
#endif
#if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(PROBE_MANUALLY)
#if ABL_PLANAR
#if ENABLED(AUTO_BED_LEVELING_LINEAR)
ABL_VAR int abl2;
#else // 3-point
#else // Bilinear
int constexpr abl2 = GRID_MAX_POINTS;
#endif
#endif
@ -4210,6 +4235,8 @@ void home_all_axes() { gcode_G28(true); }
#elif ENABLED(AUTO_BED_LEVELING_3POINT)
int constexpr abl2 = 3;
// Probe at 3 arbitrary points
ABL_VAR vector_3 points[3] = {
vector_3(ABL_PROBE_PT_1_X, ABL_PROBE_PT_1_Y, 0),
@ -4502,7 +4529,7 @@ void home_all_axes() { gcode_G28(true); }
#elif ENABLED(AUTO_BED_LEVELING_3POINT)
points[i].z = measured_z;
points[abl_probe_index].z = measured_z;
#endif
}
@ -5263,7 +5290,7 @@ void home_all_axes() { gcode_G28(true); }
recalc_delta_settings(delta_radius, delta_diagonal_rod);
}
else if(zero_std_dev >= test_precision) { // step one back
else if (zero_std_dev >= test_precision) { // step one back
COPY(endstop_adj, e_old);
delta_radius = dr_old;
home_offset[Z_AXIS] = zh_old;
@ -5940,7 +5967,8 @@ inline void gcode_M17() {
idle();
wait_for_heatup = false;
HOTEND_LOOP() {
if (abs(thermalManager.degHotend(e) - thermalManager.degTargetHotend(e)) > 3) {
const int16_t target_temp = thermalManager.degTargetHotend(e);
if (target_temp && abs(thermalManager.degHotend(e) - target_temp) > 3) {
wait_for_heatup = true;
break;
}
@ -6362,9 +6390,8 @@ inline void gcode_M42() {
#endif
SERIAL_PROTOCOLLNPGM(". deploy & stow 4 times");
pinMode(PROBE_TEST_PIN, INPUT_PULLUP);
bool deploy_state;
bool stow_state;
SET_INPUT_PULLUP(PROBE_TEST_PIN);
bool deploy_state, stow_state;
for (uint8_t i = 0; i < 4; i++) {
servo[probe_index].move(z_servo_angle[0]); //deploy
safe_delay(500);
@ -7601,7 +7628,7 @@ inline void gcode_M92() {
/**
* Output the current position to serial
*/
static void report_current_position() {
void report_current_position() {
SERIAL_PROTOCOLPGM("X:");
SERIAL_PROTOCOL(current_position[X_AXIS]);
SERIAL_PROTOCOLPGM(" Y:");
@ -7620,10 +7647,119 @@ static void report_current_position() {
#endif
}
#ifdef M114_DETAIL
static const char axis_char[XYZE] = {'X','Y','Z','E'};
void report_xyze(const float pos[XYZE], uint8_t n = 4, uint8_t precision = 3) {
char str[12];
for(uint8_t i=0; i<n; i++) {
SERIAL_CHAR(' ');
SERIAL_CHAR(axis_char[i]);
SERIAL_CHAR(':');
SERIAL_PROTOCOL(dtostrf(pos[i],8,precision,str));
}
SERIAL_EOL;
}
inline void report_xyz(const float pos[XYZ]) {
report_xyze(pos,3);
}
void report_current_position_detail() {
stepper.synchronize();
SERIAL_EOL;
SERIAL_PROTOCOLPGM("Logical:");
report_xyze(current_position);
SERIAL_PROTOCOLPGM("Raw: ");
const float raw[XYZ] = {
RAW_X_POSITION(current_position[X_AXIS]),
RAW_Y_POSITION(current_position[Y_AXIS]),
RAW_Z_POSITION(current_position[Z_AXIS])
};
report_xyz(raw);
SERIAL_PROTOCOLPGM("Leveled:");
float leveled[XYZ] = {
current_position[X_AXIS],
current_position[Y_AXIS],
current_position[Z_AXIS]
};
planner.apply_leveling(leveled);
report_xyz(leveled);
SERIAL_PROTOCOLPGM("UnLevel:");
float unleveled[XYZ] = { leveled[X_AXIS], leveled[Y_AXIS], leveled[Z_AXIS] };
planner.unapply_leveling(unleveled);
report_xyz(unleveled);
#if IS_KINEMATIC
#if IS_SCARA
SERIAL_PROTOCOLPGM("ScaraK: ");
#else
SERIAL_PROTOCOLPGM("DeltaK: ");
#endif
inverse_kinematics(leveled); // writes delta[]
report_xyz(delta);
#endif
SERIAL_PROTOCOLPGM("Stepper:");
const float step_count[XYZE] = {
(float)stepper.position(X_AXIS),
(float)stepper.position(Y_AXIS),
(float)stepper.position(Z_AXIS),
(float)stepper.position(E_AXIS)
};
report_xyze(step_count,4,0);
#if IS_SCARA
const float deg[XYZ] = {
stepper.get_axis_position_degrees(A_AXIS),
stepper.get_axis_position_degrees(B_AXIS)
};
SERIAL_PROTOCOLPGM("Degrees:");
report_xyze(deg,2);
#endif
SERIAL_PROTOCOLPGM("FromStp:");
get_cartesian_from_steppers(); // writes cartes[XYZ] (with forward kinematics)
const float from_steppers[XYZE] = {
cartes[X_AXIS],
cartes[Y_AXIS],
cartes[Z_AXIS],
stepper.get_axis_position_mm(E_AXIS)
};
report_xyze(from_steppers);
const float diff[XYZE] = {
from_steppers[X_AXIS] - leveled[X_AXIS],
from_steppers[Y_AXIS] - leveled[Y_AXIS],
from_steppers[Z_AXIS] - leveled[Z_AXIS],
from_steppers[E_AXIS] - current_position[E_AXIS]
};
SERIAL_PROTOCOLPGM("Differ: ");
report_xyze(diff);
}
#endif // M114_DETAIL
/**
* M114: Output current position to serial port
*/
inline void gcode_M114() { stepper.synchronize(); report_current_position(); }
inline void gcode_M114() {
#ifdef M114_DETAIL
if ( parser.seen('D') ) {
report_current_position_detail();
return;
}
#endif
stepper.synchronize();
report_current_position();
}
/**
* M115: Capabilities string
@ -7678,11 +7814,18 @@ inline void gcode_M115() {
SERIAL_PROTOCOLLNPGM("Cap:SOFTWARE_POWER:0");
#endif
// TOGGLE_LIGHTS (M355)
// CASE LIGHTS (M355)
#if HAS_CASE_LIGHT
SERIAL_PROTOCOLLNPGM("Cap:TOGGLE_LIGHTS:1");
bool USEABLE_HARDWARE_PWM(uint8_t pin);
if (USEABLE_HARDWARE_PWM(CASE_LIGHT_PIN)) {
SERIAL_PROTOCOLLNPGM("Cap:CASE_LIGHT_BRIGHTNESS:1");
}
else
SERIAL_PROTOCOLLNPGM("Cap:CASE_LIGHT_BRIGHTNESS:0");
#else
SERIAL_PROTOCOLLNPGM("Cap:TOGGLE_LIGHTS:0");
SERIAL_PROTOCOLLNPGM("Cap:CASE_LIGHT_BRIGHTNESS:0");
#endif
// EMERGENCY_PARSER (M108, M112, M410)
@ -9472,30 +9615,54 @@ inline void gcode_M907() {
#endif // HAS_MICROSTEPS
#if HAS_CASE_LIGHT
uint8_t case_light_brightness = 255;
#ifndef INVERT_CASE_LIGHT
#define INVERT_CASE_LIGHT false
#endif
int case_light_brightness; // LCD routine wants INT
bool case_light_on;
void update_case_light() {
WRITE(CASE_LIGHT_PIN, case_light_on != INVERT_CASE_LIGHT ? HIGH : LOW);
analogWrite(CASE_LIGHT_PIN, case_light_on != INVERT_CASE_LIGHT ? case_light_brightness : 0);
pinMode(CASE_LIGHT_PIN, OUTPUT); // digitalWrite doesn't set the port mode
uint8_t case_light_bright = (uint8_t)case_light_brightness;
if (case_light_on) {
if (USEABLE_HARDWARE_PWM(CASE_LIGHT_PIN)) {
analogWrite(CASE_LIGHT_PIN, INVERT_CASE_LIGHT ? 255 - case_light_brightness : case_light_brightness );
}
else digitalWrite(CASE_LIGHT_PIN, INVERT_CASE_LIGHT ? LOW : HIGH );
}
else digitalWrite(CASE_LIGHT_PIN, INVERT_CASE_LIGHT ? HIGH : LOW);
}
#endif // HAS_CASE_LIGHT
/**
* M355: Turn case lights on/off and set brightness
* M355: Turn case light on/off and set brightness
*
* S<bool> Turn case light on or off
* P<byte> Set case light brightness (PWM pin required)
* P<byte> Set case light brightness (PWM pin required - ignored otherwise)
*
* S<bool> Set case light on/off
*
* When S turns on the light on a PWM pin then the current brightness level is used/restored
*
* M355 P200 S0 turns off the light & sets the brightness level
* M355 S1 turns on the light with a brightness of 200 (assuming a PWM pin)
*/
inline void gcode_M355() {
#if HAS_CASE_LIGHT
if (parser.seen('P')) case_light_brightness = parser.value_byte();
if (parser.seen('S')) case_light_on = parser.value_bool();
update_case_light();
uint8_t args = 0;
if (parser.seen('P')) ++args, case_light_brightness = parser.value_byte();
if (parser.seen('S')) ++args, case_light_on = parser.value_bool();
if (args) update_case_light();
// always report case light status
SERIAL_ECHO_START;
SERIAL_ECHOPGM("Case lights ");
case_light_on ? SERIAL_ECHOLNPGM("on") : SERIAL_ECHOLNPGM("off");
if (!case_light_on) {
SERIAL_ECHOLN("Case light: off");
}
else {
if (!USEABLE_HARDWARE_PWM(CASE_LIGHT_PIN)) SERIAL_ECHOLN("Case light: on");
else SERIAL_ECHOLNPAIR("Case light: ", case_light_brightness);
}
#else
SERIAL_ERROR_START;
SERIAL_ERRORLNPGM(MSG_ERR_M355_NONE);
@ -10710,7 +10877,7 @@ void process_next_command() {
#endif // HAS_MICROSTEPS
case 355: // M355 Turn case lights on/off
case 355: // M355 set case light brightness
gcode_M355();
break;
@ -10782,6 +10949,15 @@ void ok_to_send() {
/**
* Constrain the given coordinates to the software endstops.
*/
// NOTE: This makes no sense for delta beds other than Z-axis.
// For delta the X/Y would need to be clamped at
// DELTA_PRINTABLE_RADIUS from center of bed, but delta
// now enforces is_position_reachable for X/Y regardless
// of HAS_SOFTWARE_ENDSTOPS, so that enforcement would be
// redundant here. Probably should #ifdef out the X/Y
// axis clamps here for delta and just leave the Z clamp.
void clamp_to_software_endstops(float target[XYZ]) {
if (!soft_endstops_enabled) return;
#if ENABLED(MIN_SOFTWARE_ENDSTOPS)
@ -11575,14 +11751,14 @@ void prepare_move_to_destination() {
if (
#if IS_KINEMATIC
#if UBL_DELTA
ubl.prepare_linear_move_to(destination, feedrate_mm_s)
ubl.prepare_segmented_line_to(destination, feedrate_mm_s)
#else
prepare_kinematic_move_to(destination)
#endif
#elif ENABLED(DUAL_X_CARRIAGE)
prepare_move_to_destination_dualx()
#elif UBL_DELTA // will work for CARTESIAN too (smaller segments follow mesh more closely)
ubl.prepare_linear_move_to(destination, feedrate_mm_s)
ubl.prepare_segmented_line_to(destination, feedrate_mm_s)
#else
prepare_move_to_destination_cartesian()
#endif
@ -11827,7 +12003,7 @@ void prepare_move_to_destination() {
else
C2 = (HYPOT2(sx, sy) - (L1_2 + L2_2)) / (2.0 * L1 * L2);
S2 = sqrt(sq(C2) - 1);
S2 = sqrt(1 - sq(C2));
// Unrotated Arm1 plus rotated Arm2 gives the distance from Center to End
SK1 = L1 + L2 * C2;
@ -12459,6 +12635,8 @@ void setup() {
#endif
#if HAS_CASE_LIGHT
case_light_on = CASE_LIGHT_DEFAULT_ON;
case_light_brightness = CASE_LIGHT_DEFAULT_BRIGHTNESS;
update_case_light();
#endif
@ -12552,6 +12730,14 @@ void setup() {
#if ENABLED(ENDSTOP_INTERRUPTS_FEATURE)
setup_endstop_interrupts();
#endif
#if ENABLED(SWITCHING_EXTRUDER)
move_extruder_servo(0); // Initialize extruder servo
#endif
#if ENABLED(SWITCHING_NOZZLE)
move_nozzle_servo(0); // Initialize nozzle servo
#endif
}
/**

View File

@ -319,11 +319,11 @@
* Advanced Pause
*/
#if ENABLED(ADVANCED_PAUSE_FEATURE)
#if DISABLED(ULTIPANEL)
#if DISABLED(NEWPANEL)
#error "ADVANCED_PAUSE_FEATURE currently requires an LCD controller."
#elif ENABLED(EXTRUDER_RUNOUT_PREVENT)
#error "EXTRUDER_RUNOUT_PREVENT is incompatible with ADVANCED_PAUSE_FEATURE."
#elif ENABLED(PARK_HEAD_ON_PAUSE) && DISABLED(SDSUPPORT) && DISABLED(ULTIPANEL) && DISABLED(EMERGENCY_PARSER)
#elif ENABLED(PARK_HEAD_ON_PAUSE) && DISABLED(SDSUPPORT) && DISABLED(NEWPANEL) && DISABLED(EMERGENCY_PARSER)
#error "PARK_HEAD_ON_PAUSE requires SDSUPPORT, EMERGENCY_PARSER, or an LCD controller."
#endif
#endif
@ -598,8 +598,12 @@ static_assert(1 >= 0
/**
* LCD_BED_LEVELING requirements
*/
#if ENABLED(LCD_BED_LEVELING) && DISABLED(MESH_BED_LEVELING) && !(HAS_ABL && ENABLED(PROBE_MANUALLY))
#error "LCD_BED_LEVELING requires MESH_BED_LEVELING or PROBE_MANUALLY."
#if ENABLED(LCD_BED_LEVELING)
#if DISABLED(ULTIPANEL)
#error "LCD_BED_LEVELING requires an LCD controller."
#elif DISABLED(MESH_BED_LEVELING) && !(HAS_ABL && ENABLED(PROBE_MANUALLY))
#error "LCD_BED_LEVELING requires MESH_BED_LEVELING or PROBE_MANUALLY."
#endif
#endif
/**

View File

@ -95,6 +95,7 @@
#define BOARD_BAM_DICE 401 // 2PrintBeta BAM&DICE with STK drivers
#define BOARD_BAM_DICE_DUE 402 // 2PrintBeta BAM&DICE Due with STK drivers
#define BOARD_BQ_ZUM_MEGA_3D 503 // bq ZUM Mega 3D
#define BOARD_ZRIB_V20 504 // zrib V2.0 control board (Chinese knock off RAMPS replica)
#define MB(board) (MOTHERBOARD==BOARD_##board)

View File

@ -1152,7 +1152,7 @@
* - Click the controller to view the LCD menu
* - The LCD will display Japanese, Western, or Cyrillic text
*
* See https: *github.com/MarlinFirmware/Marlin/wiki/LCD-Language
* See https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
*
* :['JAPANESE', 'WESTERN', 'CYRILLIC']
*/

View File

@ -220,12 +220,16 @@
#define EXTRUDER_AUTO_FAN_TEMPERATURE 35
#define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed
// Define a pin to turn case light on/off
//#define CASE_LIGHT_PIN 4
#if PIN_EXISTS(CASE_LIGHT)
#define INVERT_CASE_LIGHT false // Set to true if HIGH is the OFF state (active low)
//#define CASE_LIGHT_DEFAULT_ON // Uncomment to set default state to on
//#define MENU_ITEM_CASE_LIGHT // Uncomment to have a Case Light On / Off entry in main menu
/**
* M355 Case Light on-off / brightness
*/
//#define CASE_LIGHT_ENABLE
#if ENABLED(CASE_LIGHT_ENABLE)
//#define CASE_LIGHT_PIN 4 // Override the default pin if needed
#define INVERT_CASE_LIGHT false // Set true if Case Light is ON when pin is LOW
#define CASE_LIGHT_DEFAULT_ON true // Set default power-up state on
#define CASE_LIGHT_DEFAULT_BRIGHTNESS 105 // Set default power-up brightness (0-255, requires PWM pin)
//#define MENU_ITEM_CASE_LIGHT // Add a Case Light option to the LCD main menu
#endif
//===========================================================================
@ -1016,7 +1020,7 @@
*/
#define TMC2130_ADV() { }
#endif // ENABLED(HAVE_TMC2130)
#endif // HAVE_TMC2130
// @section L6470

View File

@ -1136,7 +1136,7 @@
* - Click the controller to view the LCD menu
* - The LCD will display Japanese, Western, or Cyrillic text
*
* See https: *github.com/MarlinFirmware/Marlin/wiki/LCD-Language
* See https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
*
* :['JAPANESE', 'WESTERN', 'CYRILLIC']
*/

View File

@ -220,12 +220,16 @@
#define EXTRUDER_AUTO_FAN_TEMPERATURE 50
#define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed
// Define a pin to turn case light on/off
//#define CASE_LIGHT_PIN 4
#if PIN_EXISTS(CASE_LIGHT)
#define INVERT_CASE_LIGHT false // Set to true if HIGH is the OFF state (active low)
//#define CASE_LIGHT_DEFAULT_ON // Uncomment to set default state to on
//#define MENU_ITEM_CASE_LIGHT // Uncomment to have a Case Light On / Off entry in main menu
/**
* M355 Case Light on-off / brightness
*/
//#define CASE_LIGHT_ENABLE
#if ENABLED(CASE_LIGHT_ENABLE)
//#define CASE_LIGHT_PIN 4 // Override the default pin if needed
#define INVERT_CASE_LIGHT false // Set true if Case Light is ON when pin is LOW
#define CASE_LIGHT_DEFAULT_ON true // Set default power-up state on
#define CASE_LIGHT_DEFAULT_BRIGHTNESS 105 // Set default power-up brightness (0-255, requires PWM pin)
//#define MENU_ITEM_CASE_LIGHT // Add a Case Light option to the LCD main menu
#endif
//===========================================================================
@ -1016,7 +1020,7 @@
*/
#define TMC2130_ADV() { }
#endif // ENABLED(HAVE_TMC2130)
#endif // HAVE_TMC2130
// @section L6470

View File

@ -1136,7 +1136,7 @@
* - Click the controller to view the LCD menu
* - The LCD will display Japanese, Western, or Cyrillic text
*
* See https: *github.com/MarlinFirmware/Marlin/wiki/LCD-Language
* See https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
*
* :['JAPANESE', 'WESTERN', 'CYRILLIC']
*/

View File

@ -1158,7 +1158,7 @@
* - Click the controller to view the LCD menu
* - The LCD will display Japanese, Western, or Cyrillic text
*
* See https: *github.com/MarlinFirmware/Marlin/wiki/LCD-Language
* See https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
*
* :['JAPANESE', 'WESTERN', 'CYRILLIC']
*/

View File

@ -220,12 +220,16 @@
#define EXTRUDER_AUTO_FAN_TEMPERATURE 50
#define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed
// Define a pin to turn case light on/off
//#define CASE_LIGHT_PIN 4
#if PIN_EXISTS(CASE_LIGHT)
#define INVERT_CASE_LIGHT false // Set to true if HIGH is the OFF state (active low)
//#define CASE_LIGHT_DEFAULT_ON // Uncomment to set default state to on
//#define MENU_ITEM_CASE_LIGHT // Uncomment to have a Case Light On / Off entry in main menu
/**
* M355 Case Light on-off / brightness
*/
//#define CASE_LIGHT_ENABLE
#if ENABLED(CASE_LIGHT_ENABLE)
//#define CASE_LIGHT_PIN 4 // Override the default pin if needed
#define INVERT_CASE_LIGHT false // Set true if Case Light is ON when pin is LOW
#define CASE_LIGHT_DEFAULT_ON true // Set default power-up state on
#define CASE_LIGHT_DEFAULT_BRIGHTNESS 105 // Set default power-up brightness (0-255, requires PWM pin)
//#define MENU_ITEM_CASE_LIGHT // Add a Case Light option to the LCD main menu
#endif
//===========================================================================
@ -784,7 +788,7 @@
#define PAUSE_PARK_Z_FEEDRATE 5 // Z axis feedrate in mm/s (not used for delta printers)
#define PAUSE_PARK_RETRACT_FEEDRATE 60 // Initial retract feedrate in mm/s
#define PAUSE_PARK_RETRACT_LENGTH 2 // Initial retract in mm
// It is a short retract used immediately after print interrupt before move to filament exchange position
#define FILAMENT_CHANGE_UNLOAD_FEEDRATE 10 // Unload filament feedrate in mm/s - filament unloading can be fast
#define FILAMENT_CHANGE_UNLOAD_LENGTH 100 // Unload filament length from hotend in mm
@ -1025,7 +1029,7 @@
*/
#define TMC2130_ADV() { }
#endif // ENABLED(HAVE_TMC2130)
#endif // HAVE_TMC2130
// @section L6470

View File

@ -1144,7 +1144,7 @@
* - Click the controller to view the LCD menu
* - The LCD will display Japanese, Western, or Cyrillic text
*
* See https: *github.com/MarlinFirmware/Marlin/wiki/LCD-Language
* See https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
*
* :['JAPANESE', 'WESTERN', 'CYRILLIC']
*/

View File

@ -220,12 +220,16 @@
#define EXTRUDER_AUTO_FAN_TEMPERATURE 50
#define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed
// Define a pin to turn case light on/off
//#define CASE_LIGHT_PIN 4
#if PIN_EXISTS(CASE_LIGHT)
#define INVERT_CASE_LIGHT false // Set to true if HIGH is the OFF state (active low)
//#define CASE_LIGHT_DEFAULT_ON // Uncomment to set default state to on
//#define MENU_ITEM_CASE_LIGHT // Uncomment to have a Case Light On / Off entry in main menu
/**
* M355 Case Light on-off / brightness
*/
//#define CASE_LIGHT_ENABLE
#if ENABLED(CASE_LIGHT_ENABLE)
//#define CASE_LIGHT_PIN 4 // Override the default pin if needed
#define INVERT_CASE_LIGHT false // Set true if Case Light is ON when pin is LOW
#define CASE_LIGHT_DEFAULT_ON true // Set default power-up state on
#define CASE_LIGHT_DEFAULT_BRIGHTNESS 105 // Set default power-up brightness (0-255, requires PWM pin)
//#define MENU_ITEM_CASE_LIGHT // Add a Case Light option to the LCD main menu
#endif
//===========================================================================
@ -1016,7 +1020,7 @@
*/
#define TMC2130_ADV() { }
#endif // ENABLED(HAVE_TMC2130)
#endif // HAVE_TMC2130
// @section L6470

View File

@ -1147,7 +1147,7 @@
* - Click the controller to view the LCD menu
* - The LCD will display Japanese, Western, or Cyrillic text
*
* See https: *github.com/MarlinFirmware/Marlin/wiki/LCD-Language
* See https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
*
* :['JAPANESE', 'WESTERN', 'CYRILLIC']
*/

View File

@ -220,12 +220,16 @@
#define EXTRUDER_AUTO_FAN_TEMPERATURE 50
#define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed
// Define a pin to turn case light on/off
//#define CASE_LIGHT_PIN 4
#if PIN_EXISTS(CASE_LIGHT)
#define INVERT_CASE_LIGHT false // Set to true if HIGH is the OFF state (active low)
//#define CASE_LIGHT_DEFAULT_ON // Uncomment to set default state to on
//#define MENU_ITEM_CASE_LIGHT // Uncomment to have a Case Light On / Off entry in main menu
/**
* M355 Case Light on-off / brightness
*/
//#define CASE_LIGHT_ENABLE
#if ENABLED(CASE_LIGHT_ENABLE)
//#define CASE_LIGHT_PIN 4 // Override the default pin if needed
#define INVERT_CASE_LIGHT false // Set true if Case Light is ON when pin is LOW
#define CASE_LIGHT_DEFAULT_ON true // Set default power-up state on
#define CASE_LIGHT_DEFAULT_BRIGHTNESS 105 // Set default power-up brightness (0-255, requires PWM pin)
//#define MENU_ITEM_CASE_LIGHT // Add a Case Light option to the LCD main menu
#endif
//===========================================================================
@ -1000,7 +1004,7 @@
*/
#define TMC2130_ADV() { }
#endif // ENABLED(HAVE_TMC2130)
#endif // HAVE_TMC2130
// @section L6470

View File

@ -332,6 +332,7 @@
#define K1 0.95 //smoothing factor within the PID
// If you are using a pre-configured hotend then you can use one of the value sets by uncommenting it
// Ultimaker
//#define DEFAULT_Kp 22.2
//#define DEFAULT_Ki 1.08
@ -1185,7 +1186,7 @@
* - Click the controller to view the LCD menu
* - The LCD will display Japanese, Western, or Cyrillic text
*
* See https: *github.com/MarlinFirmware/Marlin/wiki/LCD-Language
* See https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
*
* :['JAPANESE', 'WESTERN', 'CYRILLIC']
*/

View File

@ -233,12 +233,16 @@
#define EXTRUDER_AUTO_FAN_TEMPERATURE 50
#define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed
// Define a pin to turn case light on/off
//#define CASE_LIGHT_PIN 4
#if PIN_EXISTS(CASE_LIGHT)
#define INVERT_CASE_LIGHT false // Set to true if HIGH is the OFF state (active low)
//#define CASE_LIGHT_DEFAULT_ON // Uncomment to set default state to on
//#define MENU_ITEM_CASE_LIGHT // Uncomment to have a Case Light On / Off entry in main menu
/**
* M355 Case Light on-off / brightness
*/
//#define CASE_LIGHT_ENABLE
#if ENABLED(CASE_LIGHT_ENABLE)
//#define CASE_LIGHT_PIN 4 // Override the default pin if needed
#define INVERT_CASE_LIGHT false // Set true if Case Light is ON when pin is LOW
#define CASE_LIGHT_DEFAULT_ON true // Set default power-up state on
#define CASE_LIGHT_DEFAULT_BRIGHTNESS 105 // Set default power-up brightness (0-255, requires PWM pin)
//#define MENU_ITEM_CASE_LIGHT // Add a Case Light option to the LCD main menu
#endif
//===========================================================================
@ -1029,7 +1033,7 @@
*/
#define TMC2130_ADV() { }
#endif // ENABLED(HAVE_TMC2130)
#endif // HAVE_TMC2130
// @section L6470

View File

@ -312,6 +312,7 @@
#define K1 0.95 //smoothing factor within the PID
// If you are using a pre-configured hotend then you can use one of the value sets by uncommenting it
// Ultimaker
//#define DEFAULT_Kp 22.2
//#define DEFAULT_Ki 1.08
@ -1153,7 +1154,7 @@
* - Click the controller to view the LCD menu
* - The LCD will display Japanese, Western, or Cyrillic text
*
* See https: *github.com/MarlinFirmware/Marlin/wiki/LCD-Language
* See https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
*
* :['JAPANESE', 'WESTERN', 'CYRILLIC']
*/

View File

@ -220,12 +220,16 @@
#define EXTRUDER_AUTO_FAN_TEMPERATURE 50
#define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed
// Define a pin to turn case light on/off
//#define CASE_LIGHT_PIN 4
#if PIN_EXISTS(CASE_LIGHT)
#define INVERT_CASE_LIGHT false // Set to true if HIGH is the OFF state (active low)
//#define CASE_LIGHT_DEFAULT_ON // Uncomment to set default state to on
//#define MENU_ITEM_CASE_LIGHT // Uncomment to have a Case Light On / Off entry in main menu
/**
* M355 Case Light on-off / brightness
*/
//#define CASE_LIGHT_ENABLE
#if ENABLED(CASE_LIGHT_ENABLE)
//#define CASE_LIGHT_PIN 4 // Override the default pin if needed
#define INVERT_CASE_LIGHT false // Set true if Case Light is ON when pin is LOW
#define CASE_LIGHT_DEFAULT_ON true // Set default power-up state on
#define CASE_LIGHT_DEFAULT_BRIGHTNESS 105 // Set default power-up brightness (0-255, requires PWM pin)
//#define MENU_ITEM_CASE_LIGHT // Add a Case Light option to the LCD main menu
#endif
//===========================================================================
@ -1016,7 +1020,7 @@
*/
#define TMC2130_ADV() { }
#endif // ENABLED(HAVE_TMC2130)
#endif // HAVE_TMC2130
// @section L6470

View File

@ -312,6 +312,7 @@
#define K1 0.95 //smoothing factor within the PID
// If you are using a pre-configured hotend then you can use one of the value sets by uncommenting it
// Ultimaker
//#define DEFAULT_Kp 22.2
//#define DEFAULT_Ki 1.08
@ -1153,7 +1154,7 @@
* - Click the controller to view the LCD menu
* - The LCD will display Japanese, Western, or Cyrillic text
*
* See https: *github.com/MarlinFirmware/Marlin/wiki/LCD-Language
* See https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
*
* :['JAPANESE', 'WESTERN', 'CYRILLIC']
*/

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,3 @@
# Configuration for Malyan M150 hobbyking printer
# config without automatic bed level sensor
# or in other words, "as stock"

View File

@ -0,0 +1,104 @@
/**
* Marlin 3D Printer Firmware
* Copyright (C) 2016 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/>.
*
*/
/**
* Custom Bitmap for splashscreen
*
* You may use one of the following tools to generate the C++ bitmap array from
* a black and white image:
*
* - http://www.marlinfw.org/tools/u8glib/converter.html
* - http://www.digole.com/tools/PicturetoC_Hex_converter.php
*/
#include <avr/pgmspace.h>
#define CUSTOM_BOOTSCREEN_TIMEOUT 1000
#define CUSTOM_BOOTSCREEN_BMPWIDTH 128
#define CUSTOM_BOOTSCREEN_BMPHEIGHT 64
const unsigned char custom_start_bmp[1024] PROGMEM = {
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00
,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00
,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00
,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00
,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00
,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00
,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00
,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00
,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00
,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00
,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00
,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00
,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00
,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00
,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00
,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00
,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00
,0x07,0x00,0x00,0x03,0x80,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00
,0x1f,0xc0,0x00,0x0f,0xe0,0x7c,0x03,0xe0,0x78,0x1c,0x07,0x81,0xe0,0xf0,0x3e,0x0e
,0x7f,0xe0,0x00,0x3f,0xf0,0x7e,0x07,0xe0,0xfc,0x1c,0x03,0x81,0xc1,0xf8,0x3f,0x0e
,0x7f,0xf8,0x00,0x7f,0xf0,0x7e,0x07,0xe0,0xfc,0x1c,0x03,0xc3,0xc1,0xf8,0x3f,0x0e
,0x7b,0xfe,0x01,0xfe,0xf0,0x7f,0x0f,0xe1,0xfe,0x1c,0x01,0xc3,0x83,0xfc,0x3f,0x8e
,0x7c,0xff,0x87,0xf9,0xf0,0x77,0x0e,0xe1,0xfe,0x1c,0x01,0xe7,0x83,0xfc,0x3b,0x8e
,0x7f,0x7f,0xcf,0xf7,0xf0,0x77,0x9e,0xe1,0xce,0x1c,0x00,0xe7,0x03,0x9c,0x3b,0xce
,0x7f,0x9f,0xff,0xcf,0xf0,0x73,0x9c,0xe3,0xcf,0x1c,0x00,0xff,0x07,0x9e,0x39,0xce
,0x7f,0xe7,0xff,0x3f,0xf0,0x73,0xfc,0xe3,0x87,0x1c,0x00,0x7e,0x07,0x0e,0x39,0xee
,0x7f,0xfb,0xfe,0xff,0xf0,0x71,0xf8,0xe3,0x87,0x1c,0x00,0x7e,0x0f,0x0f,0x38,0xee
,0x7f,0xfc,0xf9,0xff,0xf0,0x71,0xf8,0xe7,0xff,0x9c,0x00,0x3c,0x0f,0xff,0x38,0xfe
,0x7f,0xff,0x27,0xff,0xf0,0x70,0xf0,0xe7,0xff,0x9c,0x00,0x3c,0x0f,0xff,0x38,0x7e
,0x7f,0xff,0xdf,0xff,0xf0,0x70,0xf0,0xef,0xff,0xdc,0x00,0x3c,0x1f,0xff,0xb8,0x7e
,0x7f,0xdf,0xff,0xdf,0xf0,0x70,0x60,0xef,0x03,0xdf,0xf8,0x3c,0x1e,0x07,0xb8,0x3e
,0x7f,0xc7,0xff,0x1f,0xf0,0x70,0x60,0xee,0x01,0xdf,0xf8,0x3c,0x1c,0x03,0xb8,0x3e
,0x7f,0xc3,0xfe,0x1f,0xf0,0x70,0x00,0xee,0x01,0xdf,0xf8,0x3c,0x1c,0x03,0xb8,0x1e
,0x7f,0xc3,0xfe,0x1f,0xf0,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00
,0x7f,0xc3,0xde,0x1f,0xf0,0x7f,0xff,0xff,0xff,0xff,0xff,0xff,0xff,0xff,0xff,0xfe
,0x7f,0xc3,0xde,0x1f,0xf0,0x7f,0xff,0xff,0xff,0xff,0xff,0xff,0xff,0xff,0xff,0xfe
,0x7f,0xc3,0xde,0x1f,0xf0,0x7c,0x3f,0xfa,0xfb,0xff,0xff,0xff,0xfd,0x7a,0xbf,0xfe
,0x7f,0xc3,0xde,0x1f,0xf0,0x7d,0x9f,0xfb,0xff,0xff,0xff,0xff,0xff,0x7e,0xf7,0xfe
,0x7f,0xc3,0xde,0x1f,0xf0,0x7d,0x93,0x1a,0x8a,0x18,0xe3,0x8c,0x45,0x1a,0xa2,0xde
,0x3f,0xc3,0xde,0x0f,0xf0,0x7c,0x2d,0xca,0xca,0xd6,0xe9,0x24,0xcd,0x6a,0xb6,0xbe
,0x1f,0x83,0xde,0x07,0xe0,0x7d,0xa3,0x6a,0x9a,0xd6,0xe9,0x26,0x65,0x6a,0xb6,0x3e
,0x06,0x03,0xde,0x01,0x80,0x7d,0x91,0x0a,0x8a,0xd8,0xe3,0x8c,0x45,0x1a,0xb3,0x7e
,0x00,0x03,0xde,0x00,0x00,0x7f,0xff,0xff,0xff,0xfe,0xef,0xff,0xff,0xff,0xff,0x7e
,0x00,0x03,0xde,0x00,0x00,0x7f,0xff,0xff,0xff,0xf1,0xef,0xff,0xff,0xff,0xfe,0xfe
,0x00,0x03,0xde,0x00,0x00,0x7f,0xff,0xff,0xff,0xff,0xff,0xff,0xff,0xff,0xff,0xfe
,0x00,0x03,0xde,0x00,0x00,0x7f,0xff,0xff,0xff,0xff,0xff,0xff,0xff,0xff,0xff,0xfe
,0x00,0x03,0xde,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00
,0x00,0x01,0xdc,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00
,0x00,0x00,0x50,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00
,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00
,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00
,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00
,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00
,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00
,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00
,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00
,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00
,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00
,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00
,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00
,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00
,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00
,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00
,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00
};

View File

@ -312,6 +312,7 @@
#define K1 0.95 //smoothing factor within the PID
// If you are using a pre-configured hotend then you can use one of the value sets by uncommenting it
// Ultimaker
#define DEFAULT_Kp 22.2
#define DEFAULT_Ki 1.08
@ -1153,7 +1154,7 @@
* - Click the controller to view the LCD menu
* - The LCD will display Japanese, Western, or Cyrillic text
*
* See https: *github.com/MarlinFirmware/Marlin/wiki/LCD-Language
* See https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
*
* :['JAPANESE', 'WESTERN', 'CYRILLIC']
*/

View File

@ -1152,7 +1152,7 @@
* - Click the controller to view the LCD menu
* - The LCD will display Japanese, Western, or Cyrillic text
*
* See https: *github.com/MarlinFirmware/Marlin/wiki/LCD-Language
* See https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
*
* :['JAPANESE', 'WESTERN', 'CYRILLIC']
*/

View File

@ -220,12 +220,16 @@
#define EXTRUDER_AUTO_FAN_TEMPERATURE 50
#define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed
// Define a pin to turn case light on/off
//#define CASE_LIGHT_PIN 4
#if PIN_EXISTS(CASE_LIGHT)
#define INVERT_CASE_LIGHT false // Set to true if HIGH is the OFF state (active low)
//#define CASE_LIGHT_DEFAULT_ON // Uncomment to set default state to on
//#define MENU_ITEM_CASE_LIGHT // Uncomment to have a Case Light On / Off entry in main menu
/**
* M355 Case Light on-off / brightness
*/
//#define CASE_LIGHT_ENABLE
#if ENABLED(CASE_LIGHT_ENABLE)
//#define CASE_LIGHT_PIN 4 // Override the default pin if needed
#define INVERT_CASE_LIGHT false // Set true if Case Light is ON when pin is LOW
#define CASE_LIGHT_DEFAULT_ON true // Set default power-up state on
#define CASE_LIGHT_DEFAULT_BRIGHTNESS 105 // Set default power-up brightness (0-255, requires PWM pin)
//#define MENU_ITEM_CASE_LIGHT // Add a Case Light option to the LCD main menu
#endif
//===========================================================================
@ -1016,7 +1020,7 @@
*/
#define TMC2130_ADV() { }
#endif // ENABLED(HAVE_TMC2130)
#endif // HAVE_TMC2130
// @section L6470

View File

@ -1169,7 +1169,7 @@
* - Click the controller to view the LCD menu
* - The LCD will display Japanese, Western, or Cyrillic text
*
* See https: *github.com/MarlinFirmware/Marlin/wiki/LCD-Language
* See https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
*
* :['JAPANESE', 'WESTERN', 'CYRILLIC']
*/

View File

@ -220,12 +220,16 @@
#define EXTRUDER_AUTO_FAN_TEMPERATURE 50
#define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed
// Define a pin to turn case light on/off
//#define CASE_LIGHT_PIN 4
#if PIN_EXISTS(CASE_LIGHT)
#define INVERT_CASE_LIGHT false // Set to true if HIGH is the OFF state (active low)
//#define CASE_LIGHT_DEFAULT_ON // Uncomment to set default state to on
//#define MENU_ITEM_CASE_LIGHT // Uncomment to have a Case Light On / Off entry in main menu
/**
* M355 Case Light on-off / brightness
*/
//#define CASE_LIGHT_ENABLE
#if ENABLED(CASE_LIGHT_ENABLE)
//#define CASE_LIGHT_PIN 4 // Override the default pin if needed
#define INVERT_CASE_LIGHT false // Set true if Case Light is ON when pin is LOW
#define CASE_LIGHT_DEFAULT_ON true // Set default power-up state on
#define CASE_LIGHT_DEFAULT_BRIGHTNESS 105 // Set default power-up brightness (0-255, requires PWM pin)
//#define MENU_ITEM_CASE_LIGHT // Add a Case Light option to the LCD main menu
#endif
//===========================================================================
@ -1016,7 +1020,7 @@
*/
#define TMC2130_ADV() { }
#endif // ENABLED(HAVE_TMC2130)
#endif // HAVE_TMC2130
// @section L6470

View File

@ -1173,7 +1173,7 @@
* - Click the controller to view the LCD menu
* - The LCD will display Japanese, Western, or Cyrillic text
*
* See https: *github.com/MarlinFirmware/Marlin/wiki/LCD-Language
* See https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
*
* :['JAPANESE', 'WESTERN', 'CYRILLIC']
*/

View File

@ -220,12 +220,16 @@
#define EXTRUDER_AUTO_FAN_TEMPERATURE 50
#define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed
// Define a pin to turn case light on/off
//#define CASE_LIGHT_PIN 4
#if PIN_EXISTS(CASE_LIGHT)
#define INVERT_CASE_LIGHT false // Set to true if HIGH is the OFF state (active low)
//#define CASE_LIGHT_DEFAULT_ON // Uncomment to set default state to on
//#define MENU_ITEM_CASE_LIGHT // Uncomment to have a Case Light On / Off entry in main menu
/**
* M355 Case Light on-off / brightness
*/
//#define CASE_LIGHT_ENABLE
#if ENABLED(CASE_LIGHT_ENABLE)
//#define CASE_LIGHT_PIN 4 // Override the default pin if needed
#define INVERT_CASE_LIGHT false // Set true if Case Light is ON when pin is LOW
#define CASE_LIGHT_DEFAULT_ON true // Set default power-up state on
#define CASE_LIGHT_DEFAULT_BRIGHTNESS 105 // Set default power-up brightness (0-255, requires PWM pin)
//#define MENU_ITEM_CASE_LIGHT // Add a Case Light option to the LCD main menu
#endif
//===========================================================================
@ -1016,7 +1020,7 @@
*/
#define TMC2130_ADV() { }
#endif // ENABLED(HAVE_TMC2130)
#endif // HAVE_TMC2130
// @section L6470

View File

@ -339,6 +339,7 @@
#define K1 0.95 //smoothing factor within the PID
// If you are using a pre-configured hotend then you can use one of the value sets by uncommenting it
// Ultimaker
//#define DEFAULT_Kp 22.2
//#define DEFAULT_Ki 1.08
@ -1209,7 +1210,7 @@
* - Click the controller to view the LCD menu
* - The LCD will display Japanese, Western, or Cyrillic text
*
* See https: *github.com/MarlinFirmware/Marlin/wiki/LCD-Language
* See https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
*
* :['JAPANESE', 'WESTERN', 'CYRILLIC']
*/

View File

@ -220,12 +220,16 @@
#define EXTRUDER_AUTO_FAN_TEMPERATURE 50
#define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed
// Define a pin to turn case light on/off
//#define CASE_LIGHT_PIN 4
#if PIN_EXISTS(CASE_LIGHT)
#define INVERT_CASE_LIGHT false // Set to true if HIGH is the OFF state (active low)
//#define CASE_LIGHT_DEFAULT_ON // Uncomment to set default state to on
//#define MENU_ITEM_CASE_LIGHT // Uncomment to have a Case Light On / Off entry in main menu
/**
* M355 Case Light on-off / brightness
*/
//#define CASE_LIGHT_ENABLE
#if ENABLED(CASE_LIGHT_ENABLE)
//#define CASE_LIGHT_PIN 4 // Override the default pin if needed
#define INVERT_CASE_LIGHT false // Set true if Case Light is ON when pin is LOW
#define CASE_LIGHT_DEFAULT_ON true // Set default power-up state on
#define CASE_LIGHT_DEFAULT_BRIGHTNESS 105 // Set default power-up brightness (0-255, requires PWM pin)
//#define MENU_ITEM_CASE_LIGHT // Add a Case Light option to the LCD main menu
#endif
//===========================================================================
@ -1019,7 +1023,7 @@
*/
#define TMC2130_ADV() { }
#endif // ENABLED(HAVE_TMC2130)
#endif // HAVE_TMC2130
// @section L6470

View File

@ -1144,7 +1144,7 @@
* - Click the controller to view the LCD menu
* - The LCD will display Japanese, Western, or Cyrillic text
*
* See https: *github.com/MarlinFirmware/Marlin/wiki/LCD-Language
* See https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
*
* :['JAPANESE', 'WESTERN', 'CYRILLIC']
*/

View File

@ -220,12 +220,16 @@
#define EXTRUDER_AUTO_FAN_TEMPERATURE 50
#define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed
// Define a pin to turn case light on/off
//#define CASE_LIGHT_PIN 4
#if PIN_EXISTS(CASE_LIGHT)
#define INVERT_CASE_LIGHT false // Set to true if HIGH is the OFF state (active low)
//#define CASE_LIGHT_DEFAULT_ON // Uncomment to set default state to on
//#define MENU_ITEM_CASE_LIGHT // Uncomment to have a Case Light On / Off entry in main menu
/**
* M355 Case Light on-off / brightness
*/
//#define CASE_LIGHT_ENABLE
#if ENABLED(CASE_LIGHT_ENABLE)
//#define CASE_LIGHT_PIN 4 // Override the default pin if needed
#define INVERT_CASE_LIGHT false // Set true if Case Light is ON when pin is LOW
#define CASE_LIGHT_DEFAULT_ON true // Set default power-up state on
#define CASE_LIGHT_DEFAULT_BRIGHTNESS 105 // Set default power-up brightness (0-255, requires PWM pin)
//#define MENU_ITEM_CASE_LIGHT // Add a Case Light option to the LCD main menu
#endif
//===========================================================================
@ -1016,7 +1020,7 @@
*/
#define TMC2130_ADV() { }
#endif // ENABLED(HAVE_TMC2130)
#endif // HAVE_TMC2130
// @section L6470

View File

@ -312,6 +312,7 @@
#define K1 0.95 //smoothing factor within the PID
// If you are using a pre-configured hotend then you can use one of the value sets by uncommenting it
// Ultimaker
#define DEFAULT_Kp 22.2
#define DEFAULT_Ki 1.08
@ -1153,7 +1154,7 @@
* - Click the controller to view the LCD menu
* - The LCD will display Japanese, Western, or Cyrillic text
*
* See https: *github.com/MarlinFirmware/Marlin/wiki/LCD-Language
* See https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
*
* :['JAPANESE', 'WESTERN', 'CYRILLIC']
*/

View File

@ -312,6 +312,7 @@
#define K1 0.95 //smoothing factor within the PID
// If you are using a pre-configured hotend then you can use one of the value sets by uncommenting it
// Ultimaker
//#define DEFAULT_Kp 22.2
//#define DEFAULT_Ki 1.08
@ -1271,7 +1272,7 @@
* - Click the controller to view the LCD menu
* - The LCD will display Japanese, Western, or Cyrillic text
*
* See https: *github.com/MarlinFirmware/Marlin/wiki/LCD-Language
* See https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
*
* :['JAPANESE', 'WESTERN', 'CYRILLIC']
*/

View File

@ -220,12 +220,16 @@
#define EXTRUDER_AUTO_FAN_TEMPERATURE 50
#define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed
// Define a pin to turn case light on/off
//#define CASE_LIGHT_PIN 4
#if PIN_EXISTS(CASE_LIGHT)
#define INVERT_CASE_LIGHT false // Set to true if HIGH is the OFF state (active low)
//#define CASE_LIGHT_DEFAULT_ON // Uncomment to set default state to on
//#define MENU_ITEM_CASE_LIGHT // Uncomment to have a Case Light On / Off entry in main menu
/**
* M355 Case Light on-off / brightness
*/
//#define CASE_LIGHT_ENABLE
#if ENABLED(CASE_LIGHT_ENABLE)
//#define CASE_LIGHT_PIN 4 // Override the default pin if needed
#define INVERT_CASE_LIGHT false // Set true if Case Light is ON when pin is LOW
#define CASE_LIGHT_DEFAULT_ON true // Set default power-up state on
#define CASE_LIGHT_DEFAULT_BRIGHTNESS 105 // Set default power-up brightness (0-255, requires PWM pin)
//#define MENU_ITEM_CASE_LIGHT // Add a Case Light option to the LCD main menu
#endif
//===========================================================================
@ -1021,7 +1025,7 @@
*/
#define TMC2130_ADV() { }
#endif // ENABLED(HAVE_TMC2130)
#endif // HAVE_TMC2130
// @section L6470

View File

@ -312,6 +312,7 @@
#define K1 0.95 //smoothing factor within the PID
// If you are using a pre-configured hotend then you can use one of the value sets by uncommenting it
// Ultimaker
//#define DEFAULT_Kp 22.2
//#define DEFAULT_Ki 1.08
@ -1273,7 +1274,7 @@
* - Click the controller to view the LCD menu
* - The LCD will display Japanese, Western, or Cyrillic text
*
* See https: *github.com/MarlinFirmware/Marlin/wiki/LCD-Language
* See https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
*
* :['JAPANESE', 'WESTERN', 'CYRILLIC']
*/

View File

@ -220,12 +220,16 @@
#define EXTRUDER_AUTO_FAN_TEMPERATURE 50
#define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed
// Define a pin to turn case light on/off
//#define CASE_LIGHT_PIN 4
#if PIN_EXISTS(CASE_LIGHT)
#define INVERT_CASE_LIGHT false // Set to true if HIGH is the OFF state (active low)
//#define CASE_LIGHT_DEFAULT_ON // Uncomment to set default state to on
//#define MENU_ITEM_CASE_LIGHT // Uncomment to have a Case Light On / Off entry in main menu
/**
* M355 Case Light on-off / brightness
*/
//#define CASE_LIGHT_ENABLE
#if ENABLED(CASE_LIGHT_ENABLE)
//#define CASE_LIGHT_PIN 4 // Override the default pin if needed
#define INVERT_CASE_LIGHT false // Set true if Case Light is ON when pin is LOW
#define CASE_LIGHT_DEFAULT_ON true // Set default power-up state on
#define CASE_LIGHT_DEFAULT_BRIGHTNESS 105 // Set default power-up brightness (0-255, requires PWM pin)
//#define MENU_ITEM_CASE_LIGHT // Add a Case Light option to the LCD main menu
#endif
//===========================================================================
@ -1020,7 +1024,7 @@
*/
#define TMC2130_ADV() { }
#endif // ENABLED(HAVE_TMC2130)
#endif // HAVE_TMC2130
// @section L6470

View File

@ -312,6 +312,7 @@
#define K1 0.95 //smoothing factor within the PID
// If you are using a pre-configured hotend then you can use one of the value sets by uncommenting it
// Ultimaker
#define DEFAULT_Kp 22.2
#define DEFAULT_Ki 1.08
@ -1262,7 +1263,7 @@
* - Click the controller to view the LCD menu
* - The LCD will display Japanese, Western, or Cyrillic text
*
* See https: *github.com/MarlinFirmware/Marlin/wiki/LCD-Language
* See https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
*
* :['JAPANESE', 'WESTERN', 'CYRILLIC']
*/

View File

@ -220,12 +220,16 @@
#define EXTRUDER_AUTO_FAN_TEMPERATURE 50
#define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed
// Define a pin to turn case light on/off
//#define CASE_LIGHT_PIN 4
#if PIN_EXISTS(CASE_LIGHT)
#define INVERT_CASE_LIGHT false // Set to true if HIGH is the OFF state (active low)
//#define CASE_LIGHT_DEFAULT_ON // Uncomment to set default state to on
//#define MENU_ITEM_CASE_LIGHT // Uncomment to have a Case Light On / Off entry in main menu
/**
* M355 Case Light on-off / brightness
*/
//#define CASE_LIGHT_ENABLE
#if ENABLED(CASE_LIGHT_ENABLE)
//#define CASE_LIGHT_PIN 4 // Override the default pin if needed
#define INVERT_CASE_LIGHT false // Set true if Case Light is ON when pin is LOW
#define CASE_LIGHT_DEFAULT_ON true // Set default power-up state on
#define CASE_LIGHT_DEFAULT_BRIGHTNESS 105 // Set default power-up brightness (0-255, requires PWM pin)
//#define MENU_ITEM_CASE_LIGHT // Add a Case Light option to the LCD main menu
#endif
//===========================================================================
@ -1018,7 +1022,7 @@
*/
#define TMC2130_ADV() { }
#endif // ENABLED(HAVE_TMC2130)
#endif // HAVE_TMC2130
// @section L6470

View File

@ -312,6 +312,7 @@
#define K1 0.95 //smoothing factor within the PID
// If you are using a pre-configured hotend then you can use one of the value sets by uncommenting it
// Ultimaker
#define DEFAULT_Kp 22.2
#define DEFAULT_Ki 1.08
@ -1265,7 +1266,7 @@
* - Click the controller to view the LCD menu
* - The LCD will display Japanese, Western, or Cyrillic text
*
* See https: *github.com/MarlinFirmware/Marlin/wiki/LCD-Language
* See https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
*
* :['JAPANESE', 'WESTERN', 'CYRILLIC']
*/

View File

@ -220,12 +220,16 @@
#define EXTRUDER_AUTO_FAN_TEMPERATURE 50
#define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed
// Define a pin to turn case light on/off
//#define CASE_LIGHT_PIN 4
#if PIN_EXISTS(CASE_LIGHT)
#define INVERT_CASE_LIGHT false // Set to true if HIGH is the OFF state (active low)
//#define CASE_LIGHT_DEFAULT_ON // Uncomment to set default state to on
//#define MENU_ITEM_CASE_LIGHT // Uncomment to have a Case Light On / Off entry in main menu
/**
* M355 Case Light on-off / brightness
*/
//#define CASE_LIGHT_ENABLE
#if ENABLED(CASE_LIGHT_ENABLE)
//#define CASE_LIGHT_PIN 4 // Override the default pin if needed
#define INVERT_CASE_LIGHT false // Set true if Case Light is ON when pin is LOW
#define CASE_LIGHT_DEFAULT_ON true // Set default power-up state on
#define CASE_LIGHT_DEFAULT_BRIGHTNESS 105 // Set default power-up brightness (0-255, requires PWM pin)
//#define MENU_ITEM_CASE_LIGHT // Add a Case Light option to the LCD main menu
#endif
//===========================================================================
@ -1018,7 +1022,7 @@
*/
#define TMC2130_ADV() { }
#endif // ENABLED(HAVE_TMC2130)
#endif // HAVE_TMC2130
// @section L6470

View File

@ -1271,7 +1271,7 @@
* - Click the controller to view the LCD menu
* - The LCD will display Japanese, Western, or Cyrillic text
*
* See https: *github.com/MarlinFirmware/Marlin/wiki/LCD-Language
* See https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
*
* :['JAPANESE', 'WESTERN', 'CYRILLIC']
*/

View File

@ -225,12 +225,16 @@
#define EXTRUDER_AUTO_FAN_TEMPERATURE 50
#define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed
// Define a pin to turn case light on/off
//#define CASE_LIGHT_PIN 4
#if PIN_EXISTS(CASE_LIGHT)
#define INVERT_CASE_LIGHT false // Set to true if HIGH is the OFF state (active low)
//#define CASE_LIGHT_DEFAULT_ON // Uncomment to set default state to on
//#define MENU_ITEM_CASE_LIGHT // Uncomment to have a Case Light On / Off entry in main menu
/**
* M355 Case Light on-off / brightness
*/
//#define CASE_LIGHT_ENABLE
#if ENABLED(CASE_LIGHT_ENABLE)
//#define CASE_LIGHT_PIN 4 // Override the default pin if needed
#define INVERT_CASE_LIGHT false // Set true if Case Light is ON when pin is LOW
#define CASE_LIGHT_DEFAULT_ON true // Set default power-up state on
#define CASE_LIGHT_DEFAULT_BRIGHTNESS 105 // Set default power-up brightness (0-255, requires PWM pin)
//#define MENU_ITEM_CASE_LIGHT // Add a Case Light option to the LCD main menu
#endif
//===========================================================================
@ -1023,7 +1027,7 @@
*/
#define TMC2130_ADV() { }
#endif // ENABLED(HAVE_TMC2130)
#endif // HAVE_TMC2130
// @section L6470

View File

@ -1329,7 +1329,7 @@
* - Click the controller to view the LCD menu
* - The LCD will display Japanese, Western, or Cyrillic text
*
* See https: *github.com/MarlinFirmware/Marlin/wiki/LCD-Language
* See https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
*
* :['JAPANESE', 'WESTERN', 'CYRILLIC']
*/

View File

@ -220,12 +220,16 @@
#define EXTRUDER_AUTO_FAN_TEMPERATURE 50
#define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed
// Define a pin to turn case light on/off
//#define CASE_LIGHT_PIN 4
#if PIN_EXISTS(CASE_LIGHT)
#define INVERT_CASE_LIGHT false // Set to true if HIGH is the OFF state (active low)
//#define CASE_LIGHT_DEFAULT_ON // Uncomment to set default state to on
//#define MENU_ITEM_CASE_LIGHT // Uncomment to have a Case Light On / Off entry in main menu
/**
* M355 Case Light on-off / brightness
*/
//#define CASE_LIGHT_ENABLE
#if ENABLED(CASE_LIGHT_ENABLE)
//#define CASE_LIGHT_PIN 4 // Override the default pin if needed
#define INVERT_CASE_LIGHT false // Set true if Case Light is ON when pin is LOW
#define CASE_LIGHT_DEFAULT_ON true // Set default power-up state on
#define CASE_LIGHT_DEFAULT_BRIGHTNESS 105 // Set default power-up brightness (0-255, requires PWM pin)
//#define MENU_ITEM_CASE_LIGHT // Add a Case Light option to the LCD main menu
#endif
//===========================================================================
@ -1018,7 +1022,7 @@
*/
#define TMC2130_ADV() { }
#endif // ENABLED(HAVE_TMC2130)
#endif // HAVE_TMC2130
// @section L6470

View File

@ -1170,7 +1170,7 @@
* - Click the controller to view the LCD menu
* - The LCD will display Japanese, Western, or Cyrillic text
*
* See https: *github.com/MarlinFirmware/Marlin/wiki/LCD-Language
* See https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
*
* :['JAPANESE', 'WESTERN', 'CYRILLIC']
*/

View File

@ -220,12 +220,16 @@
#define EXTRUDER_AUTO_FAN_TEMPERATURE 50
#define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed
// Define a pin to turn case light on/off
//#define CASE_LIGHT_PIN 4
#if PIN_EXISTS(CASE_LIGHT)
#define INVERT_CASE_LIGHT false // Set to true if HIGH is the OFF state (active low)
//#define CASE_LIGHT_DEFAULT_ON // Uncomment to set default state to on
//#define MENU_ITEM_CASE_LIGHT // Uncomment to have a Case Light On / Off entry in main menu
/**
* M355 Case Light on-off / brightness
*/
//#define CASE_LIGHT_ENABLE
#if ENABLED(CASE_LIGHT_ENABLE)
//#define CASE_LIGHT_PIN 4 // Override the default pin if needed
#define INVERT_CASE_LIGHT false // Set true if Case Light is ON when pin is LOW
#define CASE_LIGHT_DEFAULT_ON true // Set default power-up state on
#define CASE_LIGHT_DEFAULT_BRIGHTNESS 105 // Set default power-up brightness (0-255, requires PWM pin)
//#define MENU_ITEM_CASE_LIGHT // Add a Case Light option to the LCD main menu
#endif
//===========================================================================
@ -784,7 +788,7 @@
#define PAUSE_PARK_Z_FEEDRATE 5 // Z axis feedrate in mm/s (not used for delta printers)
#define PAUSE_PARK_RETRACT_FEEDRATE 60 // Initial retract feedrate in mm/s
#define PAUSE_PARK_RETRACT_LENGTH 2 // Initial retract in mm
// It is a short retract used immediately after print interrupt before move to filament exchange position
#define FILAMENT_CHANGE_UNLOAD_FEEDRATE 10 // Unload filament feedrate in mm/s - filament unloading can be fast
#define FILAMENT_CHANGE_UNLOAD_LENGTH 100 // Unload filament length from hotend in mm
@ -1025,7 +1029,7 @@
*/
#define TMC2130_ADV() { }
#endif // ENABLED(HAVE_TMC2130)
#endif // HAVE_TMC2130
// @section L6470

View File

@ -312,6 +312,7 @@
#define K1 0.95 //smoothing factor within the PID
// If you are using a pre-configured hotend then you can use one of the value sets by uncommenting it
// Ultimaker
#define DEFAULT_Kp 22.2
#define DEFAULT_Ki 1.08
@ -1156,7 +1157,7 @@
* - Click the controller to view the LCD menu
* - The LCD will display Japanese, Western, or Cyrillic text
*
* See https: *github.com/MarlinFirmware/Marlin/wiki/LCD-Language
* See https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
*
* :['JAPANESE', 'WESTERN', 'CYRILLIC']
*/

View File

@ -220,12 +220,16 @@
#define EXTRUDER_AUTO_FAN_TEMPERATURE 50
#define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed
// Define a pin to turn case light on/off
//#define CASE_LIGHT_PIN 4
#if PIN_EXISTS(CASE_LIGHT)
#define INVERT_CASE_LIGHT false // Set to true if HIGH is the OFF state (active low)
//#define CASE_LIGHT_DEFAULT_ON // Uncomment to set default state to on
//#define MENU_ITEM_CASE_LIGHT // Uncomment to have a Case Light On / Off entry in main menu
/**
* M355 Case Light on-off / brightness
*/
//#define CASE_LIGHT_ENABLE
#if ENABLED(CASE_LIGHT_ENABLE)
//#define CASE_LIGHT_PIN 4 // Override the default pin if needed
#define INVERT_CASE_LIGHT false // Set true if Case Light is ON when pin is LOW
#define CASE_LIGHT_DEFAULT_ON true // Set default power-up state on
#define CASE_LIGHT_DEFAULT_BRIGHTNESS 105 // Set default power-up brightness (0-255, requires PWM pin)
//#define MENU_ITEM_CASE_LIGHT // Add a Case Light option to the LCD main menu
#endif
//===========================================================================
@ -1016,7 +1020,7 @@
*/
#define TMC2130_ADV() { }
#endif // ENABLED(HAVE_TMC2130)
#endif // HAVE_TMC2130
// @section L6470

View File

@ -1149,7 +1149,7 @@
* - Click the controller to view the LCD menu
* - The LCD will display Japanese, Western, or Cyrillic text
*
* See https: *github.com/MarlinFirmware/Marlin/wiki/LCD-Language
* See https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
*
* :['JAPANESE', 'WESTERN', 'CYRILLIC']
*/

View File

@ -220,12 +220,16 @@
#define EXTRUDER_AUTO_FAN_TEMPERATURE 50
#define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed
// Define a pin to turn case light on/off
//#define CASE_LIGHT_PIN 4
#if PIN_EXISTS(CASE_LIGHT)
#define INVERT_CASE_LIGHT false // Set to true if HIGH is the OFF state (active low)
//#define CASE_LIGHT_DEFAULT_ON // Uncomment to set default state to on
//#define MENU_ITEM_CASE_LIGHT // Uncomment to have a Case Light On / Off entry in main menu
/**
* M355 Case Light on-off / brightness
*/
//#define CASE_LIGHT_ENABLE
#if ENABLED(CASE_LIGHT_ENABLE)
//#define CASE_LIGHT_PIN 4 // Override the default pin if needed
#define INVERT_CASE_LIGHT false // Set true if Case Light is ON when pin is LOW
#define CASE_LIGHT_DEFAULT_ON true // Set default power-up state on
#define CASE_LIGHT_DEFAULT_BRIGHTNESS 105 // Set default power-up brightness (0-255, requires PWM pin)
//#define MENU_ITEM_CASE_LIGHT // Add a Case Light option to the LCD main menu
#endif
//===========================================================================
@ -1016,7 +1020,7 @@
*/
#define TMC2130_ADV() { }
#endif // ENABLED(HAVE_TMC2130)
#endif // HAVE_TMC2130
// @section L6470

View File

@ -317,6 +317,7 @@
#define DEFAULT_Kd 110.78
// If you are using a pre-configured hotend then you can use one of the value sets by uncommenting it
// Ultimaker
//#define DEFAULT_Kp 22.2
//#define DEFAULT_Ki 1.08
@ -1158,7 +1159,7 @@
* - Click the controller to view the LCD menu
* - The LCD will display Japanese, Western, or Cyrillic text
*
* See https: *github.com/MarlinFirmware/Marlin/wiki/LCD-Language
* See https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
*
* :['JAPANESE', 'WESTERN', 'CYRILLIC']
*/

View File

@ -220,12 +220,16 @@
#define EXTRUDER_AUTO_FAN_TEMPERATURE 50
#define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed
// Define a pin to turn case light on/off
//#define CASE_LIGHT_PIN 4
#if PIN_EXISTS(CASE_LIGHT)
#define INVERT_CASE_LIGHT false // Set to true if HIGH is the OFF state (active low)
//#define CASE_LIGHT_DEFAULT_ON // Uncomment to set default state to on
//#define MENU_ITEM_CASE_LIGHT // Uncomment to have a Case Light On / Off entry in main menu
/**
* M355 Case Light on-off / brightness
*/
//#define CASE_LIGHT_ENABLE
#if ENABLED(CASE_LIGHT_ENABLE)
//#define CASE_LIGHT_PIN 4 // Override the default pin if needed
#define INVERT_CASE_LIGHT false // Set true if Case Light is ON when pin is LOW
#define CASE_LIGHT_DEFAULT_ON true // Set default power-up state on
#define CASE_LIGHT_DEFAULT_BRIGHTNESS 105 // Set default power-up brightness (0-255, requires PWM pin)
//#define MENU_ITEM_CASE_LIGHT // Add a Case Light option to the LCD main menu
#endif
//===========================================================================
@ -1019,7 +1023,7 @@
*/
#define TMC2130_ADV() { }
#endif // ENABLED(HAVE_TMC2130)
#endif // HAVE_TMC2130
// @section L6470

View File

@ -26,10 +26,11 @@
* Contributed by Triffid_Hunter. Modified by Kliment and the Marlin team.
*/
#ifndef _FASTIO_ARDUINO_H
#ifndef _FASTIO_ARDUINO_H
#define _FASTIO_ARDUINO_H
#include <avr/io.h>
#include "macros.h"
/**
* Enable this option to use Teensy++ 2.0 assignments for AT90USB processors.
@ -238,4 +239,93 @@ typedef enum {
#define SET_FOCB(T,V) SET_FOC(T,B,V)
#define SET_FOCC(T,V) SET_FOC(T,C,V)
/**
* PWM availability macros
*/
#define AVR_AT90USB1286_FAMILY (defined(__AVR_AT90USB1287__) || defined(__AVR_AT90USB1286__) || defined(__AVR_AT90USB1286P__) || defined(__AVR_AT90USB646__) || defined(__AVR_AT90USB646P__) || defined(__AVR_AT90USB647__))
#define AVR_ATmega1284_FAMILY (defined(__AVR_ATmega644__) || defined(__AVR_ATmega644P__) || defined(__AVR_ATmega644PA__) || defined(__AVR_ATmega1284P__))
#define AVR_ATmega2560_FAMILY (defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__))
#define AVR_ATmega2561_FAMILY (defined(__AVR_ATmega1281__) || defined(__AVR_ATmega2561__))
#define AVR_ATmega328_FAMILY (defined(__AVR_ATmega168__) || defined(__AVR_ATmega328__) || defined(__AVR_ATmega328p__))
//find out which harware PWMs are already in use
#if PIN_EXISTS(CONTROLLER_FAN)
#define PWM_CHK_FAN_B(p) (p == CONTROLLER_FAN_PIN || p == E0_AUTO_FAN_PIN || p == E1_AUTO_FAN_PIN || p == E2_AUTO_FAN_PIN || p == E3_AUTO_FAN_PIN || p == E4_AUTO_FAN_PIN)
#else
#define PWM_CHK_FAN_B(p) (p == E0_AUTO_FAN_PIN || p == E1_AUTO_FAN_PIN || p == E2_AUTO_FAN_PIN || p == E3_AUTO_FAN_PIN || p == E4_AUTO_FAN_PIN)
#endif
#if PIN_EXISTS(FAN) || PIN_EXISTS(FAN1) || PIN_EXISTS(FAN2)
#if PIN_EXISTS(FAN2)
#define PWM_CHK_FAN_A(p) (p == FAN_PIN || p == FAN1_PIN || p == FAN2_PIN)
#elif PIN_EXISTS(FAN1)
#define PWM_CHK_FAN_A(p) (p == FAN_PIN || p == FAN1_PIN)
#else
#define PWM_CHK_FAN_A(p) p == FAN_PIN
#endif
#else
#define PWM_CHK_FAN_A(p) false
#endif
#if HAS_MOTOR_CURRENT_PWM
#if PIN_EXISTS(MOTOR_CURRENT_PWM_XY)
#define PWM_CHK_MOTOR_CURRENT(p) (p == MOTOR_CURRENT_PWM_E || p == MOTOR_CURRENT_PWM_Z || p == MOTOR_CURRENT_PWM_XY)
#elif PIN_EXISTS(MOTOR_CURRENT_PWM_Z)
#define PWM_CHK_MOTOR_CURRENT(p) (p == MOTOR_CURRENT_PWM_E || p == MOTOR_CURRENT_PWM_Z)
#else
#define PWM_CHK_MOTOR_CURRENT(p) (p == MOTOR_CURRENT_PWM_E)
#endif
#else
#define PWM_CHK_MOTOR_CURRENT(p) false
#endif
#if defined(NUM_SERVOS)
#if AVR_ATmega2560_FAMILY
#define PWM_CHK_SERVO(p) ( p == 5 || NUM_SERVOS > 12 && p == 6 || NUM_SERVOS > 24 && p == 46) //PWMS 3A, 4A & 5A
#elif AVR_ATmega2561_FAMILY
#define PWM_CHK_SERVO(p) p == 5 //PWM3A
#elif AVR_ATmega1284_FAMILY
#define PWM_CHK_SERVO(p) false
#elif AVR_AT90USB1286_FAMILY
#define PWM_CHK_SERVO(p) p == 16 //PWM3A
#elif AVR_ATmega328_FAMILY
#define PWM_CHK_SERVO(p) false
#endif
#else
#define PWM_CHK_SERVO(p) false
#endif
#if ENABLED(BARICUDA)
#if HAS_HEATER_1 && HAS_HEATER_2
#define PWM_CHK_HEATER(p) (p == HEATER_1_PIN || p == HEATER_2_PIN)
#elif HAS_HEATER_1
#define PWM_CHK_HEATER(p) (p == HEATER_1_PIN)
#endif
#else
#define PWM_CHK_HEATER(p) false
#endif
#define PWM_CHK(p) (PWM_CHK_HEATER(p) || PWM_CHK_SERVO(p) || PWM_CHK_MOTOR_CURRENT(p)\
|| PWM_CHK_FAN_A(p) || PWM_CHK_FAN_B(p))
// define which hardware PWMs are available for the current CPU
// all timer 1 PWMS deleted from this list because they are never available
#if AVR_ATmega2560_FAMILY
#define PWM_PINS(p) ((p >= 2 && p <= 10 ) || p == 13 || p == 44 || p == 45 || p == 46 )
#elif AVR_ATmega2561_FAMILY
#define PWM_PINS(p) ((p >= 2 && p <= 6 ) || p == 9)
#elif AVR_ATmega1284_FAMILY
#define PWM_PINS(p) (p == 3 || p == 4 || p == 14 || p == 15)
#elif AVR_AT90USB1286_FAMILY
#define PWM_PINS(p) (p == 0 || p == 1 || p == 14 || p == 15 || p == 16 || p == 24)
#elif AVR_ATmega328_FAMILY
#define PWM_PINS(p) (p == 3 || p == 5 || p == 6 || p == 11)
#else
#error "unknown CPU"
#endif
// finally - the macro that tells us if a pin is an available hardware PWM
#define USEABLE_HARDWARE_PWM(p) (PWM_PINS(p) && !PWM_CHK(p))
#endif // _FASTIO_ARDUINO_H

View File

@ -184,6 +184,7 @@ void GCodeParser::parse(char *p) {
if (PARAM_TEST) {
while (*p == ' ') p++; // skip spaces vetween parameters & values
const bool has_num = DECIMAL_SIGNED(*p); // The parameter has a number [-+0-9.]
#if ENABLED(DEBUG_GCODE_PARSER)
@ -220,8 +221,10 @@ void GCodeParser::parse(char *p) {
#endif
}
while (*p && *p != ' ') p++; // Skip over the parameter
while (*p == ' ') p++; // Skip over all spaces
if (!WITHIN(*p, 'A', 'Z')) {
while (*p && NUMERIC(*p)) p++; // Skip over the value section of a parameter
while (*p == ' ') p++; // Skip over all spaces
}
}
}

View File

@ -120,7 +120,7 @@ public:
// Code seen bit was set. If not found, value_ptr is unchanged.
// This allows "if (seen('A')||seen('B'))" to use the last-found value.
static bool seen(const char c) {
static volatile bool seen(const char c) {
const uint8_t ind = c - 'A';
if (ind >= COUNT(param)) return false; // Only A-Z
const bool b = TEST(codebits[ind >> 3], ind & 0x7);
@ -132,10 +132,10 @@ public:
// Code is found in the string. If not found, value_ptr is unchanged.
// This allows "if (seen('A')||seen('B'))" to use the last-found value.
static bool seen(const char c) {
static volatile bool seen(const char c) {
const char *p = strchr(command_args, c);
const bool b = !!p;
if (b) value_ptr = DECIMAL_SIGNED(p[1]) ? &p[1] : NULL;
if (b) value_ptr = DECIMAL_SIGNED(p[1]) ? &p[1] : (char*)NULL;
return b;
}
@ -227,7 +227,7 @@ public:
return input_temp_units == TEMPUNIT_K ? 'K' : input_temp_units == TEMPUNIT_F ? 'F' : 'C';
}
FORCE_INLINE static char* temp_units_name() {
return input_temp_units == TEMPUNIT_K ? PSTR("Kelvin") : input_temp_units == TEMPUNIT_F ? PSTR("Fahrenheit") : PSTR("Celsius")
return input_temp_units == TEMPUNIT_K ? PSTR("Kelvin") : input_temp_units == TEMPUNIT_F ? PSTR("Fahrenheit") : PSTR("Celsius");
}
inline static float to_temp_units(const float &f) {
switch (input_temp_units) {

View File

@ -706,7 +706,9 @@
#ifndef MSG_CASE_LIGHT
#define MSG_CASE_LIGHT _UxGT("Case light")
#endif
#ifndef MSG_CASE_LIGHT_BRIGHTNESS
#define MSG_CASE_LIGHT_BRIGHTNESS _UxGT("Light BRIGHTNESS")
#endif
#if LCD_WIDTH >= 20
#ifndef MSG_INFO_PRINT_COUNT
#define MSG_INFO_PRINT_COUNT _UxGT("Print Count")

View File

@ -127,7 +127,6 @@
#define DECIMAL(a) (NUMERIC(a) || a == '.')
#define NUMERIC_SIGNED(a) (NUMERIC(a) || (a) == '-' || (a) == '+')
#define DECIMAL_SIGNED(a) (DECIMAL(a) || (a) == '-' || (a) == '+')
#define PRINTABLE(C) (((C) & 0xC0u) != 0x80u)
#define COUNT(a) (sizeof(a)/sizeof(*a))
#define ZERO(a) memset(a,0,sizeof(a))
#define COPY(a,b) memcpy(a,b,min(sizeof(a),sizeof(b)))

View File

@ -174,6 +174,8 @@
#include "pins_MKS_13.h"
#elif MB(SAINSMART_2IN1)
#include "pins_SAINSMART_2IN1.h"
#elif MB(ZRIB_V20)
#include "pins_ZRIB_V20.h"
#else
#error "Unknown MOTHERBOARD value set in Configuration.h"
#endif

View File

@ -32,11 +32,10 @@
#error "Azteeg X3 supports up to 2 hotends / E-steppers. Comment out this line to continue."
#endif
#define BOARD_NAME "Azteeg X3"
#if !PIN_EXISTS(CASE_LIGHT) // doesn't already exist so OK to change the definition coming
#define OK_TO_CHANGE_CASE_LIGHT // in from from the include file
#if ENABLED(CASE_LIGHT_ENABLE) && !PIN_EXISTS(CASE_LIGHT)
#define CASE_LIGHT_PIN 6 // must define it here or else RAMPS will define it
#endif
#define BOARD_NAME "Azteeg X3"
#include "pins_RAMPS_13.h"
@ -75,10 +74,8 @@
//
// Misc
//
#if ENABLED(OK_TO_CHANGE_CASE_LIGHT) && STAT_LED_RED_PIN == 6
#if ENABLED(CASE_LIGHT_ENABLE) && PIN_EXISTS(CASE_LIGHT) && PIN_EXISTS(STAT_LED_RED) && STAT_LED_RED_PIN == CASE_LIGHT_PIN
#undef STAT_LED_RED_PIN
#undef CASE_LIGHT_PIN
#define CASE_LIGHT_PIN 6 // open collector FET driver
#endif
//
@ -94,6 +91,7 @@
#if SERVO0_PIN == 7
#undef SERVO0_PIN
#def SERVO0_PIN 11
#endif
#define SPINDLE_LASER_PWM_PIN 7 // MUST BE HARDWARE PWM
#define SPINDLE_LASER_ENABLE_PIN 20 // Pin should have a pullup!
#define SPINDLE_DIR_PIN 21

View File

@ -28,12 +28,13 @@
#error "Azteeg X3 Pro supports up to 5 hotends / E-steppers. Comment out this line to continue."
#endif
#define BOARD_NAME "Azteeg X3 Pro"
#if !PIN_EXISTS(CASE_LIGHT) // doesn't already exist so OK to change the definition coming
#define OK_TO_CHANGE_CASE_LIGHT // in from from the include file
#if ENABLED(CASE_LIGHT_ENABLE) && !PIN_EXISTS(CASE_LIGHT)
#define CASE_LIGHT_PIN 44 // must define it here or else RAMPS will define it
#endif
#define BOARD_NAME "Azteeg X3 Pro"
#include "pins_RAMPS.h"
#ifndef __AVR_ATmega2560__
@ -144,19 +145,16 @@
//
// Misc. Functions
//
#if ENABLED(OK_TO_CHANGE_CASE_LIGHT)
#if ENABLED(CASE_LIGHT_ENABLE) && PIN_EXISTS(CASE_LIGHT) && defined(DOGLCD_A0) && DOGLCD_A0 == CASE_LIGHT_PIN
#undef DOGLCD_A0 // steal pin 44 for the case light; if you have a Viki2 and have connected it
#define DOGLCD_A0 57 // following the Panucatt wiring diagram, you may need to tweak these pin assignments
// as the wiring diagram uses pin 44 for DOGLCD_A0
#undef CASE_LIGHT_PIN
#define CASE_LIGHT_PIN 44 // must have a hardware PWM
// as the wiring diagram uses pin 44 for DOGLCD_A0
#endif
//
// M3/M4/M5 - Spindle/Laser Control
//
#undef SPINDLE_LASER_PWM_PIN // Definitions in pins_RAMPS.h are no good with the AzteegX3 board
#undef SPINDLE_LASER_PWM_PIN // Definitions in pins_RAMPS.h are no good with the AzteegX3pro board
#undef SPINDLE_LASER_ENABLE_PIN
#undef SPINDLE_DIR_PIN

View File

@ -111,9 +111,12 @@
//
// Other board specific pins
//
#define FILWIDTH_PIN 37
#define LED_PIN 13
#define SPINDLE_ENABLE_PIN 4
#define FAN_PIN 3
#define PS_ON_PIN 45
#define KILL_PIN 46
#ifndef FILWIDTH_PIN
#define FILWIDTH_PIN 37 // should be Analog Input (0-15)
#endif

View File

@ -99,7 +99,10 @@
// Misc. Functions
//
#define SDSS 26
#define FILWIDTH_PIN 2 // Analog Input
#ifndef FILWIDTH_PIN
#define FILWIDTH_PIN 2 // Analog Input
#endif
//
// LCD / Controller

View File

@ -102,7 +102,10 @@
// Misc. Functions
//
#define SDSS 20 // Teensylu pin mapping
#define FILWIDTH_PIN 2 // Analog Input
#ifndef FILWIDTH_PIN
#define FILWIDTH_PIN 2 // Analog Input
#endif
//
// LCD / Controller

View File

@ -135,10 +135,13 @@
//
#define SDSS 53
#define LED_PIN 13
#define FILWIDTH_PIN 3 // Analog Input
#define PS_ON_PIN 4
#define CASE_LIGHT_PIN 46
#ifndef FILWIDTH_PIN
#define FILWIDTH_PIN 3 // Analog Input
#endif
//
// LCD / Controller
//

View File

@ -196,16 +196,16 @@
#define SDSS 53
#define LED_PIN 13
// Use the RAMPS 1.4 Analog input 5 on the AUX2 connector
#define FILWIDTH_PIN 5 // Analog Input
#ifndef FILWIDTH_PIN
#define FILWIDTH_PIN 5 // Analog Input on AUX2
#endif
// define digital pin 4 for the filament runout sensor. Use the RAMPS 1.4 digital input 4 on the servos connector
#define FIL_RUNOUT_PIN 4
#define PS_ON_PIN 12
#if !PIN_EXISTS(CASE_LIGHT) && !defined(SPINDLE_LASER_ENABLE_PIN)
#undef CASE_LIGHT_PIN
#if ENABLED(CASE_LIGHT_ENABLE) && !PIN_EXISTS(CASE_LIGHT) && !defined(SPINDLE_LASER_ENABLE_PIN)
#if !defined(NUM_SERVOS) || NUM_SERVOS == 0 // try to use servo connector first
#define CASE_LIGHT_PIN 6 // MUST BE HARDWARE PWM
#elif !(ENABLED(ULTRA_LCD) && ENABLED(NEWPANEL) \

View File

@ -118,7 +118,10 @@
#define SDSS 53
#define LED_PIN 13
#define PS_ON_PIN 4
#define FILWIDTH_PIN 3 // Analog Input
#ifndef FILWIDTH_PIN
#define FILWIDTH_PIN 3 // Analog Input
#endif
//
// LCD / Controller

39
Marlin/pins_ZRIB_V20.h Normal file
View File

@ -0,0 +1,39 @@
/**
* Marlin 3D Printer Firmware
* Copyright (C) 2016 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/>.
*
*/
/**
* ZRIB V2.0 pin assignments
*/
#define ZRIB_V20_D6_PIN 6
#define ZRIB_V20_D9_PIN 9
#define RAMPS_D9_PIN ZRIB_V20_D6_PIN
#define ORIG_E0_AUTO_FAN_PIN ZRIB_V20_D9_PIN
#define ORIG_E1_AUTO_FAN_PIN ZRIB_V20_D9_PIN
#define ORIG_E2_AUTO_FAN_PIN ZRIB_V20_D9_PIN
#define ORIG_E3_AUTO_FAN_PIN ZRIB_V20_D9_PIN
#ifndef FILWIDTH_PIN
#define FILWIDTH_PIN 11 // Analog Input
#endif
#include "pins_MKS_13.h"

View File

@ -535,7 +535,7 @@ void Planner::check_axes_activity() {
*/
void Planner::apply_leveling(float &lx, float &ly, float &lz) {
#if ENABLED(AUTO_BED_LEVELING_UBL) && UBL_DELTA // probably should also be enabled for UBL without UBL_DELTA
#if ENABLED(AUTO_BED_LEVELING_UBL)
if (!ubl.state.active) return;
#if ENABLED(ENABLE_LEVELING_FADE_HEIGHT)
// if z_fade_height enabled (nonzero) and raw_z above it, no leveling required
@ -550,7 +550,7 @@ void Planner::check_axes_activity() {
if (!abl_enabled) return;
#endif
#if ENABLED(ENABLE_LEVELING_FADE_HEIGHT)
#if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) && DISABLED(AUTO_BED_LEVELING_UBL)
static float z_fade_factor = 1.0, last_raw_lz = -999.0;
if (z_fade_height) {
const float raw_lz = RAW_Z_POSITION(lz);
@ -599,36 +599,38 @@ void Planner::check_axes_activity() {
void Planner::unapply_leveling(float logical[XYZ]) {
#if ENABLED(AUTO_BED_LEVELING_UBL) && UBL_DELTA
#if ENABLED(AUTO_BED_LEVELING_UBL)
if (ubl.state.active) {
const float z_leveled = RAW_Z_POSITION(logical[Z_AXIS]),
z_ublmesh = ubl.get_z_correction(logical[X_AXIS], logical[Y_AXIS]);
float z_unlevel = z_leveled - ubl.state.z_offset - z_ublmesh;
const float z_physical = RAW_Z_POSITION(logical[Z_AXIS]);
const float z_ublmesh = ubl.get_z_correction(logical[X_AXIS], logical[Y_AXIS]);
const float z_virtual = z_physical - ubl.state.z_offset - z_ublmesh;
float z_logical = LOGICAL_Z_POSITION(z_virtual);
#if ENABLED(ENABLE_LEVELING_FADE_HEIGHT)
// for L=leveled, U=unleveled, M=mesh, O=offset, H=fade_height,
// Given L==U+O+M(1-U/H) (faded mesh correction formula for U<H)
// then U==L-O-M(1-U/H)
// so U==L-O-M+MU/H
// so U-MU/H==L-O-M
// so U(1-M/H)==L-O-M
// so U==(L-O-M)/(1-M/H) for U<H
// for P=physical_z, L=logical_z, M=mesh_z, O=z_offset, H=fade_height,
// Given P=L+O+M(1-L/H) (faded mesh correction formula for L<H)
// then L=P-O-M(1-L/H)
// so L=P-O-M+ML/H
// so L-ML/H=P-O-M
// so L(1-M/H)=P-O-M
// so L=(P-O-M)/(1-M/H) for L<H
if (planner.z_fade_height) {
const float z_unfaded = z_unlevel / (1.0 - z_ublmesh * planner.inverse_z_fade_height);
if (z_unfaded < planner.z_fade_height) // don't know until after compute
z_unlevel = z_unfaded;
if (z_logical < planner.z_fade_height )
z_logical = z_logical / (1.0 - (z_ublmesh * planner.inverse_z_fade_height));
if (z_logical >= planner.z_fade_height)
z_logical = LOGICAL_Z_POSITION(z_physical - ubl.state.z_offset);
}
#endif // ENABLE_LEVELING_FADE_HEIGHT
logical[Z_AXIS] = z_unlevel;
logical[Z_AXIS] = z_logical;
}
return; // don't fall thru to HAS_ABL or other ENABLE_LEVELING_FADE_HEIGHT logic
return; // don't fall thru to other ENABLE_LEVELING_FADE_HEIGHT logic
#endif

View File

@ -528,33 +528,69 @@ void Stepper::isr() {
_APPLY_STEP(AXIS)(_INVERT_STEP_PIN(AXIS),0); \
}
/**
* Estimate the number of cycles that the stepper logic already takes
* up between the start and stop of the X stepper pulse.
*
* Currently this uses very modest estimates of around 5 cycles.
* True values may be derived by careful testing.
*
* Once any delay is added, the cost of the delay code itself
* may be subtracted from this value to get a more accurate delay.
* Delays under 20 cycles (1.25µs) will be very accurate, using NOPs.
* Longer delays use a loop. The resolution is 8 cycles.
*/
#if HAS_X_STEP
#define _COUNT_STEPPERS_1 1
#define _CYCLE_APPROX_1 5
#else
#define _COUNT_STEPPERS_1 0
#define _CYCLE_APPROX_1 0
#endif
#if ENABLED(X_DUAL_STEPPER_DRIVERS)
#define _CYCLE_APPROX_2 _CYCLE_APPROX_1 + 4
#else
#define _CYCLE_APPROX_2 _CYCLE_APPROX_1
#endif
#if HAS_Y_STEP
#define _COUNT_STEPPERS_2 _COUNT_STEPPERS_1 + 1
#define _CYCLE_APPROX_3 _CYCLE_APPROX_2 + 5
#else
#define _COUNT_STEPPERS_2 _COUNT_STEPPERS_1
#define _CYCLE_APPROX_3 _CYCLE_APPROX_2
#endif
#if ENABLED(Y_DUAL_STEPPER_DRIVERS)
#define _CYCLE_APPROX_4 _CYCLE_APPROX_3 + 4
#else
#define _CYCLE_APPROX_4 _CYCLE_APPROX_3
#endif
#if HAS_Z_STEP
#define _COUNT_STEPPERS_3 _COUNT_STEPPERS_2 + 1
#define _CYCLE_APPROX_5 _CYCLE_APPROX_4 + 5
#else
#define _COUNT_STEPPERS_3 _COUNT_STEPPERS_2
#define _CYCLE_APPROX_5 _CYCLE_APPROX_4
#endif
#if ENABLED(Z_DUAL_STEPPER_DRIVERS)
#define _CYCLE_APPROX_6 _CYCLE_APPROX_5 + 4
#else
#define _CYCLE_APPROX_6 _CYCLE_APPROX_5
#endif
#if DISABLED(ADVANCE) && DISABLED(LIN_ADVANCE)
#define _COUNT_STEPPERS_4 _COUNT_STEPPERS_3 + 1
#if ENABLED(MIXING_EXTRUDER)
#define _CYCLE_APPROX_7 _CYCLE_APPROX_6 + (MIXING_STEPPERS) * 6
#else
#define _CYCLE_APPROX_7 _CYCLE_APPROX_6 + 5
#endif
#else
#define _COUNT_STEPPERS_4 _COUNT_STEPPERS_3
#define _CYCLE_APPROX_7 _CYCLE_APPROX_6
#endif
#define CYCLES_EATEN_XYZE ((_COUNT_STEPPERS_4) * 5)
#define CYCLES_EATEN_XYZE _CYCLE_APPROX_7
#define EXTRA_CYCLES_XYZE (STEP_PULSE_CYCLES - (CYCLES_EATEN_XYZE))
// If a minimum pulse time was specified get the timer 0 value
// which increments every 4µs on 16MHz and every 3.2µs on 20MHz.
// Two or 3 counts of TCNT0 should be a sufficient delay.
/**
* If a minimum pulse time was specified get the timer 0 value.
*
* TCNT0 has an 8x prescaler, so it increments every 8 cycles.
* That's every 0.5µs on 16MHz and every 0.4µs on 20MHz.
* 20 counts of TCNT0 -by itself- is a good pulse delay.
* 10µs = 160 or 200 cycles.
*/
#if EXTRA_CYCLES_XYZE > 20
uint32_t pulse_start = TCNT0;
#endif
@ -627,7 +663,7 @@ void Stepper::isr() {
break;
}
// For minimum pulse time wait before stopping pulses
// For minimum pulse time wait after stopping pulses also
#if EXTRA_CYCLES_XYZE > 20
if (i) while (EXTRA_CYCLES_XYZE > (uint32_t)(TCNT0 - pulse_start) * (INT0_PRESCALER)) { /* nada */ }
#elif EXTRA_CYCLES_XYZE > 0

View File

@ -73,10 +73,6 @@ int16_t Temperature::current_temperature_raw[HOTENDS] = { 0 },
int16_t Temperature::target_temperature_bed = 0;
#endif
#if ENABLED(TEMP_SENSOR_1_AS_REDUNDANT)
float Temperature::redundant_temperature = 0.0;
#endif
#if ENABLED(PIDTEMP)
#if ENABLED(PID_PARAMS_PER_HOTEND) && HOTENDS > 1
float Temperature::Kp[HOTENDS] = ARRAY_BY_HOTENDS1(DEFAULT_Kp),

View File

@ -112,10 +112,6 @@ class Temperature {
static volatile bool in_temp_isr;
#if ENABLED(TEMP_SENSOR_1_AS_REDUNDANT)
static float redundant_temperature;
#endif
static uint8_t soft_pwm_amount[HOTENDS],
soft_pwm_amount_bed;

View File

@ -83,7 +83,7 @@
}
void unified_bed_leveling::reset() {
state.active = false;
set_bed_leveling_enabled(false);
state.z_offset = 0;
state.storage_slot = -1;
#if ENABLED(ENABLE_LEVELING_FADE_HEIGHT)
@ -94,11 +94,17 @@
}
void unified_bed_leveling::invalidate() {
state.active = false;
set_bed_leveling_enabled(false);
state.z_offset = 0;
for (int x = 0; x < GRID_MAX_POINTS_X; x++)
for (int y = 0; y < GRID_MAX_POINTS_Y; y++)
z_values[x][y] = NAN;
set_all_mesh_points_to_value(NAN);
}
void unified_bed_leveling::set_all_mesh_points_to_value(float value) {
for (uint8_t x = 0; x < GRID_MAX_POINTS_X; x++) {
for (uint8_t y = 0; y < GRID_MAX_POINTS_Y; y++) {
z_values[x][y] = value;
}
}
}
void unified_bed_leveling::display_map(const int map_type) {

View File

@ -154,6 +154,7 @@
static mesh_index_pair find_closest_mesh_point_of_type(const MeshPointType, const float&, const float&, const bool, unsigned int[16], bool);
static void reset();
static void invalidate();
static void set_all_mesh_points_to_value(float);
static bool sanity_check();
static void G29() _O0; // O0 for no optimization
@ -385,7 +386,7 @@
FORCE_INLINE static float mesh_index_to_xpos(const uint8_t i) { return pgm_read_float(&_mesh_index_to_xpos[i]); }
FORCE_INLINE static float mesh_index_to_ypos(const uint8_t i) { return pgm_read_float(&_mesh_index_to_ypos[i]); }
static bool prepare_linear_move_to(const float ltarget[XYZE], const float &feedrate);
static bool prepare_segmented_line_to(const float ltarget[XYZE], const float &feedrate);
static void line_to_destination_cartesian(const float &fr, uint8_t e);
}; // class unified_bed_leveling

View File

@ -30,6 +30,7 @@
#include "configuration_store.h"
#include "ultralcd.h"
#include "stepper.h"
#include "planner.h"
#include "gcode.h"
#include <math.h>
@ -48,6 +49,7 @@
extern long babysteps_done;
extern float probe_pt(const float &x, const float &y, bool, int);
extern bool set_probe_deployed(bool);
extern void set_bed_leveling_enabled(bool);
#define SIZE_OF_LITTLE_RAISE 1
#define BIG_RAISE_NOT_NEEDED 0
@ -325,15 +327,23 @@
if (parser.seen('I')) {
uint8_t cnt = 0;
g29_repetition_cnt = parser.has_value() ? parser.value_int() : 1;
while (g29_repetition_cnt--) {
if (cnt > 20) { cnt = 0; idle(); }
const mesh_index_pair location = find_closest_mesh_point_of_type(REAL, g29_x_pos, g29_y_pos, USE_NOZZLE_AS_REFERENCE, NULL, false);
if (location.x_index < 0) {
SERIAL_PROTOCOLLNPGM("Entire Mesh invalidated.\n");
break; // No more invalid Mesh Points to populate
if (g29_repetition_cnt >= GRID_MAX_POINTS) {
set_all_mesh_points_to_value(NAN);
} else {
while (g29_repetition_cnt--) {
if (cnt > 20) { cnt = 0; idle(); }
const mesh_index_pair location = find_closest_mesh_point_of_type(REAL, g29_x_pos, g29_y_pos, USE_NOZZLE_AS_REFERENCE, NULL, false);
if (location.x_index < 0) {
// No more REACHABLE mesh points to invalidate, so we ASSUME the user
// meant to invalidate the ENTIRE mesh, which cannot be done with
// find_closest_mesh_point loop which only returns REACHABLE points.
set_all_mesh_points_to_value(NAN);
SERIAL_PROTOCOLLNPGM("Entire Mesh invalidated.\n");
break; // No more invalid Mesh Points to populate
}
z_values[location.x_index][location.y_index] = NAN;
cnt++;
}
z_values[location.x_index][location.y_index] = NAN;
cnt++;
}
SERIAL_PROTOCOLLNPGM("Locations invalidated.\n");
}
@ -497,18 +507,26 @@
* - Specify a constant with the 'C' parameter.
* - Allow 'G29 P3' to choose a 'reasonable' constant.
*/
if (g29_c_flag) {
if (g29_repetition_cnt >= GRID_MAX_POINTS) {
for (uint8_t x = 0; x < GRID_MAX_POINTS_X; x++) {
for (uint8_t y = 0; y < GRID_MAX_POINTS_Y; y++) {
z_values[x][y] = g29_constant;
}
}
set_all_mesh_points_to_value(g29_constant);
}
else {
while (g29_repetition_cnt--) { // this only populates reachable mesh points near
const mesh_index_pair location = find_closest_mesh_point_of_type(INVALID, g29_x_pos, g29_y_pos, USE_NOZZLE_AS_REFERENCE, NULL, false);
if (location.x_index < 0) break; // No more reachable invalid Mesh Points to populate
if (location.x_index < 0) {
// No more REACHABLE INVALID mesh points to populate, so we ASSUME
// user meant to populate ALL INVALID mesh points to value
for (uint8_t x = 0; x < GRID_MAX_POINTS_X; x++) {
for (uint8_t y = 0; y < GRID_MAX_POINTS_Y; y++) {
if ( isnan(z_values[x][y])) {
z_values[x][y] = g29_constant;
}
}
}
break; // No more invalid Mesh Points to populate
}
z_values[location.x_index][location.y_index] = g29_constant;
}
}
@ -999,12 +1017,15 @@
serialprintPGM(parser.seen('B') ? PSTR("Place shim & measure") : PSTR("Measure")); // TODO: Make translatable strings
const float z_step = 0.01; // existing behavior: 0.01mm per click, occasionally step
//const float z_step = 1.0 / planner.axis_steps_per_mm[Z_AXIS]; // approx one step each click
while (ubl_lcd_clicked()) delay(50); // wait for user to release encoder wheel
delay(50); // debounce
while (!ubl_lcd_clicked()) { // we need the loop to move the nozzle based on the encoder wheel here!
idle();
if (encoder_diff) {
do_blocking_move_to_z(current_position[Z_AXIS] + float(encoder_diff) / 100.0);
do_blocking_move_to_z(current_position[Z_AXIS] + float(encoder_diff) * z_step);
encoder_diff = 0;
}
}
@ -1115,11 +1136,11 @@
SERIAL_PROTOCOLLNPGM("?Can't activate and deactivate at the same time.\n");
return UBL_ERR;
}
state.active = true;
set_bed_leveling_enabled(true);
report_state();
}
else if (parser.seen('D')) {
state.active = false;
set_bed_leveling_enabled(false);
report_state();
}
@ -1158,7 +1179,7 @@
return;
}
ubl_state_at_invocation = state.active;
state.active = 0;
set_bed_leveling_enabled(false);
}
void unified_bed_leveling::restore_ubl_active_state_and_leave() {
@ -1168,7 +1189,7 @@
lcd_quick_feedback();
return;
}
state.active = ubl_state_at_invocation;
set_bed_leveling_enabled(ubl_state_at_invocation);
}
/**
@ -1695,6 +1716,8 @@
SERIAL_EOL;
}
#endif
if (do_ubl_mesh_map) display_map(g29_map_type);
}
#if ENABLED(UBL_G29_P31)

View File

@ -32,7 +32,25 @@
extern float destination[XYZE];
extern void set_current_to_destination();
extern float delta_segments_per_second;
#if ENABLED(DELTA)
extern float delta[ABC],
endstop_adj[ABC];
extern float delta_radius,
delta_tower_angle_trim[2],
delta_tower[ABC][2],
delta_diagonal_rod,
delta_calibration_radius,
delta_diagonal_rod_2_tower[ABC],
delta_segments_per_second,
delta_clip_start_height;
extern float delta_safe_distance_from_top();
#endif
static void debug_echo_axis(const AxisEnum axis) {
if (current_position[axis] == destination[axis])
@ -470,51 +488,76 @@
#endif
// We don't want additional apply_leveling() performed by regular buffer_line or buffer_line_kinematic,
// so we call _buffer_line directly here. Per-segmented leveling performed first.
// so we call _buffer_line directly here. Per-segmented leveling and kinematics performed first.
static inline void ubl_buffer_line_segment(const float ltarget[XYZE], const float &fr_mm_s, const uint8_t extruder) {
inline void _O2 ubl_buffer_segment_raw( float rx, float ry, float rz, float le, float fr ) {
#if IS_KINEMATIC
#if ENABLED(DELTA) // apply delta inverse_kinematics
inverse_kinematics(ltarget); // this writes delta[ABC] from ltarget[XYZ] but does not modify ltarget
float feedrate = fr_mm_s;
const float delta_A = rz + sqrt( delta_diagonal_rod_2_tower[A_AXIS]
- HYPOT2( delta_tower[A_AXIS][X_AXIS] - rx,
delta_tower[A_AXIS][Y_AXIS] - ry ));
#if IS_SCARA // scale the feed rate from mm/s to degrees/s
float adiff = abs(delta[A_AXIS] - scara_oldA),
bdiff = abs(delta[B_AXIS] - scara_oldB);
scara_oldA = delta[A_AXIS];
scara_oldB = delta[B_AXIS];
feedrate = max(adiff, bdiff) * scara_feed_factor;
#endif
const float delta_B = rz + sqrt( delta_diagonal_rod_2_tower[B_AXIS]
- HYPOT2( delta_tower[B_AXIS][X_AXIS] - rx,
delta_tower[B_AXIS][Y_AXIS] - ry ));
planner._buffer_line(delta[A_AXIS], delta[B_AXIS], delta[C_AXIS], ltarget[E_AXIS], feedrate, extruder);
const float delta_C = rz + sqrt( delta_diagonal_rod_2_tower[C_AXIS]
- HYPOT2( delta_tower[C_AXIS][X_AXIS] - rx,
delta_tower[C_AXIS][Y_AXIS] - ry ));
#else // cartesian
planner._buffer_line(delta_A, delta_B, delta_C, le, fr, active_extruder);
planner._buffer_line(ltarget[X_AXIS], ltarget[Y_AXIS], ltarget[Z_AXIS], ltarget[E_AXIS], fr_mm_s, extruder);
#elif IS_SCARA // apply scara inverse_kinematics (should be changed to save raw->logical->raw)
const float lseg[XYZ] = { LOGICAL_X_POSITION(rx),
LOGICAL_Y_POSITION(ry),
LOGICAL_Z_POSITION(rz)
};
inverse_kinematics(lseg); // this writes delta[ABC] from lseg[XYZ]
// should move the feedrate scaling to scara inverse_kinematics
float adiff = abs(delta[A_AXIS] - scara_oldA),
bdiff = abs(delta[B_AXIS] - scara_oldB);
scara_oldA = delta[A_AXIS];
scara_oldB = delta[B_AXIS];
float s_feedrate = max(adiff, bdiff) * scara_feed_factor;
planner._buffer_line(delta[A_AXIS], delta[B_AXIS], delta[C_AXIS], le, s_feedrate, active_extruder);
#else // CARTESIAN
// Cartesian _buffer_line seems to take LOGICAL, not RAW coordinates
const float lx = LOGICAL_X_POSITION(rx),
ly = LOGICAL_Y_POSITION(ry),
lz = LOGICAL_Z_POSITION(rz);
planner._buffer_line(lx, ly, lz, le, fr, active_extruder);
#endif
}
/**
* Prepare a linear move for DELTA/SCARA/CARTESIAN with UBL and FADE semantics.
* Prepare a segmented linear move for DELTA/SCARA/CARTESIAN with UBL and FADE semantics.
* This calls planner._buffer_line multiple times for small incremental moves.
* Returns true if the caller did NOT update current_position, otherwise false.
* Returns true if did NOT move, false if moved (requires current_position update).
*/
static bool unified_bed_leveling::prepare_linear_move_to(const float ltarget[XYZE], const float &feedrate) {
bool _O2 unified_bed_leveling::prepare_segmented_line_to(const float ltarget[XYZE], const float &feedrate) {
if (!position_is_reachable_xy(ltarget[X_AXIS], ltarget[Y_AXIS])) // fail if moving outside reachable boundary
return true; // did not move, so current_position still accurate
const float difference[XYZE] = { // cartesian distances moved in XYZE
ltarget[X_AXIS] - current_position[X_AXIS],
ltarget[Y_AXIS] - current_position[Y_AXIS],
ltarget[Z_AXIS] - current_position[Z_AXIS],
ltarget[E_AXIS] - current_position[E_AXIS]
};
const float tot_dx = ltarget[X_AXIS] - current_position[X_AXIS],
tot_dy = ltarget[Y_AXIS] - current_position[Y_AXIS],
tot_dz = ltarget[Z_AXIS] - current_position[Z_AXIS],
tot_de = ltarget[E_AXIS] - current_position[E_AXIS];
const float cartesian_xy_mm = HYPOT(difference[X_AXIS], difference[Y_AXIS]); // total horizontal xy distance
const float cartesian_xy_mm = HYPOT(tot_dx, tot_dy); // total horizontal xy distance
#if IS_KINEMATIC
const float seconds = cartesian_xy_mm / feedrate; // seconds to move xy distance at requested rate
@ -534,16 +577,19 @@
scara_oldB = stepper.get_axis_position_degrees(B_AXIS);
#endif
const float segment_distance[XYZE] = { // length for each segment
difference[X_AXIS] * inv_segments,
difference[Y_AXIS] * inv_segments,
difference[Z_AXIS] * inv_segments,
difference[E_AXIS] * inv_segments
};
const float seg_dx = tot_dx * inv_segments,
seg_dy = tot_dy * inv_segments,
seg_dz = tot_dz * inv_segments,
seg_de = tot_de * inv_segments;
// Note that E segment distance could vary slightly as z mesh height
// changes for each segment, but small enough to ignore.
float seg_rx = RAW_X_POSITION(current_position[X_AXIS]),
seg_ry = RAW_Y_POSITION(current_position[Y_AXIS]),
seg_rz = RAW_Z_POSITION(current_position[Z_AXIS]),
seg_le = current_position[E_AXIS];
const bool above_fade_height = (
#if ENABLED(ENABLE_LEVELING_FADE_HEIGHT)
planner.z_fade_height != 0 && planner.z_fade_height < RAW_Z_POSITION(ltarget[Z_AXIS])
@ -558,21 +604,24 @@
const float z_offset = state.active ? state.z_offset : 0.0;
float seg_dest[XYZE]; // per-segment destination,
COPY_XYZE(seg_dest, current_position); // starting from current position
do {
while (--segments) {
LOOP_XYZE(i) seg_dest[i] += segment_distance[i];
float ztemp = seg_dest[Z_AXIS];
seg_dest[Z_AXIS] += z_offset;
ubl_buffer_line_segment(seg_dest, feedrate, active_extruder);
seg_dest[Z_AXIS] = ztemp;
}
if (--segments) { // not the last segment
seg_rx += seg_dx;
seg_ry += seg_dy;
seg_rz += seg_dz;
seg_le += seg_de;
} else { // last segment, use exact destination
seg_rx = RAW_X_POSITION(ltarget[X_AXIS]);
seg_ry = RAW_Y_POSITION(ltarget[Y_AXIS]);
seg_rz = RAW_Z_POSITION(ltarget[Z_AXIS]);
seg_le = ltarget[E_AXIS];
}
ubl_buffer_segment_raw( seg_rx, seg_ry, seg_rz + z_offset, seg_le, feedrate );
} while (segments);
// Since repeated adding segment_distance accumulates small errors, final move to exact destination.
COPY_XYZE(seg_dest, ltarget);
seg_dest[Z_AXIS] += z_offset;
ubl_buffer_line_segment(seg_dest, feedrate, active_extruder);
return false; // moved but did not set_current_to_destination();
}
@ -582,14 +631,11 @@
const float fade_scaling_factor = fade_scaling_factor_for_z(ltarget[Z_AXIS]);
#endif
float seg_dest[XYZE]; // per-segment destination, initialize to first segment
LOOP_XYZE(i) seg_dest[i] = current_position[i] + segment_distance[i];
const float &dx_seg = segment_distance[X_AXIS]; // alias for clarity
const float &dy_seg = segment_distance[Y_AXIS];
float rx = RAW_X_POSITION(seg_dest[X_AXIS]), // assume raw vs logical coordinates shifted but not scaled.
ry = RAW_Y_POSITION(seg_dest[Y_AXIS]);
// increment to first segment destination
seg_rx += seg_dx;
seg_ry += seg_dy;
seg_rz += seg_dz;
seg_le += seg_de;
for(;;) { // for each mesh cell encountered during the move
@ -600,20 +646,16 @@
// in top of loop and again re-find same adjacent cell and use it, just less efficient
// for mesh inset area.
int8_t cell_xi = (rx - (UBL_MESH_MIN_X)) * (1.0 / (MESH_X_DIST)),
cell_yi = (ry - (UBL_MESH_MIN_Y)) * (1.0 / (MESH_X_DIST));
int8_t cell_xi = (seg_rx - (UBL_MESH_MIN_X)) * (1.0 / (MESH_X_DIST)),
cell_yi = (seg_ry - (UBL_MESH_MIN_Y)) * (1.0 / (MESH_X_DIST));
cell_xi = constrain(cell_xi, 0, (GRID_MAX_POINTS_X) - 1);
cell_yi = constrain(cell_yi, 0, (GRID_MAX_POINTS_Y) - 1);
const float x0 = mesh_index_to_xpos(cell_xi), // 64 byte table lookup avoids mul+add
y0 = mesh_index_to_ypos(cell_yi), // 64 byte table lookup avoids mul+add
x1 = mesh_index_to_xpos(cell_xi + 1), // 64 byte table lookup avoids mul+add
y1 = mesh_index_to_ypos(cell_yi + 1); // 64 byte table lookup avoids mul+add
const float x0 = mesh_index_to_xpos(cell_xi), // 64 byte table lookup avoids mul+add
y0 = mesh_index_to_ypos(cell_yi);
float cx = rx - x0, // cell-relative x
cy = ry - y0, // cell-relative y
z_x0y0 = z_values[cell_xi ][cell_yi ], // z at lower left corner
float z_x0y0 = z_values[cell_xi ][cell_yi ], // z at lower left corner
z_x1y0 = z_values[cell_xi+1][cell_yi ], // z at upper left corner
z_x0y1 = z_values[cell_xi ][cell_yi+1], // z at lower right corner
z_x1y1 = z_values[cell_xi+1][cell_yi+1]; // z at upper right corner
@ -623,15 +665,18 @@
if (isnan(z_x0y1)) z_x0y1 = 0; // in order to avoid isnan tests per cell,
if (isnan(z_x1y1)) z_x1y1 = 0; // thus guessing zero for undefined points
float cx = seg_rx - x0, // cell-relative x and y
cy = seg_ry - y0;
const float z_xmy0 = (z_x1y0 - z_x0y0) * (1.0 / (MESH_X_DIST)), // z slope per x along y0 (lower left to lower right)
z_xmy1 = (z_x1y1 - z_x0y1) * (1.0 / (MESH_X_DIST)); // z slope per x along y1 (upper left to upper right)
float z_cxy0 = z_x0y0 + z_xmy0 * cx; // z height along y0 at cx
float z_cxy0 = z_x0y0 + z_xmy0 * cx; // z height along y0 at cx (changes for each cx in cell)
const float z_cxy1 = z_x0y1 + z_xmy1 * cx, // z height along y1 at cx
z_cxyd = z_cxy1 - z_cxy0; // z height difference along cx from y0 to y1
float z_cxym = z_cxyd * (1.0 / (MESH_Y_DIST)); // z slope per y along cx from y0 to y1
float z_cxym = z_cxyd * (1.0 / (MESH_Y_DIST)); // z slope per y along cx from y0 to y1 (changes for each cx in cell)
// float z_cxcy = z_cxy0 + z_cxym * cy; // interpolated mesh z height along cx at cy (do inside the segment loop)
@ -639,8 +684,8 @@
// and the z_cxym slope will change, both as a function of cx within the cell, and
// each change by a constant for fixed segment lengths.
const float z_sxy0 = z_xmy0 * dx_seg, // per-segment adjustment to z_cxy0
z_sxym = (z_xmy1 - z_xmy0) * (1.0 / (MESH_Y_DIST)) * dx_seg; // per-segment adjustment to z_cxym
const float z_sxy0 = z_xmy0 * seg_dx, // per-segment adjustment to z_cxy0
z_sxym = (z_xmy1 - z_xmy0) * (1.0 / (MESH_Y_DIST)) * seg_dx; // per-segment adjustment to z_cxym
for(;;) { // for all segments within this mesh cell
@ -650,28 +695,29 @@
z_cxcy *= fade_scaling_factor; // apply fade factor to interpolated mesh height
#endif
z_cxcy += state.z_offset; // add fixed mesh offset from G29 Z
z_cxcy += state.z_offset; // add fixed mesh offset from G29 Z
if (--segments == 0) { // if this is last segment, use ltarget for exact
COPY_XYZE(seg_dest, ltarget);
seg_dest[Z_AXIS] += z_cxcy;
ubl_buffer_line_segment(seg_dest, feedrate, active_extruder);
return false; // did not set_current_to_destination()
seg_rx = RAW_X_POSITION(ltarget[X_AXIS]);
seg_ry = RAW_Y_POSITION(ltarget[Y_AXIS]);
seg_rz = RAW_Z_POSITION(ltarget[Z_AXIS]);
seg_le = ltarget[E_AXIS];
}
const float z_orig = seg_dest[Z_AXIS]; // remember the pre-leveled segment z value
seg_dest[Z_AXIS] = z_orig + z_cxcy; // adjust segment z height per mesh leveling
ubl_buffer_line_segment(seg_dest, feedrate, active_extruder);
seg_dest[Z_AXIS] = z_orig; // restore pre-leveled z before incrementing
ubl_buffer_segment_raw( seg_rx, seg_ry, seg_rz + z_cxcy, seg_le, feedrate );
LOOP_XYZE(i) seg_dest[i] += segment_distance[i]; // adjust seg_dest for next segment
if (segments == 0 ) // done with last segment
return false; // did not set_current_to_destination()
cx += dx_seg;
cy += dy_seg;
seg_rx += seg_dx;
seg_ry += seg_dy;
seg_rz += seg_dz;
seg_le += seg_de;
cx += seg_dx;
cy += seg_dy;
if (!WITHIN(cx, 0, MESH_X_DIST) || !WITHIN(cy, 0, MESH_Y_DIST)) { // done within this cell, break to next
rx = RAW_X_POSITION(seg_dest[X_AXIS]);
ry = RAW_Y_POSITION(seg_dest[Y_AXIS]);
break;
}

View File

@ -60,6 +60,7 @@ int lcd_preheat_hotend_temp[2], lcd_preheat_bed_temp[2], lcd_preheat_fan_speed[2
uint8_t lcd_status_message_level;
char lcd_status_message[3 * (LCD_WIDTH) + 1] = WELCOME_MSG; // worst case is kana with up to 3*LCD_WIDTH+1
#if ENABLED(STATUS_MESSAGE_SCROLLING)
uint8_t status_scroll_pos = 0;
#endif
@ -726,6 +727,24 @@ void kill_screen(const char* lcd_msg) {
#endif // SDSUPPORT
#if ENABLED(MENU_ITEM_CASE_LIGHT)
extern int case_light_brightness;
extern bool case_light_on;
extern void update_case_light();
void case_light_menu() {
START_MENU();
//
// ^ Main
//
MENU_BACK(MSG_MAIN);
MENU_ITEM_EDIT_CALLBACK(int3, MSG_CASE_LIGHT_BRIGHTNESS, &case_light_brightness, 0, 255, update_case_light, true);
MENU_ITEM_EDIT_CALLBACK(bool, MSG_CASE_LIGHT, (bool*)&case_light_on, update_case_light);
END_MENU();
}
#endif // MENU_ITEM_CASE_LIGHT
#if ENABLED(BLTOUCH)
/**
@ -847,11 +866,6 @@ void kill_screen(const char* lcd_msg) {
*
*/
#if ENABLED(MENU_ITEM_CASE_LIGHT)
extern bool case_light_on;
extern void update_case_light();
#endif
void lcd_main_menu() {
START_MENU();
MENU_BACK(MSG_WATCH);
@ -868,10 +882,14 @@ void kill_screen(const char* lcd_msg) {
#endif
//
// Switch case light on/off
// Set Case light on/off/brightness
//
#if ENABLED(MENU_ITEM_CASE_LIGHT)
MENU_ITEM_EDIT_CALLBACK(bool, MSG_CASE_LIGHT, &case_light_on, update_case_light);
if (USEABLE_HARDWARE_PWM(CASE_LIGHT_PIN)) {
MENU_ITEM(submenu, MSG_CASE_LIGHT, case_light_menu);
}
else
MENU_ITEM_EDIT_CALLBACK(bool, MSG_CASE_LIGHT, (bool*)&case_light_on, update_case_light);
#endif
if (planner.movesplanned() || IS_SD_PRINTING) {
@ -1580,7 +1598,6 @@ void kill_screen(const char* lcd_msg) {
//
// The last G29 will record and enable but not move.
// Since G29 is deferred,
//
lcd_wait_for_move = true;
enqueue_and_echo_commands_P(PSTR("G29 V1"));
@ -1847,7 +1864,7 @@ void kill_screen(const char* lcd_msg) {
*/
void _lcd_ubl_validate_custom_mesh() {
char UBL_LCD_GCODE[24];
const int temp =
const int temp =
#if WATCH_THE_BED
custom_bed_temp
#else
@ -2574,16 +2591,9 @@ void kill_screen(const char* lcd_msg) {
*
*/
/**
*
* Callback for LCD contrast
*
*/
#if HAS_LCD_CONTRAST
void lcd_callback_set_contrast() { set_lcd_contrast(lcd_contrast); }
#endif // HAS_LCD_CONTRAST
#endif
static void lcd_factory_settings() {
settings.reset();
@ -2598,7 +2608,7 @@ void kill_screen(const char* lcd_msg) {
MENU_ITEM(submenu, MSG_FILAMENT, lcd_control_filament_menu);
#if HAS_LCD_CONTRAST
MENU_ITEM_EDIT_CALLBACK(int3, MSG_CONTRAST, &lcd_contrast, LCD_CONTRAST_MIN, LCD_CONTRAST_MAX, lcd_callback_set_contrast, true);
MENU_ITEM_EDIT_CALLBACK(int3, MSG_CONTRAST, (int*)&lcd_contrast, LCD_CONTRAST_MIN, LCD_CONTRAST_MAX, lcd_callback_set_contrast, true);
#endif
#if ENABLED(FWRETRACT)
MENU_ITEM(submenu, MSG_RETRACT, lcd_control_retract_menu);
@ -3867,11 +3877,7 @@ void lcd_init() {
int lcd_strlen(const char* s) {
int i = 0, j = 0;
while (s[i]) {
#if ENABLED(MAPPER_NON)
j++;
#else
if (PRINTABLE(s[i])) j++;
#endif
if (PRINTABLE(s[i])) j++;
i++;
}
return j;
@ -3880,11 +3886,7 @@ int lcd_strlen(const char* s) {
int lcd_strlen_P(const char* s) {
int j = 0;
while (pgm_read_byte(s)) {
#if ENABLED(MAPPER_NON)
j++;
#else
if (PRINTABLE(pgm_read_byte(s))) j++;
#endif
if (PRINTABLE(pgm_read_byte(s))) j++;
s++;
}
return j;
@ -4144,28 +4146,28 @@ void lcd_update() {
} // ELAPSED(ms, next_lcd_update_ms)
}
#if DISABLED(STATUS_MESSAGE_SCROLLING)
void set_utf_strlen(char* s, uint8_t n) {
uint8_t i = 0, j = 0;
while (s[i] && (j < n)) {
#if ENABLED(MAPPER_NON)
j++;
#else
if (PRINTABLE(s[i])) j++;
#endif
i++;
}
while (j++ < n) s[i++] = ' ';
s[i] = '\0';
void pad_message_string() {
uint8_t i = 0, j = 0;
char c;
while ((c = lcd_status_message[i]) && j < LCD_WIDTH) {
if (PRINTABLE(c)) j++;
i++;
}
#endif // !STATUS_MESSAGE_SCROLLING
if (true
#if ENABLED(STATUS_MESSAGE_SCROLLING)
&& j < LCD_WIDTH
#endif
) {
// pad with spaces to fill up the line
while (j++ < LCD_WIDTH) lcd_status_message[i++] = ' ';
// chop off at the edge
lcd_status_message[i] = '\0';
}
}
void lcd_finishstatus(bool persist=false) {
#if DISABLED(STATUS_MESSAGE_SCROLLING)
set_utf_strlen(lcd_status_message, LCD_WIDTH);
#endif
pad_message_string();
#if !(ENABLED(LCD_PROGRESS_BAR) && (PROGRESS_MSG_EXPIRE > 0))
UNUSED(persist);

View File

@ -59,7 +59,7 @@
#if ENABLED(DOGLCD)
extern uint16_t lcd_contrast;
void set_lcd_contrast(uint16_t value);
void set_lcd_contrast(const uint16_t value);
#elif ENABLED(SHOW_BOOTSCREEN)
void bootscreen();
#endif

View File

@ -239,19 +239,17 @@ char lcd_print_and_count(const char c) {
* On DOGM all strings go through a filter for utf
* But only use lcd_print_utf and lcd_printPGM_utf for translated text
*/
void lcd_print(const char* const str) { for (uint8_t i = 0; char c = str[i]; ++i) lcd_print(c); }
void lcd_printPGM(const char* str) { for (; char c = pgm_read_byte(str); ++str) lcd_print(c); }
void lcd_print(const char *str) { while (*str) lcd_print(*str++); }
void lcd_printPGM(const char *str) { while (const char c = pgm_read_byte(str)) lcd_print(c), ++str; }
void lcd_print_utf(const char* const str, const uint8_t maxLength=LCD_WIDTH) {
void lcd_print_utf(const char *str, uint8_t n=LCD_WIDTH) {
char c;
for (uint8_t i = 0, n = maxLength; n && (c = str[i]); ++i)
n -= charset_mapper(c);
while (n && (c = *str)) n -= charset_mapper(c), ++str;
}
void lcd_printPGM_utf(const char* str, const uint8_t maxLength=LCD_WIDTH) {
void lcd_printPGM_utf(const char *str, uint8_t n=LCD_WIDTH) {
char c;
for (uint8_t i = 0, n = maxLength; n && (c = str[i]); ++i)
n -= charset_mapper(c);
while (n && (c = pgm_read_byte(str))) n -= charset_mapper(c), ++str;
}
// Initialize or re-initialize the LCD
@ -412,8 +410,8 @@ inline void lcd_implementation_status_message() {
const uint8_t slen = lcd_strlen(lcd_status_message);
if (slen > LCD_WIDTH) {
// Skip any non-printing bytes
while (!PRINTABLE(lcd_status_message[status_scroll_pos])) ++status_scroll_pos;
if (++status_scroll_pos > slen - LCD_WIDTH) status_scroll_pos = 0;
while (!PRINTABLE(lcd_status_message[status_scroll_pos++])) { /* nada */ }
if (status_scroll_pos > slen - LCD_WIDTH) status_scroll_pos = 0;
}
#else
lcd_print_utf(lcd_status_message);
@ -706,7 +704,9 @@ static void lcd_implementation_status_screen() {
lcd_print(' ');
lcd_print(itostr3(thermalManager.degHotend(active_extruder)));
lcd_print('/');
lcd_print(itostr3(thermalManager.degTargetHotend(active_extruder)));
if (lcd_blink() || !thermalManager.is_heater_idle(active_extruder))
lcd_print(itostr3(thermalManager.degTargetHotend(active_extruder)));
}
#endif // ADVANCED_PAUSE_FEATURE

View File

@ -382,19 +382,17 @@ void lcd_implementation_clear() { lcd.clear(); }
void lcd_print(const char c) { charset_mapper(c); }
void lcd_print(const char * const str) { for (uint8_t i = 0; char c = str[i]; ++i) lcd.print(c); }
void lcd_printPGM(const char* str) { for (; char c = pgm_read_byte(str); ++str) lcd.print(c); }
void lcd_print(const char *str) { while (*str) lcd.print(*str++); }
void lcd_printPGM(const char *str) { while (const char c = pgm_read_byte(str)) lcd.print(c), ++str; }
void lcd_print_utf(const char * const str, const uint8_t maxLength=LCD_WIDTH) {
void lcd_print_utf(const char *str, uint8_t n=LCD_WIDTH) {
char c;
for (uint8_t i = 0, n = maxLength; n && (c = str[i]); ++i)
n -= charset_mapper(c);
while (n && (c = *str)) n -= charset_mapper(c), ++str;
}
void lcd_printPGM_utf(const char* str, const uint8_t maxLength=LCD_WIDTH) {
void lcd_printPGM_utf(const char *str, uint8_t n=LCD_WIDTH) {
char c;
for (uint8_t i = 0, n = maxLength; n && (c = str[i]); ++i)
n -= charset_mapper(c);
while (n && (c = pgm_read_byte(str))) n -= charset_mapper(c), ++str;
}
#if ENABLED(SHOW_BOOTSCREEN)
@ -831,8 +829,8 @@ static void lcd_implementation_status_screen() {
const uint8_t slen = lcd_strlen(lcd_status_message);
if (slen > LCD_WIDTH) {
// Skip any non-printing bytes
while (!PRINTABLE(lcd_status_message[status_scroll_pos])) ++status_scroll_pos;
if (++status_scroll_pos > slen - LCD_WIDTH) status_scroll_pos = 0;
while (!PRINTABLE(lcd_status_message[status_scroll_pos++])) { /* nada */ }
if (status_scroll_pos > slen - LCD_WIDTH) status_scroll_pos = 0;
}
#else
lcd_print_utf(lcd_status_message);
@ -846,10 +844,7 @@ static void lcd_implementation_status_screen() {
static void lcd_implementation_hotend_status(const uint8_t row) {
if (row < LCD_HEIGHT) {
lcd.setCursor(LCD_WIDTH - 9, row);
lcd.print(LCD_STR_THERMOMETER[0]);
lcd.print(itostr3(thermalManager.degHotend(active_extruder)));
lcd.print('/');
lcd.print(itostr3(thermalManager.degTargetHotend(active_extruder)));
_draw_heater_status(active_extruder, LCD_STR_THERMOMETER[0], lcd_blink());
}
}

View File

@ -23,7 +23,7 @@
#ifndef UTF_MAPPER_H
#define UTF_MAPPER_H
#include "language.h"
#include "language.h"
#if ENABLED(DOGLCD)
#define HARDWARE_CHAR_OUT u8g.print
@ -144,6 +144,8 @@
#endif // DISPLAY_CHARSET_HD44780
#endif // SIMULATE_ROMFONT
#define PRINTABLE(C) (((C) & 0xC0u) != 0x80u)
#if ENABLED(MAPPER_C2C3)
char charset_mapper(const char c) {
@ -466,8 +468,11 @@
#define MAPPER_NON
#undef PRINTABLE
#define PRINTABLE(C) true
char charset_mapper(const char c) {
HARDWARE_CHAR_OUT( c );
HARDWARE_CHAR_OUT(c);
return 1;
}