Merge remote-tracking branch 'upstream/Development' into K8200_2015-04-23_TEST
Conflicts: Marlin/example_configurations/K8200/Configuration.h
This commit is contained in:
commit
d1c1f766d5
@ -3,14 +3,14 @@
|
||||
1. Install the latest non-beta arduino software IDE/toolset: http://www.arduino.cc/en/Main/Software
|
||||
2. Download the Marlin firmware
|
||||
- [Latest developement version](https://github.com/MarlinFirmware/Marlin/tree/Development)
|
||||
- [Stable version](https://github.com/MarlinFirmware/Marlin/tree/Development)
|
||||
- [Stable version]()
|
||||
3. In both cases use the "Download Zip" button on the right.
|
||||
4. Some boards require special files and/or libraries from the ArduinoAddons directory. Take a look at the dedicated [README](/ArduinoAddons/README.md) for details.
|
||||
5. Start the arduino IDE.
|
||||
6. Select Tools -> Board -> Arduino Mega 2560 or your microcontroller
|
||||
6. Select Tools -> Board -> Arduino Mega 2560 or your microcontroller
|
||||
7. Select the correct serial port in Tools ->Serial Port
|
||||
8. Open Marlin.pde or .ino
|
||||
9. Click the Verify/Compile button
|
||||
10. Click the Upload button. If all goes well the firmware is uploading
|
||||
|
||||
That's ok. Enjoy Silky Smooth Printing.
|
||||
That's ok. Enjoy Silky Smooth Printing.
|
||||
|
@ -364,6 +364,7 @@ const bool Z_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the logic
|
||||
#define E_ENABLE_ON 0 // For all extruders
|
||||
|
||||
// Disables axis when it's not being used.
|
||||
// WARNING: When motors turn off there is a chance of losing position accuracy!
|
||||
#define DISABLE_X false
|
||||
#define DISABLE_Y false
|
||||
#define DISABLE_Z false
|
||||
@ -661,10 +662,9 @@ const bool Z_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the logic
|
||||
//#define ENCODER_STEPS_PER_MENU_ITEM 5 // Set according to ENCODER_PULSES_PER_STEP or your liking
|
||||
//#define ULTIMAKERCONTROLLER //as available from the Ultimaker online store.
|
||||
//#define ULTIPANEL //the UltiPanel as on Thingiverse
|
||||
//#define LCD_FEEDBACK_FREQUENCY_HZ 1000 // this is the tone frequency the buzzer plays when on UI feedback. ie Screen Click
|
||||
//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 100 // the duration the buzzer plays the UI feedback sound. ie Screen Click
|
||||
// 0 to disable buzzer feedback
|
||||
|
||||
//#define LCD_FEEDBACK_FREQUENCY_HZ 1000 // this is the tone frequency the buzzer plays when on UI feedback. ie Screen Click
|
||||
// 0 to disable buzzer feedback. Test with M300 S<frequency Hz> P<duration ms>
|
||||
// PanelOne from T3P3 (via RAMPS 1.4 AUX2/AUX3)
|
||||
// http://reprap.org/wiki/PanelOne
|
||||
//#define PANEL_ONE
|
||||
@ -792,13 +792,13 @@ const bool Z_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the logic
|
||||
// Uncomment below to enable
|
||||
//#define FILAMENT_SENSOR
|
||||
|
||||
#define FILAMENT_SENSOR_EXTRUDER_NUM 0 //The number of the extruder that has the filament sensor (0,1,2)
|
||||
#define MEASUREMENT_DELAY_CM 14 //measurement delay in cm. This is the distance from filament sensor to middle of barrel
|
||||
#define FILAMENT_SENSOR_EXTRUDER_NUM 0 //The number of the extruder that has the filament sensor (0,1,2)
|
||||
#define MEASUREMENT_DELAY_CM 14 //measurement delay in cm. This is the distance from filament sensor to middle of barrel
|
||||
|
||||
#define DEFAULT_NOMINAL_FILAMENT_DIA 3.0 //Enter the diameter (in mm) of the filament generally used (3.0 mm or 1.75 mm) - this is then used in the slicer software. Used for sensor reading validation
|
||||
#define MEASURED_UPPER_LIMIT 3.30 //upper limit factor used for sensor reading validation in mm
|
||||
#define MEASURED_LOWER_LIMIT 1.90 //lower limit factor for sensor reading validation in mm
|
||||
#define MAX_MEASUREMENT_DELAY 20 //delay buffer size in bytes (1 byte = 1cm)- limits maximum measurement delay allowable (must be larger than MEASUREMENT_DELAY_CM and lower number saves RAM)
|
||||
#define DEFAULT_NOMINAL_FILAMENT_DIA 3.0 //Enter the diameter (in mm) of the filament generally used (3.0 mm or 1.75 mm) - this is then used in the slicer software. Used for sensor reading validation
|
||||
#define MEASURED_UPPER_LIMIT 3.3 //upper limit factor used for sensor reading validation in mm
|
||||
#define MEASURED_LOWER_LIMIT 1.9 //lower limit factor for sensor reading validation in mm
|
||||
#define MAX_MEASUREMENT_DELAY 20 //delay buffer size in bytes (1 byte = 1cm)- limits maximum measurement delay allowable (must be larger than MEASUREMENT_DELAY_CM and lower number saves RAM)
|
||||
|
||||
//defines used in the code
|
||||
#define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA //set measured to nominal initially
|
||||
|
@ -267,8 +267,8 @@ endif
|
||||
CXXSRC = WMath.cpp WString.cpp Print.cpp Marlin_main.cpp \
|
||||
MarlinSerial.cpp Sd2Card.cpp SdBaseFile.cpp SdFatUtil.cpp \
|
||||
SdFile.cpp SdVolume.cpp motion_control.cpp planner.cpp \
|
||||
stepper.cpp temperature.cpp cardreader.cpp ConfigurationStore.cpp \
|
||||
watchdog.cpp SPI.cpp Servo.cpp Tone.cpp ultralcd.cpp digipot_mcp4451.cpp \
|
||||
stepper.cpp temperature.cpp cardreader.cpp configuration_store.cpp \
|
||||
watchdog.cpp SPI.cpp servo.cpp Tone.cpp ultralcd.cpp digipot_mcp4451.cpp \
|
||||
vector_3.cpp qr_solve.cpp
|
||||
ifeq ($(LIQUID_TWI2), 0)
|
||||
CXXSRC += LiquidCrystal.cpp
|
||||
|
@ -223,6 +223,18 @@ void Stop();
|
||||
void filrunout();
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Debug flags - not yet widely applied
|
||||
*/
|
||||
enum DebugFlags {
|
||||
DEBUG_ECHO = BIT(0),
|
||||
DEBUG_INFO = BIT(1),
|
||||
DEBUG_ERRORS = BIT(2),
|
||||
DEBUG_DRYRUN = BIT(3),
|
||||
DEBUG_COMMUNICATION = BIT(4)
|
||||
};
|
||||
extern uint8_t marlin_debug_flags;
|
||||
|
||||
extern bool Running;
|
||||
inline bool IsRunning() { return Running; }
|
||||
inline bool IsStopped() { return !Running; }
|
||||
|
@ -49,18 +49,18 @@
|
||||
#include "motion_control.h"
|
||||
#include "cardreader.h"
|
||||
#include "watchdog.h"
|
||||
#include "ConfigurationStore.h"
|
||||
#include "configuration_store.h"
|
||||
#include "language.h"
|
||||
#include "pins_arduino.h"
|
||||
#include "math.h"
|
||||
|
||||
#ifdef BLINKM
|
||||
#include "BlinkM.h"
|
||||
#include "blinkm.h"
|
||||
#include "Wire.h"
|
||||
#endif
|
||||
|
||||
#if NUM_SERVOS > 0
|
||||
#include "Servo.h"
|
||||
#include "servo.h"
|
||||
#endif
|
||||
|
||||
#if HAS_DIGIPOTSS
|
||||
@ -122,7 +122,7 @@
|
||||
* Call gcode file : "M32 P !filename#" and return to caller file after finishing (similar to #include).
|
||||
* The '#' is necessary when calling from within sd files, as it stops buffer prereading
|
||||
* M42 - Change pin status via gcode Use M42 Px Sy to set pin x to value y, when omitting Px the onboard led will be used.
|
||||
* M48 - Measure Z_Probe repeatability. M48 [n # of points] [X position] [Y position] [V_erboseness #] [E_ngage Probe] [L # of legs of travel]
|
||||
* M48 - Measure Z_Probe repeatability. M48 [P # of points] [X position] [Y position] [V_erboseness #] [E_ngage Probe] [L # of legs of travel]
|
||||
* M80 - Turn on Power Supply
|
||||
* M81 - Turn off Power Supply
|
||||
* M82 - Set E codes absolute (default)
|
||||
@ -138,6 +138,7 @@
|
||||
* M109 - Sxxx Wait for extruder current temp to reach target temp. Waits only when heating
|
||||
* Rxxx Wait for extruder current temp to reach target temp. Waits when heating and cooling
|
||||
* IF AUTOTEMP is enabled, S<mintemp> B<maxtemp> F<factor>. Exit autotemp by any M109 without F
|
||||
* M111 - Set debug flags with S<mask>. See flag bits defined in Marlin.h.
|
||||
* M112 - Emergency stop
|
||||
* M114 - Output current position to serial port
|
||||
* M115 - Capabilities string
|
||||
@ -184,6 +185,7 @@
|
||||
* M405 - Turn on Filament Sensor extrusion control. Optional D<delay in cm> to set delay in centimeters between sensor and extruder
|
||||
* M406 - Turn off Filament Sensor extrusion control
|
||||
* M407 - Display measured filament diameter
|
||||
* M410 - Quickstop. Abort all the planned moves
|
||||
* M500 - Store parameters in EEPROM
|
||||
* M501 - Read parameters from EEPROM (if you need reset them after you changed them temporarily).
|
||||
* M502 - Revert to the default "factory settings". You still need to store them in EEPROM afterwards if you want to.
|
||||
@ -217,6 +219,8 @@
|
||||
|
||||
bool Running = true;
|
||||
|
||||
uint8_t marlin_debug_flags = DEBUG_INFO|DEBUG_ERRORS;
|
||||
|
||||
static float feedrate = 1500.0, next_feedrate, saved_feedrate;
|
||||
float current_position[NUM_AXIS] = { 0.0 };
|
||||
static float destination[NUM_AXIS] = { 0.0 };
|
||||
@ -748,9 +752,10 @@ void get_command() {
|
||||
gcode_N = (strtol(strchr_pointer + 1, NULL, 10));
|
||||
if (gcode_N != gcode_LastN + 1 && strstr_P(command, PSTR("M110")) == NULL) {
|
||||
SERIAL_ERROR_START;
|
||||
SERIAL_ERRORPGM(MSG_ERR_LINE_NO);
|
||||
SERIAL_ERRORLN(gcode_LastN);
|
||||
//Serial.println(gcode_N);
|
||||
SERIAL_ERRORPGM(MSG_ERR_LINE_NO1);
|
||||
SERIAL_ERROR(gcode_LastN + 1);
|
||||
SERIAL_ERRORPGM(MSG_ERR_LINE_NO2);
|
||||
SERIAL_ERRORLN(gcode_N);
|
||||
FlushSerialRequestResend();
|
||||
serial_count = 0;
|
||||
return;
|
||||
@ -889,8 +894,11 @@ void get_command() {
|
||||
}
|
||||
|
||||
bool code_has_value() {
|
||||
char c = strchr_pointer[1];
|
||||
return (c >= '0' && c <= '9') || c == '-' || c == '+' || c == '.';
|
||||
int i = 1;
|
||||
char c = strchr_pointer[i];
|
||||
if (c == '-' || c == '+') c = strchr_pointer[++i];
|
||||
if (c == '.') c = strchr_pointer[++i];
|
||||
return (c >= '0' && c <= '9');
|
||||
}
|
||||
|
||||
float code_value() {
|
||||
@ -989,10 +997,10 @@ static void axis_is_at_home(int axis) {
|
||||
#endif
|
||||
|
||||
#ifdef SCARA
|
||||
float homeposition[3];
|
||||
|
||||
if (axis < 2) {
|
||||
if (axis == X_AXIS || axis == Y_AXIS) {
|
||||
|
||||
float homeposition[3];
|
||||
for (int i = 0; i < 3; i++) homeposition[i] = base_home_pos(i);
|
||||
|
||||
// SERIAL_ECHOPGM("homeposition[x]= "); SERIAL_ECHO(homeposition[0]);
|
||||
@ -1022,17 +1030,18 @@ static void axis_is_at_home(int axis) {
|
||||
// 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
|
||||
else
|
||||
#endif
|
||||
{
|
||||
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
|
||||
|
||||
#if defined(ENABLE_AUTO_BED_LEVELING) && Z_HOME_DIR < 0
|
||||
if (axis == Z_AXIS) current_position[Z_AXIS] += zprobe_zoffset;
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
@ -1187,8 +1196,8 @@ inline void set_destination_to_current() { memcpy(destination, current_position,
|
||||
st_synchronize();
|
||||
endstops_hit_on_purpose(); // clear endstop hit flags
|
||||
|
||||
// Get the current stepper position after bumping an endstop
|
||||
current_position[Z_AXIS] = st_get_position_mm(Z_AXIS);
|
||||
// make sure the planner knows where we are as it may be a bit different than we last said to move to
|
||||
sync_plan_position();
|
||||
|
||||
#endif // !DELTA
|
||||
@ -1500,13 +1509,11 @@ static void homeaxis(AxisEnum axis) {
|
||||
|
||||
if (axis == X_AXIS ? HOMEAXIS_DO(X) : axis == Y_AXIS ? HOMEAXIS_DO(Y) : axis == Z_AXIS ? HOMEAXIS_DO(Z) : 0) {
|
||||
|
||||
int axis_home_dir;
|
||||
|
||||
#ifdef DUAL_X_CARRIAGE
|
||||
if (axis == X_AXIS) axis_home_dir = x_home_dir(active_extruder);
|
||||
#else
|
||||
axis_home_dir = home_dir(axis);
|
||||
#endif
|
||||
int axis_home_dir =
|
||||
#ifdef DUAL_X_CARRIAGE
|
||||
(axis == X_AXIS) ? x_home_dir(active_extruder) :
|
||||
#endif
|
||||
home_dir(axis);
|
||||
|
||||
// Set the axis position as setup for the move
|
||||
current_position[axis] = 0;
|
||||
@ -1744,14 +1751,15 @@ inline void gcode_G2_G3(bool clockwise) {
|
||||
inline void gcode_G4() {
|
||||
millis_t codenum = 0;
|
||||
|
||||
LCD_MESSAGEPGM(MSG_DWELL);
|
||||
|
||||
if (code_seen('P')) codenum = code_value_long(); // milliseconds to wait
|
||||
if (code_seen('S')) codenum = code_value_long() * 1000; // seconds to wait
|
||||
|
||||
st_synchronize();
|
||||
refresh_cmd_timeout();
|
||||
codenum += previous_cmd_ms; // keep track of when we started waiting
|
||||
|
||||
if (!lcd_hasstatus()) LCD_MESSAGEPGM(MSG_DWELL);
|
||||
|
||||
while (millis() < codenum) {
|
||||
manage_heater();
|
||||
manage_inactivity();
|
||||
@ -1794,12 +1802,6 @@ inline void gcode_G4() {
|
||||
* Y Home to the Y endstop
|
||||
* Z Home to the Z endstop
|
||||
*
|
||||
* If numbers are included with XYZ set the position as with G92
|
||||
* Currently adds the home_offset, which may be wrong and removed soon.
|
||||
*
|
||||
* Xn Home X, setting X to n + home_offset[X_AXIS]
|
||||
* Yn Home Y, setting Y to n + home_offset[Y_AXIS]
|
||||
* Zn Home Z, setting Z to n + home_offset[Z_AXIS]
|
||||
*/
|
||||
inline void gcode_G28() {
|
||||
|
||||
@ -1859,7 +1861,7 @@ inline void gcode_G28() {
|
||||
homeY = code_seen(axis_codes[Y_AXIS]),
|
||||
homeZ = code_seen(axis_codes[Z_AXIS]);
|
||||
|
||||
home_all_axis = !(homeX || homeY || homeZ) || (homeX && homeY && homeZ);
|
||||
home_all_axis = (!homeX && !homeY && !homeZ) || (homeX && homeY && homeZ);
|
||||
|
||||
if (home_all_axis || homeZ) {
|
||||
|
||||
@ -1946,14 +1948,6 @@ inline void gcode_G28() {
|
||||
// Home Y
|
||||
if (home_all_axis || homeY) HOMEAXIS(Y);
|
||||
|
||||
// Set the X position, if included
|
||||
if (code_seen(axis_codes[X_AXIS]) && code_has_value())
|
||||
current_position[X_AXIS] = code_value();
|
||||
|
||||
// Set the Y position, if included
|
||||
if (code_seen(axis_codes[Y_AXIS]) && code_has_value())
|
||||
current_position[Y_AXIS] = code_value();
|
||||
|
||||
// Home Z last if homing towards the bed
|
||||
#if Z_HOME_DIR < 0
|
||||
|
||||
@ -2037,14 +2031,6 @@ inline void gcode_G28() {
|
||||
|
||||
#endif // Z_HOME_DIR < 0
|
||||
|
||||
// Set the Z position, if included
|
||||
if (code_seen(axis_codes[Z_AXIS]) && code_has_value())
|
||||
current_position[Z_AXIS] = code_value();
|
||||
|
||||
#if defined(ENABLE_AUTO_BED_LEVELING) && (Z_HOME_DIR < 0)
|
||||
if (home_all_axis || homeZ) current_position[Z_AXIS] += zprobe_zoffset; // Add Z_Probe offset (the distance is negative)
|
||||
#endif
|
||||
|
||||
sync_plan_position();
|
||||
|
||||
#endif // else DELTA
|
||||
@ -2893,7 +2879,7 @@ inline void gcode_M42() {
|
||||
* M48: Z-Probe repeatability measurement function.
|
||||
*
|
||||
* Usage:
|
||||
* M48 <n#> <X#> <Y#> <V#> <E> <L#>
|
||||
* M48 <P#> <X#> <Y#> <V#> <E> <L#>
|
||||
* P = Number of sampled points (4-50, default 10)
|
||||
* X = Sample X position
|
||||
* Y = Sample Y position
|
||||
@ -2905,10 +2891,6 @@ inline void gcode_M42() {
|
||||
* as been issued prior to invoking the M48 Z-Probe repeatability measurement function.
|
||||
* Any information generated by a prior G29 Bed leveling command will be lost and need to be
|
||||
* regenerated.
|
||||
*
|
||||
* The number of samples will default to 10 if not specified. You can use upper or lower case
|
||||
* letters for any of the options EXCEPT n. n must be in lower case because Marlin uses a capital
|
||||
* N for its communication protocol and will get horribly confused if you send it a capital N.
|
||||
*/
|
||||
inline void gcode_M48() {
|
||||
|
||||
@ -2926,7 +2908,7 @@ inline void gcode_M42() {
|
||||
if (verbose_level > 0)
|
||||
SERIAL_PROTOCOLPGM("M48 Z-Probe Repeatability test\n");
|
||||
|
||||
if (code_seen('P') || code_seen('p') || code_seen('n')) { // `n` for legacy support only - please use `P`!
|
||||
if (code_seen('P') || code_seen('p')) {
|
||||
n_samples = code_value_short();
|
||||
if (n_samples < 4 || n_samples > 50) {
|
||||
SERIAL_PROTOCOLPGM("?Sample size not plausible (4-50).\n");
|
||||
@ -2934,12 +2916,12 @@ inline void gcode_M42() {
|
||||
}
|
||||
}
|
||||
|
||||
double X_probe_location, Y_probe_location,
|
||||
X_current = X_probe_location = st_get_position_mm(X_AXIS),
|
||||
Y_current = Y_probe_location = st_get_position_mm(Y_AXIS),
|
||||
double X_current = st_get_position_mm(X_AXIS),
|
||||
Y_current = st_get_position_mm(Y_AXIS),
|
||||
Z_current = st_get_position_mm(Z_AXIS),
|
||||
Z_start_location = Z_current + Z_RAISE_BEFORE_PROBING,
|
||||
ext_position = st_get_position_mm(E_AXIS);
|
||||
E_current = st_get_position_mm(E_AXIS),
|
||||
X_probe_location = X_current, Y_probe_location = Y_current,
|
||||
Z_start_location = Z_current + Z_RAISE_BEFORE_PROBING;
|
||||
|
||||
bool deploy_probe_for_each_reading = code_seen('E') || code_seen('e');
|
||||
|
||||
@ -2974,10 +2956,7 @@ inline void gcode_M42() {
|
||||
|
||||
st_synchronize();
|
||||
plan_bed_level_matrix.set_to_identity();
|
||||
plan_buffer_line(X_current, Y_current, Z_start_location,
|
||||
ext_position,
|
||||
homing_feedrate[Z_AXIS] / 60,
|
||||
active_extruder);
|
||||
plan_buffer_line(X_current, Y_current, Z_start_location, E_current, homing_feedrate[Z_AXIS] / 60, active_extruder);
|
||||
st_synchronize();
|
||||
|
||||
//
|
||||
@ -2989,7 +2968,7 @@ inline void gcode_M42() {
|
||||
SERIAL_PROTOCOLPGM("Positioning the probe...\n");
|
||||
|
||||
plan_buffer_line( X_probe_location, Y_probe_location, Z_start_location,
|
||||
ext_position,
|
||||
E_current,
|
||||
homing_feedrate[X_AXIS]/60,
|
||||
active_extruder);
|
||||
st_synchronize();
|
||||
@ -2997,7 +2976,7 @@ inline void gcode_M42() {
|
||||
current_position[X_AXIS] = X_current = st_get_position_mm(X_AXIS);
|
||||
current_position[Y_AXIS] = Y_current = st_get_position_mm(Y_AXIS);
|
||||
current_position[Z_AXIS] = Z_current = st_get_position_mm(Z_AXIS);
|
||||
current_position[E_AXIS] = ext_position = st_get_position_mm(E_AXIS);
|
||||
current_position[E_AXIS] = E_current = st_get_position_mm(E_AXIS);
|
||||
|
||||
//
|
||||
// OK, do the inital probe to get us close to the bed.
|
||||
@ -3013,7 +2992,7 @@ inline void gcode_M42() {
|
||||
Z_start_location = st_get_position_mm(Z_AXIS) + Z_RAISE_BEFORE_PROBING;
|
||||
|
||||
plan_buffer_line( X_probe_location, Y_probe_location, Z_start_location,
|
||||
ext_position,
|
||||
E_current,
|
||||
homing_feedrate[X_AXIS]/60,
|
||||
active_extruder);
|
||||
st_synchronize();
|
||||
@ -3043,8 +3022,8 @@ inline void gcode_M42() {
|
||||
if (radius < 0.0) radius = -radius;
|
||||
|
||||
X_current = X_probe_location + cos(theta) * radius;
|
||||
Y_current = Y_probe_location + sin(theta) * radius;
|
||||
X_current = constrain(X_current, X_MIN_POS, X_MAX_POS);
|
||||
Y_current = Y_probe_location + sin(theta) * radius;
|
||||
Y_current = constrain(Y_current, Y_MIN_POS, Y_MAX_POS);
|
||||
|
||||
if (verbose_level > 3) {
|
||||
@ -3160,7 +3139,7 @@ inline void gcode_M104() {
|
||||
inline void gcode_M105() {
|
||||
if (setTargetedHotend(105)) return;
|
||||
|
||||
#if HAS_TEMP_0 || HAS_TEMP_BED
|
||||
#if HAS_TEMP_0 || HAS_TEMP_BED || defined(HEATER_0_USES_MAX6675)
|
||||
SERIAL_PROTOCOLPGM("ok");
|
||||
#if HAS_TEMP_0
|
||||
SERIAL_PROTOCOLPGM(" T:");
|
||||
@ -3361,12 +3340,17 @@ inline void gcode_M109() {
|
||||
|
||||
#endif // HAS_TEMP_BED
|
||||
|
||||
/**
|
||||
* M111: Set the debug level
|
||||
*/
|
||||
inline void gcode_M111() {
|
||||
marlin_debug_flags = code_seen('S') ? code_value_short() : DEBUG_INFO|DEBUG_ERRORS;
|
||||
}
|
||||
|
||||
/**
|
||||
* M112: Emergency Stop
|
||||
*/
|
||||
inline void gcode_M112() {
|
||||
kill();
|
||||
}
|
||||
inline void gcode_M112() { kill(); }
|
||||
|
||||
#ifdef BARICUDA
|
||||
|
||||
@ -3809,23 +3793,23 @@ inline void gcode_M206() {
|
||||
* M666: Set delta endstop adjustment
|
||||
*/
|
||||
inline void gcode_M666() {
|
||||
for (int8_t i = 0; i < 3; i++) {
|
||||
for (int8_t i = X_AXIS; i <= Z_AXIS; i++) {
|
||||
if (code_seen(axis_codes[i])) {
|
||||
endstop_adj[i] = code_value();
|
||||
}
|
||||
}
|
||||
}
|
||||
#elif defined(Z_DUAL_ENDSTOPS)
|
||||
#elif defined(Z_DUAL_ENDSTOPS) // !DELTA && defined(Z_DUAL_ENDSTOPS)
|
||||
/**
|
||||
* M666: For Z Dual Endstop setup, set z axis offset to the z2 axis.
|
||||
*/
|
||||
inline void gcode_M666() {
|
||||
if (code_seen('Z')) z_endstop_adj = code_value();
|
||||
SERIAL_ECHOPAIR("Z Endstop Adjustment set to (mm):", z_endstop_adj );
|
||||
SERIAL_EOL;
|
||||
if (code_seen('Z')) z_endstop_adj = code_value();
|
||||
SERIAL_ECHOPAIR("Z Endstop Adjustment set to (mm):", z_endstop_adj);
|
||||
SERIAL_EOL;
|
||||
}
|
||||
|
||||
#endif // DELTA
|
||||
#endif // !DELTA && defined(Z_DUAL_ENDSTOPS)
|
||||
|
||||
#ifdef FWRETRACT
|
||||
|
||||
@ -4025,20 +4009,8 @@ inline void gcode_M226() {
|
||||
inline void gcode_M300() {
|
||||
uint16_t beepS = code_seen('S') ? code_value_short() : 110;
|
||||
uint32_t beepP = code_seen('P') ? code_value_long() : 1000;
|
||||
if (beepS > 0) {
|
||||
#if BEEPER > 0
|
||||
tone(BEEPER, beepS);
|
||||
delay(beepP);
|
||||
noTone(BEEPER);
|
||||
#elif defined(ULTRALCD)
|
||||
lcd_buzz(beepS, beepP);
|
||||
#elif defined(LCD_USE_I2C_BUZZER)
|
||||
lcd_buzz(beepP, beepS);
|
||||
#endif
|
||||
}
|
||||
else {
|
||||
delay(beepP);
|
||||
}
|
||||
if (beepP > 5000) beepP = 5000; // limit to 5 seconds
|
||||
lcd_buzz(beepP, beepS);
|
||||
}
|
||||
|
||||
#endif // BEEPER>0 || ULTRALCD || LCD_USE_I2C_BUZZER
|
||||
@ -4313,14 +4285,34 @@ inline void gcode_M400() { st_synchronize(); }
|
||||
|
||||
#if defined(ENABLE_AUTO_BED_LEVELING) && (defined(SERVO_ENDSTOPS) || defined(Z_PROBE_ALLEN_KEY)) && not defined(Z_PROBE_SLED)
|
||||
|
||||
#ifdef SERVO_ENDSTOPS
|
||||
void raise_z_for_servo() {
|
||||
float zpos = current_position[Z_AXIS], z_dest = Z_RAISE_BEFORE_HOMING;
|
||||
if (!axis_known_position[Z_AXIS]) z_dest += zpos;
|
||||
if (zpos < z_dest)
|
||||
do_blocking_move_to(current_position[X_AXIS], current_position[Y_AXIS], z_dest); // also updates current_position
|
||||
}
|
||||
#endif
|
||||
|
||||
/**
|
||||
* M401: Engage Z Servo endstop if available
|
||||
*/
|
||||
inline void gcode_M401() { deploy_z_probe(); }
|
||||
inline void gcode_M401() {
|
||||
#ifdef SERVO_ENDSTOPS
|
||||
raise_z_for_servo();
|
||||
#endif
|
||||
deploy_z_probe();
|
||||
}
|
||||
|
||||
/**
|
||||
* M402: Retract Z Servo endstop if enabled
|
||||
*/
|
||||
inline void gcode_M402() { stow_z_probe(); }
|
||||
inline void gcode_M402() {
|
||||
#ifdef SERVO_ENDSTOPS
|
||||
raise_z_for_servo();
|
||||
#endif
|
||||
stow_z_probe();
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
@ -4380,6 +4372,14 @@ inline void gcode_M400() { st_synchronize(); }
|
||||
|
||||
#endif // FILAMENT_SENSOR
|
||||
|
||||
/**
|
||||
* M410: Quickstop - Abort all planned moves
|
||||
*
|
||||
* This will stop the carriages mid-move, so most likely they
|
||||
* will be out of sync with the stepper position after this.
|
||||
*/
|
||||
inline void gcode_M410() { quickStop(); }
|
||||
|
||||
/**
|
||||
* M500: Store settings in EEPROM
|
||||
*/
|
||||
@ -4426,7 +4426,7 @@ inline void gcode_M503() {
|
||||
if (code_seen('Z')) {
|
||||
value = code_value();
|
||||
if (Z_PROBE_OFFSET_RANGE_MIN <= value && value <= Z_PROBE_OFFSET_RANGE_MAX) {
|
||||
zprobe_zoffset = -value; // compare w/ line 278 of ConfigurationStore.cpp
|
||||
zprobe_zoffset = -value; // compare w/ line 278 of configuration_store.cpp
|
||||
SERIAL_ECHO_START;
|
||||
SERIAL_ECHOLNPGM(MSG_ZPROBE_ZOFFSET " " MSG_OK);
|
||||
SERIAL_EOL;
|
||||
@ -4790,6 +4790,12 @@ inline void gcode_T() {
|
||||
* This is called from the main loop()
|
||||
*/
|
||||
void process_commands() {
|
||||
|
||||
if ((marlin_debug_flags & DEBUG_ECHO)) {
|
||||
SERIAL_ECHO_START;
|
||||
SERIAL_ECHOLN(command_queue[cmd_queue_index_r]);
|
||||
}
|
||||
|
||||
if (code_seen('G')) {
|
||||
|
||||
int gCode = code_value_short();
|
||||
@ -4928,34 +4934,38 @@ void process_commands() {
|
||||
gcode_M104();
|
||||
break;
|
||||
|
||||
case 112: // M112 Emergency Stop
|
||||
case 111: // M111: Set debug level
|
||||
gcode_M111();
|
||||
break;
|
||||
|
||||
case 112: // M112: Emergency Stop
|
||||
gcode_M112();
|
||||
break;
|
||||
|
||||
case 140: // M140 Set bed temp
|
||||
case 140: // M140: Set bed temp
|
||||
gcode_M140();
|
||||
break;
|
||||
|
||||
case 105: // M105 Read current temperature
|
||||
case 105: // M105: Read current temperature
|
||||
gcode_M105();
|
||||
return;
|
||||
break;
|
||||
|
||||
case 109: // M109 Wait for temperature
|
||||
case 109: // M109: Wait for temperature
|
||||
gcode_M109();
|
||||
break;
|
||||
|
||||
#if HAS_TEMP_BED
|
||||
case 190: // M190 - Wait for bed heater to reach target.
|
||||
case 190: // M190: Wait for bed heater to reach target
|
||||
gcode_M190();
|
||||
break;
|
||||
#endif // HAS_TEMP_BED
|
||||
|
||||
#if HAS_FAN
|
||||
case 106: //M106 Fan On
|
||||
case 106: // M106: Fan On
|
||||
gcode_M106();
|
||||
break;
|
||||
case 107: //M107 Fan Off
|
||||
case 107: // M107: Fan Off
|
||||
gcode_M107();
|
||||
break;
|
||||
#endif // HAS_FAN
|
||||
@ -4963,20 +4973,20 @@ void process_commands() {
|
||||
#ifdef BARICUDA
|
||||
// PWM for HEATER_1_PIN
|
||||
#if HAS_HEATER_1
|
||||
case 126: // M126 valve open
|
||||
case 126: // M126: valve open
|
||||
gcode_M126();
|
||||
break;
|
||||
case 127: // M127 valve closed
|
||||
case 127: // M127: valve closed
|
||||
gcode_M127();
|
||||
break;
|
||||
#endif // HAS_HEATER_1
|
||||
|
||||
// PWM for HEATER_2_PIN
|
||||
#if HAS_HEATER_2
|
||||
case 128: // M128 valve open
|
||||
case 128: // M128: valve open
|
||||
gcode_M128();
|
||||
break;
|
||||
case 129: // M129 valve closed
|
||||
case 129: // M129: valve closed
|
||||
gcode_M129();
|
||||
break;
|
||||
#endif // HAS_HEATER_2
|
||||
@ -4984,13 +4994,13 @@ void process_commands() {
|
||||
|
||||
#if HAS_POWER_SWITCH
|
||||
|
||||
case 80: // M80 - Turn on Power Supply
|
||||
case 80: // M80: Turn on Power Supply
|
||||
gcode_M80();
|
||||
break;
|
||||
|
||||
#endif // HAS_POWER_SWITCH
|
||||
|
||||
case 81: // M81 - Turn off Power, including Power Supply, if possible
|
||||
case 81: // M81: Turn off Power, including Power Supply, if possible
|
||||
gcode_M81();
|
||||
break;
|
||||
|
||||
@ -5000,7 +5010,7 @@ void process_commands() {
|
||||
case 83:
|
||||
gcode_M83();
|
||||
break;
|
||||
case 18: //compatibility
|
||||
case 18: // (for compatibility)
|
||||
case 84: // M84
|
||||
gcode_M18_M84();
|
||||
break;
|
||||
@ -5199,6 +5209,10 @@ void process_commands() {
|
||||
break;
|
||||
#endif // FILAMENT_SENSOR
|
||||
|
||||
case 410: // M410 quickstop - Abort all the planned moves.
|
||||
gcode_M410();
|
||||
break;
|
||||
|
||||
case 500: // M500 Store settings in EEPROM
|
||||
gcode_M500();
|
||||
break;
|
||||
|
@ -87,8 +87,8 @@
|
||||
/**
|
||||
* Required LCD language
|
||||
*/
|
||||
#if !defined(DOGLCD) && defined(ULTRA_LCD) && !defined(DISPLAY_CHARSET_HD44780_JAPAN) && !defined(DISPLAY_CHARSET_HD44780_WESTERN)
|
||||
#error You must enable either DISPLAY_CHARSET_HD44780_JAPAN or DISPLAY_CHARSET_HD44780_WESTERN for your LCD controller.
|
||||
#if !defined(DOGLCD) && defined(ULTRA_LCD) && !defined(DISPLAY_CHARSET_HD44780_JAPAN) && !defined(DISPLAY_CHARSET_HD44780_WESTERN)&& !defined(DISPLAY_CHARSET_HD44780_CYRILLIC)
|
||||
#error You must enable either DISPLAY_CHARSET_HD44780_JAPAN or DISPLAY_CHARSET_HD44780_WESTERN or DISPLAY_CHARSET_HD44780_CYRILLIC for your LCD controller.
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -1,5 +1,5 @@
|
||||
/*
|
||||
Servo.cpp - Interrupt driven Servo library for Arduino using 16 bit timers- Version 2
|
||||
servo.cpp - Interrupt driven Servo library for Arduino using 16 bit timers- Version 2
|
||||
Copyright (c) 2009 Michael Margolis. All right reserved.
|
||||
|
||||
This library is free software; you can redistribute it and/or
|
||||
@ -48,7 +48,7 @@
|
||||
#include <avr/interrupt.h>
|
||||
#include <Arduino.h>
|
||||
|
||||
#include "Servo.h"
|
||||
#include "servo.h"
|
||||
|
||||
#define usToTicks(_us) (( clockCyclesPerMicrosecond()* _us) / 8) // converts microseconds to tick (assumes prescale of 8) // 12 Aug 2009
|
||||
#define ticksToUs(_ticks) (( (unsigned)_ticks * 8)/ clockCyclesPerMicrosecond() ) // converts from ticks back to microseconds
|
||||
|
@ -1,5 +1,5 @@
|
||||
/*
|
||||
Servo.h - Interrupt driven Servo library for Arduino using 16 bit timers- Version 2
|
||||
servo.h - Interrupt driven Servo library for Arduino using 16 bit timers- Version 2
|
||||
Copyright (c) 2009 Michael Margolis. All right reserved.
|
||||
|
||||
This library is free software; you can redistribute it and/or
|
||||
@ -42,8 +42,8 @@
|
||||
detach() - Stops an attached servos from pulsing its i/o pin.
|
||||
*/
|
||||
|
||||
#ifndef Servo_h
|
||||
#define Servo_h
|
||||
#ifndef servo_h
|
||||
#define servo_h
|
||||
|
||||
#include <inttypes.h>
|
||||
|
||||
|
@ -1,11 +1,11 @@
|
||||
/*
|
||||
BlinkM.cpp - Library for controlling a BlinkM over i2c
|
||||
blinkm.cpp - Library for controlling a BlinkM over i2c
|
||||
Created by Tim Koster, August 21 2013.
|
||||
*/
|
||||
#include "Marlin.h"
|
||||
#ifdef BLINKM
|
||||
|
||||
#include "BlinkM.h"
|
||||
#include "blinkm.h"
|
||||
|
||||
void SendColors(byte red, byte grn, byte blu) {
|
||||
Wire.begin();
|
@ -1,5 +1,5 @@
|
||||
/*
|
||||
BlinkM.h
|
||||
blinkm.h
|
||||
Library header file for BlinkM library
|
||||
*/
|
||||
#if ARDUINO >= 100
|
@ -1,5 +1,5 @@
|
||||
/**
|
||||
* ConfigurationStore.cpp
|
||||
* configuration_store.cpp
|
||||
*
|
||||
* Configuration and EEPROM storage
|
||||
*
|
||||
@ -93,7 +93,7 @@
|
||||
#include "planner.h"
|
||||
#include "temperature.h"
|
||||
#include "ultralcd.h"
|
||||
#include "ConfigurationStore.h"
|
||||
#include "configuration_store.h"
|
||||
|
||||
#ifdef MESH_BED_LEVELING
|
||||
#include "mesh_bed_leveling.h"
|
@ -1,5 +1,5 @@
|
||||
#ifndef CONFIGURATIONSTORE_H
|
||||
#define CONFIGURATIONSTORE_H
|
||||
#ifndef CONFIGURATION_STORE_H
|
||||
#define CONFIGURATION_STORE_H
|
||||
|
||||
#include "Configuration.h"
|
||||
|
||||
@ -19,4 +19,4 @@ void Config_ResetDefault();
|
||||
FORCE_INLINE void Config_RetrieveSettings() { Config_ResetDefault(); Config_PrintSettings(); }
|
||||
#endif
|
||||
|
||||
#endif //CONFIGURATIONSTORE_H
|
||||
#endif //CONFIGURATION_STORE_H
|
@ -364,6 +364,7 @@ const bool Z_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the logic
|
||||
#define E_ENABLE_ON 0 // For all extruders
|
||||
|
||||
// Disables axis when it's not being used.
|
||||
// WARNING: When motors turn off there is a chance of losing position accuracy!
|
||||
#define DISABLE_X false
|
||||
#define DISABLE_Y false
|
||||
#define DISABLE_Z false
|
||||
@ -660,9 +661,9 @@ const bool Z_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the logic
|
||||
//#define ENCODER_STEPS_PER_MENU_ITEM 5 // Set according to ENCODER_PULSES_PER_STEP or your liking
|
||||
//#define ULTIMAKERCONTROLLER //as available from the Ultimaker online store.
|
||||
//#define ULTIPANEL //the UltiPanel as on Thingiverse
|
||||
//#define LCD_FEEDBACK_FREQUENCY_HZ 1000 // this is the tone frequency the buzzer plays when on UI feedback. ie Screen Click
|
||||
//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 100 // the duration the buzzer plays the UI feedback sound. ie Screen Click
|
||||
// 0 to disable buzzer feedback
|
||||
//#define LCD_FEEDBACK_FREQUENCY_HZ 1000 // this is the tone frequency the buzzer plays when on UI feedback. ie Screen Click
|
||||
// 0 to disable buzzer feedback. Test with M300 S<frequency Hz> P<duration ms>
|
||||
|
||||
// PanelOne from T3P3 (via RAMPS 1.4 AUX2/AUX3)
|
||||
// http://reprap.org/wiki/PanelOne
|
||||
|
@ -122,7 +122,8 @@
|
||||
#define MSG_PLANNER_BUFFER_BYTES " PlannerBufferBytes: "
|
||||
#define MSG_OK "ok"
|
||||
#define MSG_FILE_SAVED "Done saving file."
|
||||
#define MSG_ERR_LINE_NO "Line Number is not Last Line Number+1, Last Line: "
|
||||
#define MSG_ERR_LINE_NO1 "Line Number out of sequence. Expected: "
|
||||
#define MSG_ERR_LINE_NO2 " Got: "
|
||||
#define MSG_ERR_CHECKSUM_MISMATCH "checksum mismatch, Last Line: "
|
||||
#define MSG_ERR_NO_CHECKSUM "No Checksum with line number, Last Line: "
|
||||
#define MSG_ERR_NO_LINENUMBER_WITH_CHECKSUM "No Line Number with checksum, Last Line: "
|
||||
@ -209,7 +210,7 @@
|
||||
#define MSG_OK_B "ok B:"
|
||||
#define MSG_OK_T "ok T:"
|
||||
#define MSG_AT " @:"
|
||||
#define MSG_PID_AUTOTUNE_FINISHED MSG_PID_AUTOTUNE " finished! Put the last Kp, Ki and Kd constants from above into Configuration.h"
|
||||
#define MSG_PID_AUTOTUNE_FINISHED MSG_PID_AUTOTUNE " finished! Put the last Kp, Ki and Kd constants from below into Configuration.h"
|
||||
#define MSG_PID_DEBUG " PID_DEBUG "
|
||||
#define MSG_PID_DEBUG_INPUT ": Input "
|
||||
#define MSG_PID_DEBUG_OUTPUT " Output "
|
||||
|
@ -29,7 +29,7 @@
|
||||
#endif
|
||||
|
||||
#include <U8glib.h>
|
||||
#include "DOGMbitmaps.h"
|
||||
#include "dogm_bitmaps.h"
|
||||
|
||||
#include "ultralcd.h"
|
||||
#include "ultralcd_st7920_u8glib_rrd.h"
|
||||
|
@ -1,4 +1,4 @@
|
||||
#ifndef CONFIGURATION_H
|
||||
#ifndef CONFIGURATION_H
|
||||
#define CONFIGURATION_H
|
||||
|
||||
#include "boards.h"
|
||||
@ -317,6 +317,7 @@ const bool Z_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the logic
|
||||
#define E_ENABLE_ON 0 // For all extruders
|
||||
|
||||
// Disables axis when it's not being used.
|
||||
// WARNING: When motors turn off there is a chance of losing position accuracy!
|
||||
#define DISABLE_X false
|
||||
#define DISABLE_Y false
|
||||
#define DISABLE_Z false
|
||||
@ -594,9 +595,9 @@ const bool Z_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the logic
|
||||
//#define ENCODER_STEPS_PER_MENU_ITEM 5 // Set according to ENCODER_PULSES_PER_STEP or your liking
|
||||
//#define ULTIMAKERCONTROLLER //as available from the Ultimaker online store.
|
||||
//#define ULTIPANEL //the UltiPanel as on Thingiverse
|
||||
//#define LCD_FEEDBACK_FREQUENCY_HZ 1000 // this is the tone frequency the buzzer plays when on UI feedback. ie Screen Click
|
||||
//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 100 // the duration the buzzer plays the UI feedback sound. ie Screen Click
|
||||
// 0 to disable buzzer feedback
|
||||
//#define LCD_FEEDBACK_FREQUENCY_HZ 1000 // this is the tone frequency the buzzer plays when on UI feedback. ie Screen Click
|
||||
// 0 to disable buzzer feedback. Test with M300 S<frequency Hz> P<duration ms>
|
||||
|
||||
// PanelOne from T3P3 (via RAMPS 1.4 AUX2/AUX3)
|
||||
// http://reprap.org/wiki/PanelOne
|
||||
|
@ -317,6 +317,7 @@ const bool Z_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the logic
|
||||
#define E_ENABLE_ON 0 // For all extruders
|
||||
|
||||
// Disables axis when it's not being used.
|
||||
// WARNING: When motors turn off there is a chance of losing position accuracy!
|
||||
#define DISABLE_X false
|
||||
#define DISABLE_Y false
|
||||
#define DISABLE_Z false
|
||||
@ -590,9 +591,9 @@ const bool Z_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the logic
|
||||
//#define ENCODER_STEPS_PER_MENU_ITEM 5 // Set according to ENCODER_PULSES_PER_STEP or your liking
|
||||
//#define ULTIMAKERCONTROLLER //as available from the Ultimaker online store.
|
||||
//#define ULTIPANEL //the UltiPanel as on Thingiverse
|
||||
//#define LCD_FEEDBACK_FREQUENCY_HZ 1000 // this is the tone frequency the buzzer plays when on UI feedback. ie Screen Click
|
||||
//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 100 // the duration the buzzer plays the UI feedback sound. ie Screen Click
|
||||
// 0 to disable buzzer feedback
|
||||
//#define LCD_FEEDBACK_FREQUENCY_HZ 1000 // this is the tone frequency the buzzer plays when on UI feedback. ie Screen Click
|
||||
// 0 to disable buzzer feedback. Test with M300 S<frequency Hz> P<duration ms>
|
||||
|
||||
// PanelOne from T3P3 (via RAMPS 1.4 AUX2/AUX3)
|
||||
// http://reprap.org/wiki/PanelOne
|
||||
|
@ -1,4 +1,4 @@
|
||||
#ifndef CONFIGURATION_H
|
||||
#ifndef CONFIGURATION_H
|
||||
#define CONFIGURATION_H
|
||||
|
||||
#include "boards.h"
|
||||
@ -338,6 +338,7 @@ const bool Z_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the logic
|
||||
#define E_ENABLE_ON 0 // For all extruders
|
||||
|
||||
// Disables axis when it's not being used.
|
||||
// WARNING: When motors turn off there is a chance of losing position accuracy!
|
||||
#define DISABLE_X false
|
||||
#define DISABLE_Y false
|
||||
#define DISABLE_Z false
|
||||
@ -614,9 +615,9 @@ const bool Z_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the logic
|
||||
//#define ENCODER_STEPS_PER_MENU_ITEM 5 // Set according to ENCODER_PULSES_PER_STEP or your liking
|
||||
//#define ULTIMAKERCONTROLLER //as available from the Ultimaker online store.
|
||||
//#define ULTIPANEL //the UltiPanel as on Thingiverse
|
||||
//#define LCD_FEEDBACK_FREQUENCY_HZ 1000 // this is the tone frequency the buzzer plays when on UI feedback. ie Screen Click
|
||||
//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 100 // the duration the buzzer plays the UI feedback sound. ie Screen Click
|
||||
// 0 to disable buzzer feedback
|
||||
//#define LCD_FEEDBACK_FREQUENCY_HZ 1000 // this is the tone frequency the buzzer plays when on UI feedback. ie Screen Click
|
||||
// 0 to disable buzzer feedback. Test with M300 S<frequency Hz> P<duration ms>
|
||||
|
||||
// PanelOne from T3P3 (via RAMPS 1.4 AUX2/AUX3)
|
||||
// http://reprap.org/wiki/PanelOne
|
||||
|
@ -1,4 +1,4 @@
|
||||
// Example configuration file for Vellemann K8200
|
||||
// Example configuration file for Vellemann K8200
|
||||
// tested on K8200 with VM8201 (Display)
|
||||
// and Arduino 1.6.1 (Win) by @CONSULitAS, 2015-04-14
|
||||
// https://github.com/CONSULitAS/Marlin-K8200/archive/K8200_stable_2015-04-14.zip
|
||||
@ -380,6 +380,7 @@ const bool Z_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the logic
|
||||
#define E_ENABLE_ON 0 // For all extruders
|
||||
|
||||
// Disables axis when it's not being used.
|
||||
// WARNING: When motors turn off there is a chance of losing position accuracy!
|
||||
#define DISABLE_X false
|
||||
#define DISABLE_Y false
|
||||
#define DISABLE_Z true
|
||||
@ -677,9 +678,9 @@ const bool Z_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the logic
|
||||
//#define ENCODER_STEPS_PER_MENU_ITEM 5 // Set according to ENCODER_PULSES_PER_STEP or your liking
|
||||
#define ULTIMAKERCONTROLLER // K8200: for Display VM8201 // as available from the Ultimaker online store.
|
||||
//#define ULTIPANEL //the UltiPanel as on Thingiverse
|
||||
//#define LCD_FEEDBACK_FREQUENCY_HZ 1000 // this is the tone frequency the buzzer plays when on UI feedback. ie Screen Click
|
||||
//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 100 // the duration the buzzer plays the UI feedback sound. ie Screen Click
|
||||
// 0 to disable buzzer feedback
|
||||
//#define LCD_FEEDBACK_FREQUENCY_HZ 1000 // this is the tone frequency the buzzer plays when on UI feedback. ie Screen Click
|
||||
// 0 to disable buzzer feedback. Test with M300 S<frequency Hz> P<duration ms>
|
||||
|
||||
// PanelOne from T3P3 (via RAMPS 1.4 AUX2/AUX3)
|
||||
// http://reprap.org/wiki/PanelOne
|
||||
|
@ -1,4 +1,4 @@
|
||||
#ifndef CONFIGURATION_H
|
||||
#ifndef CONFIGURATION_H
|
||||
#define CONFIGURATION_H
|
||||
|
||||
#include "boards.h"
|
||||
@ -369,6 +369,7 @@ const bool Z_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the logic
|
||||
#define E_ENABLE_ON 0 // For all extruders
|
||||
|
||||
// Disables axis when it's not being used.
|
||||
// WARNING: When motors turn off there is a chance of losing position accuracy!
|
||||
#define DISABLE_X false
|
||||
#define DISABLE_Y false
|
||||
#define DISABLE_Z false
|
||||
@ -645,9 +646,9 @@ const bool Z_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the logic
|
||||
//#define ENCODER_STEPS_PER_MENU_ITEM 5 // Set according to ENCODER_PULSES_PER_STEP or your liking
|
||||
//#define ULTIMAKERCONTROLLER //as available from the Ultimaker online store.
|
||||
//#define ULTIPANEL //the UltiPanel as on Thingiverse
|
||||
//#define LCD_FEEDBACK_FREQUENCY_HZ 1000 // this is the tone frequency the buzzer plays when on UI feedback. ie Screen Click
|
||||
//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 100 // the duration the buzzer plays the UI feedback sound. ie Screen Click
|
||||
// 0 to disable buzzer feedback
|
||||
//#define LCD_FEEDBACK_FREQUENCY_HZ 1000 // this is the tone frequency the buzzer plays when on UI feedback. ie Screen Click
|
||||
// 0 to disable buzzer feedback. Test with M300 S<frequency Hz> P<duration ms>
|
||||
|
||||
// PanelOne from T3P3 (via RAMPS 1.4 AUX2/AUX3)
|
||||
// http://reprap.org/wiki/PanelOne
|
||||
|
@ -1,4 +1,4 @@
|
||||
#ifndef CONFIGURATION_H
|
||||
#ifndef CONFIGURATION_H
|
||||
#define CONFIGURATION_H
|
||||
|
||||
#include "boards.h"
|
||||
@ -337,6 +337,7 @@ const bool Z_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the logic
|
||||
#define E_ENABLE_ON 0 // For all extruders
|
||||
|
||||
// Disables axis when it's not being used.
|
||||
// WARNING: When motors turn off there is a chance of losing position accuracy!
|
||||
#define DISABLE_X false
|
||||
#define DISABLE_Y false
|
||||
#define DISABLE_Z true
|
||||
@ -613,9 +614,9 @@ const bool Z_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the logic
|
||||
//#define ENCODER_STEPS_PER_MENU_ITEM 5 // Set according to ENCODER_PULSES_PER_STEP or your liking
|
||||
//#define ULTIMAKERCONTROLLER //as available from the Ultimaker online store.
|
||||
//#define ULTIPANEL //the UltiPanel as on Thingiverse
|
||||
//#define LCD_FEEDBACK_FREQUENCY_HZ 1000 // this is the tone frequency the buzzer plays when on UI feedback. ie Screen Click
|
||||
//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 100 // the duration the buzzer plays the UI feedback sound. ie Screen Click
|
||||
// 0 to disable buzzer feedback
|
||||
//#define LCD_FEEDBACK_FREQUENCY_HZ 1000 // this is the tone frequency the buzzer plays when on UI feedback. ie Screen Click
|
||||
// 0 to disable buzzer feedback. Test with M300 S<frequency Hz> P<duration ms>
|
||||
|
||||
// PanelOne from T3P3 (via RAMPS 1.4 AUX2/AUX3)
|
||||
// http://reprap.org/wiki/PanelOne
|
||||
|
@ -1,4 +1,4 @@
|
||||
#ifndef CONFIGURATION_H
|
||||
#ifndef CONFIGURATION_H
|
||||
#define CONFIGURATION_H
|
||||
|
||||
#include "boards.h"
|
||||
@ -367,6 +367,7 @@ const bool Z_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the logic
|
||||
#define E_ENABLE_ON 0 // For all extruders
|
||||
|
||||
// Disables axis when it's not being used.
|
||||
// WARNING: When motors turn off there is a chance of losing position accuracy!
|
||||
#define DISABLE_X false
|
||||
#define DISABLE_Y false
|
||||
#define DISABLE_Z false
|
||||
@ -662,9 +663,9 @@ const bool Z_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the logic
|
||||
//#define ENCODER_STEPS_PER_MENU_ITEM 5 // Set according to ENCODER_PULSES_PER_STEP or your liking
|
||||
//#define ULTIMAKERCONTROLLER //as available from the Ultimaker online store.
|
||||
//#define ULTIPANEL //the UltiPanel as on Thingiverse
|
||||
//#define LCD_FEEDBACK_FREQUENCY_HZ 1000 // this is the tone frequency the buzzer plays when on UI feedback. ie Screen Click
|
||||
//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 100 // the duration the buzzer plays the UI feedback sound. ie Screen Click
|
||||
// 0 to disable buzzer feedback
|
||||
//#define LCD_FEEDBACK_FREQUENCY_HZ 1000 // this is the tone frequency the buzzer plays when on UI feedback. ie Screen Click
|
||||
// 0 to disable buzzer feedback. Test with M300 S<frequency Hz> P<duration ms>
|
||||
|
||||
// PanelOne from T3P3 (via RAMPS 1.4 AUX2/AUX3)
|
||||
// http://reprap.org/wiki/PanelOne
|
||||
|
@ -1,4 +1,4 @@
|
||||
#ifndef CONFIGURATION_H
|
||||
#ifndef CONFIGURATION_H
|
||||
#define CONFIGURATION_H
|
||||
|
||||
#include "boards.h"
|
||||
@ -367,6 +367,7 @@ const bool Z_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the logic
|
||||
#define E_ENABLE_ON 0 // For all extruders
|
||||
|
||||
// Disables axis when it's not being used.
|
||||
// WARNING: When motors turn off there is a chance of losing position accuracy!
|
||||
#define DISABLE_X false
|
||||
#define DISABLE_Y false
|
||||
#define DISABLE_Z false
|
||||
@ -666,9 +667,9 @@ const bool Z_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the logic
|
||||
//#define ENCODER_STEPS_PER_MENU_ITEM 5 // Set according to ENCODER_PULSES_PER_STEP or your liking
|
||||
//#define ULTIMAKERCONTROLLER //as available from the Ultimaker online store.
|
||||
//#define ULTIPANEL //the UltiPanel as on Thingiverse
|
||||
//#define LCD_FEEDBACK_FREQUENCY_HZ 1000 // this is the tone frequency the buzzer plays when on UI feedback. ie Screen Click
|
||||
//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 100 // the duration the buzzer plays the UI feedback sound. ie Screen Click
|
||||
// 0 to disable buzzer feedback
|
||||
//#define LCD_FEEDBACK_FREQUENCY_HZ 1000 // this is the tone frequency the buzzer plays when on UI feedback. ie Screen Click
|
||||
// 0 to disable buzzer feedback. Test with M300 S<frequency Hz> P<duration ms>
|
||||
|
||||
// PanelOne from T3P3 (via RAMPS 1.4 AUX2/AUX3)
|
||||
// http://reprap.org/wiki/PanelOne
|
||||
|
@ -1,4 +1,4 @@
|
||||
#ifndef CONFIGURATION_H
|
||||
#ifndef CONFIGURATION_H
|
||||
#define CONFIGURATION_H
|
||||
|
||||
#include "boards.h"
|
||||
@ -337,6 +337,7 @@ const bool Z_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the logic
|
||||
#define E_ENABLE_ON 0 // For all extruders
|
||||
|
||||
// Disables axis when it's not being used.
|
||||
// WARNING: When motors turn off there is a chance of losing position accuracy!
|
||||
#define DISABLE_X false
|
||||
#define DISABLE_Y false
|
||||
#define DISABLE_Z false
|
||||
@ -613,9 +614,9 @@ const bool Z_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the logic
|
||||
//#define ENCODER_STEPS_PER_MENU_ITEM 5 // Set according to ENCODER_PULSES_PER_STEP or your liking
|
||||
//#define ULTIMAKERCONTROLLER //as available from the Ultimaker online store.
|
||||
//#define ULTIPANEL //the UltiPanel as on Thingiverse
|
||||
//#define LCD_FEEDBACK_FREQUENCY_HZ 1000 // this is the tone frequency the buzzer plays when on UI feedback. ie Screen Click
|
||||
//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 100 // the duration the buzzer plays the UI feedback sound. ie Screen Click
|
||||
// 0 to disable buzzer feedback
|
||||
//#define LCD_FEEDBACK_FREQUENCY_HZ 1000 // this is the tone frequency the buzzer plays when on UI feedback. ie Screen Click
|
||||
// 0 to disable buzzer feedback. Test with M300 S<frequency Hz> P<duration ms>
|
||||
|
||||
// PanelOne from T3P3 (via RAMPS 1.4 AUX2/AUX3)
|
||||
// http://reprap.org/wiki/PanelOne
|
||||
|
@ -1,4 +1,4 @@
|
||||
#ifndef CONFIGURATION_H
|
||||
#ifndef CONFIGURATION_H
|
||||
#define CONFIGURATION_H
|
||||
|
||||
#include "boards.h"
|
||||
@ -339,6 +339,7 @@ const bool Z_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the logic
|
||||
#define E_ENABLE_ON 1 // For all extruders
|
||||
|
||||
// Disables axis when it's not being used.
|
||||
// WARNING: When motors turn off there is a chance of losing position accuracy!
|
||||
#define DISABLE_X false
|
||||
#define DISABLE_Y false
|
||||
#define DISABLE_Z false
|
||||
@ -619,9 +620,9 @@ const bool Z_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the logic
|
||||
//#define ENCODER_STEPS_PER_MENU_ITEM 5 // Set according to ENCODER_PULSES_PER_STEP or your liking
|
||||
//#define ULTIMAKERCONTROLLER //as available from the Ultimaker online store.
|
||||
//#define ULTIPANEL //the UltiPanel as on Thingiverse
|
||||
//#define LCD_FEEDBACK_FREQUENCY_HZ 1000 // this is the tone frequency the buzzer plays when on UI feedback. ie Screen Click
|
||||
//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 100 // the duration the buzzer plays the UI feedback sound. ie Screen Click
|
||||
// 0 to disable buzzer feedback
|
||||
//#define LCD_FEEDBACK_FREQUENCY_HZ 1000 // this is the tone frequency the buzzer plays when on UI feedback. ie Screen Click
|
||||
// 0 to disable buzzer feedback. Test with M300 S<frequency Hz> P<duration ms>
|
||||
|
||||
// PanelOne from T3P3 (via RAMPS 1.4 AUX2/AUX3)
|
||||
// http://reprap.org/wiki/PanelOne
|
||||
|
@ -3,4 +3,23 @@ In Fony export the fonts to bdf-format. Maybe another one can edit them with Fon
|
||||
Then run make_fonts.bat what calls bdf2u8g.exe with the needed parameters to produce the .h files.
|
||||
The .h files must be edited to replace '#include "u8g.h"' with '#include <utility/u8g.h>', replace 'U8G_FONT_SECTION' with 'U8G_SECTION', insert '.progmem.' right behind the first '"' and moved to the main directory.
|
||||
|
||||
Especially the Kana and Cyrillic fonts should be revised by someone who knows what he/she does. I am only a west-European with very little knowledge about this scripts.
|
||||
How to integrate a new font:
|
||||
Currently we are limited to 256 symbols per font. We use a menu system with 5 lines, on a display with 64 pixel height. That means we have 12 pixel for a line. To have some space in between the lines we can't use more then 10 pixel height for the symbols.
|
||||
We use fixed width fonts. To fit 22 Symbols on the 128 pixel wide screen, the symbols can't be wider than 5 pixel. Maybe you can work with half symbols - two places in the charset will than build one wide symbol.
|
||||
|
||||
* Get 'Fony.exe'
|
||||
* Copy one of the existing *.fon files and work with this.
|
||||
* Change the pixels. Don't change width or height.
|
||||
* Export as *.bdf
|
||||
* Use 'bdf2u8g.exe' to produce the *.h file. Examples for the existing fonts are in 'make_fonts.bat'
|
||||
* Edit the produced .h file to match our needs. See hints in 'README.fonts' or the other 'dogm_font_data_.h' files.
|
||||
* Make a new entry in the font list in 'dogm_lcd_implementation.h' before the '#else // fall back'
|
||||
#elif defined( DISPLAY_CHARSET_NEWNAME )
|
||||
#include "dogm_font_data_yourfont.h"
|
||||
#define FONT_MENU_NAME YOURFONTNAME
|
||||
#else // fall-back
|
||||
* Add your font to the list of permitted fonts in 'language_en.h'
|
||||
... || defined(DISPLAY_CHARSET_YOUR_NEW_FONT) ... )
|
||||
|
||||
|
||||
Especially the Kana font should be revised by someone who knows what he/she does. I am only a west-European with very little knowledge about this script.
|
||||
|
@ -122,7 +122,8 @@
|
||||
#define MSG_PLANNER_BUFFER_BYTES " PlannerBufferBytes: "
|
||||
#define MSG_OK "ok"
|
||||
#define MSG_FILE_SAVED "Done saving file."
|
||||
#define MSG_ERR_LINE_NO "Line Number is not Last Line Number+1, Last Line: "
|
||||
#define MSG_ERR_LINE_NO1 "Line Number out of sequence. Expected: "
|
||||
#define MSG_ERR_LINE_NO2 " Got: "
|
||||
#define MSG_ERR_CHECKSUM_MISMATCH "checksum mismatch, Last Line: "
|
||||
#define MSG_ERR_NO_CHECKSUM "No Checksum with line number, Last Line: "
|
||||
#define MSG_ERR_NO_LINENUMBER_WITH_CHECKSUM "No Line Number with checksum, Last Line: "
|
||||
@ -209,7 +210,7 @@
|
||||
#define MSG_OK_B "ok B:"
|
||||
#define MSG_OK_T "ok T:"
|
||||
#define MSG_AT " @:"
|
||||
#define MSG_PID_AUTOTUNE_FINISHED MSG_PID_AUTOTUNE " finished! Put the last Kp, Ki and Kd constants from above into Configuration.h"
|
||||
#define MSG_PID_AUTOTUNE_FINISHED MSG_PID_AUTOTUNE " finished! Put the last Kp, Ki and Kd constants from below into Configuration.h"
|
||||
#define MSG_PID_DEBUG " PID_DEBUG "
|
||||
#define MSG_PID_DEBUG_INPUT ": Input "
|
||||
#define MSG_PID_DEBUG_OUTPUT " Output "
|
||||
|
@ -17,7 +17,7 @@
|
||||
#define MSG_SD_INSERTED "Tarjeta colocada"
|
||||
#define MSG_SD_REMOVED "Tarjeta retirada"
|
||||
#define MSG_MAIN "Menu principal"
|
||||
#define MSG_AUTOSTART " Autostart"
|
||||
#define MSG_AUTOSTART "Autostart"
|
||||
#define MSG_DISABLE_STEPPERS "Apagar motores"
|
||||
#define MSG_AUTO_HOME "Llevar al origen"
|
||||
#define MSG_SET_HOME_OFFSETS "Ajustar offsets"
|
||||
@ -46,7 +46,7 @@
|
||||
#define MSG_MOVE_1MM "Mover 1mm"
|
||||
#define MSG_MOVE_10MM "Mover 10mm"
|
||||
#define MSG_SPEED "Velocidad"
|
||||
#define MSG_NOZZLE "Nozzle"
|
||||
#define MSG_NOZZLE "Fusor"
|
||||
#define MSG_BED "Base"
|
||||
#define MSG_FAN_SPEED "Ventilador"
|
||||
#define MSG_FLOW "Flujo"
|
||||
@ -80,7 +80,7 @@
|
||||
#define MSG_ESTEPS "E pasos/mm"
|
||||
#define MSG_TEMPERATURE "Temperatura"
|
||||
#define MSG_MOTION "Movimiento"
|
||||
#define MSG_VOLUMETRIC "Filament"
|
||||
#define MSG_VOLUMETRIC "Filamento"
|
||||
#define MSG_VOLUMETRIC_ENABLED "E in mm3"
|
||||
#define MSG_FILAMENT_SIZE_EXTRUDER_0 "Fil. Dia. 1"
|
||||
#define MSG_FILAMENT_SIZE_EXTRUDER_1 "Fil. Dia. 2"
|
||||
@ -116,22 +116,22 @@
|
||||
#define MSG_FILAMENTCHANGE "Cambiar filamento"
|
||||
#define MSG_INIT_SDCARD "Iniciando tarjeta"
|
||||
#define MSG_CNG_SDCARD "Cambiar tarjeta"
|
||||
#define MSG_ZPROBE_OUT "sonda Z fuera"
|
||||
#define MSG_ZPROBE_OUT "Sonda Z fuera"
|
||||
#define MSG_POSITION_UNKNOWN "Reiniciar X/Y y Z"
|
||||
#define MSG_ZPROBE_ZOFFSET "Offset Z"
|
||||
#define MSG_BABYSTEP_X "Babystep X"
|
||||
#define MSG_BABYSTEP_Y "Babystep Y"
|
||||
#define MSG_BABYSTEP_Z "Babystep Z"
|
||||
#define MSG_BABYSTEP_X "Micropaso X"
|
||||
#define MSG_BABYSTEP_Y "Micropaso Y"
|
||||
#define MSG_BABYSTEP_Z "Micropaso Z"
|
||||
#define MSG_ENDSTOP_ABORT "Endstop abort"
|
||||
#define MSG_END_HOUR "horas"
|
||||
#define MSG_END_MINUTE "minutos"
|
||||
|
||||
#ifdef DELTA_CALIBRATION_MENU
|
||||
#define MSG_DELTA_CALIBRATE "Delta Calibration"
|
||||
#define MSG_DELTA_CALIBRATE_X "Calibrate X"
|
||||
#define MSG_DELTA_CALIBRATE_Y "Calibrate Y"
|
||||
#define MSG_DELTA_CALIBRATE_Z "Calibrate Z"
|
||||
#define MSG_DELTA_CALIBRATE_CENTER "Calibrate Center"
|
||||
#define MSG_DELTA_CALIBRATE "Calibracion Delta"
|
||||
#define MSG_DELTA_CALIBRATE_X "Calibrar X"
|
||||
#define MSG_DELTA_CALIBRATE_Y "Calibrar Y"
|
||||
#define MSG_DELTA_CALIBRATE_Z "Calibrar Z"
|
||||
#define MSG_DELTA_CALIBRATE_CENTER "Calibrar Centro"
|
||||
#endif // DELTA_CALIBRATION_MENU
|
||||
|
||||
#endif // LANGUAGE_ES_H
|
||||
|
@ -28,9 +28,7 @@
|
||||
#define STAT_LED_RED 64
|
||||
#define STAT_LED_BLUE 63
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#elif define TEMP_STAT_LEDS
|
||||
#elif defined(TEMP_STAT_LEDS)
|
||||
#define STAT_LED_RED 6
|
||||
#define STAT_LED_BLUE 11
|
||||
#endif
|
||||
|
@ -82,7 +82,7 @@
|
||||
#define HOME_PIN -1 // A4 = marlin 44 - teensy = 42
|
||||
|
||||
#ifdef NUM_SERVOS
|
||||
#define SERVO0_PIN 41 // In teensy's pin definition for pinMode (in Servo.cpp)
|
||||
#define SERVO0_PIN 41 // In teensy's pin definition for pinMode (in servo.cpp)
|
||||
#endif
|
||||
|
||||
#endif // SAV_3DLCD
|
||||
|
@ -46,7 +46,7 @@ block_t *current_block; // A pointer to the block currently being traced
|
||||
|
||||
// Variables used by The Stepper Driver Interrupt
|
||||
static unsigned char out_bits; // The next stepping-bits to be output
|
||||
static unsigned int cleaning_buffer_counter;
|
||||
static unsigned int cleaning_buffer_counter;
|
||||
|
||||
#ifdef Z_DUAL_ENDSTOPS
|
||||
static bool performing_homing = false,
|
||||
@ -54,7 +54,7 @@ static unsigned int cleaning_buffer_counter;
|
||||
locked_z2_motor = false;
|
||||
#endif
|
||||
|
||||
// Counter variables for the bresenham line tracer
|
||||
// Counter variables for the Bresenham line tracer
|
||||
static long counter_x, counter_y, counter_z, counter_e;
|
||||
volatile static unsigned long step_events_completed; // The number of step events executed in the current block
|
||||
|
||||
@ -66,7 +66,7 @@ volatile static unsigned long step_events_completed; // The number of step event
|
||||
|
||||
static long acceleration_time, deceleration_time;
|
||||
//static unsigned long accelerate_until, decelerate_after, acceleration_rate, initial_rate, final_rate, nominal_rate;
|
||||
static unsigned short acc_step_rate; // needed for deccelaration start point
|
||||
static unsigned short acc_step_rate; // needed for deceleration start point
|
||||
static char step_loops;
|
||||
static unsigned short OCR1A_nominal;
|
||||
static unsigned short step_loops_nominal;
|
||||
@ -205,8 +205,14 @@ volatile signed char count_direction[NUM_AXIS] = { 1, 1, 1, 1 };
|
||||
// intRes = longIn1 * longIn2 >> 24
|
||||
// uses:
|
||||
// r26 to store 0
|
||||
// r27 to store the byte 1 of the 48bit result
|
||||
#define MultiU24X24toH16(intRes, longIn1, longIn2) \
|
||||
// r27 to store bits 16-23 of the 48bit result. The top bit is used to round the two byte result.
|
||||
// note that the lower two bytes and the upper byte of the 48bit result are not calculated.
|
||||
// this can cause the result to be out by one as the lower bytes may cause carries into the upper ones.
|
||||
// B0 A0 are bits 24-39 and are the returned value
|
||||
// C1 B1 A1 is longIn1
|
||||
// D2 C2 B2 A2 is longIn2
|
||||
//
|
||||
#define MultiU24X32toH16(intRes, longIn1, longIn2) \
|
||||
asm volatile ( \
|
||||
"clr r26 \n\t" \
|
||||
"mul %A1, %B2 \n\t" \
|
||||
@ -237,6 +243,11 @@ volatile signed char count_direction[NUM_AXIS] = { 1, 1, 1, 1 };
|
||||
"lsr r27 \n\t" \
|
||||
"adc %A0, r26 \n\t" \
|
||||
"adc %B0, r26 \n\t" \
|
||||
"mul %D2, %A1 \n\t" \
|
||||
"add %A0, r0 \n\t" \
|
||||
"adc %B0, r1 \n\t" \
|
||||
"mul %D2, %B1 \n\t" \
|
||||
"add %B0, r0 \n\t" \
|
||||
"clr r1 \n\t" \
|
||||
: \
|
||||
"=&r" (intRes) \
|
||||
@ -274,8 +285,8 @@ void checkHitEndstops() {
|
||||
}
|
||||
#ifdef Z_PROBE_ENDSTOP
|
||||
if (endstop_z_probe_hit) {
|
||||
SERIAL_ECHOPAIR(" Z_PROBE:", (float)endstops_trigsteps[Z_AXIS] / axis_steps_per_unit[Z_AXIS]);
|
||||
LCD_MESSAGEPGM(MSG_ENDSTOPS_HIT "ZP");
|
||||
SERIAL_ECHOPAIR(" Z_PROBE:", (float)endstops_trigsteps[Z_AXIS] / axis_steps_per_unit[Z_AXIS]);
|
||||
LCD_MESSAGEPGM(MSG_ENDSTOPS_HIT "ZP");
|
||||
}
|
||||
#endif
|
||||
SERIAL_EOL;
|
||||
@ -313,7 +324,7 @@ void enable_endstops(bool check) { check_endstops = check; }
|
||||
// The trapezoid is the shape the speed curve over time. It starts at block->initial_rate, accelerates
|
||||
// first block->accelerate_until step_events_completed, then keeps going at constant speed until
|
||||
// step_events_completed reaches block->decelerate_after after which it decelerates until the trapezoid generator is reset.
|
||||
// The slope of acceleration is calculated with the leib ramp alghorithm.
|
||||
// The slope of acceleration is calculated using v = u + at where t is the accumulated timer values of the steps so far.
|
||||
|
||||
void st_wake_up() {
|
||||
// TCNT1 = 0;
|
||||
@ -400,7 +411,7 @@ ISR(TIMER1_COMPA_vect) {
|
||||
OCR1A = 200;
|
||||
return;
|
||||
}
|
||||
|
||||
|
||||
// If there is no current block, attempt to pop one from the buffer
|
||||
if (!current_block) {
|
||||
// Anything in the buffer?
|
||||
@ -452,14 +463,22 @@ ISR(TIMER1_COMPA_vect) {
|
||||
count_direction[Y_AXIS] = 1;
|
||||
}
|
||||
|
||||
#define _ENDSTOP(axis, minmax) axis ##_## minmax ##_endstop
|
||||
#define _ENDSTOP_PIN(AXIS, MINMAX) AXIS ##_## MINMAX ##_PIN
|
||||
#define _ENDSTOP_INVERTING(AXIS, MINMAX) AXIS ##_## MINMAX ##_ENDSTOP_INVERTING
|
||||
#define _OLD_ENDSTOP(axis, minmax) old_## axis ##_## minmax ##_endstop
|
||||
#define _AXIS(AXIS) AXIS ##_AXIS
|
||||
#define _ENDSTOP_HIT(axis) endstop_## axis ##_hit
|
||||
|
||||
#define UPDATE_ENDSTOP(axis,AXIS,minmax,MINMAX) \
|
||||
bool axis ##_## minmax ##_endstop = (READ(AXIS ##_## MINMAX ##_PIN) != AXIS ##_## MINMAX ##_ENDSTOP_INVERTING); \
|
||||
if (axis ##_## minmax ##_endstop && old_## axis ##_## minmax ##_endstop && (current_block->steps[AXIS ##_AXIS] > 0)) { \
|
||||
endstops_trigsteps[AXIS ##_AXIS] = count_position[AXIS ##_AXIS]; \
|
||||
endstop_## axis ##_hit = true; \
|
||||
bool _ENDSTOP(axis, minmax) = (READ(_ENDSTOP_PIN(AXIS, MINMAX)) != _ENDSTOP_INVERTING(AXIS, MINMAX)); \
|
||||
if (_ENDSTOP(axis, minmax) && _OLD_ENDSTOP(axis, minmax) && (current_block->steps[_AXIS(AXIS)] > 0)) { \
|
||||
endstops_trigsteps[_AXIS(AXIS)] = count_position[_AXIS(AXIS)]; \
|
||||
_ENDSTOP_HIT(axis) = true; \
|
||||
step_events_completed = current_block->step_event_count; \
|
||||
} \
|
||||
old_## axis ##_## minmax ##_endstop = axis ##_## minmax ##_endstop;
|
||||
_OLD_ENDSTOP(axis, minmax) = _ENDSTOP(axis, minmax);
|
||||
|
||||
|
||||
// Check X and Y endstops
|
||||
if (check_endstops) {
|
||||
@ -469,13 +488,13 @@ ISR(TIMER1_COMPA_vect) {
|
||||
if ((current_block->steps[A_AXIS] != current_block->steps[B_AXIS]) || (TEST(out_bits, A_AXIS) == TEST(out_bits, B_AXIS))) {
|
||||
if (TEST(out_bits, X_HEAD))
|
||||
#else
|
||||
if (TEST(out_bits, X_AXIS)) // stepping along -X axis (regular cartesians bot)
|
||||
if (TEST(out_bits, X_AXIS)) // stepping along -X axis (regular Cartesian bot)
|
||||
#endif
|
||||
{ // -direction
|
||||
#ifdef DUAL_X_CARRIAGE
|
||||
// with 2 x-carriages, endstops are only checked in the homing direction for the active extruder
|
||||
if ((current_block->active_extruder == 0 && X_HOME_DIR == -1) || (current_block->active_extruder != 0 && X2_HOME_DIR == -1))
|
||||
#endif
|
||||
#endif
|
||||
{
|
||||
#if HAS_X_MIN
|
||||
UPDATE_ENDSTOP(x, X, min, MIN);
|
||||
@ -561,14 +580,14 @@ ISR(TIMER1_COMPA_vect) {
|
||||
z_probe_endstop=(READ(Z_PROBE_PIN) != Z_PROBE_ENDSTOP_INVERTING);
|
||||
if(z_probe_endstop && old_z_probe_endstop)
|
||||
{
|
||||
endstops_trigsteps[Z_AXIS] = count_position[Z_AXIS];
|
||||
endstop_z_probe_hit=true;
|
||||
endstops_trigsteps[Z_AXIS] = count_position[Z_AXIS];
|
||||
endstop_z_probe_hit=true;
|
||||
|
||||
// if (z_probe_endstop && old_z_probe_endstop) SERIAL_ECHOLN("z_probe_endstop = true");
|
||||
// if (z_probe_endstop && old_z_probe_endstop) SERIAL_ECHOLN("z_probe_endstop = true");
|
||||
}
|
||||
old_z_probe_endstop = z_probe_endstop;
|
||||
#endif
|
||||
|
||||
|
||||
} // check_endstops
|
||||
|
||||
}
|
||||
@ -614,15 +633,15 @@ ISR(TIMER1_COMPA_vect) {
|
||||
#endif // !Z_DUAL_ENDSTOPS
|
||||
|
||||
#endif // Z_MAX_PIN
|
||||
|
||||
|
||||
#ifdef Z_PROBE_ENDSTOP
|
||||
UPDATE_ENDSTOP(z, Z, probe, PROBE);
|
||||
z_probe_endstop=(READ(Z_PROBE_PIN) != Z_PROBE_ENDSTOP_INVERTING);
|
||||
if(z_probe_endstop && old_z_probe_endstop)
|
||||
{
|
||||
endstops_trigsteps[Z_AXIS] = count_position[Z_AXIS];
|
||||
endstop_z_probe_hit=true;
|
||||
// if (z_probe_endstop && old_z_probe_endstop) SERIAL_ECHOLN("z_probe_endstop = true");
|
||||
endstops_trigsteps[Z_AXIS] = count_position[Z_AXIS];
|
||||
endstop_z_probe_hit=true;
|
||||
// if (z_probe_endstop && old_z_probe_endstop) SERIAL_ECHOLN("z_probe_endstop = true");
|
||||
}
|
||||
old_z_probe_endstop = z_probe_endstop;
|
||||
#endif
|
||||
@ -656,6 +675,11 @@ ISR(TIMER1_COMPA_vect) {
|
||||
}
|
||||
#endif //ADVANCE
|
||||
|
||||
#define _COUNTER(axis) counter_## axis
|
||||
#define _WRITE_STEP(AXIS, HIGHLOW) AXIS ##_STEP_WRITE(HIGHLOW)
|
||||
#define _APPLY_STEP(AXIS) AXIS ##_APPLY_STEP
|
||||
#define _INVERT_STEP_PIN(AXIS) INVERT_## AXIS ##_STEP_PIN
|
||||
|
||||
#ifdef CONFIG_STEPPERS_TOSHIBA
|
||||
/**
|
||||
* The Toshiba stepper controller require much longer pulses.
|
||||
@ -664,8 +688,8 @@ ISR(TIMER1_COMPA_vect) {
|
||||
* lag to allow it work with without needing NOPs
|
||||
*/
|
||||
#define STEP_ADD(axis, AXIS) \
|
||||
counter_## axis += current_block->steps[AXIS ##_AXIS]; \
|
||||
if (counter_## axis > 0) { AXIS ##_STEP_WRITE(HIGH); }
|
||||
_COUNTER(axis) += current_block->steps[_AXIS(AXIS)]; \
|
||||
if (_COUNTER(axis) > 0) { _WRITE_STEP(AXIS, HIGH); }
|
||||
STEP_ADD(x,X);
|
||||
STEP_ADD(y,Y);
|
||||
STEP_ADD(z,Z);
|
||||
@ -674,10 +698,10 @@ ISR(TIMER1_COMPA_vect) {
|
||||
#endif
|
||||
|
||||
#define STEP_IF_COUNTER(axis, AXIS) \
|
||||
if (counter_## axis > 0) { \
|
||||
counter_## axis -= current_block->step_event_count; \
|
||||
count_position[AXIS ##_AXIS] += count_direction[AXIS ##_AXIS]; \
|
||||
AXIS ##_STEP_WRITE(LOW); \
|
||||
if (_COUNTER(axis) > 0) { \
|
||||
_COUNTER(axis) -= current_block->step_event_count; \
|
||||
count_position[_AXIS(AXIS)] += count_direction[_AXIS(AXIS)]; \
|
||||
_WRITE_STEP(AXIS, LOW); \
|
||||
}
|
||||
|
||||
STEP_IF_COUNTER(x, X);
|
||||
@ -690,12 +714,12 @@ ISR(TIMER1_COMPA_vect) {
|
||||
#else // !CONFIG_STEPPERS_TOSHIBA
|
||||
|
||||
#define APPLY_MOVEMENT(axis, AXIS) \
|
||||
counter_## axis += current_block->steps[AXIS ##_AXIS]; \
|
||||
if (counter_## axis > 0) { \
|
||||
AXIS ##_APPLY_STEP(!INVERT_## AXIS ##_STEP_PIN,0); \
|
||||
counter_## axis -= current_block->step_event_count; \
|
||||
count_position[AXIS ##_AXIS] += count_direction[AXIS ##_AXIS]; \
|
||||
AXIS ##_APPLY_STEP(INVERT_## AXIS ##_STEP_PIN,0); \
|
||||
_COUNTER(axis) += current_block->steps[_AXIS(AXIS)]; \
|
||||
if (_COUNTER(axis) > 0) { \
|
||||
_APPLY_STEP(AXIS)(!_INVERT_STEP_PIN(AXIS),0); \
|
||||
_COUNTER(axis) -= current_block->step_event_count; \
|
||||
count_position[_AXIS(AXIS)] += count_direction[_AXIS(AXIS)]; \
|
||||
_APPLY_STEP(AXIS)(_INVERT_STEP_PIN(AXIS),0); \
|
||||
}
|
||||
|
||||
APPLY_MOVEMENT(x, X);
|
||||
@ -714,7 +738,7 @@ ISR(TIMER1_COMPA_vect) {
|
||||
unsigned short step_rate;
|
||||
if (step_events_completed <= (unsigned long)current_block->accelerate_until) {
|
||||
|
||||
MultiU24X24toH16(acc_step_rate, acceleration_time, current_block->acceleration_rate);
|
||||
MultiU24X32toH16(acc_step_rate, acceleration_time, current_block->acceleration_rate);
|
||||
acc_step_rate += current_block->initial_rate;
|
||||
|
||||
// upper limit
|
||||
@ -737,7 +761,7 @@ ISR(TIMER1_COMPA_vect) {
|
||||
#endif
|
||||
}
|
||||
else if (step_events_completed > (unsigned long)current_block->decelerate_after) {
|
||||
MultiU24X24toH16(step_rate, deceleration_time, current_block->acceleration_rate);
|
||||
MultiU24X32toH16(step_rate, deceleration_time, current_block->acceleration_rate);
|
||||
|
||||
if (step_rate > acc_step_rate) { // Check step_rate stays positive
|
||||
step_rate = current_block->final_rate;
|
||||
@ -863,7 +887,7 @@ void st_init() {
|
||||
#ifdef HAVE_L6470DRIVER
|
||||
L6470_init();
|
||||
#endif
|
||||
|
||||
|
||||
// Initialize Dir Pins
|
||||
#if HAS_X_DIR
|
||||
X_DIR_INIT;
|
||||
@ -909,11 +933,11 @@ void st_init() {
|
||||
#if HAS_Y_ENABLE
|
||||
Y_ENABLE_INIT;
|
||||
if (!Y_ENABLE_ON) Y_ENABLE_WRITE(HIGH);
|
||||
|
||||
#if defined(Y_DUAL_STEPPER_DRIVERS) && HAS_Y2_ENABLE
|
||||
Y2_ENABLE_INIT;
|
||||
if (!Y_ENABLE_ON) Y2_ENABLE_WRITE(HIGH);
|
||||
#endif
|
||||
|
||||
#if defined(Y_DUAL_STEPPER_DRIVERS) && HAS_Y2_ENABLE
|
||||
Y2_ENABLE_INIT;
|
||||
if (!Y_ENABLE_ON) Y2_ENABLE_WRITE(HIGH);
|
||||
#endif
|
||||
#endif
|
||||
#if HAS_Z_ENABLE
|
||||
Z_ENABLE_INIT;
|
||||
@ -990,8 +1014,8 @@ void st_init() {
|
||||
#ifdef ENDSTOPPULLUP_ZMAX
|
||||
WRITE(Z2_MAX_PIN,HIGH);
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#endif
|
||||
|
||||
#if (defined(Z_PROBE_PIN) && Z_PROBE_PIN >= 0) && defined(Z_PROBE_ENDSTOP) // Check for Z_PROBE_ENDSTOP so we don't pull a pin high unless it's to be used.
|
||||
SET_INPUT(Z_PROBE_PIN);
|
||||
#ifdef ENDSTOPPULLUP_ZPROBE
|
||||
@ -999,10 +1023,13 @@ void st_init() {
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#define _STEP_INIT(AXIS) AXIS ##_STEP_INIT
|
||||
#define _DISABLE(axis) disable_## axis()
|
||||
|
||||
#define AXIS_INIT(axis, AXIS, PIN) \
|
||||
AXIS ##_STEP_INIT; \
|
||||
AXIS ##_STEP_WRITE(INVERT_## PIN ##_STEP_PIN); \
|
||||
disable_## axis()
|
||||
_STEP_INIT(AXIS); \
|
||||
_WRITE_STEP(AXIS, _INVERT_STEP_PIN(PIN)); \
|
||||
_DISABLE(axis)
|
||||
|
||||
#define E_AXIS_INIT(NUM) AXIS_INIT(e## NUM, E## NUM, E)
|
||||
|
||||
@ -1135,14 +1162,19 @@ void quickStop() {
|
||||
// No other ISR should ever interrupt this!
|
||||
void babystep(const uint8_t axis, const bool direction) {
|
||||
|
||||
#define _ENABLE(axis) enable_## axis()
|
||||
#define _READ_DIR(AXIS) AXIS ##_DIR_READ
|
||||
#define _INVERT_DIR(AXIS) INVERT_## AXIS ##_DIR
|
||||
#define _APPLY_DIR(AXIS, INVERT) AXIS ##_APPLY_DIR(INVERT, true)
|
||||
|
||||
#define BABYSTEP_AXIS(axis, AXIS, INVERT) { \
|
||||
enable_## axis(); \
|
||||
uint8_t old_pin = AXIS ##_DIR_READ; \
|
||||
AXIS ##_APPLY_DIR(INVERT_## AXIS ##_DIR^direction^INVERT, true); \
|
||||
AXIS ##_APPLY_STEP(!INVERT_## AXIS ##_STEP_PIN, true); \
|
||||
_delay_us(1U); \
|
||||
AXIS ##_APPLY_STEP(INVERT_## AXIS ##_STEP_PIN, true); \
|
||||
AXIS ##_APPLY_DIR(old_pin, true); \
|
||||
_ENABLE(axis); \
|
||||
uint8_t old_pin = _READ_DIR(AXIS); \
|
||||
_APPLY_DIR(AXIS, _INVERT_DIR(AXIS)^direction^INVERT); \
|
||||
_APPLY_STEP(AXIS)(!_INVERT_STEP_PIN(AXIS), true); \
|
||||
delayMicroseconds(2); \
|
||||
_APPLY_STEP(AXIS)(_INVERT_STEP_PIN(AXIS), true); \
|
||||
_APPLY_DIR(AXIS, old_pin); \
|
||||
}
|
||||
|
||||
switch(axis) {
|
||||
@ -1154,7 +1186,7 @@ void quickStop() {
|
||||
case Y_AXIS:
|
||||
BABYSTEP_AXIS(y, Y, false);
|
||||
break;
|
||||
|
||||
|
||||
case Z_AXIS: {
|
||||
|
||||
#ifndef DELTA
|
||||
@ -1179,7 +1211,7 @@ void quickStop() {
|
||||
X_STEP_WRITE(!INVERT_X_STEP_PIN);
|
||||
Y_STEP_WRITE(!INVERT_Y_STEP_PIN);
|
||||
Z_STEP_WRITE(!INVERT_Z_STEP_PIN);
|
||||
_delay_us(1U);
|
||||
delayMicroseconds(2);
|
||||
X_STEP_WRITE(INVERT_X_STEP_PIN);
|
||||
Y_STEP_WRITE(INVERT_Y_STEP_PIN);
|
||||
Z_STEP_WRITE(INVERT_Z_STEP_PIN);
|
||||
@ -1191,7 +1223,7 @@ void quickStop() {
|
||||
#endif
|
||||
|
||||
} break;
|
||||
|
||||
|
||||
default: break;
|
||||
}
|
||||
}
|
||||
@ -1255,7 +1287,7 @@ void microstep_init() {
|
||||
|
||||
#if HAS_MICROSTEPS
|
||||
pinMode(X_MS1_PIN,OUTPUT);
|
||||
pinMode(X_MS2_PIN,OUTPUT);
|
||||
pinMode(X_MS2_PIN,OUTPUT);
|
||||
pinMode(Y_MS1_PIN,OUTPUT);
|
||||
pinMode(Y_MS2_PIN,OUTPUT);
|
||||
pinMode(Z_MS1_PIN,OUTPUT);
|
||||
|
@ -341,6 +341,9 @@ void PID_autotune(float temp, int extruder, int ncycles)
|
||||
}
|
||||
if (cycles > ncycles) {
|
||||
SERIAL_PROTOCOLLNPGM(MSG_PID_AUTOTUNE_FINISHED);
|
||||
SERIAL_PROTOCOLPGM("#define DEFAULT_Kp "); SERIAL_PROTOCOLLN(Kp);
|
||||
SERIAL_PROTOCOLPGM("#define DEFAULT_Ki "); SERIAL_PROTOCOLLN(Ki);
|
||||
SERIAL_PROTOCOLPGM("#define DEFAULT_Kd "); SERIAL_PROTOCOLLN(Kd);
|
||||
return;
|
||||
}
|
||||
lcd_update();
|
||||
|
@ -5,7 +5,7 @@
|
||||
#include "cardreader.h"
|
||||
#include "temperature.h"
|
||||
#include "stepper.h"
|
||||
#include "ConfigurationStore.h"
|
||||
#include "configuration_store.h"
|
||||
|
||||
int8_t encoderDiff; /* encoderDiff is updated from interrupt context and added to encoderPosition every LCD update */
|
||||
|
||||
@ -267,28 +267,28 @@ static void lcd_status_screen() {
|
||||
#ifdef LCD_PROGRESS_BAR
|
||||
millis_t ms = millis();
|
||||
#ifndef PROGRESS_MSG_ONCE
|
||||
if (ms > progressBarTick + PROGRESS_BAR_MSG_TIME + PROGRESS_BAR_BAR_TIME) {
|
||||
progressBarTick = ms;
|
||||
if (ms > progress_bar_ms + PROGRESS_BAR_MSG_TIME + PROGRESS_BAR_BAR_TIME) {
|
||||
progress_bar_ms = ms;
|
||||
}
|
||||
#endif
|
||||
#if PROGRESS_MSG_EXPIRE > 0
|
||||
// Handle message expire
|
||||
if (expireStatusMillis > 0) {
|
||||
if (expire_status_ms > 0) {
|
||||
if (card.isFileOpen()) {
|
||||
// Expire the message when printing is active
|
||||
if (IS_SD_PRINTING) {
|
||||
// Expire the message when printing is active
|
||||
if (ms >= expireStatusMillis) {
|
||||
if (ms >= expire_status_ms) {
|
||||
lcd_status_message[0] = '\0';
|
||||
expireStatusMillis = 0;
|
||||
expire_status_ms = 0;
|
||||
}
|
||||
}
|
||||
else {
|
||||
expireStatusMillis += LCD_UPDATE_INTERVAL;
|
||||
expire_status_ms += LCD_UPDATE_INTERVAL;
|
||||
}
|
||||
}
|
||||
else {
|
||||
expireStatusMillis = 0;
|
||||
expire_status_ms = 0;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
@ -648,26 +648,26 @@ static void lcd_prepare_menu() {
|
||||
|
||||
#endif // DELTA_CALIBRATION_MENU
|
||||
|
||||
inline void line_to_current() {
|
||||
inline void line_to_current(AxisEnum axis) {
|
||||
#ifdef DELTA
|
||||
calculate_delta(current_position);
|
||||
plan_buffer_line(delta[X_AXIS], delta[Y_AXIS], delta[Z_AXIS], current_position[E_AXIS], manual_feedrate[X_AXIS]/60, active_extruder);
|
||||
plan_buffer_line(delta[X_AXIS], delta[Y_AXIS], delta[Z_AXIS], current_position[E_AXIS], manual_feedrate[axis]/60, active_extruder);
|
||||
#else
|
||||
plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], manual_feedrate[X_AXIS]/60, active_extruder);
|
||||
plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], manual_feedrate[axis]/60, active_extruder);
|
||||
#endif
|
||||
}
|
||||
|
||||
float move_menu_scale;
|
||||
static void lcd_move_menu_axis();
|
||||
|
||||
static void _lcd_move(const char *name, int axis, int min, int max) {
|
||||
static void _lcd_move(const char *name, AxisEnum axis, int min, int max) {
|
||||
if (encoderPosition != 0) {
|
||||
refresh_cmd_timeout();
|
||||
current_position[axis] += float((int)encoderPosition) * move_menu_scale;
|
||||
if (min_software_endstops && current_position[axis] < min) current_position[axis] = min;
|
||||
if (max_software_endstops && current_position[axis] > max) current_position[axis] = max;
|
||||
encoderPosition = 0;
|
||||
line_to_current();
|
||||
line_to_current(axis);
|
||||
lcdDrawUpdate = 1;
|
||||
}
|
||||
if (lcdDrawUpdate) lcd_implementation_drawedit(name, ftostr31(current_position[axis]));
|
||||
@ -680,7 +680,7 @@ static void lcd_move_e() {
|
||||
if (encoderPosition != 0) {
|
||||
current_position[E_AXIS] += float((int)encoderPosition) * move_menu_scale;
|
||||
encoderPosition = 0;
|
||||
line_to_current();
|
||||
line_to_current(E_AXIS);
|
||||
lcdDrawUpdate = 1;
|
||||
}
|
||||
if (lcdDrawUpdate) lcd_implementation_drawedit(PSTR("Extruder"), ftostr31(current_position[E_AXIS]));
|
||||
@ -1131,23 +1131,18 @@ void lcd_quick_feedback() {
|
||||
#endif
|
||||
lcd_buzz(LCD_FEEDBACK_FREQUENCY_DURATION_MS, LCD_FEEDBACK_FREQUENCY_HZ);
|
||||
#elif defined(BEEPER) && BEEPER > -1
|
||||
SET_OUTPUT(BEEPER);
|
||||
#ifndef LCD_FEEDBACK_FREQUENCY_HZ
|
||||
#define LCD_FEEDBACK_FREQUENCY_HZ 5000
|
||||
#endif
|
||||
#ifndef LCD_FEEDBACK_FREQUENCY_DURATION_MS
|
||||
#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 2
|
||||
#endif
|
||||
const uint16_t delay = 1000000 / LCD_FEEDBACK_FREQUENCY_HZ / 2;
|
||||
uint16_t i = LCD_FEEDBACK_FREQUENCY_DURATION_MS * LCD_FEEDBACK_FREQUENCY_HZ / 1000;
|
||||
while (i--) {
|
||||
WRITE(BEEPER,HIGH);
|
||||
delayMicroseconds(delay);
|
||||
WRITE(BEEPER,LOW);
|
||||
delayMicroseconds(delay);
|
||||
}
|
||||
const uint16_t j = max(10000 - LCD_FEEDBACK_FREQUENCY_DURATION_MS * 1000, 0);
|
||||
if (j) delayMicroseconds(j);
|
||||
lcd_buzz(LCD_FEEDBACK_FREQUENCY_DURATION_MS, LCD_FEEDBACK_FREQUENCY_HZ);
|
||||
#else
|
||||
#ifndef LCD_FEEDBACK_FREQUENCY_DURATION_MS
|
||||
#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 2
|
||||
#endif
|
||||
delay(LCD_FEEDBACK_FREQUENCY_DURATION_MS);
|
||||
#endif
|
||||
}
|
||||
|
||||
@ -1397,9 +1392,9 @@ void lcd_ignore_click(bool b) {
|
||||
|
||||
void lcd_finishstatus(bool persist=false) {
|
||||
#ifdef LCD_PROGRESS_BAR
|
||||
progressBarTick = millis();
|
||||
progress_bar_ms = millis();
|
||||
#if PROGRESS_MSG_EXPIRE > 0
|
||||
expireStatusMillis = persist ? 0 : progressBarTick + PROGRESS_MSG_EXPIRE;
|
||||
expire_status_ms = persist ? 0 : progress_bar_ms + PROGRESS_MSG_EXPIRE;
|
||||
#endif
|
||||
#endif
|
||||
lcdDrawUpdate = 2;
|
||||
@ -1410,7 +1405,7 @@ void lcd_finishstatus(bool persist=false) {
|
||||
}
|
||||
|
||||
#if defined(LCD_PROGRESS_BAR) && PROGRESS_MSG_EXPIRE > 0
|
||||
void dontExpireStatus() { expireStatusMillis = 0; }
|
||||
void dontExpireStatus() { expire_status_ms = 0; }
|
||||
#endif
|
||||
|
||||
void set_utf_strlen(char *s, uint8_t n) {
|
||||
@ -1423,6 +1418,8 @@ void set_utf_strlen(char *s, uint8_t n) {
|
||||
s[i] = 0;
|
||||
}
|
||||
|
||||
bool lcd_hasstatus() { return (lcd_status_message[0] != '\0'); }
|
||||
|
||||
void lcd_setstatus(const char* message, bool persist) {
|
||||
if (lcd_status_message_level > 0) return;
|
||||
strncpy(lcd_status_message, message, 3*LCD_WIDTH);
|
||||
@ -1544,9 +1541,20 @@ bool lcd_detected(void) {
|
||||
}
|
||||
|
||||
void lcd_buzz(long duration, uint16_t freq) {
|
||||
#ifdef LCD_USE_I2C_BUZZER
|
||||
lcd.buzz(duration,freq);
|
||||
#endif
|
||||
if (freq > 0) {
|
||||
#if BEEPER > 0
|
||||
SET_OUTPUT(BEEPER);
|
||||
tone(BEEPER, freq, duration);
|
||||
delay(duration);
|
||||
#elif defined(LCD_USE_I2C_BUZZER)
|
||||
lcd.buzz(duration, freq);
|
||||
#else
|
||||
delay(duration);
|
||||
#endif
|
||||
}
|
||||
else {
|
||||
delay(duration);
|
||||
}
|
||||
}
|
||||
|
||||
bool lcd_clicked() { return LCD_CLICKED; }
|
||||
@ -1798,7 +1806,7 @@ char *ftostr52(const float &x) {
|
||||
if (min_software_endstops && current_position[Z_AXIS] < Z_MIN_POS) current_position[Z_AXIS] = Z_MIN_POS;
|
||||
if (max_software_endstops && current_position[Z_AXIS] > Z_MAX_POS) current_position[Z_AXIS] = Z_MAX_POS;
|
||||
encoderPosition = 0;
|
||||
line_to_current();
|
||||
line_to_current(Z_AXIS);
|
||||
lcdDrawUpdate = 2;
|
||||
}
|
||||
if (lcdDrawUpdate) lcd_implementation_drawedit(PSTR("Z"), ftostr43(current_position[Z_AXIS]));
|
||||
@ -1806,48 +1814,44 @@ char *ftostr52(const float &x) {
|
||||
if (LCD_CLICKED) {
|
||||
if (!debounce_click) {
|
||||
debounce_click = true;
|
||||
int ix = _lcd_level_bed_position % MESH_NUM_X_POINTS;
|
||||
int iy = _lcd_level_bed_position / MESH_NUM_X_POINTS;
|
||||
if (iy&1) { // Zig zag
|
||||
ix = (MESH_NUM_X_POINTS - 1) - ix;
|
||||
}
|
||||
int ix = _lcd_level_bed_position % MESH_NUM_X_POINTS,
|
||||
iy = _lcd_level_bed_position / MESH_NUM_X_POINTS;
|
||||
if (iy & 1) ix = (MESH_NUM_X_POINTS - 1) - ix; // Zig zag
|
||||
mbl.set_z(ix, iy, current_position[Z_AXIS]);
|
||||
_lcd_level_bed_position++;
|
||||
if (_lcd_level_bed_position == MESH_NUM_X_POINTS*MESH_NUM_Y_POINTS) {
|
||||
current_position[Z_AXIS] = MESH_HOME_SEARCH_Z;
|
||||
line_to_current();
|
||||
line_to_current(Z_AXIS);
|
||||
mbl.active = 1;
|
||||
enqueuecommands_P(PSTR("G28"));
|
||||
lcd_return_to_status();
|
||||
} else {
|
||||
}
|
||||
else {
|
||||
current_position[Z_AXIS] = MESH_HOME_SEARCH_Z;
|
||||
line_to_current();
|
||||
line_to_current(Z_AXIS);
|
||||
ix = _lcd_level_bed_position % MESH_NUM_X_POINTS;
|
||||
iy = _lcd_level_bed_position / MESH_NUM_X_POINTS;
|
||||
if (iy&1) { // Zig zag
|
||||
ix = (MESH_NUM_X_POINTS - 1) - ix;
|
||||
}
|
||||
if (iy & 1) ix = (MESH_NUM_X_POINTS - 1) - ix; // Zig zag
|
||||
current_position[X_AXIS] = mbl.get_x(ix);
|
||||
current_position[Y_AXIS] = mbl.get_y(iy);
|
||||
line_to_current();
|
||||
line_to_current(manual_feedrate[X_AXIS] <= manual_feedrate[Y_AXIS] ? X_AXIS : Y_AXIS);
|
||||
lcdDrawUpdate = 2;
|
||||
}
|
||||
}
|
||||
} else {
|
||||
}
|
||||
else {
|
||||
debounce_click = false;
|
||||
}
|
||||
}
|
||||
|
||||
static void _lcd_level_bed_homing() {
|
||||
if (lcdDrawUpdate) lcd_implementation_drawedit(PSTR("XYZ"), "Homing");
|
||||
if (axis_known_position[X_AXIS] &&
|
||||
axis_known_position[Y_AXIS] &&
|
||||
axis_known_position[Z_AXIS]) {
|
||||
if (axis_known_position[X_AXIS] && axis_known_position[Y_AXIS] && axis_known_position[Z_AXIS]) {
|
||||
current_position[Z_AXIS] = MESH_HOME_SEARCH_Z;
|
||||
plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
|
||||
current_position[X_AXIS] = MESH_MIN_X;
|
||||
current_position[Y_AXIS] = MESH_MIN_Y;
|
||||
line_to_current();
|
||||
line_to_current(manual_feedrate[X_AXIS] <= manual_feedrate[Y_AXIS] ? X_AXIS : Y_AXIS);
|
||||
_lcd_level_bed_position = 0;
|
||||
lcd_goto_menu(_lcd_level_bed);
|
||||
}
|
||||
@ -1855,9 +1859,7 @@ char *ftostr52(const float &x) {
|
||||
}
|
||||
|
||||
static void lcd_level_bed() {
|
||||
axis_known_position[X_AXIS] = false;
|
||||
axis_known_position[Y_AXIS] = false;
|
||||
axis_known_position[Z_AXIS] = false;
|
||||
axis_known_position[X_AXIS] = axis_known_position[Y_AXIS] = axis_known_position[Z_AXIS] = false;
|
||||
mbl.reset();
|
||||
enqueuecommands_P(PSTR("G28"));
|
||||
lcdDrawUpdate = 2;
|
||||
|
@ -8,6 +8,7 @@
|
||||
int lcd_strlen_P(const char *s);
|
||||
void lcd_update();
|
||||
void lcd_init();
|
||||
bool lcd_hasstatus();
|
||||
void lcd_setstatus(const char* message, const bool persist=false);
|
||||
void lcd_setstatuspgm(const char* message, const uint8_t level=0);
|
||||
void lcd_setalertstatuspgm(const char* message);
|
||||
@ -100,6 +101,7 @@
|
||||
#else //no LCD
|
||||
FORCE_INLINE void lcd_update() {}
|
||||
FORCE_INLINE void lcd_init() {}
|
||||
FORCE_INLINE bool lcd_hasstatus() { return false; }
|
||||
FORCE_INLINE void lcd_setstatus(const char* message, const bool persist=false) {}
|
||||
FORCE_INLINE void lcd_setstatuspgm(const char* message, const uint8_t level=0) {}
|
||||
FORCE_INLINE void lcd_buttons_update() {}
|
||||
@ -107,8 +109,8 @@
|
||||
FORCE_INLINE void lcd_buzz(long duration,uint16_t freq) {}
|
||||
FORCE_INLINE bool lcd_detected(void) { return true; }
|
||||
|
||||
#define LCD_MESSAGEPGM(x)
|
||||
#define LCD_ALERTMESSAGEPGM(x)
|
||||
#define LCD_MESSAGEPGM(x) do{}while(0)
|
||||
#define LCD_ALERTMESSAGEPGM(x) do{}while(0)
|
||||
|
||||
#endif //ULTRA_LCD
|
||||
|
||||
|
@ -194,9 +194,9 @@
|
||||
#include "utf_mapper.h"
|
||||
|
||||
#ifdef LCD_PROGRESS_BAR
|
||||
static uint16_t progressBarTick = 0;
|
||||
static millis_t progress_bar_ms = 0;
|
||||
#if PROGRESS_MSG_EXPIRE > 0
|
||||
static uint16_t expireStatusMillis = 0;
|
||||
static millis_t expire_status_ms = 0;
|
||||
#endif
|
||||
#define LCD_STR_PROGRESS "\x03\x04\x05"
|
||||
#endif
|
||||
@ -588,8 +588,9 @@ static void lcd_implementation_status_screen() {
|
||||
#ifdef LCD_PROGRESS_BAR
|
||||
|
||||
if (card.isFileOpen()) {
|
||||
if (millis() >= progressBarTick + PROGRESS_BAR_MSG_TIME || !lcd_status_message[0]) {
|
||||
// draw the progress bar
|
||||
// Draw the progress bar if the message has shown long enough
|
||||
// or if there is no message set.
|
||||
if (millis() >= progress_bar_ms + PROGRESS_BAR_MSG_TIME || !lcd_status_message[0]) {
|
||||
int tix = (int)(card.percentDone() * LCD_WIDTH * 3) / 100,
|
||||
cel = tix / 3, rem = tix % 3, i = LCD_WIDTH;
|
||||
char msg[LCD_WIDTH+1], b = ' ';
|
||||
|
14
README.md
14
README.md
@ -24,14 +24,13 @@ This firmware is a mashup between [Sprinter](https://github.com/kliment/Sprinter
|
||||
## Current Status: Bug Fixing
|
||||
|
||||
The Marlin development is currently revived. There's a long list of reported issues and pull requests, which we are working on currently.
|
||||
We are actively looking for testers. So please try the current development version and report new issues and feedback.
|
||||
|
||||
[![Coverity Scan Build Status](https://scan.coverity.com/projects/2224/badge.svg)](https://scan.coverity.com/projects/2224)
|
||||
[![Travis Build Status](https://travis-ci.org/MarlinFirmware/Marlin.svg)](https://travis-ci.org/MarlinFirmware/Marlin)
|
||||
|
||||
## Contact
|
||||
|
||||
__Google Hangout:__ <a href="https://plus.google.com/hangouts/_/g2wp5duzb2y6ahikg6tmwao3kua" target="_blank">Hangout</a>
|
||||
__Google Hangout:__ <a href="https://plus.google.com/hangouts/_/gxn3wrea5gdhoo223yimsiforia" target="_blank">Hangout</a>
|
||||
|
||||
## Credits
|
||||
|
||||
@ -40,10 +39,9 @@ The current Marlin dev team consists of:
|
||||
- Scott Lahteine [@thinkyhead]
|
||||
-
|
||||
|
||||
Sprinters lead developers are Kliment and caru.
|
||||
Grbl's lead developer is Simen Svale Skogsrud.
|
||||
Sonney Jeon (Chamnit) improved some parts of grbl.
|
||||
A fork by bkubicek for the Ultimaker was merged.
|
||||
## Donation
|
||||
|
||||
If you find our work usefull please consider donating. Donations will be used to pay for our website http://www.marlinfirmware.org/ and to pay some food or rent money for the very active Collaborators
|
||||
|
||||
More features have been added by:
|
||||
- Lampmaker,
|
||||
@ -52,7 +50,7 @@ More features have been added by:
|
||||
|
||||
## License
|
||||
|
||||
Marlin is published under the [GPL license](/Documentation/COPYING.md) because I believe in open development.
|
||||
Please do not use this code in products (3D printers, CNC etc) that are closed source or are crippled by a patent.
|
||||
Marlin is published under the [GPL license](/Documentation/COPYING.md) because We believe in open development.
|
||||
Do not use this code in products (3D printers, CNC etc) that are closed source or are crippled by a patent.
|
||||
|
||||
[![Flattr this git repo](http://api.flattr.com/button/flattr-badge-large.png)](https://flattr.com/submit/auto?user_id=ErikZalm&url=https://github.com/MarlinFirmware/Marlin&title=Marlin&language=&tags=github&category=software)
|
||||
|
Loading…
Reference in New Issue
Block a user