commit
f47fc879fe
21 changed files with 433 additions and 360 deletions
|
@ -263,8 +263,6 @@ void Config_StoreSettings() {
|
|||
EEPROM_WRITE_VAR(i, dummy);
|
||||
}
|
||||
|
||||
int storageSize = i;
|
||||
|
||||
char ver2[4] = EEPROM_VERSION;
|
||||
int j = EEPROM_OFFSET;
|
||||
EEPROM_WRITE_VAR(j, ver2); // validate data
|
||||
|
@ -446,7 +444,7 @@ void Config_ResetDefault() {
|
|||
float tmp1[] = DEFAULT_AXIS_STEPS_PER_UNIT;
|
||||
float tmp2[] = DEFAULT_MAX_FEEDRATE;
|
||||
long tmp3[] = DEFAULT_MAX_ACCELERATION;
|
||||
for (int i = 0; i < NUM_AXIS; i++) {
|
||||
for (uint16_t i = 0; i < NUM_AXIS; i++) {
|
||||
axis_steps_per_unit[i] = tmp1[i];
|
||||
max_feedrate[i] = tmp2[i];
|
||||
max_acceleration_units_per_sq_second[i] = tmp3[i];
|
||||
|
|
|
@ -388,7 +388,11 @@ const char axis_codes[NUM_AXIS] = {'X', 'Y', 'Z', 'E'};
|
|||
static float destination[NUM_AXIS] = { 0, 0, 0, 0 };
|
||||
|
||||
static float offset[3] = { 0, 0, 0 };
|
||||
static bool home_all_axis = true;
|
||||
|
||||
#ifndef DELTA
|
||||
static bool home_all_axis = true;
|
||||
#endif
|
||||
|
||||
static float feedrate = 1500.0, next_feedrate, saved_feedrate;
|
||||
static long gcode_N, gcode_LastN, Stopped_gcode_LastN = 0;
|
||||
|
||||
|
@ -396,8 +400,8 @@ static bool relative_mode = false; //Determines Absolute or Relative Coordinate
|
|||
|
||||
static char cmdbuffer[BUFSIZE][MAX_CMD_SIZE];
|
||||
#ifdef SDSUPPORT
|
||||
static bool fromsd[BUFSIZE];
|
||||
#endif //!SDSUPPORT
|
||||
static bool fromsd[BUFSIZE];
|
||||
#endif
|
||||
static int bufindr = 0;
|
||||
static int bufindw = 0;
|
||||
static int buflen = 0;
|
||||
|
@ -933,24 +937,22 @@ void get_command()
|
|||
|
||||
}
|
||||
|
||||
|
||||
float code_value()
|
||||
{
|
||||
float code_value() {
|
||||
float ret;
|
||||
char *e = strchr(strchr_pointer, 'E');
|
||||
if (e != NULL) *e = 0;
|
||||
ret = strtod(strchr_pointer+1, NULL);
|
||||
if (e != NULL) *e = 'E';
|
||||
if (e) {
|
||||
*e = 0;
|
||||
ret = strtod(strchr_pointer+1, NULL);
|
||||
*e = 'E';
|
||||
}
|
||||
else
|
||||
ret = strtod(strchr_pointer+1, NULL);
|
||||
return ret;
|
||||
}
|
||||
|
||||
long code_value_long()
|
||||
{
|
||||
return (strtol(strchr_pointer + 1, NULL, 10));
|
||||
}
|
||||
long code_value_long() { return (strtol(strchr_pointer + 1, NULL, 10)); }
|
||||
|
||||
bool code_seen(char code)
|
||||
{
|
||||
bool code_seen(char code) {
|
||||
strchr_pointer = strchr(cmdbuffer[bufindr], code);
|
||||
return (strchr_pointer != NULL); //Return True if a character was found
|
||||
}
|
||||
|
@ -1009,76 +1011,70 @@ XYZ_CONSTS_FROM_CONFIG(signed char, home_dir, HOME_DIR);
|
|||
#endif //DUAL_X_CARRIAGE
|
||||
|
||||
static void axis_is_at_home(int axis) {
|
||||
#ifdef DUAL_X_CARRIAGE
|
||||
if (axis == X_AXIS) {
|
||||
if (active_extruder != 0) {
|
||||
current_position[X_AXIS] = x_home_pos(active_extruder);
|
||||
min_pos[X_AXIS] = X2_MIN_POS;
|
||||
max_pos[X_AXIS] = max(extruder_offset[X_AXIS][1], X2_MAX_POS);
|
||||
return;
|
||||
|
||||
#ifdef DUAL_X_CARRIAGE
|
||||
if (axis == X_AXIS) {
|
||||
if (active_extruder != 0) {
|
||||
current_position[X_AXIS] = x_home_pos(active_extruder);
|
||||
min_pos[X_AXIS] = X2_MIN_POS;
|
||||
max_pos[X_AXIS] = max(extruder_offset[X_AXIS][1], X2_MAX_POS);
|
||||
return;
|
||||
}
|
||||
else if (dual_x_carriage_mode == DXC_DUPLICATION_MODE) {
|
||||
current_position[X_AXIS] = base_home_pos(X_AXIS) + home_offset[X_AXIS];
|
||||
min_pos[X_AXIS] = base_min_pos(X_AXIS) + home_offset[X_AXIS];
|
||||
max_pos[X_AXIS] = min(base_max_pos(X_AXIS) + home_offset[X_AXIS],
|
||||
max(extruder_offset[X_AXIS][1], X2_MAX_POS) - duplicate_extruder_x_offset);
|
||||
return;
|
||||
}
|
||||
}
|
||||
else if (dual_x_carriage_mode == DXC_DUPLICATION_MODE && active_extruder == 0) {
|
||||
current_position[X_AXIS] = base_home_pos(X_AXIS) + home_offset[X_AXIS];
|
||||
min_pos[X_AXIS] = base_min_pos(X_AXIS) + home_offset[X_AXIS];
|
||||
max_pos[X_AXIS] = min(base_max_pos(X_AXIS) + home_offset[X_AXIS],
|
||||
max(extruder_offset[X_AXIS][1], X2_MAX_POS) - duplicate_extruder_x_offset);
|
||||
return;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
#ifdef SCARA
|
||||
float homeposition[3];
|
||||
char i;
|
||||
#endif
|
||||
|
||||
#ifdef SCARA
|
||||
float homeposition[3];
|
||||
|
||||
if (axis < 2)
|
||||
{
|
||||
|
||||
for (i=0; i<3; i++)
|
||||
{
|
||||
homeposition[i] = base_home_pos(i);
|
||||
}
|
||||
// SERIAL_ECHOPGM("homeposition[x]= "); SERIAL_ECHO(homeposition[0]);
|
||||
// SERIAL_ECHOPGM("homeposition[y]= "); SERIAL_ECHOLN(homeposition[1]);
|
||||
// Works out real Homeposition angles using inverse kinematics,
|
||||
// and calculates homing offset using forward kinematics
|
||||
calculate_delta(homeposition);
|
||||
if (axis < 2) {
|
||||
|
||||
for (int i = 0; i < 3; i++) homeposition[i] = base_home_pos(i);
|
||||
|
||||
// SERIAL_ECHOPGM("homeposition[x]= "); SERIAL_ECHO(homeposition[0]);
|
||||
// SERIAL_ECHOPGM("homeposition[y]= "); SERIAL_ECHOLN(homeposition[1]);
|
||||
// Works out real Homeposition angles using inverse kinematics,
|
||||
// and calculates homing offset using forward kinematics
|
||||
calculate_delta(homeposition);
|
||||
|
||||
// SERIAL_ECHOPGM("base Theta= "); SERIAL_ECHO(delta[X_AXIS]);
|
||||
// SERIAL_ECHOPGM(" base Psi+Theta="); SERIAL_ECHOLN(delta[Y_AXIS]);
|
||||
// SERIAL_ECHOPGM("base Theta= "); SERIAL_ECHO(delta[X_AXIS]);
|
||||
// SERIAL_ECHOPGM(" base Psi+Theta="); SERIAL_ECHOLN(delta[Y_AXIS]);
|
||||
|
||||
for (i=0; i<2; i++)
|
||||
{
|
||||
delta[i] -= home_offset[i];
|
||||
}
|
||||
for (int i = 0; i < 2; i++) delta[i] -= home_offset[i];
|
||||
|
||||
// SERIAL_ECHOPGM("addhome X="); SERIAL_ECHO(home_offset[X_AXIS]);
|
||||
// SERIAL_ECHOPGM(" addhome Y="); SERIAL_ECHO(home_offset[Y_AXIS]);
|
||||
// SERIAL_ECHOPGM(" addhome Theta="); SERIAL_ECHO(delta[X_AXIS]);
|
||||
// SERIAL_ECHOPGM(" addhome Psi+Theta="); SERIAL_ECHOLN(delta[Y_AXIS]);
|
||||
// SERIAL_ECHOPGM("addhome X="); SERIAL_ECHO(home_offset[X_AXIS]);
|
||||
// SERIAL_ECHOPGM(" addhome Y="); SERIAL_ECHO(home_offset[Y_AXIS]);
|
||||
// SERIAL_ECHOPGM(" addhome Theta="); SERIAL_ECHO(delta[X_AXIS]);
|
||||
// SERIAL_ECHOPGM(" addhome Psi+Theta="); SERIAL_ECHOLN(delta[Y_AXIS]);
|
||||
|
||||
calculate_SCARA_forward_Transform(delta);
|
||||
calculate_SCARA_forward_Transform(delta);
|
||||
|
||||
// SERIAL_ECHOPGM("Delta X="); SERIAL_ECHO(delta[X_AXIS]);
|
||||
// SERIAL_ECHOPGM(" Delta Y="); SERIAL_ECHOLN(delta[Y_AXIS]);
|
||||
// SERIAL_ECHOPGM("Delta X="); SERIAL_ECHO(delta[X_AXIS]);
|
||||
// SERIAL_ECHOPGM(" Delta Y="); SERIAL_ECHOLN(delta[Y_AXIS]);
|
||||
|
||||
current_position[axis] = delta[axis];
|
||||
current_position[axis] = delta[axis];
|
||||
|
||||
// SCARA home positions are based on configuration since the actual limits are determined by the
|
||||
// inverse kinematic transform.
|
||||
min_pos[axis] = base_min_pos(axis); // + (delta[axis] - base_home_pos(axis));
|
||||
max_pos[axis] = base_max_pos(axis); // + (delta[axis] - base_home_pos(axis));
|
||||
}
|
||||
else
|
||||
{
|
||||
// SCARA home positions are based on configuration since the actual limits are determined by the
|
||||
// inverse kinematic transform.
|
||||
min_pos[axis] = base_min_pos(axis); // + (delta[axis] - base_home_pos(axis));
|
||||
max_pos[axis] = base_max_pos(axis); // + (delta[axis] - base_home_pos(axis));
|
||||
}
|
||||
else {
|
||||
current_position[axis] = base_home_pos(axis) + home_offset[axis];
|
||||
min_pos[axis] = base_min_pos(axis) + home_offset[axis];
|
||||
max_pos[axis] = base_max_pos(axis) + home_offset[axis];
|
||||
}
|
||||
#else
|
||||
current_position[axis] = base_home_pos(axis) + home_offset[axis];
|
||||
min_pos[axis] = base_min_pos(axis) + home_offset[axis];
|
||||
max_pos[axis] = base_max_pos(axis) + home_offset[axis];
|
||||
#endif
|
||||
min_pos[axis] = base_min_pos(axis) + home_offset[axis];
|
||||
max_pos[axis] = base_max_pos(axis) + home_offset[axis];
|
||||
}
|
||||
#else
|
||||
current_position[axis] = base_home_pos(axis) + home_offset[axis];
|
||||
min_pos[axis] = base_min_pos(axis) + home_offset[axis];
|
||||
max_pos[axis] = base_max_pos(axis) + home_offset[axis];
|
||||
#endif
|
||||
}
|
||||
|
||||
#ifdef ENABLE_AUTO_BED_LEVELING
|
||||
|
@ -1233,10 +1229,6 @@ static void do_blocking_move_to(float x, float y, float z) {
|
|||
feedrate = oldFeedRate;
|
||||
}
|
||||
|
||||
static void do_blocking_move_relative(float offset_x, float offset_y, float offset_z) {
|
||||
do_blocking_move_to(current_position[X_AXIS] + offset_x, current_position[Y_AXIS] + offset_y, current_position[Z_AXIS] + offset_z);
|
||||
}
|
||||
|
||||
static void setup_for_endstop_move() {
|
||||
saved_feedrate = feedrate;
|
||||
saved_feedmultiply = feedmultiply;
|
||||
|
@ -2156,7 +2148,6 @@ inline void gcode_G28() {
|
|||
}
|
||||
|
||||
int verbose_level = 1;
|
||||
float x_tmp, y_tmp, z_tmp, real_z;
|
||||
|
||||
if (code_seen('V') || code_seen('v')) {
|
||||
verbose_level = code_value_long();
|
||||
|
@ -2444,6 +2435,7 @@ inline void gcode_G28() {
|
|||
// When the bed is uneven, this height must be corrected.
|
||||
if (!dryrun)
|
||||
{
|
||||
float x_tmp, y_tmp, z_tmp, real_z;
|
||||
real_z = float(st_get_position(Z_AXIS)) / axis_steps_per_unit[Z_AXIS]; //get the real Z (since the auto bed leveling is already correcting the plane)
|
||||
x_tmp = current_position[X_AXIS] + X_PROBE_OFFSET_FROM_EXTRUDER;
|
||||
y_tmp = current_position[Y_AXIS] + Y_PROBE_OFFSET_FROM_EXTRUDER;
|
||||
|
@ -4590,7 +4582,6 @@ inline void gcode_T() {
|
|||
#if EXTRUDERS > 1
|
||||
bool make_move = false;
|
||||
#endif
|
||||
|
||||
if (code_seen('F')) {
|
||||
#if EXTRUDERS > 1
|
||||
make_move = true;
|
||||
|
@ -5193,16 +5184,10 @@ void ClearToSend()
|
|||
|
||||
void get_coordinates() {
|
||||
for (int i = 0; i < NUM_AXIS; i++) {
|
||||
float dest;
|
||||
if (code_seen(axis_codes[i])) {
|
||||
dest = code_value();
|
||||
if (axis_relative_modes[i] || relative_mode)
|
||||
dest += current_position[i];
|
||||
}
|
||||
if (code_seen(axis_codes[i]))
|
||||
destination[i] = code_value() + (axis_relative_modes[i] || relative_mode ? current_position[i] : 0);
|
||||
else
|
||||
dest = current_position[i];
|
||||
|
||||
destination[i] = dest;
|
||||
destination[i] = current_position[i];
|
||||
}
|
||||
if (code_seen('F')) {
|
||||
next_feedrate = code_value();
|
||||
|
|
|
@ -489,7 +489,7 @@ void CardReader::updir() {
|
|||
if (workDirDepth > 0) {
|
||||
--workDirDepth;
|
||||
workDir = workDirParents[0];
|
||||
for (int d = 0; d < workDirDepth; d++)
|
||||
for (uint16_t d = 0; d < workDirDepth; d++)
|
||||
workDirParents[d] = workDirParents[d+1];
|
||||
}
|
||||
}
|
||||
|
|
|
@ -34,7 +34,6 @@
|
|||
#endif
|
||||
|
||||
#define PROTOCOL_VERSION "1.0"
|
||||
#define FIRMWARE_URL "https://github.com/MarlinFirmware/Marlin"
|
||||
|
||||
#if MB(ULTIMAKER)|| MB(ULTIMAKER_OLD)|| MB(ULTIMAIN_2)
|
||||
#define MACHINE_NAME "Ultimaker"
|
||||
|
@ -59,14 +58,16 @@
|
|||
#define FIRMWARE_URL "http://www.bq.com/gb/downloads-prusa-i3-hephestos.html"
|
||||
#else // Default firmware set to Mendel
|
||||
#define MACHINE_NAME "Mendel"
|
||||
#define FIRMWARE_URL "https://github.com/MarlinFirmware/Marlin"
|
||||
#endif
|
||||
|
||||
#ifdef CUSTOM_MENDEL_NAME
|
||||
#undef MACHINE_NAME
|
||||
#define MACHINE_NAME CUSTOM_MENDEL_NAME
|
||||
#endif
|
||||
|
||||
#ifndef MACHINE_UUID
|
||||
#define MACHINE_UUID "00000000-0000-0000-0000-000000000000"
|
||||
#define MACHINE_UUID "00000000-0000-0000-0000-000000000000"
|
||||
#endif
|
||||
|
||||
|
||||
|
|
|
@ -275,13 +275,9 @@
|
|||
|
||||
#ifdef ADVANCE
|
||||
#define EXTRUDER_ADVANCE_K .0
|
||||
|
||||
#define D_FILAMENT 1.75
|
||||
#define STEPS_MM_E 1000
|
||||
#define EXTRUSION_AREA (0.25 * D_FILAMENT * D_FILAMENT * 3.14159)
|
||||
#define STEPS_PER_CUBIC_MM_E (axis_steps_per_unit[E_AXIS]/ EXTRUSION_AREA)
|
||||
|
||||
#endif // ADVANCE
|
||||
#endif
|
||||
|
||||
// Arc interpretation settings:
|
||||
#define MM_PER_ARC_SEGMENT 1
|
||||
|
|
|
@ -40,12 +40,14 @@
|
|||
#define FIRMWARE_URL "https://github.com/MarlinFirmware/Marlin"
|
||||
|
||||
#if MB(ULTIMAKER)|| MB(ULTIMAKER_OLD)|| MB(ULTIMAIN_2)
|
||||
#undef FIRMWARE_URL
|
||||
#define MACHINE_NAME "Ultimaker"
|
||||
#define FIRMWARE_URL "http://firmware.ultimaker.com"
|
||||
#elif MB(RUMBA)
|
||||
#define MACHINE_NAME "Rumba"
|
||||
#elif MB(3DRAG)
|
||||
#define MACHINE_NAME "3Drag"
|
||||
#undef FIRMWARE_URL
|
||||
#define FIRMWARE_URL "http://3dprint.elettronicain.it/"
|
||||
#elif MB(K8200)
|
||||
#define MACHINE_NAME "K8200"
|
||||
|
@ -53,18 +55,22 @@
|
|||
#define MACHINE_NAME "Makibox"
|
||||
#elif MB(SAV_MKI)
|
||||
#define MACHINE_NAME "SAV MkI"
|
||||
#undef FIRMWARE_URL
|
||||
#define FIRMWARE_URL "https://github.com/fmalpartida/Marlin/tree/SAV-MkI-config"
|
||||
#elif MB(WITBOX)
|
||||
#define MACHINE_NAME "WITBOX"
|
||||
#undef FIRMWARE_URL
|
||||
#define FIRMWARE_URL "http://www.bq.com/gb/downloads-witbox.html"
|
||||
#elif MB(HEPHESTOS)
|
||||
#define MACHINE_NAME "HEPHESTOS"
|
||||
#undef FIRMWARE_URL
|
||||
#define FIRMWARE_URL "http://www.bq.com/gb/downloads-prusa-i3-hephestos.html"
|
||||
#else // Default firmware set to Mendel
|
||||
#define MACHINE_NAME "Mendel"
|
||||
#endif
|
||||
|
||||
#ifdef CUSTOM_MENDEL_NAME
|
||||
#undef MACHINE_NAME
|
||||
#define MACHINE_NAME CUSTOM_MENDEL_NAME
|
||||
#endif
|
||||
|
||||
|
|
|
@ -127,10 +127,13 @@
|
|||
#define _E3_PINS
|
||||
|
||||
#if EXTRUDERS > 1
|
||||
#undef _E1_PINS
|
||||
#define _E1_PINS E1_STEP_PIN, E1_DIR_PIN, E1_ENABLE_PIN, HEATER_1_PIN, analogInputToDigitalPin(TEMP_1_PIN),
|
||||
#if EXTRUDERS > 2
|
||||
#undef _E2_PINS
|
||||
#define _E2_PINS E2_STEP_PIN, E2_DIR_PIN, E2_ENABLE_PIN, HEATER_2_PIN, analogInputToDigitalPin(TEMP_2_PIN),
|
||||
#if EXTRUDERS > 3
|
||||
#undef _E3_PINS
|
||||
#define _E3_PINS E3_STEP_PIN, E3_DIR_PIN, E3_ENABLE_PIN, HEATER_3_PIN, analogInputToDigitalPin(TEMP_3_PIN),
|
||||
#endif
|
||||
#endif
|
||||
|
@ -167,12 +170,18 @@
|
|||
#endif
|
||||
|
||||
#ifdef DISABLE_MAX_ENDSTOPS
|
||||
#undef X_MAX_PIN
|
||||
#undef Y_MAX_PIN
|
||||
#undef Z_MAX_PIN
|
||||
#define X_MAX_PIN -1
|
||||
#define Y_MAX_PIN -1
|
||||
#define Z_MAX_PIN -1
|
||||
#endif
|
||||
|
||||
#ifdef DISABLE_MIN_ENDSTOPS
|
||||
#undef X_MIN_PIN
|
||||
#undef Y_MIN_PIN
|
||||
#undef Z_MIN_PIN
|
||||
#define X_MIN_PIN -1
|
||||
#define Y_MIN_PIN -1
|
||||
#define Z_MIN_PIN -1
|
||||
|
|
|
@ -4,18 +4,25 @@
|
|||
|
||||
#include "pins_RAMPS_13.h"
|
||||
|
||||
#undef Z_ENABLE_PIN
|
||||
#define Z_ENABLE_PIN 63
|
||||
|
||||
#undef X_MAX_PIN
|
||||
#undef Y_MAX_PIN
|
||||
#undef Z_MAX_PIN
|
||||
#define X_MAX_PIN 2
|
||||
#define Y_MAX_PIN 15
|
||||
#define Z_MAX_PIN -1
|
||||
|
||||
#undef SDSS
|
||||
#define SDSS 25//53
|
||||
|
||||
#define BEEPER 33
|
||||
|
||||
#undef FAN_PIN
|
||||
#define FAN_PIN 8
|
||||
|
||||
#undef HEATER_1_PIN
|
||||
#undef HEATER_2_PIN
|
||||
#undef HEATER_BED_PIN
|
||||
#define HEATER_0_PIN 10
|
||||
#define HEATER_1_PIN 12
|
||||
#define HEATER_2_PIN 6
|
||||
|
@ -23,8 +30,15 @@
|
|||
#define HEATER_BED_PIN 9 // BED
|
||||
|
||||
#if defined(ULTRA_LCD) && defined(NEWPANEL)
|
||||
#undef BEEPER
|
||||
#define BEEPER -1
|
||||
|
||||
#undef LCD_PINS_RS
|
||||
#undef LCD_PINS_ENABLE
|
||||
#undef LCD_PINS_D4
|
||||
#undef LCD_PINS_D5
|
||||
#undef LCD_PINS_D6
|
||||
#undef LCD_PINS_D7
|
||||
#define LCD_PINS_RS 27
|
||||
#define LCD_PINS_ENABLE 29
|
||||
#define LCD_PINS_D4 37
|
||||
|
@ -33,7 +47,15 @@
|
|||
#define LCD_PINS_D7 31
|
||||
|
||||
// Buttons
|
||||
#undef BTN_EN1
|
||||
#undef BTN_EN2
|
||||
#undef BTN_ENC
|
||||
#define BTN_EN1 16
|
||||
#define BTN_EN2 17
|
||||
#define BTN_ENC 23 //the click
|
||||
|
||||
#else
|
||||
|
||||
#define BEEPER 33
|
||||
|
||||
#endif // ULTRA_LCD && NEWPANEL
|
||||
|
|
|
@ -64,6 +64,15 @@
|
|||
// Microstepping pins
|
||||
// Note that the pin mapping is not from fastio.h
|
||||
// See Sd2PinMap.h for the pin configurations
|
||||
|
||||
#undef X_MS1_PIN
|
||||
#undef X_MS2_PIN
|
||||
#undef Y_MS1_PIN
|
||||
#undef Y_MS2_PIN
|
||||
#undef Z_MS1_PIN
|
||||
#undef Z_MS2_PIN
|
||||
#undef E0_MS1_PIN
|
||||
#undef E0_MS2_PIN
|
||||
#define X_MS1_PIN 25
|
||||
#define X_MS2_PIN 26
|
||||
#define Y_MS1_PIN 9
|
||||
|
|
|
@ -4,7 +4,10 @@
|
|||
|
||||
#include "pins_RAMPS_13.h"
|
||||
|
||||
#undef FAN_PIN
|
||||
#define FAN_PIN 9 // (Sprinter config)
|
||||
|
||||
#undef HEATER_1_PIN
|
||||
#define HEATER_1_PIN -1
|
||||
|
||||
#ifdef TEMP_STAT_LEDS
|
||||
|
|
|
@ -4,7 +4,9 @@
|
|||
|
||||
#include "pins_RAMPS_13.h"
|
||||
|
||||
#undef FAN_PIN
|
||||
#define FAN_PIN 9 // (Sprinter config)
|
||||
|
||||
#define BEEPER 33
|
||||
|
||||
#define E2_STEP_PIN 23
|
||||
|
@ -19,6 +21,9 @@
|
|||
#define E4_DIR_PIN 37
|
||||
#define E4_ENABLE_PIN 42
|
||||
|
||||
#undef HEATER_1_PIN
|
||||
#undef HEATER_2_PIN
|
||||
#undef HEATER_3_PIN
|
||||
#define HEATER_1_PIN -1
|
||||
#define HEATER_2_PIN 16
|
||||
#define HEATER_3_PIN 17
|
||||
|
@ -27,6 +32,8 @@
|
|||
#define HEATER_6_PIN 6
|
||||
#define HEATER_7_PIN 11
|
||||
|
||||
#undef TEMP_2_PIN
|
||||
#undef TEMP_3_PIN
|
||||
#define TEMP_2_PIN 12 // ANALOG NUMBERING
|
||||
#define TEMP_3_PIN 11 // ANALOG NUMBERING
|
||||
#define TEMP_4_PIN 10 // ANALOG NUMBERING
|
||||
|
|
|
@ -4,8 +4,13 @@
|
|||
|
||||
#include "pins_RAMPS_13.h"
|
||||
|
||||
#undef FAN_PIN
|
||||
#define FAN_PIN 9 // (Sprinter config)
|
||||
|
||||
#undef HEATER_1_PIN
|
||||
#define HEATER_1_PIN -1
|
||||
|
||||
#undef TEMP_0_PIN
|
||||
#undef TEMP_1_PIN
|
||||
#define TEMP_0_PIN 9 // ANALOG NUMBERING
|
||||
#define TEMP_1_PIN 11 // ANALOG NUMBERING
|
||||
|
|
|
@ -4,13 +4,23 @@
|
|||
|
||||
#include "pins_RAMPS_13.h"
|
||||
|
||||
#undef X_MAX_PIN
|
||||
#undef Y_MAX_PIN
|
||||
#undef Z_MAX_PIN
|
||||
#define X_MAX_PIN -1
|
||||
#define Y_MAX_PIN -1
|
||||
#define Z_MAX_PIN -1
|
||||
|
||||
#undef Y2_STEP_PIN
|
||||
#undef Y2_DIR_PIN
|
||||
#undef Y2_ENABLE_PIN
|
||||
#define Y2_STEP_PIN -1
|
||||
#define Y2_DIR_PIN -1
|
||||
#define Y2_ENABLE_PIN -1
|
||||
|
||||
#undef Z2_STEP_PIN
|
||||
#undef Z2_DIR_PIN
|
||||
#undef Z2_ENABLE_PIN
|
||||
#define Z2_STEP_PIN -1
|
||||
#define Z2_DIR_PIN -1
|
||||
#define Z2_ENABLE_PIN -1
|
||||
|
@ -19,11 +29,14 @@
|
|||
#define E1_DIR_PIN 34
|
||||
#define E1_ENABLE_PIN 30
|
||||
|
||||
#undef SDPOWER
|
||||
#define SDPOWER 1
|
||||
|
||||
#undef FAN_PIN
|
||||
#define FAN_PIN 9 // (Sprinter config)
|
||||
#define PS_ON_PIN 12
|
||||
|
||||
#undef HEATER_1_PIN
|
||||
#define HEATER_1_PIN 7 // EXTRUDER 2
|
||||
|
||||
#if defined(ULTRA_LCD) && defined(NEWPANEL)
|
||||
|
|
|
@ -4,5 +4,8 @@
|
|||
|
||||
#include "pins_RAMPS_13.h"
|
||||
|
||||
#undef FAN_PIN
|
||||
#define FAN_PIN 9 // (Sprinter config)
|
||||
|
||||
#undef HEATER_1_PIN
|
||||
#define HEATER_1_PIN -1
|
||||
|
|
|
@ -4,5 +4,8 @@
|
|||
|
||||
#include "pins_RAMPS_13.h"
|
||||
|
||||
#undef FAN_PIN
|
||||
#define FAN_PIN 9 // (Sprinter config)
|
||||
|
||||
#undef HEATER_1_PIN
|
||||
#define HEATER_1_PIN -1
|
||||
|
|
|
@ -701,26 +701,26 @@ float junction_deviation = 0.1;
|
|||
|
||||
int moves_queued = movesplanned();
|
||||
|
||||
// slow down when de buffer starts to empty, rather than wait at the corner for a buffer refill
|
||||
bool mq = moves_queued > 1 && moves_queued < BLOCK_BUFFER_SIZE / 2;
|
||||
#ifdef OLD_SLOWDOWN
|
||||
if (mq) feed_rate *= 2.0 * moves_queued / BLOCK_BUFFER_SIZE;
|
||||
#endif
|
||||
|
||||
#ifdef SLOWDOWN
|
||||
// segment time im micro seconds
|
||||
unsigned long segment_time = lround(1000000.0/inverse_second);
|
||||
if (mq) {
|
||||
if (segment_time < minsegmenttime) {
|
||||
// buffer is draining, add extra time. The amount of time added increases if the buffer is still emptied more.
|
||||
inverse_second = 1000000.0 / (segment_time + lround(2 * (minsegmenttime - segment_time) / moves_queued));
|
||||
#ifdef XY_FREQUENCY_LIMIT
|
||||
segment_time = lround(1000000.0 / inverse_second);
|
||||
#endif
|
||||
// Slow down when the buffer starts to empty, rather than wait at the corner for a buffer refill
|
||||
#if defined(OLD_SLOWDOWN) || defined(SLOWDOWN)
|
||||
bool mq = moves_queued > 1 && moves_queued < BLOCK_BUFFER_SIZE / 2;
|
||||
#ifdef OLD_SLOWDOWN
|
||||
if (mq) feed_rate *= 2.0 * moves_queued / BLOCK_BUFFER_SIZE;
|
||||
#endif
|
||||
#ifdef SLOWDOWN
|
||||
// segment time im micro seconds
|
||||
unsigned long segment_time = lround(1000000.0/inverse_second);
|
||||
if (mq) {
|
||||
if (segment_time < minsegmenttime) {
|
||||
// buffer is draining, add extra time. The amount of time added increases if the buffer is still emptied more.
|
||||
inverse_second = 1000000.0 / (segment_time + lround(2 * (minsegmenttime - segment_time) / moves_queued));
|
||||
#ifdef XY_FREQUENCY_LIMIT
|
||||
segment_time = lround(1000000.0 / inverse_second);
|
||||
#endif
|
||||
}
|
||||
}
|
||||
}
|
||||
#endif
|
||||
#endif
|
||||
// END OF SLOW DOWN SECTION
|
||||
|
||||
block->nominal_speed = block->millimeters * inverse_second; // (mm/sec) Always > 0
|
||||
block->nominal_rate = ceil(block->step_event_count * inverse_second); // (step/sec) Always > 0
|
||||
|
|
|
@ -607,7 +607,6 @@ double dnrm2 ( int n, double x[], int incx )
|
|||
double norm;
|
||||
double scale;
|
||||
double ssq;
|
||||
double value;
|
||||
|
||||
if ( n < 1 || incx < 1 )
|
||||
{
|
||||
|
|
|
@ -85,18 +85,32 @@ static volatile bool endstop_z_hit = false;
|
|||
int motor_current_setting[3] = DEFAULT_PWM_MOTOR_CURRENT;
|
||||
#endif
|
||||
|
||||
static bool old_x_min_endstop = false,
|
||||
old_x_max_endstop = false,
|
||||
old_y_min_endstop = false,
|
||||
old_y_max_endstop = false,
|
||||
old_z_min_endstop = false,
|
||||
#ifndef Z_DUAL_ENDSTOPS
|
||||
old_z_max_endstop = false;
|
||||
#else
|
||||
old_z_max_endstop = false,
|
||||
old_z2_min_endstop = false,
|
||||
old_z2_max_endstop = false;
|
||||
#endif
|
||||
#if defined(X_MIN_PIN) && X_MIN_PIN >= 0
|
||||
static bool old_x_min_endstop = false;
|
||||
#endif
|
||||
#if defined(X_MAX_PIN) && X_MAX_PIN >= 0
|
||||
static bool old_x_max_endstop = false;
|
||||
#endif
|
||||
#if defined(Y_MIN_PIN) && Y_MIN_PIN >= 0
|
||||
static bool old_y_min_endstop = false;
|
||||
#endif
|
||||
#if defined(Y_MAX_PIN) && Y_MAX_PIN >= 0
|
||||
static bool old_y_max_endstop = false;
|
||||
#endif
|
||||
#if defined(Z_MIN_PIN) && Z_MIN_PIN >= 0
|
||||
static bool old_z_min_endstop = false;
|
||||
#endif
|
||||
#if defined(Z_MAX_PIN) && Z_MAX_PIN >= 0
|
||||
static bool old_z_max_endstop = false;
|
||||
#endif
|
||||
#ifdef Z_DUAL_ENDSTOPS
|
||||
#if defined(Z2_MIN_PIN) && Z2_MIN_PIN >= 0
|
||||
static bool old_z2_min_endstop = false;
|
||||
#endif
|
||||
#if defined(Z2_MAX_PIN) && Z2_MAX_PIN >= 0
|
||||
static bool old_z2_max_endstop = false;
|
||||
#endif
|
||||
#endif
|
||||
|
||||
static bool check_endstops = true;
|
||||
|
||||
|
@ -1192,7 +1206,7 @@ void microstep_init() {
|
|||
pinMode(E0_MS2_PIN,OUTPUT);
|
||||
const uint8_t microstep_modes[] = MICROSTEP_MODES;
|
||||
for (int i = 0; i < sizeof(microstep_modes) / sizeof(microstep_modes[0]); i++)
|
||||
microstep_mode(i, microstep_modes[i]);
|
||||
microstep_mode(i, microstep_modes[i]);
|
||||
#endif
|
||||
}
|
||||
|
||||
|
|
|
@ -586,7 +586,9 @@ void manage_heater() {
|
|||
if (ct < max(HEATER_0_MINTEMP, 0.01)) min_temp_error(0);
|
||||
#endif //HEATER_0_USES_MAX6675
|
||||
|
||||
unsigned long ms = millis();
|
||||
#if defined(WATCH_TEMP_PERIOD) || !defined(PIDTEMPBED) || HAS_AUTO_FAN
|
||||
unsigned long ms = millis();
|
||||
#endif
|
||||
|
||||
// Loop through all extruders
|
||||
for (int e = 0; e < EXTRUDERS; e++) {
|
||||
|
|
|
@ -25,10 +25,6 @@ int absPreheatFanSpeed;
|
|||
unsigned long message_millis = 0;
|
||||
#endif
|
||||
|
||||
#ifdef ULTIPANEL
|
||||
static float manual_feedrate[] = MANUAL_FEEDRATE;
|
||||
#endif // ULTIPANEL
|
||||
|
||||
/* !Configuration settings */
|
||||
|
||||
//Function pointer to menu functions.
|
||||
|
@ -38,193 +34,197 @@ uint8_t lcd_status_message_level;
|
|||
char lcd_status_message[LCD_WIDTH+1] = WELCOME_MSG;
|
||||
|
||||
#ifdef DOGLCD
|
||||
#include "dogm_lcd_implementation.h"
|
||||
#include "dogm_lcd_implementation.h"
|
||||
#else
|
||||
#include "ultralcd_implementation_hitachi_HD44780.h"
|
||||
#include "ultralcd_implementation_hitachi_HD44780.h"
|
||||
#endif
|
||||
|
||||
/* Different menus */
|
||||
// The main status screen
|
||||
static void lcd_status_screen();
|
||||
|
||||
#ifdef ULTIPANEL
|
||||
extern bool powersupply;
|
||||
static void lcd_main_menu();
|
||||
static void lcd_tune_menu();
|
||||
static void lcd_prepare_menu();
|
||||
static void lcd_move_menu();
|
||||
static void lcd_control_menu();
|
||||
static void lcd_control_temperature_menu();
|
||||
static void lcd_control_temperature_preheat_pla_settings_menu();
|
||||
static void lcd_control_temperature_preheat_abs_settings_menu();
|
||||
static void lcd_control_motion_menu();
|
||||
static void lcd_control_volumetric_menu();
|
||||
#ifdef DOGLCD
|
||||
static void lcd_set_contrast();
|
||||
#endif
|
||||
#ifdef FWRETRACT
|
||||
static void lcd_control_retract_menu();
|
||||
#endif
|
||||
static void lcd_sdcard_menu();
|
||||
|
||||
#ifdef DELTA_CALIBRATION_MENU
|
||||
static void lcd_delta_calibrate_menu();
|
||||
#endif // DELTA_CALIBRATION_MENU
|
||||
|
||||
#if defined(MANUAL_BED_LEVELING)
|
||||
#include "mesh_bed_leveling.h"
|
||||
static void _lcd_level_bed();
|
||||
static void _lcd_level_bed_homing();
|
||||
static void lcd_level_bed();
|
||||
#endif // MANUAL_BED_LEVELING
|
||||
|
||||
static void lcd_quick_feedback();//Cause an LCD refresh, and give the user visual or audible feedback that something has happened
|
||||
|
||||
/* Different types of actions that can be used in menu items. */
|
||||
static void menu_action_back(menuFunc_t data);
|
||||
static void menu_action_submenu(menuFunc_t data);
|
||||
static void menu_action_gcode(const char* pgcode);
|
||||
static void menu_action_function(menuFunc_t data);
|
||||
static void menu_action_sdfile(const char* filename, char* longFilename);
|
||||
static void menu_action_sddirectory(const char* filename, char* longFilename);
|
||||
static void menu_action_setting_edit_bool(const char* pstr, bool* ptr);
|
||||
static void menu_action_setting_edit_int3(const char* pstr, int* ptr, int minValue, int maxValue);
|
||||
static void menu_action_setting_edit_float3(const char* pstr, float* ptr, float minValue, float maxValue);
|
||||
static void menu_action_setting_edit_float32(const char* pstr, float* ptr, float minValue, float maxValue);
|
||||
static void menu_action_setting_edit_float43(const char* pstr, float* ptr, float minValue, float maxValue);
|
||||
static void menu_action_setting_edit_float5(const char* pstr, float* ptr, float minValue, float maxValue);
|
||||
static void menu_action_setting_edit_float51(const char* pstr, float* ptr, float minValue, float maxValue);
|
||||
static void menu_action_setting_edit_float52(const char* pstr, float* ptr, float minValue, float maxValue);
|
||||
static void menu_action_setting_edit_long5(const char* pstr, unsigned long* ptr, unsigned long minValue, unsigned long maxValue);
|
||||
static void menu_action_setting_edit_callback_bool(const char* pstr, bool* ptr, menuFunc_t callbackFunc);
|
||||
static void menu_action_setting_edit_callback_int3(const char* pstr, int* ptr, int minValue, int maxValue, menuFunc_t callbackFunc);
|
||||
static void menu_action_setting_edit_callback_float3(const char* pstr, float* ptr, float minValue, float maxValue, menuFunc_t callbackFunc);
|
||||
static void menu_action_setting_edit_callback_float32(const char* pstr, float* ptr, float minValue, float maxValue, menuFunc_t callbackFunc);
|
||||
static void menu_action_setting_edit_callback_float43(const char* pstr, float* ptr, float minValue, float maxValue, menuFunc_t callbackFunc);
|
||||
static void menu_action_setting_edit_callback_float5(const char* pstr, float* ptr, float minValue, float maxValue, menuFunc_t callbackFunc);
|
||||
static void menu_action_setting_edit_callback_float51(const char* pstr, float* ptr, float minValue, float maxValue, menuFunc_t callbackFunc);
|
||||
static void menu_action_setting_edit_callback_float52(const char* pstr, float* ptr, float minValue, float maxValue, menuFunc_t callbackFunc);
|
||||
static void menu_action_setting_edit_callback_long5(const char* pstr, unsigned long* ptr, unsigned long minValue, unsigned long maxValue, menuFunc_t callbackFunc);
|
||||
|
||||
#define ENCODER_FEEDRATE_DEADZONE 10
|
||||
|
||||
#if !defined(LCD_I2C_VIKI)
|
||||
#ifndef ENCODER_STEPS_PER_MENU_ITEM
|
||||
#define ENCODER_STEPS_PER_MENU_ITEM 5
|
||||
extern bool powersupply;
|
||||
static float manual_feedrate[] = MANUAL_FEEDRATE;
|
||||
static void lcd_main_menu();
|
||||
static void lcd_tune_menu();
|
||||
static void lcd_prepare_menu();
|
||||
static void lcd_move_menu();
|
||||
static void lcd_control_menu();
|
||||
static void lcd_control_temperature_menu();
|
||||
static void lcd_control_temperature_preheat_pla_settings_menu();
|
||||
static void lcd_control_temperature_preheat_abs_settings_menu();
|
||||
static void lcd_control_motion_menu();
|
||||
static void lcd_control_volumetric_menu();
|
||||
#ifdef DOGLCD
|
||||
static void lcd_set_contrast();
|
||||
#endif
|
||||
#ifndef ENCODER_PULSES_PER_STEP
|
||||
#define ENCODER_PULSES_PER_STEP 1
|
||||
#ifdef FWRETRACT
|
||||
static void lcd_control_retract_menu();
|
||||
#endif
|
||||
#else
|
||||
#ifndef ENCODER_STEPS_PER_MENU_ITEM
|
||||
#define ENCODER_STEPS_PER_MENU_ITEM 2 // VIKI LCD rotary encoder uses a different number of steps per rotation
|
||||
static void lcd_sdcard_menu();
|
||||
|
||||
#ifdef DELTA_CALIBRATION_MENU
|
||||
static void lcd_delta_calibrate_menu();
|
||||
#endif
|
||||
#ifndef ENCODER_PULSES_PER_STEP
|
||||
#define ENCODER_PULSES_PER_STEP 1
|
||||
|
||||
#if defined(MANUAL_BED_LEVELING)
|
||||
#include "mesh_bed_leveling.h"
|
||||
static void _lcd_level_bed();
|
||||
static void _lcd_level_bed_homing();
|
||||
static void lcd_level_bed();
|
||||
#endif
|
||||
|
||||
static void lcd_quick_feedback();//Cause an LCD refresh, and give the user visual or audible feedback that something has happened
|
||||
|
||||
/* Different types of actions that can be used in menu items. */
|
||||
static void menu_action_back(menuFunc_t data);
|
||||
static void menu_action_submenu(menuFunc_t data);
|
||||
static void menu_action_gcode(const char* pgcode);
|
||||
static void menu_action_function(menuFunc_t data);
|
||||
static void menu_action_sdfile(const char* filename, char* longFilename);
|
||||
static void menu_action_sddirectory(const char* filename, char* longFilename);
|
||||
static void menu_action_setting_edit_bool(const char* pstr, bool* ptr);
|
||||
static void menu_action_setting_edit_int3(const char* pstr, int* ptr, int minValue, int maxValue);
|
||||
static void menu_action_setting_edit_float3(const char* pstr, float* ptr, float minValue, float maxValue);
|
||||
static void menu_action_setting_edit_float32(const char* pstr, float* ptr, float minValue, float maxValue);
|
||||
static void menu_action_setting_edit_float43(const char* pstr, float* ptr, float minValue, float maxValue);
|
||||
static void menu_action_setting_edit_float5(const char* pstr, float* ptr, float minValue, float maxValue);
|
||||
static void menu_action_setting_edit_float51(const char* pstr, float* ptr, float minValue, float maxValue);
|
||||
static void menu_action_setting_edit_float52(const char* pstr, float* ptr, float minValue, float maxValue);
|
||||
static void menu_action_setting_edit_long5(const char* pstr, unsigned long* ptr, unsigned long minValue, unsigned long maxValue);
|
||||
static void menu_action_setting_edit_callback_bool(const char* pstr, bool* ptr, menuFunc_t callbackFunc);
|
||||
static void menu_action_setting_edit_callback_int3(const char* pstr, int* ptr, int minValue, int maxValue, menuFunc_t callbackFunc);
|
||||
static void menu_action_setting_edit_callback_float3(const char* pstr, float* ptr, float minValue, float maxValue, menuFunc_t callbackFunc);
|
||||
static void menu_action_setting_edit_callback_float32(const char* pstr, float* ptr, float minValue, float maxValue, menuFunc_t callbackFunc);
|
||||
static void menu_action_setting_edit_callback_float43(const char* pstr, float* ptr, float minValue, float maxValue, menuFunc_t callbackFunc);
|
||||
static void menu_action_setting_edit_callback_float5(const char* pstr, float* ptr, float minValue, float maxValue, menuFunc_t callbackFunc);
|
||||
static void menu_action_setting_edit_callback_float51(const char* pstr, float* ptr, float minValue, float maxValue, menuFunc_t callbackFunc);
|
||||
static void menu_action_setting_edit_callback_float52(const char* pstr, float* ptr, float minValue, float maxValue, menuFunc_t callbackFunc);
|
||||
static void menu_action_setting_edit_callback_long5(const char* pstr, unsigned long* ptr, unsigned long minValue, unsigned long maxValue, menuFunc_t callbackFunc);
|
||||
|
||||
#define ENCODER_FEEDRATE_DEADZONE 10
|
||||
|
||||
#if !defined(LCD_I2C_VIKI)
|
||||
#ifndef ENCODER_STEPS_PER_MENU_ITEM
|
||||
#define ENCODER_STEPS_PER_MENU_ITEM 5
|
||||
#endif
|
||||
#ifndef ENCODER_PULSES_PER_STEP
|
||||
#define ENCODER_PULSES_PER_STEP 1
|
||||
#endif
|
||||
#else
|
||||
#ifndef ENCODER_STEPS_PER_MENU_ITEM
|
||||
#define ENCODER_STEPS_PER_MENU_ITEM 2 // VIKI LCD rotary encoder uses a different number of steps per rotation
|
||||
#endif
|
||||
#ifndef ENCODER_PULSES_PER_STEP
|
||||
#define ENCODER_PULSES_PER_STEP 1
|
||||
#endif
|
||||
#endif
|
||||
#endif
|
||||
|
||||
|
||||
/* Helper macros for menus */
|
||||
/* Helper macros for menus */
|
||||
|
||||
/**
|
||||
* START_MENU generates the init code for a menu function
|
||||
*/
|
||||
#define START_MENU() do { \
|
||||
encoderRateMultiplierEnabled = false; \
|
||||
if (encoderPosition > 0x8000) encoderPosition = 0; \
|
||||
uint8_t encoderLine = encoderPosition / ENCODER_STEPS_PER_MENU_ITEM; \
|
||||
if (encoderLine < currentMenuViewOffset) currentMenuViewOffset = encoderLine; \
|
||||
uint8_t _lineNr = currentMenuViewOffset, _menuItemNr; \
|
||||
bool wasClicked = LCD_CLICKED, itemSelected; \
|
||||
if (wasClicked) lcd_quick_feedback(); \
|
||||
for (uint8_t _drawLineNr = 0; _drawLineNr < LCD_HEIGHT; _drawLineNr++, _lineNr++) { \
|
||||
_menuItemNr = 0;
|
||||
|
||||
/**
|
||||
* MENU_ITEM generates draw & handler code for a menu item, potentially calling:
|
||||
*
|
||||
* lcd_implementation_drawmenu_[type](sel, row, label, arg3...)
|
||||
* menu_action_[type](arg3...)
|
||||
*
|
||||
* Examples:
|
||||
* MENU_ITEM(back, MSG_WATCH, lcd_status_screen)
|
||||
* lcd_implementation_drawmenu_back(sel, row, PSTR(MSG_WATCH), lcd_status_screen)
|
||||
* menu_action_back(lcd_status_screen)
|
||||
*
|
||||
* MENU_ITEM(function, MSG_PAUSE_PRINT, lcd_sdcard_pause)
|
||||
* lcd_implementation_drawmenu_function(sel, row, PSTR(MSG_PAUSE_PRINT), lcd_sdcard_pause)
|
||||
* menu_action_function(lcd_sdcard_pause)
|
||||
*
|
||||
* MENU_ITEM_EDIT(int3, MSG_SPEED, &feedmultiply, 10, 999)
|
||||
* MENU_ITEM(setting_edit_int3, MSG_SPEED, PSTR(MSG_SPEED), &feedmultiply, 10, 999)
|
||||
* lcd_implementation_drawmenu_setting_edit_int3(sel, row, PSTR(MSG_SPEED), PSTR(MSG_SPEED), &feedmultiply, 10, 999)
|
||||
* menu_action_setting_edit_int3(PSTR(MSG_SPEED), &feedmultiply, 10, 999)
|
||||
*
|
||||
*/
|
||||
#define MENU_ITEM(type, label, args...) do { \
|
||||
if (_menuItemNr == _lineNr) { \
|
||||
itemSelected = encoderLine == _menuItemNr; \
|
||||
if (lcdDrawUpdate) \
|
||||
lcd_implementation_drawmenu_ ## type(itemSelected, _drawLineNr, PSTR(label), ## args); \
|
||||
if (wasClicked && itemSelected) { \
|
||||
menu_action_ ## type(args); \
|
||||
return; \
|
||||
} \
|
||||
} \
|
||||
_menuItemNr++; \
|
||||
} while(0)
|
||||
|
||||
#ifdef ENCODER_RATE_MULTIPLIER
|
||||
/**
|
||||
* MENU_MULTIPLIER_ITEM generates drawing and handling code for a multiplier menu item
|
||||
* START_MENU generates the init code for a menu function
|
||||
*/
|
||||
#define MENU_MULTIPLIER_ITEM(type, label, args...) do { \
|
||||
#define START_MENU() do { \
|
||||
encoderRateMultiplierEnabled = false; \
|
||||
if (encoderPosition > 0x8000) encoderPosition = 0; \
|
||||
uint8_t encoderLine = encoderPosition / ENCODER_STEPS_PER_MENU_ITEM; \
|
||||
if (encoderLine < currentMenuViewOffset) currentMenuViewOffset = encoderLine; \
|
||||
uint8_t _lineNr = currentMenuViewOffset, _menuItemNr; \
|
||||
bool wasClicked = LCD_CLICKED, itemSelected; \
|
||||
if (wasClicked) lcd_quick_feedback(); \
|
||||
for (uint8_t _drawLineNr = 0; _drawLineNr < LCD_HEIGHT; _drawLineNr++, _lineNr++) { \
|
||||
_menuItemNr = 0;
|
||||
|
||||
/**
|
||||
* MENU_ITEM generates draw & handler code for a menu item, potentially calling:
|
||||
*
|
||||
* lcd_implementation_drawmenu_[type](sel, row, label, arg3...)
|
||||
* menu_action_[type](arg3...)
|
||||
*
|
||||
* Examples:
|
||||
* MENU_ITEM(back, MSG_WATCH, lcd_status_screen)
|
||||
* lcd_implementation_drawmenu_back(sel, row, PSTR(MSG_WATCH), lcd_status_screen)
|
||||
* menu_action_back(lcd_status_screen)
|
||||
*
|
||||
* MENU_ITEM(function, MSG_PAUSE_PRINT, lcd_sdcard_pause)
|
||||
* lcd_implementation_drawmenu_function(sel, row, PSTR(MSG_PAUSE_PRINT), lcd_sdcard_pause)
|
||||
* menu_action_function(lcd_sdcard_pause)
|
||||
*
|
||||
* MENU_ITEM_EDIT(int3, MSG_SPEED, &feedmultiply, 10, 999)
|
||||
* MENU_ITEM(setting_edit_int3, MSG_SPEED, PSTR(MSG_SPEED), &feedmultiply, 10, 999)
|
||||
* lcd_implementation_drawmenu_setting_edit_int3(sel, row, PSTR(MSG_SPEED), PSTR(MSG_SPEED), &feedmultiply, 10, 999)
|
||||
* menu_action_setting_edit_int3(PSTR(MSG_SPEED), &feedmultiply, 10, 999)
|
||||
*
|
||||
*/
|
||||
#define MENU_ITEM(type, label, args...) do { \
|
||||
if (_menuItemNr == _lineNr) { \
|
||||
itemSelected = encoderLine == _menuItemNr; \
|
||||
if (lcdDrawUpdate) \
|
||||
lcd_implementation_drawmenu_ ## type(itemSelected, _drawLineNr, PSTR(label), ## args); \
|
||||
if (wasClicked && itemSelected) { \
|
||||
encoderRateMultiplierEnabled = true; \
|
||||
lastEncoderMovementMillis = 0; \
|
||||
menu_action_ ## type(args); \
|
||||
return; \
|
||||
} \
|
||||
} \
|
||||
_menuItemNr++; \
|
||||
} while(0)
|
||||
#endif //ENCODER_RATE_MULTIPLIER
|
||||
|
||||
#define MENU_ITEM_DUMMY() do { _menuItemNr++; } while(0)
|
||||
#define MENU_ITEM_EDIT(type, label, args...) MENU_ITEM(setting_edit_ ## type, label, PSTR(label), ## args)
|
||||
#define MENU_ITEM_EDIT_CALLBACK(type, label, args...) MENU_ITEM(setting_edit_callback_ ## type, label, PSTR(label), ## args)
|
||||
#ifdef ENCODER_RATE_MULTIPLIER
|
||||
#define MENU_MULTIPLIER_ITEM_EDIT(type, label, args...) MENU_MULTIPLIER_ITEM(setting_edit_ ## type, label, PSTR(label), ## args)
|
||||
#define MENU_MULTIPLIER_ITEM_EDIT_CALLBACK(type, label, args...) MENU_MULTIPLIER_ITEM(setting_edit_callback_ ## type, label, PSTR(label), ## args)
|
||||
#else //!ENCODER_RATE_MULTIPLIER
|
||||
#define MENU_MULTIPLIER_ITEM_EDIT(type, label, args...) MENU_ITEM(setting_edit_ ## type, label, PSTR(label), ## args)
|
||||
#define MENU_MULTIPLIER_ITEM_EDIT_CALLBACK(type, label, args...) MENU_ITEM(setting_edit_callback_ ## type, label, PSTR(label), ## args)
|
||||
#endif //!ENCODER_RATE_MULTIPLIER
|
||||
#define END_MENU() \
|
||||
if (encoderLine >= _menuItemNr) { encoderPosition = _menuItemNr * ENCODER_STEPS_PER_MENU_ITEM - 1; encoderLine = encoderPosition / ENCODER_STEPS_PER_MENU_ITEM; }\
|
||||
if (encoderLine >= currentMenuViewOffset + LCD_HEIGHT) { currentMenuViewOffset = encoderLine - LCD_HEIGHT + 1; lcdDrawUpdate = 1; _lineNr = currentMenuViewOffset - 1; _drawLineNr = -1; } \
|
||||
} } while(0)
|
||||
#ifdef ENCODER_RATE_MULTIPLIER
|
||||
/**
|
||||
* MENU_MULTIPLIER_ITEM generates drawing and handling code for a multiplier menu item
|
||||
*/
|
||||
#define MENU_MULTIPLIER_ITEM(type, label, args...) do { \
|
||||
if (_menuItemNr == _lineNr) { \
|
||||
itemSelected = encoderLine == _menuItemNr; \
|
||||
if (lcdDrawUpdate) \
|
||||
lcd_implementation_drawmenu_ ## type(itemSelected, _drawLineNr, PSTR(label), ## args); \
|
||||
if (wasClicked && itemSelected) { \
|
||||
encoderRateMultiplierEnabled = true; \
|
||||
lastEncoderMovementMillis = 0; \
|
||||
menu_action_ ## type(args); \
|
||||
return; \
|
||||
} \
|
||||
} \
|
||||
_menuItemNr++; \
|
||||
} while(0)
|
||||
#endif //ENCODER_RATE_MULTIPLIER
|
||||
|
||||
/** Used variables to keep track of the menu */
|
||||
#ifndef REPRAPWORLD_KEYPAD
|
||||
volatile uint8_t buttons;//Contains the bits of the currently pressed buttons.
|
||||
#else
|
||||
volatile uint8_t buttons_reprapworld_keypad; // to store the reprapworld_keypad shift register values
|
||||
#endif
|
||||
#ifdef LCD_HAS_SLOW_BUTTONS
|
||||
volatile uint8_t slow_buttons;//Contains the bits of the currently pressed buttons.
|
||||
#endif
|
||||
uint8_t currentMenuViewOffset; /* scroll offset in the current menu */
|
||||
uint32_t blocking_enc;
|
||||
uint8_t lastEncoderBits;
|
||||
uint32_t encoderPosition;
|
||||
#if (SDCARDDETECT > 0)
|
||||
bool lcd_oldcardstatus;
|
||||
#endif
|
||||
#endif //ULTIPANEL
|
||||
#define MENU_ITEM_DUMMY() do { _menuItemNr++; } while(0)
|
||||
#define MENU_ITEM_EDIT(type, label, args...) MENU_ITEM(setting_edit_ ## type, label, PSTR(label), ## args)
|
||||
#define MENU_ITEM_EDIT_CALLBACK(type, label, args...) MENU_ITEM(setting_edit_callback_ ## type, label, PSTR(label), ## args)
|
||||
#ifdef ENCODER_RATE_MULTIPLIER
|
||||
#define MENU_MULTIPLIER_ITEM_EDIT(type, label, args...) MENU_MULTIPLIER_ITEM(setting_edit_ ## type, label, PSTR(label), ## args)
|
||||
#define MENU_MULTIPLIER_ITEM_EDIT_CALLBACK(type, label, args...) MENU_MULTIPLIER_ITEM(setting_edit_callback_ ## type, label, PSTR(label), ## args)
|
||||
#else //!ENCODER_RATE_MULTIPLIER
|
||||
#define MENU_MULTIPLIER_ITEM_EDIT(type, label, args...) MENU_ITEM(setting_edit_ ## type, label, PSTR(label), ## args)
|
||||
#define MENU_MULTIPLIER_ITEM_EDIT_CALLBACK(type, label, args...) MENU_ITEM(setting_edit_callback_ ## type, label, PSTR(label), ## args)
|
||||
#endif //!ENCODER_RATE_MULTIPLIER
|
||||
#define END_MENU() \
|
||||
if (encoderLine >= _menuItemNr) { encoderPosition = _menuItemNr * ENCODER_STEPS_PER_MENU_ITEM - 1; encoderLine = encoderPosition / ENCODER_STEPS_PER_MENU_ITEM; }\
|
||||
if (encoderLine >= currentMenuViewOffset + LCD_HEIGHT) { currentMenuViewOffset = encoderLine - LCD_HEIGHT + 1; lcdDrawUpdate = 1; _lineNr = currentMenuViewOffset - 1; _drawLineNr = -1; } \
|
||||
} } while(0)
|
||||
|
||||
/** Used variables to keep track of the menu */
|
||||
#ifndef REPRAPWORLD_KEYPAD
|
||||
volatile uint8_t buttons; // Bits of the pressed buttons.
|
||||
#else
|
||||
volatile uint8_t buttons_reprapworld_keypad; // The reprapworld_keypad shift register values
|
||||
#endif
|
||||
#ifdef LCD_HAS_SLOW_BUTTONS
|
||||
volatile uint8_t slow_buttons; // Bits of the pressed buttons.
|
||||
#endif
|
||||
uint8_t currentMenuViewOffset; /* scroll offset in the current menu */
|
||||
uint32_t blocking_enc;
|
||||
uint8_t lastEncoderBits;
|
||||
uint32_t encoderPosition;
|
||||
#if (SDCARDDETECT > 0)
|
||||
bool lcd_oldcardstatus;
|
||||
#endif
|
||||
|
||||
#endif // ULTIPANEL
|
||||
|
||||
menuFunc_t currentMenu = lcd_status_screen; /* function pointer to the currently active menu */
|
||||
uint32_t lcd_next_update_millis;
|
||||
|
@ -520,22 +520,21 @@ void _lcd_preheat(int endnum, const float temph, const float tempb, const int fa
|
|||
void lcd_preheat_pla0() { _lcd_preheat(0, plaPreheatHotendTemp, plaPreheatHPBTemp, plaPreheatFanSpeed); }
|
||||
void lcd_preheat_abs0() { _lcd_preheat(0, absPreheatHotendTemp, absPreheatHPBTemp, absPreheatFanSpeed); }
|
||||
|
||||
#if TEMP_SENSOR_1 != 0 //2nd extruder preheat
|
||||
void lcd_preheat_pla1() { _lcd_preheat(1, plaPreheatHotendTemp, plaPreheatHPBTemp, plaPreheatFanSpeed); }
|
||||
void lcd_preheat_abs1() { _lcd_preheat(1, absPreheatHotendTemp, absPreheatHPBTemp, absPreheatFanSpeed); }
|
||||
#endif //2nd extruder preheat
|
||||
#if TEMP_SENSOR_1 != 0 || TEMP_SENSOR_2 != 0 || TEMP_SENSOR_3 != 0 || TEMP_SENSOR_BED != 0 //more than one extruder present
|
||||
|
||||
#if TEMP_SENSOR_2 != 0 //3 extruder preheat
|
||||
void lcd_preheat_pla2() { _lcd_preheat(2, plaPreheatHotendTemp, plaPreheatHPBTemp, plaPreheatFanSpeed); }
|
||||
void lcd_preheat_abs2() { _lcd_preheat(2, absPreheatHotendTemp, absPreheatHPBTemp, absPreheatFanSpeed); }
|
||||
#endif //3 extruder preheat
|
||||
#if TEMP_SENSOR_1 != 0
|
||||
void lcd_preheat_pla1() { _lcd_preheat(1, plaPreheatHotendTemp, plaPreheatHPBTemp, plaPreheatFanSpeed); }
|
||||
void lcd_preheat_abs1() { _lcd_preheat(1, absPreheatHotendTemp, absPreheatHPBTemp, absPreheatFanSpeed); }
|
||||
#endif
|
||||
#if TEMP_SENSOR_2 != 0
|
||||
void lcd_preheat_pla2() { _lcd_preheat(2, plaPreheatHotendTemp, plaPreheatHPBTemp, plaPreheatFanSpeed); }
|
||||
void lcd_preheat_abs2() { _lcd_preheat(2, absPreheatHotendTemp, absPreheatHPBTemp, absPreheatFanSpeed); }
|
||||
#endif
|
||||
#if TEMP_SENSOR_3 != 0
|
||||
void lcd_preheat_pla3() { _lcd_preheat(3, plaPreheatHotendTemp, plaPreheatHPBTemp, plaPreheatFanSpeed); }
|
||||
void lcd_preheat_abs3() { _lcd_preheat(3, absPreheatHotendTemp, absPreheatHPBTemp, absPreheatFanSpeed); }
|
||||
#endif
|
||||
|
||||
#if TEMP_SENSOR_3 != 0 //4 extruder preheat
|
||||
void lcd_preheat_pla3() { _lcd_preheat(3, plaPreheatHotendTemp, plaPreheatHPBTemp, plaPreheatFanSpeed); }
|
||||
void lcd_preheat_abs3() { _lcd_preheat(3, absPreheatHotendTemp, absPreheatHPBTemp, absPreheatFanSpeed); }
|
||||
#endif //4 extruder preheat
|
||||
|
||||
#if TEMP_SENSOR_1 != 0 || TEMP_SENSOR_2 != 0 || TEMP_SENSOR_3 != 0 //more than one extruder present
|
||||
void lcd_preheat_pla0123() {
|
||||
setTargetHotend0(plaPreheatHotendTemp);
|
||||
setTargetHotend1(plaPreheatHotendTemp);
|
||||
|
@ -548,54 +547,54 @@ void lcd_preheat_abs0() { _lcd_preheat(0, absPreheatHotendTemp, absPreheatHPBTem
|
|||
setTargetHotend2(absPreheatHotendTemp);
|
||||
_lcd_preheat(3, absPreheatHotendTemp, absPreheatHPBTemp, absPreheatFanSpeed);
|
||||
}
|
||||
#endif //more than one extruder present
|
||||
|
||||
void lcd_preheat_pla_bedonly() { _lcd_preheat(0, 0, plaPreheatHPBTemp, plaPreheatFanSpeed); }
|
||||
void lcd_preheat_abs_bedonly() { _lcd_preheat(0, 0, absPreheatHPBTemp, absPreheatFanSpeed); }
|
||||
#if TEMP_SENSOR_0 != 0
|
||||
|
||||
static void lcd_preheat_pla_menu() {
|
||||
START_MENU();
|
||||
MENU_ITEM(back, MSG_PREPARE, lcd_prepare_menu);
|
||||
MENU_ITEM(function, MSG_PREHEAT_PLA_N MSG_H1, lcd_preheat_pla0);
|
||||
#if TEMP_SENSOR_1 != 0 //2 extruder preheat
|
||||
MENU_ITEM(function, MSG_PREHEAT_PLA_N MSG_H2, lcd_preheat_pla1);
|
||||
#endif //2 extruder preheat
|
||||
#if TEMP_SENSOR_2 != 0 //3 extruder preheat
|
||||
MENU_ITEM(function, MSG_PREHEAT_PLA_N MSG_H3, lcd_preheat_pla2);
|
||||
#endif //3 extruder preheat
|
||||
#if TEMP_SENSOR_3 != 0 //4 extruder preheat
|
||||
MENU_ITEM(function, MSG_PREHEAT_PLA_N MSG_H4, lcd_preheat_pla3);
|
||||
#endif //4 extruder preheat
|
||||
#if TEMP_SENSOR_1 != 0 || TEMP_SENSOR_2 != 0 || TEMP_SENSOR_3 != 0 //all extruder preheat
|
||||
MENU_ITEM(function, MSG_PREHEAT_PLA_ALL, lcd_preheat_pla0123);
|
||||
#endif //all extruder preheat
|
||||
#if TEMP_SENSOR_BED != 0
|
||||
MENU_ITEM(function, MSG_PREHEAT_PLA_BEDONLY, lcd_preheat_pla_bedonly);
|
||||
void lcd_preheat_pla_bedonly() { _lcd_preheat(0, 0, plaPreheatHPBTemp, plaPreheatFanSpeed); }
|
||||
void lcd_preheat_abs_bedonly() { _lcd_preheat(0, 0, absPreheatHPBTemp, absPreheatFanSpeed); }
|
||||
|
||||
static void lcd_preheat_pla_menu() {
|
||||
START_MENU();
|
||||
MENU_ITEM(back, MSG_PREPARE, lcd_prepare_menu);
|
||||
MENU_ITEM(function, MSG_PREHEAT_PLA_N MSG_H1, lcd_preheat_pla0);
|
||||
#if TEMP_SENSOR_1 != 0
|
||||
MENU_ITEM(function, MSG_PREHEAT_PLA_N MSG_H2, lcd_preheat_pla1);
|
||||
#endif
|
||||
#if TEMP_SENSOR_2 != 0
|
||||
MENU_ITEM(function, MSG_PREHEAT_PLA_N MSG_H3, lcd_preheat_pla2);
|
||||
#endif
|
||||
#if TEMP_SENSOR_3 != 0
|
||||
MENU_ITEM(function, MSG_PREHEAT_PLA_N MSG_H4, lcd_preheat_pla3);
|
||||
#endif
|
||||
MENU_ITEM(function, MSG_PREHEAT_PLA_ALL, lcd_preheat_pla0123);
|
||||
#if TEMP_SENSOR_BED != 0
|
||||
MENU_ITEM(function, MSG_PREHEAT_PLA_BEDONLY, lcd_preheat_pla_bedonly);
|
||||
#endif
|
||||
END_MENU();
|
||||
}
|
||||
|
||||
static void lcd_preheat_abs_menu() {
|
||||
START_MENU();
|
||||
MENU_ITEM(back, MSG_PREPARE, lcd_prepare_menu);
|
||||
MENU_ITEM(function, MSG_PREHEAT_ABS_N MSG_H1, lcd_preheat_abs0);
|
||||
#if TEMP_SENSOR_1 != 0
|
||||
MENU_ITEM(function, MSG_PREHEAT_ABS_N MSG_H2, lcd_preheat_abs1);
|
||||
#endif
|
||||
#if TEMP_SENSOR_2 != 0
|
||||
MENU_ITEM(function, MSG_PREHEAT_ABS_N MSG_H3, lcd_preheat_abs2);
|
||||
#endif
|
||||
#if TEMP_SENSOR_3 != 0
|
||||
MENU_ITEM(function, MSG_PREHEAT_ABS_N MSG_H4, lcd_preheat_abs3);
|
||||
#endif
|
||||
MENU_ITEM(function, MSG_PREHEAT_ABS_ALL, lcd_preheat_abs0123);
|
||||
#if TEMP_SENSOR_BED != 0
|
||||
MENU_ITEM(function, MSG_PREHEAT_ABS_BEDONLY, lcd_preheat_abs_bedonly);
|
||||
#endif
|
||||
END_MENU();
|
||||
}
|
||||
#endif
|
||||
END_MENU();
|
||||
}
|
||||
|
||||
static void lcd_preheat_abs_menu() {
|
||||
START_MENU();
|
||||
MENU_ITEM(back, MSG_PREPARE, lcd_prepare_menu);
|
||||
MENU_ITEM(function, MSG_PREHEAT_ABS_N MSG_H1, lcd_preheat_abs0);
|
||||
#if TEMP_SENSOR_1 != 0 //2 extruder preheat
|
||||
MENU_ITEM(function, MSG_PREHEAT_ABS_N MSG_H2, lcd_preheat_abs1);
|
||||
#endif //2 extruder preheat
|
||||
#if TEMP_SENSOR_2 != 0 //3 extruder preheat
|
||||
MENU_ITEM(function, MSG_PREHEAT_ABS_N MSG_H3, lcd_preheat_abs2);
|
||||
#endif //3 extruder preheat
|
||||
#if TEMP_SENSOR_3 != 0 //4 extruder preheat
|
||||
MENU_ITEM(function, MSG_PREHEAT_ABS_N MSG_H4, lcd_preheat_abs3);
|
||||
#endif //4 extruder preheat
|
||||
#if TEMP_SENSOR_1 != 0 || TEMP_SENSOR_2 != 0 || TEMP_SENSOR_3 != 0 //all extruder preheat
|
||||
MENU_ITEM(function, MSG_PREHEAT_ABS_ALL, lcd_preheat_abs0123);
|
||||
#endif //all extruder preheat
|
||||
#if TEMP_SENSOR_BED != 0
|
||||
MENU_ITEM(function, MSG_PREHEAT_ABS_BEDONLY, lcd_preheat_abs_bedonly);
|
||||
#endif
|
||||
END_MENU();
|
||||
}
|
||||
#endif // more than one temperature sensor present
|
||||
|
||||
void lcd_cooldown() {
|
||||
setTargetHotend0(0);
|
||||
|
@ -618,7 +617,7 @@ static void lcd_prepare_menu() {
|
|||
MENU_ITEM(function, MSG_SET_HOME_OFFSETS, lcd_set_home_offsets);
|
||||
//MENU_ITEM(gcode, MSG_SET_ORIGIN, PSTR("G92 X0 Y0 Z0"));
|
||||
#if TEMP_SENSOR_0 != 0
|
||||
#if TEMP_SENSOR_1 != 0 || TEMP_SENSOR_2 != 0 || TEMP_SENSOR_BED != 0
|
||||
#if TEMP_SENSOR_1 != 0 || TEMP_SENSOR_2 != 0 || TEMP_SENSOR_3 != 0 || TEMP_SENSOR_BED != 0
|
||||
MENU_ITEM(submenu, MSG_PREHEAT_PLA, lcd_preheat_pla_menu);
|
||||
MENU_ITEM(submenu, MSG_PREHEAT_ABS, lcd_preheat_abs_menu);
|
||||
#else
|
||||
|
|
|
@ -17,10 +17,9 @@
|
|||
#ifdef DOGLCD
|
||||
extern int lcd_contrast;
|
||||
void lcd_setcontrast(uint8_t value);
|
||||
static unsigned char blink = 0; // Variable for visualization of fan rotation in GLCD
|
||||
#endif
|
||||
|
||||
static unsigned char blink = 0; // Variable for visualization of fan rotation in GLCD
|
||||
|
||||
#define LCD_MESSAGEPGM(x) lcd_setstatuspgm(PSTR(x))
|
||||
#define LCD_ALERTMESSAGEPGM(x) lcd_setalertstatuspgm(PSTR(x))
|
||||
|
||||
|
|
Reference in a new issue