Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Use createChar_P to save SRAM in bootscreen #6965

Merged
merged 16 commits into from
Jun 7, 2017
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion Marlin/Conditionals_LCD.h
Original file line number Diff line number Diff line change
Expand Up @@ -243,7 +243,7 @@
/* Custom characters defined in the first 8 characters of the LCD */
#define LCD_BEDTEMP_CHAR 0x00 // Print only as a char. This will have 'unexpected' results when used in a string!
#define LCD_DEGREE_CHAR 0x01
#define LCD_STR_THERMOMETER "\x02" // Too many places use preprocessor string concatination to change this to a char right now.
#define LCD_STR_THERMOMETER "\x02" // Still used with string concatenation
#define LCD_UPLEVEL_CHAR 0x03
#define LCD_REFRESH_CHAR 0x04
#define LCD_STR_FOLDER "\x05"
Expand Down
6 changes: 4 additions & 2 deletions Marlin/Configuration.h
Original file line number Diff line number Diff line change
Expand Up @@ -881,12 +881,14 @@
#define UBL_MESH_INSET 1 // Mesh inset margin on print area
#define GRID_MAX_POINTS_X 10 // Don't use more than 15 points per axis, implementation limited.
#define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
#define UBL_PROBE_PT_1_X 39 // These set the probe locations for when UBL does a 3-Point leveling
#define UBL_PROBE_PT_1_Y 180 // of the mesh.

#define UBL_PROBE_PT_1_X 39 // Probing points for 3-Point leveling of the mesh
#define UBL_PROBE_PT_1_Y 180
#define UBL_PROBE_PT_2_X 39
#define UBL_PROBE_PT_2_Y 20
#define UBL_PROBE_PT_3_X 180
#define UBL_PROBE_PT_3_Y 20

#define UBL_G26_MESH_VALIDATION // Enable G26 mesh validation
#define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle

Expand Down
22 changes: 10 additions & 12 deletions Marlin/Configuration_adv.h
Original file line number Diff line number Diff line change
Expand Up @@ -225,13 +225,11 @@
*/
//#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
//#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

//===========================================================================
Expand Down Expand Up @@ -421,16 +419,16 @@
* M908 - BQ_ZUM_MEGA_3D, RAMBO, PRINTRBOARD_REVF, RIGIDBOARD_V2 & SCOOVO_X9H
* M909, M910 & LCD - only PRINTRBOARD_REVF & RIGIDBOARD_V2
*/
//#define PWM_MOTOR_CURRENT {1300, 1300, 1250} // Values in milliamps
//#define DIGIPOT_MOTOR_CURRENT {135,135,135,135,135} // Values 0-255 (RAMBO 135 = ~0.75A, 185 = ~1A)
//#define DAC_MOTOR_CURRENT_DEFAULT { 70, 80, 90, 80 } // Default drive percent - X, Y, Z, E axis
//#define PWM_MOTOR_CURRENT { 1300, 1300, 1250 } // Values in milliamps
//#define DIGIPOT_MOTOR_CURRENT { 135,135,135,135,135 } // Values 0-255 (RAMBO 135 = ~0.75A, 185 = ~1A)
//#define DAC_MOTOR_CURRENT_DEFAULT { 70, 80, 90, 80 } // Default drive percent - X, Y, Z, E axis

// Uncomment to enable an I2C based DIGIPOT like on the Azteeg X3 Pro
//#define DIGIPOT_I2C
//#define DIGIPOT_MCP4018
//#define DIGIPOT_MCP4018 // Requires library from https://github.com/stawel/SlowSoftI2CMaster
#define DIGIPOT_I2C_NUM_CHANNELS 8 // 5DPRINT: 4 AZTEEG_X3_PRO: 8
// Actual motor currents in Amps, need as many here as DIGIPOT_I2C_NUM_CHANNELS
#define DIGIPOT_I2C_MOTOR_CURRENTS {1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0} // AZTEEG_X3_PRO
#define DIGIPOT_I2C_MOTOR_CURRENTS { 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0 } // AZTEEG_X3_PRO

//===========================================================================
//=============================Additional Features===========================
Expand Down
16 changes: 8 additions & 8 deletions Marlin/G26_Mesh_Validation_Tool.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -252,8 +252,8 @@
// Move nozzle to the specified height for the first layer
set_destination_to_current();
destination[Z_AXIS] = g26_layer_height;
move_to(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], 0.0);
move_to(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], g26_ooze_amount);
move_to(destination, 0.0);
move_to(destination, g26_ooze_amount);

has_control_of_lcd_panel = true;
//debug_current_and_destination(PSTR("Starting G26 Mesh Validation Pattern."));
Expand Down Expand Up @@ -368,14 +368,14 @@
destination[Z_AXIS] = Z_CLEARANCE_BETWEEN_PROBES;

//debug_current_and_destination(PSTR("ready to do Z-Raise."));
move_to(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], 0); // Raise the nozzle
move_to(destination, 0); // Raise the nozzle
//debug_current_and_destination(PSTR("done doing Z-Raise."));

destination[X_AXIS] = g26_x_pos; // Move back to the starting position
destination[Y_AXIS] = g26_y_pos;
//destination[Z_AXIS] = Z_CLEARANCE_BETWEEN_PROBES; // Keep the nozzle where it is

move_to(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], 0); // Move back to the starting position
move_to(destination, 0); // Move back to the starting position
//debug_current_and_destination(PSTR("done doing X/Y move."));

has_control_of_lcd_panel = false; // Give back control of the LCD Panel!
Expand Down Expand Up @@ -554,16 +554,16 @@

}

void unified_bed_leveling::retract_filament(float where[XYZE]) {
void unified_bed_leveling::retract_filament(const float where[XYZE]) {
if (!g26_retracted) { // Only retract if we are not already retracted!
g26_retracted = true;
move_to(where[X_AXIS], where[Y_AXIS], where[Z_AXIS], -1.0 * g26_retraction_multiplier);
move_to(where, -1.0 * g26_retraction_multiplier);
}
}

void unified_bed_leveling::recover_filament(float where[XYZE]) {
void unified_bed_leveling::recover_filament(const float where[XYZE]) {
if (g26_retracted) { // Only un-retract if we are retracted.
move_to(where[X_AXIS], where[Y_AXIS], where[Z_AXIS], 1.2 * g26_retraction_multiplier);
move_to(where, 1.2 * g26_retraction_multiplier);
g26_retracted = false;
}
}
Expand Down
Loading