get latest Marlin_v1 changes

master
Scott Lahteine 10 years ago
parent d407a43ac1
commit 5714f64927

@ -0,0 +1,14 @@
---
language: c
before_install:
- sudo add-apt-repository -y ppa:ubuntu-toolchain-r/test
- sudo apt-get update -qq
install:
- sudo apt-get install -qq gcc-avr binutils-avr avr-libc gcc-4.8 g++-4.8 arduino
- sudo update-alternatives --install /usr/bin/gcc gcc /usr/bin/gcc-4.8 90
- sudo update-alternatives --install /usr/bin/g++ g++ /usr/bin/g++-4.8 90
- gcc --version
- g++ --version
script: "cd Marlin && make HARDWARE_MOTHERBOARD=70 ARDUINO_INSTALL_DIR=/usr/share/arduino"

@ -0,0 +1,53 @@
*** These modified files were found in JOE when it aborted on Wed Nov 26 20:52:44 2014
*** JOE was aborted because the terminal closed
*** File '/Volumes/Projects/MAKER/Firmware/Marlin-thinkyhead/.git/MERGE_MSG'
Merge remote-tracking branch 'upstream/Marlin_v1' into lcd_wait_better
# Please enter a commit message to explain why this merge is necessary,
# especially if it merges an updated upstream into a topic branch.
#
# Lines starting with '#' will be ignored, and an empty message aborts
# the commit.
*** File '(Unnamed)'
sort
echo
*** File '(Unnamed)'
d7
/drupal7
3bl-justmeans-wp/editorial
SLICER_HOME
remindmeinbox
&>
8
alchemist
/Users/lordscott/Sites/git.loc
goth
*** File '(Unnamed)'
mysql
socket
.sock
error_repo
zone
ini_set
localhost
/Library/WebServer/Documents/gitprojects
mydemoproject1
alias
*** File '(Unnamed)'
/Users/lordscott/bin/clean
thinkyhead.conf
/etc/hosts
thinkyhead.conf
drupal7.conf
thinkyhead.conf
thinkyhead.conf
thinkyhead.conf
drupal7.conf
thinkyhead.conf
/Volumes/Projects/MAKER/Firmware/Marlin-thinkyhead/.git/MERGE_MSG

@ -30,7 +30,6 @@
// Serial port 0 is still used by the Arduino bootloader regardless of this setting. // Serial port 0 is still used by the Arduino bootloader regardless of this setting.
#define SERIAL_PORT 0 #define SERIAL_PORT 0
// This determines the communication speed of the printer
// This determines the communication speed of the printer // This determines the communication speed of the printer
#define BAUDRATE 250000 #define BAUDRATE 250000
@ -49,6 +48,7 @@
// 33 = RAMPS 1.3 / 1.4 (Power outputs: Extruder, Fan, Bed) // 33 = RAMPS 1.3 / 1.4 (Power outputs: Extruder, Fan, Bed)
// 34 = RAMPS 1.3 / 1.4 (Power outputs: Extruder0, Extruder1, Bed) // 34 = RAMPS 1.3 / 1.4 (Power outputs: Extruder0, Extruder1, Bed)
// 35 = RAMPS 1.3 / 1.4 (Power outputs: Extruder, Fan, Fan) // 35 = RAMPS 1.3 / 1.4 (Power outputs: Extruder, Fan, Fan)
// 36 = RAMPS 1.3 / 1.4 (Power outputs: Extruder0, Extruder1, Fan)
// 4 = Duemilanove w/ ATMega328P pin assignment // 4 = Duemilanove w/ ATMega328P pin assignment
// 5 = Gen6 // 5 = Gen6
// 51 = Gen6 deluxe // 51 = Gen6 deluxe
@ -127,6 +127,7 @@
// 10 is 100k RS thermistor 198-961 (4.7k pullup) // 10 is 100k RS thermistor 198-961 (4.7k pullup)
// 11 is 100k beta 3950 1% thermistor (4.7k pullup) // 11 is 100k beta 3950 1% thermistor (4.7k pullup)
// 12 is 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup) (calibrated for Makibox hot bed) // 12 is 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup) (calibrated for Makibox hot bed)
// 13 is 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
// 20 is the PT100 circuit found in the Ultimainboard V2.x // 20 is the PT100 circuit found in the Ultimainboard V2.x
// 60 is 100k Maker's Tool Works Kapton Bed Thermistor beta=3950 // 60 is 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
// //
@ -192,7 +193,7 @@
// is more then PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max. // is more then PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
#define PID_INTEGRAL_DRIVE_MAX 255 //limit for the integral term #define PID_INTEGRAL_DRIVE_MAX 255 //limit for the integral term
#define K1 0.95 //smoothing factor within the PID #define K1 0.95 //smoothing factor within the PID
#define PID_dT ((OVERSAMPLENR * 8.0)/(F_CPU / 64.0 / 256.0)) //sampling period of the temperature routine #define PID_dT ((OVERSAMPLENR * 10.0)/(F_CPU / 64.0 / 256.0)) //sampling period of the temperature routine
// If you are using a pre-configured hotend then you can use one of the value sets by uncommenting it // If you are using a pre-configured hotend then you can use one of the value sets by uncommenting it
// Ultimaker // Ultimaker
@ -765,6 +766,37 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
//#define SERVO_ENDSTOPS {-1, -1, 0} // Servo index for X, Y, Z. Disable with -1 //#define SERVO_ENDSTOPS {-1, -1, 0} // Servo index for X, Y, Z. Disable with -1
//#define SERVO_ENDSTOP_ANGLES {0,0, 0,0, 70,0} // X,Y,Z Axis Extend and Retract angles //#define SERVO_ENDSTOP_ANGLES {0,0, 0,0, 70,0} // X,Y,Z Axis Extend and Retract angles
/**********************************************************************\
* Support for a filament diameter sensor
* Also allows adjustment of diameter at print time (vs at slicing)
* Single extruder only at this point (extruder 0)
*
* Motherboards
* 34 - RAMPS1.4 - uses Analog input 5 on the AUX2 connector
* 81 - Printrboard - Uses Analog input 2 on the Aux 2 connector
* 301 - Rambo - uses Analog input 3
* Note may require analog pins to be defined for different motherboards
**********************************************************************/
// 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 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)
//defines used in the code
#define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA //set measured to nominal initially
#include "Configuration_adv.h" #include "Configuration_adv.h"
#include "thermistortables.h" #include "thermistortables.h"

@ -65,7 +65,7 @@ void Config_StoreSettings()
EEPROM_WRITE_VAR(i,max_xy_jerk); EEPROM_WRITE_VAR(i,max_xy_jerk);
EEPROM_WRITE_VAR(i,max_z_jerk); EEPROM_WRITE_VAR(i,max_z_jerk);
EEPROM_WRITE_VAR(i,max_e_jerk); EEPROM_WRITE_VAR(i,max_e_jerk);
EEPROM_WRITE_VAR(i,add_homeing); EEPROM_WRITE_VAR(i,add_homing);
#ifdef DELTA #ifdef DELTA
EEPROM_WRITE_VAR(i,endstop_adj); EEPROM_WRITE_VAR(i,endstop_adj);
EEPROM_WRITE_VAR(i,delta_radius); EEPROM_WRITE_VAR(i,delta_radius);
@ -170,9 +170,9 @@ SERIAL_ECHOLNPGM("Scaling factors:");
SERIAL_ECHO_START; SERIAL_ECHO_START;
SERIAL_ECHOLNPGM("Home offset (mm):"); SERIAL_ECHOLNPGM("Home offset (mm):");
SERIAL_ECHO_START; SERIAL_ECHO_START;
SERIAL_ECHOPAIR(" M206 X",add_homeing[0] ); SERIAL_ECHOPAIR(" M206 X",add_homing[0] );
SERIAL_ECHOPAIR(" Y" ,add_homeing[1] ); SERIAL_ECHOPAIR(" Y" ,add_homing[1] );
SERIAL_ECHOPAIR(" Z" ,add_homeing[2] ); SERIAL_ECHOPAIR(" Z" ,add_homing[2] );
SERIAL_ECHOLN(""); SERIAL_ECHOLN("");
#ifdef DELTA #ifdef DELTA
SERIAL_ECHO_START; SERIAL_ECHO_START;
@ -229,7 +229,7 @@ void Config_RetrieveSettings()
EEPROM_READ_VAR(i,max_xy_jerk); EEPROM_READ_VAR(i,max_xy_jerk);
EEPROM_READ_VAR(i,max_z_jerk); EEPROM_READ_VAR(i,max_z_jerk);
EEPROM_READ_VAR(i,max_e_jerk); EEPROM_READ_VAR(i,max_e_jerk);
EEPROM_READ_VAR(i,add_homeing); EEPROM_READ_VAR(i,add_homing);
#ifdef DELTA #ifdef DELTA
EEPROM_READ_VAR(i,endstop_adj); EEPROM_READ_VAR(i,endstop_adj);
EEPROM_READ_VAR(i,delta_radius); EEPROM_READ_VAR(i,delta_radius);
@ -303,7 +303,7 @@ void Config_ResetDefault()
max_xy_jerk=DEFAULT_XYJERK; max_xy_jerk=DEFAULT_XYJERK;
max_z_jerk=DEFAULT_ZJERK; max_z_jerk=DEFAULT_ZJERK;
max_e_jerk=DEFAULT_EJERK; max_e_jerk=DEFAULT_EJERK;
add_homeing[0] = add_homeing[1] = add_homeing[2] = 0; add_homing[0] = add_homing[1] = add_homing[2] = 0;
#ifdef DELTA #ifdef DELTA
endstop_adj[0] = endstop_adj[1] = endstop_adj[2] = 0; endstop_adj[0] = endstop_adj[1] = endstop_adj[2] = 0;
delta_radius= DELTA_RADIUS; delta_radius= DELTA_RADIUS;

@ -68,54 +68,162 @@ const unsigned char start_bmp[574] PROGMEM = { //AVR-GCC, WinAVR
0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xF0 0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xF0
}; };
#define STATUS_SCREENWIDTH 115 //Width in pixels // Here comes a compile-time operation to match the extruder symbols
#define STATUS_SCREENHEIGHT 19 //Height in pixels // on the info screen to the set number of extruders in configuration.h
#define STATUS_SCREENBYTEWIDTH 15 //Width in bytes //
const unsigned char status_screen0_bmp[] PROGMEM = { //AVR-GCC, WinAVR // When only one extruder is selected, the "1" on the symbol will not
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x7F,0xFF,0xE0, // be displayed.
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x70,0x00,0xE0,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x63,0x0C,0x60,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x47,0x0E,0x20,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x4F,0x0F,0x20,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x5F,0x0F,0xA0,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x5E,0x07,0xA0,
0x7F,0x80,0x00,0x3F,0xC0,0x00,0x3F,0xC0,0x00,0x41,0x04,0x00,0x40,0x60,0x20,
0xFB,0xC0,0x00,0x79,0xE0,0x00,0x79,0xE0,0x00,0x20,0x82,0x00,0x40,0xF0,0x20,
0xF3,0xC0,0x00,0x76,0xE0,0x00,0x76,0xE0,0x00,0x20,0x82,0x00,0x40,0xF0,0x20,
0xEB,0xC0,0x00,0x7E,0xE0,0x00,0x7E,0xE0,0x00,0x41,0x04,0x00,0x40,0x60,0x20,
0x7B,0x80,0x00,0x3D,0xC0,0x00,0x39,0xC0,0x00,0x82,0x08,0x00,0x5E,0x07,0xA0,
0x7B,0x80,0x00,0x3B,0xC0,0x00,0x3E,0xC0,0x01,0x04,0x10,0x00,0x5F,0x0F,0xA0,
0xFB,0xC0,0x00,0x77,0xE0,0x00,0x76,0xE0,0x01,0x04,0x10,0x00,0x4F,0x0F,0x20,
0xFB,0xC0,0x00,0x70,0xE0,0x00,0x79,0xE0,0x00,0x82,0x08,0x00,0x47,0x0E,0x20,
0xFF,0xC0,0x00,0x7F,0xE0,0x00,0x7F,0xE0,0x00,0x41,0x04,0x00,0x63,0x0C,0x60,
0x3F,0x00,0x00,0x1F,0x80,0x00,0x1F,0x80,0x00,0x00,0x00,0x00,0x70,0x00,0xE0,
0x1E,0x00,0x00,0x0F,0x00,0x00,0x0F,0x00,0x01,0xFF,0xFF,0x80,0x7F,0xFF,0xE0,
0x0C,0x00,0x00,0x06,0x00,0x00,0x06,0x00,0x01,0xFF,0xFF,0x80,0x00,0x00,0x00
};
#define STATUS_SCREENWIDTH 115 //Width in pixels #if EXTRUDERS == 1
#define STATUS_SCREENHEIGHT 19 //Height in pixels #define STATUS_SCREENWIDTH 115 //Width in pixels
#define STATUS_SCREENBYTEWIDTH 15 //Width in bytes #define STATUS_SCREENHEIGHT 19 //Height in pixels
const unsigned char status_screen1_bmp[] PROGMEM = { //AVR-GCC, WinAVR #define STATUS_SCREENBYTEWIDTH 15 //Width in bytes
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x7F,0xFF,0xE0, const unsigned char status_screen0_bmp[] PROGMEM = { //AVR-GCC, WinAVR
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x70,0x00,0xE0, 0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x7F,0xFF,0xE0,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x61,0xF8,0x60, 0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x70,0x00,0xE0,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x41,0xF8,0x20, 0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x63,0x0C,0x60,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x40,0xF0,0x20, 0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x47,0x0E,0x20,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x40,0x60,0x20, 0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x4F,0x0F,0x20,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x58,0x01,0xA0, 0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x5F,0x0F,0xA0,
0x7F,0x80,0x00,0x3F,0xC0,0x00,0x3F,0xC0,0x00,0x41,0x04,0x00,0x5C,0x63,0xA0, 0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x5E,0x07,0xA0,
0xFB,0xC0,0x00,0x79,0xE0,0x00,0x79,0xE0,0x00,0x20,0x82,0x00,0x5E,0xF7,0xA0, 0x7F,0x80,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x41,0x04,0x00,0x40,0x60,0x20,
0xF3,0xC0,0x00,0x76,0xE0,0x00,0x76,0xE0,0x00,0x20,0x82,0x00,0x5E,0xF7,0xA0, 0xFF,0xC0,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x20,0x82,0x00,0x40,0xF0,0x20,
0xEB,0xC0,0x00,0x7E,0xE0,0x00,0x7E,0xE0,0x00,0x41,0x04,0x00,0x5C,0x63,0xA0, 0xFF,0xC0,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x20,0x82,0x00,0x40,0xF0,0x20,
0x7B,0x80,0x00,0x3D,0xC0,0x00,0x39,0xC0,0x00,0x82,0x08,0x00,0x58,0x01,0xA0, 0xFF,0xC0,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x41,0x04,0x00,0x40,0x60,0x20,
0x7B,0x80,0x00,0x3B,0xC0,0x00,0x3E,0xC0,0x01,0x04,0x10,0x00,0x40,0x60,0x20, 0x7F,0x80,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x82,0x08,0x00,0x5E,0x07,0xA0,
0xFB,0xC0,0x00,0x77,0xE0,0x00,0x76,0xE0,0x01,0x04,0x10,0x00,0x40,0xF0,0x20, 0x7F,0x80,0x00,0x00,0x00,0x00,0x00,0x00,0x01,0x04,0x10,0x00,0x5F,0x0F,0xA0,
0xFB,0xC0,0x00,0x70,0xE0,0x00,0x79,0xE0,0x00,0x82,0x08,0x00,0x41,0xF8,0x20, 0xFF,0xC0,0x00,0x00,0x00,0x00,0x00,0x00,0x01,0x04,0x10,0x00,0x4F,0x0F,0x20,
0xFF,0xC0,0x00,0x7F,0xE0,0x00,0x7F,0xE0,0x00,0x41,0x04,0x00,0x61,0xF8,0x60, 0xFF,0xC0,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x82,0x08,0x00,0x47,0x0E,0x20,
0x3F,0x00,0x00,0x1F,0x80,0x00,0x1F,0x80,0x00,0x00,0x00,0x00,0x70,0x00,0xE0, 0xFF,0xC0,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x41,0x04,0x00,0x63,0x0C,0x60,
0x1E,0x00,0x00,0x0F,0x00,0x00,0x0F,0x00,0x01,0xFF,0xFF,0x80,0x7F,0xFF,0xE0, 0x3F,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x70,0x00,0xE0,
0x0C,0x00,0x00,0x06,0x00,0x00,0x06,0x00,0x01,0xFF,0xFF,0x80,0x00,0x00,0x00 0x1E,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x01,0xFF,0xFF,0x80,0x7F,0xFF,0xE0,
}; 0x0C,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x01,0xFF,0xFF,0x80,0x00,0x00,0x00
};
#define STATUS_SCREENWIDTH 115 //Width in pixels
#define STATUS_SCREENHEIGHT 19 //Height in pixels
#define STATUS_SCREENBYTEWIDTH 15 //Width in bytes
const unsigned char status_screen1_bmp[] PROGMEM = { //AVR-GCC, WinAVR
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x7F,0xFF,0xE0,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x70,0x00,0xE0,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x61,0xF8,0x60,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x41,0xF8,0x20,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x40,0xF0,0x20,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x40,0x60,0x20,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x58,0x01,0xA0,
0x7F,0x80,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x41,0x04,0x00,0x5C,0x63,0xA0,
0xFF,0xC0,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x20,0x82,0x00,0x5E,0xF7,0xA0,
0xFF,0xC0,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x20,0x82,0x00,0x5E,0xF7,0xA0,
0xFF,0xC0,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x41,0x04,0x00,0x5C,0x63,0xA0,
0x7F,0x80,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x82,0x08,0x00,0x58,0x01,0xA0,
0x7F,0x80,0x00,0x00,0x00,0x00,0x00,0x00,0x01,0x04,0x10,0x00,0x40,0x60,0x20,
0xFF,0xC0,0x00,0x00,0x00,0x00,0x00,0x00,0x01,0x04,0x10,0x00,0x40,0xF0,0x20,
0xFF,0xC0,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x82,0x08,0x00,0x41,0xF8,0x20,
0xFF,0xC0,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x41,0x04,0x00,0x61,0xF8,0x60,
0x3F,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x70,0x00,0xE0,
0x1E,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x01,0xFF,0xFF,0x80,0x7F,0xFF,0xE0,
0x0C,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x01,0xFF,0xFF,0x80,0x00,0x00,0x00
};
#elif EXTRUDERS == 2
#define STATUS_SCREENWIDTH 115 //Width in pixels
#define STATUS_SCREENHEIGHT 19 //Height in pixels
#define STATUS_SCREENBYTEWIDTH 15 //Width in bytes
const unsigned char status_screen0_bmp[] PROGMEM = { //AVR-GCC, WinAVR
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x7F,0xFF,0xE0,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x70,0x00,0xE0,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x63,0x0C,0x60,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x47,0x0E,0x20,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x4F,0x0F,0x20,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x5F,0x0F,0xA0,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x5E,0x07,0xA0,
0x7F,0x80,0x00,0x3F,0xC0,0x00,0x00,0x00,0x00,0x41,0x04,0x00,0x40,0x60,0x20,
0xFB,0xC0,0x00,0x79,0xE0,0x00,0x00,0x00,0x00,0x20,0x82,0x00,0x40,0xF0,0x20,
0xF3,0xC0,0x00,0x76,0xE0,0x00,0x00,0x00,0x00,0x20,0x82,0x00,0x40,0xF0,0x20,
0xEB,0xC0,0x00,0x7E,0xE0,0x00,0x00,0x00,0x00,0x41,0x04,0x00,0x40,0x60,0x20,
0x7B,0x80,0x00,0x3D,0xC0,0x00,0x00,0x00,0x00,0x82,0x08,0x00,0x5E,0x07,0xA0,
0x7B,0x80,0x00,0x3B,0xC0,0x00,0x00,0x00,0x01,0x04,0x10,0x00,0x5F,0x0F,0xA0,
0xFB,0xC0,0x00,0x77,0xE0,0x00,0x00,0x00,0x01,0x04,0x10,0x00,0x4F,0x0F,0x20,
0xFB,0xC0,0x00,0x70,0xE0,0x00,0x00,0x00,0x00,0x82,0x08,0x00,0x47,0x0E,0x20,
0xFF,0xC0,0x00,0x7F,0xE0,0x00,0x00,0x00,0x00,0x41,0x04,0x00,0x63,0x0C,0x60,
0x3F,0x00,0x00,0x1F,0x80,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x70,0x00,0xE0,
0x1E,0x00,0x00,0x0F,0x00,0x00,0x00,0x00,0x01,0xFF,0xFF,0x80,0x7F,0xFF,0xE0,
0x0C,0x00,0x00,0x06,0x00,0x00,0x00,0x00,0x01,0xFF,0xFF,0x80,0x00,0x00,0x00
};
#define STATUS_SCREENWIDTH 115 //Width in pixels
#define STATUS_SCREENHEIGHT 19 //Height in pixels
#define STATUS_SCREENBYTEWIDTH 15 //Width in bytes
const unsigned char status_screen1_bmp[] PROGMEM = { //AVR-GCC, WinAVR
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x7F,0xFF,0xE0,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x70,0x00,0xE0,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x61,0xF8,0x60,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x41,0xF8,0x20,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x40,0xF0,0x20,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x40,0x60,0x20,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x58,0x01,0xA0,
0x7F,0x80,0x00,0x3F,0xC0,0x00,0x00,0x00,0x00,0x41,0x04,0x00,0x5C,0x63,0xA0,
0xFB,0xC0,0x00,0x79,0xE0,0x00,0x00,0x00,0x00,0x20,0x82,0x00,0x5E,0xF7,0xA0,
0xF3,0xC0,0x00,0x76,0xE0,0x00,0x00,0x00,0x00,0x20,0x82,0x00,0x5E,0xF7,0xA0,
0xEB,0xC0,0x00,0x7E,0xE0,0x00,0x00,0x00,0x00,0x41,0x04,0x00,0x5C,0x63,0xA0,
0x7B,0x80,0x00,0x3D,0xC0,0x00,0x00,0x00,0x00,0x82,0x08,0x00,0x58,0x01,0xA0,
0x7B,0x80,0x00,0x3B,0xC0,0x00,0x00,0x00,0x01,0x04,0x10,0x00,0x40,0x60,0x20,
0xFB,0xC0,0x00,0x77,0xE0,0x00,0x00,0x00,0x01,0x04,0x10,0x00,0x40,0xF0,0x20,
0xFB,0xC0,0x00,0x70,0xE0,0x00,0x00,0x00,0x00,0x82,0x08,0x00,0x41,0xF8,0x20,
0xFF,0xC0,0x00,0x7F,0xE0,0x00,0x00,0x00,0x00,0x41,0x04,0x00,0x61,0xF8,0x60,
0x3F,0x00,0x00,0x1F,0x80,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x70,0x00,0xE0,
0x1E,0x00,0x00,0x0F,0x00,0x00,0x00,0x00,0x01,0xFF,0xFF,0x80,0x7F,0xFF,0xE0,
0x0C,0x00,0x00,0x06,0x00,0x00,0x00,0x00,0x01,0xFF,0xFF,0x80,0x00,0x00,0x00
};
#else
#define STATUS_SCREENWIDTH 115 //Width in pixels
#define STATUS_SCREENHEIGHT 19 //Height in pixels
#define STATUS_SCREENBYTEWIDTH 15 //Width in bytes
const unsigned char status_screen0_bmp[] PROGMEM = { //AVR-GCC, WinAVR
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x7F,0xFF,0xE0,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x70,0x00,0xE0,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x63,0x0C,0x60,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x47,0x0E,0x20,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x4F,0x0F,0x20,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x5F,0x0F,0xA0,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x5E,0x07,0xA0,
0x7F,0x80,0x00,0x3F,0xC0,0x00,0x3F,0xC0,0x00,0x41,0x04,0x00,0x40,0x60,0x20,
0xFB,0xC0,0x00,0x79,0xE0,0x00,0x79,0xE0,0x00,0x20,0x82,0x00,0x40,0xF0,0x20,
0xF3,0xC0,0x00,0x76,0xE0,0x00,0x76,0xE0,0x00,0x20,0x82,0x00,0x40,0xF0,0x20,
0xEB,0xC0,0x00,0x7E,0xE0,0x00,0x7E,0xE0,0x00,0x41,0x04,0x00,0x40,0x60,0x20,
0x7B,0x80,0x00,0x3D,0xC0,0x00,0x39,0xC0,0x00,0x82,0x08,0x00,0x5E,0x07,0xA0,
0x7B,0x80,0x00,0x3B,0xC0,0x00,0x3E,0xC0,0x01,0x04,0x10,0x00,0x5F,0x0F,0xA0,
0xFB,0xC0,0x00,0x77,0xE0,0x00,0x76,0xE0,0x01,0x04,0x10,0x00,0x4F,0x0F,0x20,
0xFB,0xC0,0x00,0x70,0xE0,0x00,0x79,0xE0,0x00,0x82,0x08,0x00,0x47,0x0E,0x20,
0xFF,0xC0,0x00,0x7F,0xE0,0x00,0x7F,0xE0,0x00,0x41,0x04,0x00,0x63,0x0C,0x60,
0x3F,0x00,0x00,0x1F,0x80,0x00,0x1F,0x80,0x00,0x00,0x00,0x00,0x70,0x00,0xE0,
0x1E,0x00,0x00,0x0F,0x00,0x00,0x0F,0x00,0x01,0xFF,0xFF,0x80,0x7F,0xFF,0xE0,
0x0C,0x00,0x00,0x06,0x00,0x00,0x06,0x00,0x01,0xFF,0xFF,0x80,0x00,0x00,0x00
};
#define STATUS_SCREENWIDTH 115 //Width in pixels
#define STATUS_SCREENHEIGHT 19 //Height in pixels
#define STATUS_SCREENBYTEWIDTH 15 //Width in bytes
const unsigned char status_screen1_bmp[] PROGMEM = { //AVR-GCC, WinAVR
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x7F,0xFF,0xE0,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x70,0x00,0xE0,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x61,0xF8,0x60,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x41,0xF8,0x20,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x40,0xF0,0x20,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x40,0x60,0x20,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x58,0x01,0xA0,
0x7F,0x80,0x00,0x3F,0xC0,0x00,0x3F,0xC0,0x00,0x41,0x04,0x00,0x5C,0x63,0xA0,
0xFB,0xC0,0x00,0x79,0xE0,0x00,0x79,0xE0,0x00,0x20,0x82,0x00,0x5E,0xF7,0xA0,
0xF3,0xC0,0x00,0x76,0xE0,0x00,0x76,0xE0,0x00,0x20,0x82,0x00,0x5E,0xF7,0xA0,
0xEB,0xC0,0x00,0x7E,0xE0,0x00,0x7E,0xE0,0x00,0x41,0x04,0x00,0x5C,0x63,0xA0,
0x7B,0x80,0x00,0x3D,0xC0,0x00,0x39,0xC0,0x00,0x82,0x08,0x00,0x58,0x01,0xA0,
0x7B,0x80,0x00,0x3B,0xC0,0x00,0x3E,0xC0,0x01,0x04,0x10,0x00,0x40,0x60,0x20,
0xFB,0xC0,0x00,0x77,0xE0,0x00,0x76,0xE0,0x01,0x04,0x10,0x00,0x40,0xF0,0x20,
0xFB,0xC0,0x00,0x70,0xE0,0x00,0x79,0xE0,0x00,0x82,0x08,0x00,0x41,0xF8,0x20,
0xFF,0xC0,0x00,0x7F,0xE0,0x00,0x7F,0xE0,0x00,0x41,0x04,0x00,0x61,0xF8,0x60,
0x3F,0x00,0x00,0x1F,0x80,0x00,0x1F,0x80,0x00,0x00,0x00,0x00,0x70,0x00,0xE0,
0x1E,0x00,0x00,0x0F,0x00,0x00,0x0F,0x00,0x01,0xFF,0xFF,0x80,0x7F,0xFF,0xE0,
0x0C,0x00,0x00,0x06,0x00,0x00,0x06,0x00,0x01,0xFF,0xFF,0x80,0x00,0x00,0x00
};
#endif // Extruders

@ -211,7 +211,7 @@ extern int extrudemultiply; // Sets extrude multiply factor (in percent) for all
extern int extruder_multiply[EXTRUDERS]; // sets extrude multiply factor (in percent) for each extruder individually extern int extruder_multiply[EXTRUDERS]; // sets extrude multiply factor (in percent) for each extruder individually
extern float volumetric_multiplier[EXTRUDERS]; // reciprocal of cross-sectional area of filament (in square millimeters), stored this way to reduce computational burden in planner extern float volumetric_multiplier[EXTRUDERS]; // reciprocal of cross-sectional area of filament (in square millimeters), stored this way to reduce computational burden in planner
extern float current_position[NUM_AXIS] ; extern float current_position[NUM_AXIS] ;
extern float add_homeing[3]; extern float add_homing[3];
#ifdef DELTA #ifdef DELTA
extern float endstop_adj[3]; extern float endstop_adj[3];
extern float delta_radius; extern float delta_radius;
@ -236,6 +236,16 @@ extern int EtoPPressure;
extern unsigned char fanSpeedSoftPwm; extern unsigned char fanSpeedSoftPwm;
#endif #endif
#ifdef FILAMENT_SENSOR
extern float filament_width_nominal; //holds the theoretical filament diameter ie., 3.00 or 1.75
extern bool filament_sensor; //indicates that filament sensor readings should control extrusion
extern float filament_width_meas; //holds the filament diameter as accurately measured
extern signed char measurement_delay[]; //ring buffer to delay measurement
extern int delay_index1, delay_index2; //index into ring buffer
extern float delay_dist; //delay distance counter
extern int meas_delay_cm; //delay distance
#endif
#ifdef FWRETRACT #ifdef FWRETRACT
extern bool autoretract_enabled; extern bool autoretract_enabled;
extern bool retracted[EXTRUDERS]; extern bool retracted[EXTRUDERS];

@ -73,7 +73,7 @@ void MarlinSerial::begin(long baud)
bool useU2X = true; bool useU2X = true;
#if F_CPU == 16000000UL && SERIAL_PORT == 0 #if F_CPU == 16000000UL && SERIAL_PORT == 0
// hard coded exception for compatibility with the bootloader shipped // hard-coded exception for compatibility with the bootloader shipped
// with the Duemilanove and previous boards and the firmware on the 8U2 // with the Duemilanove and previous boards and the firmware on the 8U2
// on the Uno and Mega 2560. // on the Uno and Mega 2560.
if (baud == 57600) { if (baud == 57600) {

@ -159,6 +159,10 @@
// M400 - Finish all moves // M400 - Finish all moves
// M401 - Lower z-probe if present // M401 - Lower z-probe if present
// M402 - Raise z-probe if present // M402 - Raise z-probe if present
// M404 - N<dia in mm> Enter the nominal filament width (3mm, 1.75mm ) or will display nominal filament width without parameters
// 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 - Displays measured filament diameter
// M500 - stores parameters in EEPROM // M500 - stores parameters in EEPROM
// M501 - reads parameters from EEPROM (if you need reset them after you changed them temporarily). // M501 - reads parameters from EEPROM (if you need reset them after you changed them temporarily).
// M502 - reverts to the default "factory settings". You still need to store them in EEPROM afterwards if you want to. // M502 - reverts to the default "factory settings". You still need to store them in EEPROM afterwards if you want to.
@ -220,7 +224,7 @@ float volumetric_multiplier[EXTRUDERS] = {1.0
#endif #endif
}; };
float current_position[NUM_AXIS] = { 0.0, 0.0, 0.0, 0.0 }; float current_position[NUM_AXIS] = { 0.0, 0.0, 0.0, 0.0 };
float add_homeing[3]={0,0,0}; float add_homing[3]={0,0,0};
#ifdef DELTA #ifdef DELTA
float endstop_adj[3]={0,0,0}; float endstop_adj[3]={0,0,0};
#endif #endif
@ -313,12 +317,28 @@ float axis_scaling[3]={1,1,1}; // Build size scaling, default to 1
bool cancel_heatup = false ; bool cancel_heatup = false ;
#ifdef FILAMENT_SENSOR
//Variables for Filament Sensor input
float filament_width_nominal=DEFAULT_NOMINAL_FILAMENT_DIA; //Set nominal filament width, can be changed with M404
bool filament_sensor=false; //M405 turns on filament_sensor control, M406 turns it off
float filament_width_meas=DEFAULT_MEASURED_FILAMENT_DIA; //Stores the measured filament diameter
signed char measurement_delay[MAX_MEASUREMENT_DELAY+1]; //ring buffer to delay measurement store extruder factor after subtracting 100
int delay_index1=0; //index into ring buffer
int delay_index2=-1; //index into ring buffer - set to -1 on startup to indicate ring buffer needs to be initialized
float delay_dist=0; //delay distance counter
int meas_delay_cm = MEASUREMENT_DELAY_CM; //distance delay setting
#endif
//=========================================================================== //===========================================================================
//=============================Private Variables============================= //=============================Private Variables=============================
//=========================================================================== //===========================================================================
const char axis_codes[NUM_AXIS] = {'X', 'Y', 'Z', 'E'}; const char axis_codes[NUM_AXIS] = {'X', 'Y', 'Z', 'E'};
static float destination[NUM_AXIS] = { 0.0, 0.0, 0.0, 0.0}; static float destination[NUM_AXIS] = { 0.0, 0.0, 0.0, 0.0};
#ifndef DELTA
static float delta[3] = {0.0, 0.0, 0.0}; static float delta[3] = {0.0, 0.0, 0.0};
#endif
static float offset[3] = {0.0, 0.0, 0.0}; static float offset[3] = {0.0, 0.0, 0.0};
static bool home_all_axis = true; static bool home_all_axis = true;
static float feedrate = 1500.0, next_feedrate, saved_feedrate; static float feedrate = 1500.0, next_feedrate, saved_feedrate;
@ -506,6 +526,7 @@ void servo_init()
#endif #endif
} }
void setup() void setup()
{ {
setup_killpin(); setup_killpin();
@ -556,6 +577,7 @@ void setup()
setup_photpin(); setup_photpin();
servo_init(); servo_init();
lcd_init(); lcd_init();
_delay_ms(1000); // wait 1sec to display the splash screen _delay_ms(1000); // wait 1sec to display the splash screen
@ -852,7 +874,7 @@ static int dual_x_carriage_mode = DEFAULT_DUAL_X_CARRIAGE_MODE;
static float x_home_pos(int extruder) { static float x_home_pos(int extruder) {
if (extruder == 0) if (extruder == 0)
return base_home_pos(X_AXIS) + add_homeing[X_AXIS]; return base_home_pos(X_AXIS) + add_homing[X_AXIS];
else else
// In dual carriage mode the extruder offset provides an override of the // In dual carriage mode the extruder offset provides an override of the
// second X-carriage offset when homed - otherwise X2_HOME_POS is used. // second X-carriage offset when homed - otherwise X2_HOME_POS is used.
@ -884,9 +906,9 @@ static void axis_is_at_home(int axis) {
return; return;
} }
else if (dual_x_carriage_mode == DXC_DUPLICATION_MODE && active_extruder == 0) { else if (dual_x_carriage_mode == DXC_DUPLICATION_MODE && active_extruder == 0) {
current_position[X_AXIS] = base_home_pos(X_AXIS) + add_homeing[X_AXIS]; current_position[X_AXIS] = base_home_pos(X_AXIS) + add_homing[X_AXIS];
min_pos[X_AXIS] = base_min_pos(X_AXIS) + add_homeing[X_AXIS]; min_pos[X_AXIS] = base_min_pos(X_AXIS) + add_homing[X_AXIS];
max_pos[X_AXIS] = min(base_max_pos(X_AXIS) + add_homeing[X_AXIS], max_pos[X_AXIS] = min(base_max_pos(X_AXIS) + add_homing[X_AXIS],
max(extruder_offset[X_AXIS][1], X2_MAX_POS) - duplicate_extruder_x_offset); max(extruder_offset[X_AXIS][1], X2_MAX_POS) - duplicate_extruder_x_offset);
return; return;
} }
@ -914,11 +936,11 @@ static void axis_is_at_home(int axis) {
for (i=0; i<2; i++) for (i=0; i<2; i++)
{ {
delta[i] -= add_homeing[i]; delta[i] -= add_homing[i];
} }
// SERIAL_ECHOPGM("addhome X="); SERIAL_ECHO(add_homeing[X_AXIS]); // SERIAL_ECHOPGM("addhome X="); SERIAL_ECHO(add_homing[X_AXIS]);
// SERIAL_ECHOPGM(" addhome Y="); SERIAL_ECHO(add_homeing[Y_AXIS]); // SERIAL_ECHOPGM(" addhome Y="); SERIAL_ECHO(add_homing[Y_AXIS]);
// SERIAL_ECHOPGM(" addhome Theta="); SERIAL_ECHO(delta[X_AXIS]); // SERIAL_ECHOPGM(" addhome Theta="); SERIAL_ECHO(delta[X_AXIS]);
// SERIAL_ECHOPGM(" addhome Psi+Theta="); SERIAL_ECHOLN(delta[Y_AXIS]); // SERIAL_ECHOPGM(" addhome Psi+Theta="); SERIAL_ECHOLN(delta[Y_AXIS]);
@ -936,14 +958,14 @@ static void axis_is_at_home(int axis) {
} }
else else
{ {
current_position[axis] = base_home_pos(axis) + add_homeing[axis]; current_position[axis] = base_home_pos(axis) + add_homing[axis];
min_pos[axis] = base_min_pos(axis) + add_homeing[axis]; min_pos[axis] = base_min_pos(axis) + add_homing[axis];
max_pos[axis] = base_max_pos(axis) + add_homeing[axis]; max_pos[axis] = base_max_pos(axis) + add_homing[axis];
} }
#else #else
current_position[axis] = base_home_pos(axis) + add_homeing[axis]; current_position[axis] = base_home_pos(axis) + add_homing[axis];
min_pos[axis] = base_min_pos(axis) + add_homeing[axis]; min_pos[axis] = base_min_pos(axis) + add_homing[axis];
max_pos[axis] = base_max_pos(axis) + add_homeing[axis]; max_pos[axis] = base_max_pos(axis) + add_homing[axis];
#endif #endif
} }
@ -1515,7 +1537,7 @@ void process_commands()
#ifdef SCARA #ifdef SCARA
current_position[X_AXIS]=code_value(); current_position[X_AXIS]=code_value();
#else #else
current_position[X_AXIS]=code_value()+add_homeing[0]; current_position[X_AXIS]=code_value()+add_homing[0];
#endif #endif
} }
} }
@ -1525,7 +1547,7 @@ void process_commands()
#ifdef SCARA #ifdef SCARA
current_position[Y_AXIS]=code_value(); current_position[Y_AXIS]=code_value();
#else #else
current_position[Y_AXIS]=code_value()+add_homeing[1]; current_position[Y_AXIS]=code_value()+add_homing[1];
#endif #endif
} }
} }
@ -1590,7 +1612,7 @@ void process_commands()
if(code_seen(axis_codes[Z_AXIS])) { if(code_seen(axis_codes[Z_AXIS])) {
if(code_value_long() != 0) { if(code_value_long() != 0) {
current_position[Z_AXIS]=code_value()+add_homeing[2]; current_position[Z_AXIS]=code_value()+add_homing[2];
} }
} }
#ifdef ENABLE_AUTO_BED_LEVELING #ifdef ENABLE_AUTO_BED_LEVELING
@ -1819,10 +1841,10 @@ void process_commands()
current_position[i] = code_value(); current_position[i] = code_value();
} }
else { else {
current_position[i] = code_value()+add_homeing[i]; current_position[i] = code_value()+add_homing[i];
} }
#else #else
current_position[i] = code_value()+add_homeing[i]; current_position[i] = code_value()+add_homing[i];
#endif #endif
plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]); plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
} }
@ -2721,9 +2743,9 @@ Sigma_Exit:
SERIAL_PROTOCOLLN(""); SERIAL_PROTOCOLLN("");
SERIAL_PROTOCOLPGM("SCARA Cal - Theta:"); SERIAL_PROTOCOLPGM("SCARA Cal - Theta:");
SERIAL_PROTOCOL(delta[X_AXIS]+add_homeing[0]); SERIAL_PROTOCOL(delta[X_AXIS]+add_homing[0]);
SERIAL_PROTOCOLPGM(" Psi+Theta (90):"); SERIAL_PROTOCOLPGM(" Psi+Theta (90):");
SERIAL_PROTOCOL(delta[Y_AXIS]-delta[X_AXIS]-90+add_homeing[1]); SERIAL_PROTOCOL(delta[Y_AXIS]-delta[X_AXIS]-90+add_homing[1]);
SERIAL_PROTOCOLLN(""); SERIAL_PROTOCOLLN("");
SERIAL_PROTOCOLPGM("SCARA step Cal - Theta:"); SERIAL_PROTOCOLPGM("SCARA step Cal - Theta:");
@ -2797,6 +2819,8 @@ Sigma_Exit:
} else { } else {
//reserved for setting filament diameter via UFID or filament measuring device //reserved for setting filament diameter via UFID or filament measuring device
break; break;
} }
tmp_extruder = active_extruder; tmp_extruder = active_extruder;
if(code_seen('T')) { if(code_seen('T')) {
@ -2849,19 +2873,19 @@ Sigma_Exit:
if(code_seen('E')) max_e_jerk = code_value() ; if(code_seen('E')) max_e_jerk = code_value() ;
} }
break; break;
case 206: // M206 additional homeing offset case 206: // M206 additional homing offset
for(int8_t i=0; i < 3; i++) for(int8_t i=0; i < 3; i++)
{ {
if(code_seen(axis_codes[i])) add_homeing[i] = code_value(); if(code_seen(axis_codes[i])) add_homing[i] = code_value();
} }
#ifdef SCARA #ifdef SCARA
if(code_seen('T')) // Theta if(code_seen('T')) // Theta
{ {
add_homeing[0] = code_value() ; add_homing[0] = code_value() ;
} }
if(code_seen('P')) // Psi if(code_seen('P')) // Psi
{ {
add_homeing[1] = code_value() ; add_homing[1] = code_value() ;
} }
#endif #endif
break; break;
@ -3359,6 +3383,70 @@ Sigma_Exit:
} }
break; break;
#endif #endif
#ifdef FILAMENT_SENSOR
case 404: //M404 Enter the nominal filament width (3mm, 1.75mm ) N<3.0> or display nominal filament width
{
#if (FILWIDTH_PIN > -1)
if(code_seen('N')) filament_width_nominal=code_value();
else{
SERIAL_PROTOCOLPGM("Filament dia (nominal mm):");
SERIAL_PROTOCOLLN(filament_width_nominal);
}
#endif
}
break;
case 405: //M405 Turn on filament sensor for control
{
if(code_seen('D')) meas_delay_cm=code_value();
if(meas_delay_cm> MAX_MEASUREMENT_DELAY)
meas_delay_cm = MAX_MEASUREMENT_DELAY;
if(delay_index2 == -1) //initialize the ring buffer if it has not been done since startup
{
int temp_ratio = widthFil_to_size_ratio();
for (delay_index1=0; delay_index1<(MAX_MEASUREMENT_DELAY+1); ++delay_index1 ){
measurement_delay[delay_index1]=temp_ratio-100; //subtract 100 to scale within a signed byte
}
delay_index1=0;
delay_index2=0;
}
filament_sensor = true ;
//SERIAL_PROTOCOLPGM("Filament dia (measured mm):");
//SERIAL_PROTOCOL(filament_width_meas);
//SERIAL_PROTOCOLPGM("Extrusion ratio(%):");
//SERIAL_PROTOCOL(extrudemultiply);
}
break;
case 406: //M406 Turn off filament sensor for control
{
filament_sensor = false ;
}
break;
case 407: //M407 Display measured filament diameter
{
SERIAL_PROTOCOLPGM("Filament dia (measured mm):");
SERIAL_PROTOCOLLN(filament_width_meas);
}
break;
#endif
case 500: // M500 Store settings in EEPROM case 500: // M500 Store settings in EEPROM
{ {
Config_StoreSettings(); Config_StoreSettings();

@ -245,9 +245,6 @@ static void lcd_implementation_status_screen()
u8g.drawBox(38,17,2,2); u8g.drawBox(38,17,2,2);
u8g.setColorIndex(1); // black on white u8g.setColorIndex(1); // black on white
} }
#else
u8g.setPrintPos(31,27);
u8g.print("---");
#endif #endif
// Extruder 3 // Extruder 3
@ -266,9 +263,6 @@ static void lcd_implementation_status_screen()
u8g.drawBox(62,17,2,2); u8g.drawBox(62,17,2,2);
u8g.setColorIndex(1); // black on white u8g.setColorIndex(1); // black on white
} }
#else
u8g.setPrintPos(55,27);
u8g.print("---");
#endif #endif
// Heatbed // Heatbed

@ -8,7 +8,7 @@
//=========================================================================== //===========================================================================
//============================= DELTA Printer =============================== //============================= DELTA Printer ===============================
//=========================================================================== //===========================================================================
// For a Delta printer rplace the configuration files wilth the files in the // For a Delta printer replace the configuration files with the files in the
// example_configurations/delta directory. // example_configurations/delta directory.
// //
@ -41,6 +41,7 @@
// 33 = RAMPS 1.3 / 1.4 (Power outputs: Extruder, Fan, Bed) // 33 = RAMPS 1.3 / 1.4 (Power outputs: Extruder, Fan, Bed)
// 34 = RAMPS 1.3 / 1.4 (Power outputs: Extruder0, Extruder1, Bed) // 34 = RAMPS 1.3 / 1.4 (Power outputs: Extruder0, Extruder1, Bed)
// 35 = RAMPS 1.3 / 1.4 (Power outputs: Extruder, Fan, Fan) // 35 = RAMPS 1.3 / 1.4 (Power outputs: Extruder, Fan, Fan)
// 36 = RAMPS 1.3 / 1.4 (Power outputs: Extruder0, Extruder1, Fan)
// 4 = Duemilanove w/ ATMega328P pin assignment // 4 = Duemilanove w/ ATMega328P pin assignment
// 5 = Gen6 // 5 = Gen6
// 51 = Gen6 deluxe // 51 = Gen6 deluxe
@ -54,20 +55,24 @@
// 68 = Azteeg X3 Pro // 68 = Azteeg X3 Pro
// 7 = Ultimaker // 7 = Ultimaker
// 71 = Ultimaker (Older electronics. Pre 1.5.4. This is rare) // 71 = Ultimaker (Older electronics. Pre 1.5.4. This is rare)
// 72 = Ultimainboard 2.x (Uses TEMP_SENSOR 20)
// 77 = 3Drag Controller // 77 = 3Drag Controller
// 8 = Teensylu // 8 = Teensylu
// 80 = Rumba // 80 = Rumba
// 81 = Printrboard (AT90USB1286) // 81 = Printrboard (AT90USB1286)
// 82 = Brainwave (AT90USB646) // 82 = Brainwave (AT90USB646)
// 83 = SAV Mk-I (AT90USB1286) // 83 = SAV Mk-I (AT90USB1286)
// 84 = Teensy++2.0 (AT90USB1286) // CLI compile: DEFINES=AT90USBxx_TEENSYPP_ASSIGNMENTS HARDWARE_MOTHERBOARD=84 make
// 9 = Gen3+ // 9 = Gen3+
// 70 = Megatronics // 70 = Megatronics
// 701= Megatronics v2.0 // 701= Megatronics v2.0
// 702= Minitronics v1.0 // 702= Minitronics v1.0
// 90 = Alpha OMCA board // 90 = Alpha OMCA board
// 91 = Final OMCA board // 91 = Final OMCA board
// 301 = Rambo // 301= Rambo
// 21 = Elefu Ra Board (v3) // 21 = Elefu Ra Board (v3)
// 88 = 5DPrint D8 Driver Board
// 999 = Leapfrog
#ifndef MOTHERBOARD #ifndef MOTHERBOARD
#define MOTHERBOARD 33 #define MOTHERBOARD 33
@ -89,7 +94,7 @@
#define POWER_SUPPLY 1 #define POWER_SUPPLY 1
// Define this to have the electronics keep the powersupply off on startup. If you don't know what this is leave it. // Define this to have the electronics keep the power supply off on startup. If you don't know what this is leave it.
// #define PS_DEFAULT_OFF // #define PS_DEFAULT_OFF
//=========================================================================== //===========================================================================
@ -103,7 +108,7 @@
// and processor overload (too many expensive sqrt calls). // and processor overload (too many expensive sqrt calls).
#define DELTA_SEGMENTS_PER_SECOND 200 #define DELTA_SEGMENTS_PER_SECOND 200
// NOTE NB all values for DELTA_* values MOUST be floating point, so always have a decimal point in them // NOTE NB all values for DELTA_* values MUST be floating point, so always have a decimal point in them
// Center-to-center distance of the holes in the diagonal push rods. // Center-to-center distance of the holes in the diagonal push rods.
#define DELTA_DIAGONAL_ROD 250.0 // mm #define DELTA_DIAGONAL_ROD 250.0 // mm
@ -132,7 +137,7 @@
// 0 is not used // 0 is not used
// 1 is 100k thermistor - best choice for EPCOS 100k (4.7k pullup) // 1 is 100k thermistor - best choice for EPCOS 100k (4.7k pullup)
// 2 is 200k thermistor - ATC Semitec 204GT-2 (4.7k pullup) // 2 is 200k thermistor - ATC Semitec 204GT-2 (4.7k pullup)
// 3 is mendel-parts thermistor (4.7k pullup) // 3 is Mendel-parts thermistor (4.7k pullup)
// 4 is 10k thermistor !! do not use it for a hotend. It gives bad resolution at high temp. !! // 4 is 10k thermistor !! do not use it for a hotend. It gives bad resolution at high temp. !!
// 5 is 100K thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (4.7k pullup) // 5 is 100K thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (4.7k pullup)
// 6 is 100k EPCOS - Not as accurate as table 1 (created using a fluke thermocouple) (4.7k pullup) // 6 is 100k EPCOS - Not as accurate as table 1 (created using a fluke thermocouple) (4.7k pullup)
@ -141,13 +146,22 @@
// 8 is 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup) // 8 is 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup)
// 9 is 100k GE Sensing AL03006-58.2K-97-G1 (4.7k pullup) // 9 is 100k GE Sensing AL03006-58.2K-97-G1 (4.7k pullup)
// 10 is 100k RS thermistor 198-961 (4.7k pullup) // 10 is 100k RS thermistor 198-961 (4.7k pullup)
// 60 is 100k Maker's Tool Works Kapton Bed Thermister // 11 is 100k beta 3950 1% thermistor (4.7k pullup)
// 12 is 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup) (calibrated for Makibox hot bed)
// 13 is 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
// 20 is the PT100 circuit found in the Ultimainboard V2.x
// 60 is 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
// //
// 1k ohm pullup tables - This is not normal, you would have to have changed out your 4.7k for 1k // 1k ohm pullup tables - This is not normal, you would have to have changed out your 4.7k for 1k
// (but gives greater accuracy and more stable PID) // (but gives greater accuracy and more stable PID)
// 51 is 100k thermistor - EPCOS (1k pullup) // 51 is 100k thermistor - EPCOS (1k pullup)
// 52 is 200k thermistor - ATC Semitec 204GT-2 (1k pullup) // 52 is 200k thermistor - ATC Semitec 204GT-2 (1k pullup)
// 55 is 100k thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (1k pullup) // 55 is 100k thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (1k pullup)
//
// 1047 is Pt1000 with 4k7 pullup
// 1010 is Pt1000 with 1k pullup (non standard)
// 147 is Pt100 with 4k7 pullup
// 110 is Pt100 with 1k pullup (non standard)
#define TEMP_SENSOR_0 -1 #define TEMP_SENSOR_0 -1
#define TEMP_SENSOR_1 -1 #define TEMP_SENSOR_1 -1
@ -184,6 +198,10 @@
// HEATER_BED_DUTY_CYCLE_DIVIDER intervals. // HEATER_BED_DUTY_CYCLE_DIVIDER intervals.
//#define HEATER_BED_DUTY_CYCLE_DIVIDER 4 //#define HEATER_BED_DUTY_CYCLE_DIVIDER 4
// If you want the M105 heater power reported in watts, define the BED_WATTS, and (shared for all extruders) EXTRUDER_WATTS
//#define EXTRUDER_WATTS (12.0*12.0/6.7) // P=I^2/R
//#define BED_WATTS (12.0*12.0/1.1) // P=I^2/R
// PID settings: // PID settings:
// Comment the following line to disable PID and enable bang-bang. // Comment the following line to disable PID and enable bang-bang.
#define PIDTEMP #define PIDTEMP
@ -196,15 +214,15 @@
// is more then PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max. // is more then PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
#define PID_INTEGRAL_DRIVE_MAX 255 //limit for the integral term #define PID_INTEGRAL_DRIVE_MAX 255 //limit for the integral term
#define K1 0.95 //smoothing factor within the PID #define K1 0.95 //smoothing factor within the PID
#define PID_dT ((16.0 * 8.0)/(F_CPU / 64.0 / 256.0)) //sampling period of the temperature routine #define PID_dT ((OVERSAMPLENR * 10.0)/(F_CPU / 64.0 / 256.0)) //sampling period of the temperature routine
// If you are using a preconfigured hotend then you can use one of the value sets by uncommenting it // If you are using a pre-configured hotend then you can use one of the value sets by uncommenting it
// Ultimaker // Ultimaker
#define DEFAULT_Kp 22.2 #define DEFAULT_Kp 22.2
#define DEFAULT_Ki 1.08 #define DEFAULT_Ki 1.08
#define DEFAULT_Kd 114 #define DEFAULT_Kd 114
// Makergear // MakerGear
// #define DEFAULT_Kp 7.0 // #define DEFAULT_Kp 7.0
// #define DEFAULT_Ki 0.1 // #define DEFAULT_Ki 0.1
// #define DEFAULT_Kd 12 // #define DEFAULT_Kd 12
@ -262,6 +280,44 @@
#define EXTRUDE_MINTEMP 170 #define EXTRUDE_MINTEMP 170
#define EXTRUDE_MAXLENGTH (X_MAX_LENGTH+Y_MAX_LENGTH) //prevent extrusion of very large distances. #define EXTRUDE_MAXLENGTH (X_MAX_LENGTH+Y_MAX_LENGTH) //prevent extrusion of very large distances.
/*================== Thermal Runaway Protection ==============================
This is a feature to protect your printer from burn up in flames if it has
a thermistor coming off place (this happened to a friend of mine recently and
motivated me writing this feature).
The issue: If a thermistor come off, it will read a lower temperature than actual.
The system will turn the heater on forever, burning up the filament and anything
else around.
After the temperature reaches the target for the first time, this feature will
start measuring for how long the current temperature stays below the target
minus _HYSTERESIS (set_temperature - THERMAL_RUNAWAY_PROTECTION_HYSTERESIS).
If it stays longer than _PERIOD, it means the thermistor temperature
cannot catch up with the target, so something *may be* wrong. Then, to be on the
safe side, the system will he halt.
Bear in mind the count down will just start AFTER the first time the
thermistor temperature is over the target, so you will have no problem if
your extruder heater takes 2 minutes to hit the target on heating.
*/
// If you want to enable this feature for all your extruder heaters,
// uncomment the 2 defines below:
// Parameters for all extruder heaters
//#define THERMAL_RUNAWAY_PROTECTION_PERIOD 40 //in seconds
//#define THERMAL_RUNAWAY_PROTECTION_HYSTERESIS 4 // in degree Celsius
// If you want to enable this feature for your bed heater,
// uncomment the 2 defines below:
// Parameters for the bed heater
//#define THERMAL_RUNAWAY_PROTECTION_BED_PERIOD 20 //in seconds
//#define THERMAL_RUNAWAY_PROTECTION_BED_HYSTERESIS 2 // in degree Celsius
//===========================================================================
//=========================================================================== //===========================================================================
//=============================Mechanical Settings=========================== //=============================Mechanical Settings===========================
//=========================================================================== //===========================================================================
@ -273,7 +329,7 @@
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors #define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors
#ifndef ENDSTOPPULLUPS #ifndef ENDSTOPPULLUPS
// fine Enstop settings: Individual Pullups. will be ignored if ENDSTOPPULLUPS is defined // fine endstop settings: Individual pullups. will be ignored if ENDSTOPPULLUPS is defined
// #define ENDSTOPPULLUP_XMAX // #define ENDSTOPPULLUP_XMAX
// #define ENDSTOPPULLUP_YMAX // #define ENDSTOPPULLUP_YMAX
// #define ENDSTOPPULLUP_ZMAX // #define ENDSTOPPULLUP_ZMAX
@ -317,6 +373,7 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
#define DISABLE_Y false #define DISABLE_Y false
#define DISABLE_Z false #define DISABLE_Z false
#define DISABLE_E false // For all extruders #define DISABLE_E false // For all extruders
#define DISABLE_INACTIVE_EXTRUDER true //disable only inactive extruders and keep active extruder enabled
#define INVERT_X_DIR false // DELTA does not invert #define INVERT_X_DIR false // DELTA does not invert
#define INVERT_Y_DIR false #define INVERT_Y_DIR false
@ -350,16 +407,55 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
//============================= Bed Auto Leveling =========================== //============================= Bed Auto Leveling ===========================
//#define ENABLE_AUTO_BED_LEVELING // Delete the comment to enable (remove // at the start of the line) //#define ENABLE_AUTO_BED_LEVELING // Delete the comment to enable (remove // at the start of the line)
#define Z_PROBE_REPEATABILITY_TEST // If not commented out, Z-Probe Repeatability test will be included if Auto Bed Leveling is Enabled.
#ifdef ENABLE_AUTO_BED_LEVELING #ifdef ENABLE_AUTO_BED_LEVELING
// these are the positions on the bed to do the probing // There are 2 different ways to pick the X and Y locations to probe:
#define LEFT_PROBE_BED_POSITION 15
#define RIGHT_PROBE_BED_POSITION 170 // - "grid" mode
#define BACK_PROBE_BED_POSITION 180 // Probe every point in a rectangular grid
#define FRONT_PROBE_BED_POSITION 20 // You must specify the rectangle, and the density of sample points
// This mode is preferred because there are more measurements.
// It used to be called ACCURATE_BED_LEVELING but "grid" is more descriptive
// - "3-point" mode
// Probe 3 arbitrary points on the bed (that aren't colinear)
// You must specify the X & Y coordinates of all 3 points
#define AUTO_BED_LEVELING_GRID
// with AUTO_BED_LEVELING_GRID, the bed is sampled in a
// AUTO_BED_LEVELING_GRID_POINTSxAUTO_BED_LEVELING_GRID_POINTS grid
// and least squares solution is calculated
// Note: this feature occupies 10'206 byte
#ifdef AUTO_BED_LEVELING_GRID
// set the rectangle in which to probe
#define LEFT_PROBE_BED_POSITION 15
#define RIGHT_PROBE_BED_POSITION 170
#define BACK_PROBE_BED_POSITION 180
#define FRONT_PROBE_BED_POSITION 20
// set the number of grid points per dimension
// I wouldn't see a reason to go above 3 (=9 probing points on the bed)
#define AUTO_BED_LEVELING_GRID_POINTS 2
#else // not AUTO_BED_LEVELING_GRID
// with no grid, just probe 3 arbitrary points. A simple cross-product
// is used to esimate the plane of the print bed
#define ABL_PROBE_PT_1_X 15
#define ABL_PROBE_PT_1_Y 180
#define ABL_PROBE_PT_2_X 15
#define ABL_PROBE_PT_2_Y 20
#define ABL_PROBE_PT_3_X 170
#define ABL_PROBE_PT_3_Y 20
#endif // AUTO_BED_LEVELING_GRID
// these are the offsets to the prob relative to the extruder tip (Hotend - Probe)
// these are the offsets to the probe relative to the extruder tip (Hotend - Probe)
#define X_PROBE_OFFSET_FROM_EXTRUDER -25 #define X_PROBE_OFFSET_FROM_EXTRUDER -25
#define Y_PROBE_OFFSET_FROM_EXTRUDER -29 #define Y_PROBE_OFFSET_FROM_EXTRUDER -29
#define Z_PROBE_OFFSET_FROM_EXTRUDER -12.35 #define Z_PROBE_OFFSET_FROM_EXTRUDER -12.35
@ -372,6 +468,8 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
#define Z_RAISE_BEFORE_PROBING 15 //How much the extruder will be raised before traveling to the first probing point. #define Z_RAISE_BEFORE_PROBING 15 //How much the extruder will be raised before traveling to the first probing point.
#define Z_RAISE_BETWEEN_PROBINGS 5 //How much the extruder will be raised when traveling from between next probing points #define Z_RAISE_BETWEEN_PROBINGS 5 //How much the extruder will be raised when traveling from between next probing points
//#define Z_PROBE_SLED // turn on if you have a z-probe mounted on a sled like those designed by Charles Bell
//#define SLED_DOCKING_OFFSET 5 // the extra distance the X axis must travel to pickup the sled. 0 should be fine but you can push it further if you'd like.
//If defined, the Probe servo will be turned on only during movement and then turned off to avoid jerk //If defined, the Probe servo will be turned on only during movement and then turned off to avoid jerk
//The value is the delay to turn the servo off after powered on - depends on the servo speed; 300ms is good value, but you can try lower it. //The value is the delay to turn the servo off after powered on - depends on the servo speed; 300ms is good value, but you can try lower it.
@ -380,7 +478,7 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
// #define PROBE_SERVO_DEACTIVATION_DELAY 300 // #define PROBE_SERVO_DEACTIVATION_DELAY 300
//If you have enabled the Bed Auto Levelling and are using the same Z Probe for Z Homing, //If you have enabled the Bed Auto Leveling and are using the same Z Probe for Z Homing,
//it is highly recommended you let this Z_SAFE_HOMING enabled!!! //it is highly recommended you let this Z_SAFE_HOMING enabled!!!
#define Z_SAFE_HOMING // This feature is meant to avoid Z homing with probe outside the bed area. #define Z_SAFE_HOMING // This feature is meant to avoid Z homing with probe outside the bed area.
@ -397,7 +495,7 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
#endif #endif
#endif #endif // ENABLE_AUTO_BED_LEVELING
// The position of the homing switches // The position of the homing switches
@ -407,7 +505,7 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
//Manual homing switch locations: //Manual homing switch locations:
#define MANUAL_HOME_POSITIONS // MANUAL_*_HOME_POS below will be used #define MANUAL_HOME_POSITIONS // MANUAL_*_HOME_POS below will be used
// For deltabots this means top and center of the cartesian print volume. // For deltabots this means top and center of the Cartesian print volume.
#define MANUAL_X_HOME_POS 0 #define MANUAL_X_HOME_POS 0
#define MANUAL_Y_HOME_POS 0 #define MANUAL_Y_HOME_POS 0
#define MANUAL_Z_HOME_POS 250 // For delta: Distance between nozzle and print surface after homing. #define MANUAL_Z_HOME_POS 250 // For delta: Distance between nozzle and print surface after homing.
@ -442,12 +540,21 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
//=============================Additional Features=========================== //=============================Additional Features===========================
//=========================================================================== //===========================================================================
// Custom M code points
#define CUSTOM_M_CODES
#ifdef CUSTOM_M_CODES
#define CUSTOM_M_CODE_SET_Z_PROBE_OFFSET 851
#define Z_PROBE_OFFSET_RANGE_MIN -15
#define Z_PROBE_OFFSET_RANGE_MAX -5
#endif
// EEPROM // EEPROM
// the microcontroller can store settings in the EEPROM, e.g. max velocity... // The microcontroller can store settings in the EEPROM, e.g. max velocity...
// M500 - stores paramters in EEPROM // M500 - stores parameters in EEPROM
// M501 - reads parameters from EEPROM (if you need reset them after you changed them temporarily). // M501 - reads parameters from EEPROM (if you need reset them after you changed them temporarily).
// M502 - reverts to the default "factory settings". You still need to store them in EEPROM afterwards if you want to. // M502 - reverts to the default "factory settings". You still need to store them in EEPROM afterwards if you want to.
//define this to enable eeprom support //define this to enable EEPROM support
//#define EEPROM_SETTINGS //#define EEPROM_SETTINGS
//to disable EEPROM Serial responses and decrease program space by ~1700 byte: comment this out: //to disable EEPROM Serial responses and decrease program space by ~1700 byte: comment this out:
// please keep turned on if you can. // please keep turned on if you can.
@ -463,14 +570,17 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
#define ABS_PREHEAT_FAN_SPEED 255 // Insert Value between 0 and 255 #define ABS_PREHEAT_FAN_SPEED 255 // Insert Value between 0 and 255
//LCD and SD support //LCD and SD support
//#define ULTRA_LCD //general lcd support, also 16x2 //#define ULTRA_LCD //general LCD support, also 16x2
//#define DOGLCD // Support for SPI LCD 128x64 (Controller ST7565R graphic Display Family) //#define DOGLCD // Support for SPI LCD 128x64 (Controller ST7565R graphic Display Family)
//#define SDSUPPORT // Enable SD Card Support in Hardware Console //#define SDSUPPORT // Enable SD Card Support in Hardware Console
//#define SDSLOW // Use slower SD transfer mode (not normally needed - uncomment if you're getting volume init error) //#define SDSLOW // Use slower SD transfer mode (not normally needed - uncomment if you're getting volume init error)
//#define SD_CHECK_AND_RETRY // Use CRC checks and retries on the SD communication
//#define ENCODER_PULSES_PER_STEP 1 // Increase if you have a high resolution encoder //#define ENCODER_PULSES_PER_STEP 1 // Increase if you have a high resolution encoder
//#define ENCODER_STEPS_PER_MENU_ITEM 5 // Set according to ENCODER_PULSES_PER_STEP or your liking //#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 ULTIMAKERCONTROLLER //as available from the Ultimaker online store.
//#define ULTIPANEL //the ultipanel as on thingiverse //#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
// The MaKr3d Makr-Panel with graphic controller and SD support // The MaKr3d Makr-Panel with graphic controller and SD support
// http://reprap.org/wiki/MaKr3d_MaKrPanel // http://reprap.org/wiki/MaKr3d_MaKrPanel
@ -556,6 +666,21 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
#define LCD_USE_I2C_BUZZER //comment out to disable buzzer on LCD #define LCD_USE_I2C_BUZZER //comment out to disable buzzer on LCD
#define NEWPANEL #define NEWPANEL
#define ULTIPANEL #define ULTIPANEL
#ifndef ENCODER_PULSES_PER_STEP
#define ENCODER_PULSES_PER_STEP 4
#endif
#ifndef ENCODER_STEPS_PER_MENU_ITEM
#define ENCODER_STEPS_PER_MENU_ITEM 1
#endif
#ifdef LCD_USE_I2C_BUZZER
#define LCD_FEEDBACK_FREQUENCY_HZ 1000
#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 100
#endif
#endif #endif
// Panucatt VIKI LCD with status LEDs, integrated click & L/R/U/P buttons, separate encoder inputs // Panucatt VIKI LCD with status LEDs, integrated click & L/R/U/P buttons, separate encoder inputs
@ -578,7 +703,7 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
// https://bitbucket.org/fmalpartida/new-liquidcrystal/wiki/schematics#!shiftregister-connection // https://bitbucket.org/fmalpartida/new-liquidcrystal/wiki/schematics#!shiftregister-connection
//#define SR_LCD //#define SR_LCD
#ifdef SR_LCD #ifdef SR_LCD
#define SR_LCD_2W_NL // Non latching 2 wire shiftregister #define SR_LCD_2W_NL // Non latching 2 wire shift register
//#define NEWPANEL //#define NEWPANEL
#endif #endif
@ -594,7 +719,7 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
#define LCD_WIDTH 20 #define LCD_WIDTH 20
#define LCD_HEIGHT 4 #define LCD_HEIGHT 4
#endif #endif
#else //no panel but just lcd #else //no panel but just LCD
#ifdef ULTRA_LCD #ifdef ULTRA_LCD
#ifdef DOGLCD // Change number of lines to match the 128x64 graphics display #ifdef DOGLCD // Change number of lines to match the 128x64 graphics display
#define LCD_WIDTH 20 #define LCD_WIDTH 20
@ -616,8 +741,8 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
// Increase the FAN pwm frequency. Removes the PWM noise but increases heating in the FET/Arduino // Increase the FAN pwm frequency. Removes the PWM noise but increases heating in the FET/Arduino
//#define FAST_PWM_FAN //#define FAST_PWM_FAN
// Temperature status leds that display the hotend and bet temperature. // Temperature status LEDs that display the hotend and bet temperature.
// If alle hotends and bed temperature and temperature setpoint are < 54C then the BLUE led is on. // If all hotends and bed temperature and temperature setpoint are < 54C then the BLUE led is on.
// Otherwise the RED led is on. There is 1C hysteresis. // Otherwise the RED led is on. There is 1C hysteresis.
//#define TEMP_STAT_LEDS //#define TEMP_STAT_LEDS
@ -667,6 +792,35 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
//#define SERVO_ENDSTOPS {-1, -1, 0} // Servo index for X, Y, Z. Disable with -1 //#define SERVO_ENDSTOPS {-1, -1, 0} // Servo index for X, Y, Z. Disable with -1
//#define SERVO_ENDSTOP_ANGLES {0,0, 0,0, 70,0} // X,Y,Z Axis Extend and Retract angles //#define SERVO_ENDSTOP_ANGLES {0,0, 0,0, 70,0} // X,Y,Z Axis Extend and Retract angles
/**********************************************************************\
* Support for a filament diameter sensor
* Also allows adjustment of diameter at print time (vs at slicing)
* Single extruder only at this point (extruder 0)
*
* Motherboards
* 34 - RAMPS1.4 - uses Analog input 5 on the AUX2 connector
* 81 - Printrboard - Uses Analog input 2 on the Aux 2 connector
* 301 - Rambo - uses Analog input 3
* Note may require analog pins to be defined for different motherboards
**********************************************************************/
#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 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)
//defines used in the code
#define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA //set measured to nominal initially
#include "Configuration_adv.h" #include "Configuration_adv.h"
#include "thermistortables.h" #include "thermistortables.h"

@ -281,6 +281,9 @@
//=============================Additional Features=========================== //=============================Additional Features===========================
//=========================================================================== //===========================================================================
//#define CHDK 4 //Pin for triggering CHDK to take a picture see how to use it here http://captain-slow.dk/2014/03/09/3d-printing-timelapses/
#define CHDK_DELAY 50 //How long in ms the pin should stay HIGH before going LOW again
#define SD_FINISHED_STEPPERRELEASE true //if sd support and the file is finished: disable steppers? #define SD_FINISHED_STEPPERRELEASE true //if sd support and the file is finished: disable steppers?
#define SD_FINISHED_RELEASECOMMAND "M84 X Y Z E" // You might want to keep the z enabled so your bed stays in place. #define SD_FINISHED_RELEASECOMMAND "M84 X Y Z E" // You might want to keep the z enabled so your bed stays in place.
@ -401,8 +404,16 @@ const unsigned int dropsegments=5; //everything with less than this number of st
// the moves are than replaced by the firmware controlled ones. // the moves are than replaced by the firmware controlled ones.
// #define FWRETRACT //ONLY PARTIALLY TESTED // #define FWRETRACT //ONLY PARTIALLY TESTED
#define MIN_RETRACT 0.1 //minimum extruded mm to accept a automatic gcode retraction attempt #ifdef FWRETRACT
#define MIN_RETRACT 0.1 //minimum extruded mm to accept a automatic gcode retraction attempt
#define RETRACT_LENGTH 3 //default retract length (positive mm)
#define RETRACT_LENGTH_SWAP 13 //default swap retract length (positive mm), for extruder change
#define RETRACT_FEEDRATE 45 //default feedrate for retracting (mm/s)
#define RETRACT_ZLIFT 0 //default retract Z-lift
#define RETRACT_RECOVER_LENGTH 0 //default additional recover length (mm, added to retract length when recovering)
#define RETRACT_RECOVER_LENGTH_SWAP 0 //default additional swap recover length (mm, added to retract length when recovering from extruder change)
#define RETRACT_RECOVER_FEEDRATE 8 //default feedrate for recovering from retraction (mm/s)
#endif
//adds support for experimental filament exchange support M600; requires display //adds support for experimental filament exchange support M600; requires display
#ifdef ULTIPANEL #ifdef ULTIPANEL

@ -155,6 +155,7 @@
#define MSG_AUTOSTART "Autostart" #define MSG_AUTOSTART "Autostart"
#define MSG_DISABLE_STEPPERS "Disable steppers" #define MSG_DISABLE_STEPPERS "Disable steppers"
#define MSG_AUTO_HOME "Auto home" #define MSG_AUTO_HOME "Auto home"
#define MSG_SET_HOME_OFFSETS "Set home offsets"
#define MSG_SET_ORIGIN "Set origin" #define MSG_SET_ORIGIN "Set origin"
#define MSG_PREHEAT_PLA "Preheat PLA" #define MSG_PREHEAT_PLA "Preheat PLA"
#define MSG_PREHEAT_PLA0 "Preheat PLA 1" #define MSG_PREHEAT_PLA0 "Preheat PLA 1"
@ -279,6 +280,7 @@
#define MSG_AUTOSTART "Autostart" #define MSG_AUTOSTART "Autostart"
#define MSG_DISABLE_STEPPERS "Wylacz silniki" #define MSG_DISABLE_STEPPERS "Wylacz silniki"
#define MSG_AUTO_HOME "Auto. poz. zerowa" #define MSG_AUTO_HOME "Auto. poz. zerowa"
#define MSG_SET_HOME_OFFSETS "Set home offsets"
#define MSG_SET_ORIGIN "Ustaw punkt zero" #define MSG_SET_ORIGIN "Ustaw punkt zero"
#define MSG_PREHEAT_PLA "Rozgrzej PLA" #define MSG_PREHEAT_PLA "Rozgrzej PLA"
#define MSG_PREHEAT_PLA0 "Rozgrzej PLA 1" #define MSG_PREHEAT_PLA0 "Rozgrzej PLA 1"
@ -406,10 +408,11 @@
#define MSG_AUTOSTART "Demarrage auto" #define MSG_AUTOSTART "Demarrage auto"
#define MSG_DISABLE_STEPPERS "Arreter moteurs" #define MSG_DISABLE_STEPPERS "Arreter moteurs"
#define MSG_AUTO_HOME "Home auto." #define MSG_AUTO_HOME "Home auto."
#define MSG_SET_HOME_OFFSETS "Set home offsets"
#define MSG_SET_ORIGIN "Regler origine" #define MSG_SET_ORIGIN "Regler origine"
#define MSG_PREHEAT_PLA " Prechauffage PLA" #define MSG_PREHEAT_PLA " Prechauffage PLA"
#define MSG_PREHEAT_PLA0 "Prechauff. PLA 1" #define MSG_PREHEAT_PLA0 "Prechauff. PLA 1"
#define MSG_PREHEAT_PLA1 "Prechauff. PLA 2" #define MSG_PREHEAT_PLA1 "Prechauff. PLA 2"
#define MSG_PREHEAT_PLA2 "Prechauff. PLA 3" #define MSG_PREHEAT_PLA2 "Prechauff. PLA 3"
#define MSG_PREHEAT_PLA012 "Prech. PLA Tout" #define MSG_PREHEAT_PLA012 "Prech. PLA Tout"
#define MSG_PREHEAT_PLA_BEDONLY "Prech. PLA Plateau" #define MSG_PREHEAT_PLA_BEDONLY "Prech. PLA Plateau"
@ -534,6 +537,7 @@
#define MSG_AUTOSTART "Autostart" #define MSG_AUTOSTART "Autostart"
#define MSG_DISABLE_STEPPERS "Stepper abschalt." #define MSG_DISABLE_STEPPERS "Stepper abschalt."
#define MSG_AUTO_HOME "Auto Nullpunkt" #define MSG_AUTO_HOME "Auto Nullpunkt"
#define MSG_SET_HOME_OFFSETS "Set home offsets"
#define MSG_SET_ORIGIN "Setze Nullpunkt" #define MSG_SET_ORIGIN "Setze Nullpunkt"
#define MSG_PREHEAT_PLA "Vorwärmen PLA" #define MSG_PREHEAT_PLA "Vorwärmen PLA"
#define MSG_PREHEAT_PLA0 "Vorwärmen PLA 1" #define MSG_PREHEAT_PLA0 "Vorwärmen PLA 1"
@ -661,6 +665,7 @@
#define MSG_AUTOSTART " Autostart" #define MSG_AUTOSTART " Autostart"
#define MSG_DISABLE_STEPPERS "Apagar motores" #define MSG_DISABLE_STEPPERS "Apagar motores"
#define MSG_AUTO_HOME "Llevar al origen" #define MSG_AUTO_HOME "Llevar al origen"
#define MSG_SET_HOME_OFFSETS "Set home offsets"
#define MSG_SET_ORIGIN "Establecer cero" #define MSG_SET_ORIGIN "Establecer cero"
#define MSG_PREHEAT_PLA "Precalentar PLA" #define MSG_PREHEAT_PLA "Precalentar PLA"
#define MSG_PREHEAT_PLA0 "Precalentar PLA 1" #define MSG_PREHEAT_PLA0 "Precalentar PLA 1"
@ -794,6 +799,7 @@
#define MSG_AUTOSTART "Автостарт" #define MSG_AUTOSTART "Автостарт"
#define MSG_DISABLE_STEPPERS "Выкл. двигатели" #define MSG_DISABLE_STEPPERS "Выкл. двигатели"
#define MSG_AUTO_HOME "Парковка" #define MSG_AUTO_HOME "Парковка"
#define MSG_SET_HOME_OFFSETS "Set home offsets"
#define MSG_SET_ORIGIN "Запомнить ноль" #define MSG_SET_ORIGIN "Запомнить ноль"
#define MSG_PREHEAT_PLA "Преднагрев PLA" #define MSG_PREHEAT_PLA "Преднагрев PLA"
#define MSG_PREHEAT_PLA0 "Преднагрев PLA0" #define MSG_PREHEAT_PLA0 "Преднагрев PLA0"
@ -885,11 +891,11 @@
#define MSG_KILLED "УБИТО." #define MSG_KILLED "УБИТО."
#define MSG_STOPPED "ОСТАНОВЛЕНО." #define MSG_STOPPED "ОСТАНОВЛЕНО."
#define MSG_CONTROL_RETRACT "Откат mm:" #define MSG_CONTROL_RETRACT "Откат mm:"
#define MSG_CONTROL_RETRACT_SWAP "своп Откат mm:" #define MSG_CONTROL_RETRACT_SWAP "своп Откат mm:"
#define MSG_CONTROL_RETRACTF "Откат V:" #define MSG_CONTROL_RETRACTF "Откат V:"
#define MSG_CONTROL_RETRACT_ZLIFT "Прыжок mm:" #define MSG_CONTROL_RETRACT_ZLIFT "Прыжок mm:"
#define MSG_CONTROL_RETRACT_RECOVER "Возврат +mm:" #define MSG_CONTROL_RETRACT_RECOVER "Возврат +mm:"
#define MSG_CONTROL_RETRACT_RECOVER_SWAP "своп Возврат +mm:" #define MSG_CONTROL_RETRACT_RECOVER_SWAP "своп Возврат +mm:"
#define MSG_CONTROL_RETRACT_RECOVERF "Возврат V:" #define MSG_CONTROL_RETRACT_RECOVERF "Возврат V:"
#define MSG_AUTORETRACT "АвтоОткат:" #define MSG_AUTORETRACT "АвтоОткат:"
#define MSG_FILAMENTCHANGE "Change filament" #define MSG_FILAMENTCHANGE "Change filament"
@ -919,6 +925,7 @@
#define MSG_AUTOSTART "Autostart" #define MSG_AUTOSTART "Autostart"
#define MSG_DISABLE_STEPPERS "Disabilita Motori" #define MSG_DISABLE_STEPPERS "Disabilita Motori"
#define MSG_AUTO_HOME "Auto Home" #define MSG_AUTO_HOME "Auto Home"
#define MSG_SET_HOME_OFFSETS "Set home offsets"
#define MSG_SET_ORIGIN "Imposta Origine" #define MSG_SET_ORIGIN "Imposta Origine"
#define MSG_PREHEAT_PLA "Preriscalda PLA" #define MSG_PREHEAT_PLA "Preriscalda PLA"
#define MSG_PREHEAT_PLA0 "Preriscalda PLA 1" #define MSG_PREHEAT_PLA0 "Preriscalda PLA 1"
@ -1044,6 +1051,7 @@
#define MSG_AUTOSTART "Autostart" #define MSG_AUTOSTART "Autostart"
#define MSG_DISABLE_STEPPERS " Apagar motores" #define MSG_DISABLE_STEPPERS " Apagar motores"
#define MSG_AUTO_HOME "Ir para origen" #define MSG_AUTO_HOME "Ir para origen"
#define MSG_SET_HOME_OFFSETS "Set home offsets"
#define MSG_SET_ORIGIN "Estabelecer orig." #define MSG_SET_ORIGIN "Estabelecer orig."
#define MSG_PREHEAT_PLA "Pre-aquecer PLA" #define MSG_PREHEAT_PLA "Pre-aquecer PLA"
#define MSG_PREHEAT_PLA0 " pre-aquecer PLA 1" #define MSG_PREHEAT_PLA0 " pre-aquecer PLA 1"
@ -1176,6 +1184,7 @@
#define MSG_AUTOSTART "Automaatti" #define MSG_AUTOSTART "Automaatti"
#define MSG_DISABLE_STEPPERS "Vapauta moottorit" #define MSG_DISABLE_STEPPERS "Vapauta moottorit"
#define MSG_AUTO_HOME "Aja referenssiin" #define MSG_AUTO_HOME "Aja referenssiin"
#define MSG_SET_HOME_OFFSETS "Set home offsets"
#define MSG_SET_ORIGIN "Aseta origo" #define MSG_SET_ORIGIN "Aseta origo"
#define MSG_PREHEAT_PLA "Esilammita PLA" #define MSG_PREHEAT_PLA "Esilammita PLA"
#define MSG_PREHEAT_PLA0 "Esilammita PLA 1" #define MSG_PREHEAT_PLA0 "Esilammita PLA 1"
@ -1299,6 +1308,7 @@
#define MSG_AUTOSTART " Autostart" #define MSG_AUTOSTART " Autostart"
#define MSG_DISABLE_STEPPERS "Amortar motors" #define MSG_DISABLE_STEPPERS "Amortar motors"
#define MSG_AUTO_HOME "Levar a l'orichen" #define MSG_AUTO_HOME "Levar a l'orichen"
#define MSG_SET_HOME_OFFSETS "Set home offsets"
#define MSG_SET_ORIGIN "Establir zero" #define MSG_SET_ORIGIN "Establir zero"
#define MSG_PREHEAT_PLA "Precalentar PLA" #define MSG_PREHEAT_PLA "Precalentar PLA"
#define MSG_PREHEAT_PLA0 "Precalentar PLA0" #define MSG_PREHEAT_PLA0 "Precalentar PLA0"
@ -1431,6 +1441,7 @@
#define MSG_AUTOSTART "Autostart" #define MSG_AUTOSTART "Autostart"
#define MSG_DISABLE_STEPPERS "Motoren uit" #define MSG_DISABLE_STEPPERS "Motoren uit"
#define MSG_AUTO_HOME "Auto home" #define MSG_AUTO_HOME "Auto home"
#define MSG_SET_HOME_OFFSETS "Set home offsets"
#define MSG_SET_ORIGIN "Nulpunt instellen" #define MSG_SET_ORIGIN "Nulpunt instellen"
#define MSG_PREHEAT_PLA "PLA voorverwarmen" #define MSG_PREHEAT_PLA "PLA voorverwarmen"
#define MSG_PREHEAT_PLA0 "PLA voorverw. 0" #define MSG_PREHEAT_PLA0 "PLA voorverw. 0"

@ -44,6 +44,14 @@ void mc_arc(float *position, float *target, float *offset, uint8_t axis_0, uint8
if (angular_travel < 0) { angular_travel += 2*M_PI; } if (angular_travel < 0) { angular_travel += 2*M_PI; }
if (isclockwise) { angular_travel -= 2*M_PI; } if (isclockwise) { angular_travel -= 2*M_PI; }
//20141002:full circle for G03 did not work, e.g. G03 X80 Y80 I20 J0 F2000 is giving an Angle of zero so head is not moving
//to compensate when start pos = target pos && angle is zero -> angle = 2Pi
if (position[axis_0] == target[axis_0] && position[axis_1] == target[axis_1] && angular_travel == 0)
{
angular_travel += 2*M_PI;
}
//end fix G03
float millimeters_of_travel = hypot(angular_travel*radius, fabs(linear_travel)); float millimeters_of_travel = hypot(angular_travel*radius, fabs(linear_travel));
if (millimeters_of_travel < 0.001) { return; } if (millimeters_of_travel < 0.001) { return; }
uint16_t segments = floor(millimeters_of_travel/MM_PER_ARC_SEGMENT); uint16_t segments = floor(millimeters_of_travel/MM_PER_ARC_SEGMENT);

@ -531,7 +531,7 @@
* Arduino Mega pin assignment * Arduino Mega pin assignment
* *
****************************************************************************************/ ****************************************************************************************/
#if MOTHERBOARD == 3 || MOTHERBOARD == 33 || MOTHERBOARD == 34 || MOTHERBOARD == 35 || MOTHERBOARD == 77 || MOTHERBOARD == 67 || MOTHERBOARD == 68 #if MOTHERBOARD == 3 || MOTHERBOARD == 33 || MOTHERBOARD == 34 || MOTHERBOARD == 35 || MOTHERBOARD == 36 || MOTHERBOARD == 77 || MOTHERBOARD == 67 || MOTHERBOARD == 68
#define KNOWN_BOARD 1 #define KNOWN_BOARD 1
//////////////////FIX THIS////////////// //////////////////FIX THIS//////////////
@ -547,7 +547,7 @@
// #define RAMPS_V_1_0 // #define RAMPS_V_1_0
#if MOTHERBOARD == 33 || MOTHERBOARD == 34 || MOTHERBOARD == 35 || MOTHERBOARD == 77 || MOTHERBOARD == 67 || MOTHERBOARD == 68 #if MOTHERBOARD == 33 || MOTHERBOARD == 34 || MOTHERBOARD == 35 || MOTHERBOARD == 36 || MOTHERBOARD == 77 || MOTHERBOARD == 67 || MOTHERBOARD == 68
#define LARGE_FLASH true #define LARGE_FLASH true
@ -628,6 +628,15 @@
#define E1_DIR_PIN 34 #define E1_DIR_PIN 34
#define E1_ENABLE_PIN 30 #define E1_ENABLE_PIN 30
#if MOTHERBOARD == 34 //FMM added for Filament Extruder
#ifdef FILAMENT_SENSOR
//define analog pin for the filament width sensor input
//Use the RAMPS 1.4 Analog input 5 on the AUX2 connector
#define FILWIDTH_PIN 5
#endif
#endif
#if MOTHERBOARD == 68 #if MOTHERBOARD == 68
#define E2_STEP_PIN 23 #define E2_STEP_PIN 23
#define E2_DIR_PIN 25 #define E2_DIR_PIN 25
@ -653,7 +662,7 @@
#define FAN_PIN 4 // IO pin. Buffer needed #define FAN_PIN 4 // IO pin. Buffer needed
#endif #endif
#if MOTHERBOARD == 77 #if MOTHERBOARD == 77 || MOTHERBOARD == 36
#define FAN_PIN 8 #define FAN_PIN 8
#endif #endif
@ -709,7 +718,7 @@
#define TEMP_2_PIN -1 // ANALOG NUMBERING #define TEMP_2_PIN -1 // ANALOG NUMBERING
#endif #endif
#if MOTHERBOARD == 35 #if MOTHERBOARD == 35 || MOTHERBOARD == 36
#define HEATER_BED_PIN -1 // NO BED #define HEATER_BED_PIN -1 // NO BED
#else #else
#if MOTHERBOARD == 77 #if MOTHERBOARD == 77
@ -1762,6 +1771,9 @@
#define Z_STOP_PIN 36 #define Z_STOP_PIN 36
#define TEMP_0_PIN 1 // Extruder / Analog pin numbering #define TEMP_0_PIN 1 // Extruder / Analog pin numbering
#define TEMP_BED_PIN 0 // Bed / Analog pin numbering #define TEMP_BED_PIN 0 // Bed / Analog pin numbering
#ifdef FILAMENT_SENSOR
#define FILWIDTH_PIN 2
#endif //FILAMENT_SENSOR
#endif #endif
#define TEMP_1_PIN -1 #define TEMP_1_PIN -1
@ -2078,8 +2090,8 @@ DaveX plan for Teensylu/printrboard-type pinouts (ref teensylu & sprinter) for a
#define Z_DIR_PIN 28 #define Z_DIR_PIN 28
#define Z_STOP_PIN 30 #define Z_STOP_PIN 30
#define E0_STEP_PIN 17 #define E0_STEP_PIN 17
#define E0_DIR_PIN 21 #define E0_DIR_PIN 21
#define LED_PIN -1 #define LED_PIN -1
@ -2396,6 +2408,10 @@ DaveX plan for Teensylu/printrboard-type pinouts (ref teensylu & sprinter) for a
#endif #endif
#endif //ULTRA_LCD #endif //ULTRA_LCD
#ifdef FILAMENT_SENSOR
//Filip added pin for Filament sensor analog input
#define FILWIDTH_PIN 3
#endif //FILAMENT_SENSOR
#endif #endif

@ -119,6 +119,10 @@ static long x_segment_time[3]={MAX_FREQ_TIME + 1,0,0}; // Segment times (in
static long y_segment_time[3]={MAX_FREQ_TIME + 1,0,0}; static long y_segment_time[3]={MAX_FREQ_TIME + 1,0,0};
#endif #endif
#ifdef FILAMENT_SENSOR
static char meas_sample; //temporary variable to hold filament measurement sample
#endif
// Returns the index of the next block in the ring buffer // Returns the index of the next block in the ring buffer
// NOTE: Removed modulo (%) operator, which uses an expensive divide and multiplication. // NOTE: Removed modulo (%) operator, which uses an expensive divide and multiplication.
static int8_t next_block_index(int8_t block_index) { static int8_t next_block_index(int8_t block_index) {
@ -762,6 +766,49 @@ block->steps_y = labs((target[X_AXIS]-position[X_AXIS]) - (target[Y_AXIS]-positi
block->nominal_speed = block->millimeters * inverse_second; // (mm/sec) Always > 0 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 block->nominal_rate = ceil(block->step_event_count * inverse_second); // (step/sec) Always > 0
#ifdef FILAMENT_SENSOR
//FMM update ring buffer used for delay with filament measurements
if((extruder==FILAMENT_SENSOR_EXTRUDER_NUM) && (delay_index2 > -1)) //only for extruder with filament sensor and if ring buffer is initialized
{
delay_dist = delay_dist + delta_mm[E_AXIS]; //increment counter with next move in e axis
while (delay_dist >= (10*(MAX_MEASUREMENT_DELAY+1))) //check if counter is over max buffer size in mm
delay_dist = delay_dist - 10*(MAX_MEASUREMENT_DELAY+1); //loop around the buffer
while (delay_dist<0)
delay_dist = delay_dist + 10*(MAX_MEASUREMENT_DELAY+1); //loop around the buffer
delay_index1=delay_dist/10.0; //calculate index
//ensure the number is within range of the array after converting from floating point
if(delay_index1<0)
delay_index1=0;
else if (delay_index1>MAX_MEASUREMENT_DELAY)
delay_index1=MAX_MEASUREMENT_DELAY;
if(delay_index1 != delay_index2) //moved index
{
meas_sample=widthFil_to_size_ratio()-100; //subtract off 100 to reduce magnitude - to store in a signed char
}
while( delay_index1 != delay_index2)
{
delay_index2 = delay_index2 + 1;
if(delay_index2>MAX_MEASUREMENT_DELAY)
delay_index2=delay_index2-(MAX_MEASUREMENT_DELAY+1); //loop around buffer when incrementing
if(delay_index2<0)
delay_index2=0;
else if (delay_index2>MAX_MEASUREMENT_DELAY)
delay_index2=MAX_MEASUREMENT_DELAY;
measurement_delay[delay_index2]=meas_sample;
}
}
#endif
// Calculate and limit speed in mm/sec for each axis // Calculate and limit speed in mm/sec for each axis
float current_speed[4]; float current_speed[4];
float speed_factor = 1.0; //factor <=1 do decrease speed float speed_factor = 1.0; //factor <=1 do decrease speed

@ -75,6 +75,9 @@ unsigned char soft_pwm_bed;
volatile int babystepsTodo[3]={0,0,0}; volatile int babystepsTodo[3]={0,0,0};
#endif #endif
#ifdef FILAMENT_SENSOR
int current_raw_filwidth = 0; //Holds measured filament diameter - one extruder only
#endif
//=========================================================================== //===========================================================================
//=============================private variables============================ //=============================private variables============================
//=========================================================================== //===========================================================================
@ -161,6 +164,9 @@ unsigned long watchmillis[EXTRUDERS] = ARRAY_BY_EXTRUDERS(0,0,0);
#define SOFT_PWM_SCALE 0 #define SOFT_PWM_SCALE 0
#endif #endif
#ifdef FILAMENT_SENSOR
static int meas_shift_index; //used to point to a delayed sample in buffer for filament width sensor
#endif
//=========================================================================== //===========================================================================
//============================= functions ============================ //============================= functions ============================
//=========================================================================== //===========================================================================
@ -604,6 +610,28 @@ void manage_heater()
} }
#endif #endif
#endif #endif
//code for controlling the extruder rate based on the width sensor
#ifdef FILAMENT_SENSOR
if(filament_sensor)
{
meas_shift_index=delay_index1-meas_delay_cm;
if(meas_shift_index<0)
meas_shift_index = meas_shift_index + (MAX_MEASUREMENT_DELAY+1); //loop around buffer if needed
//get the delayed info and add 100 to reconstitute to a percent of the nominal filament diameter
//then square it to get an area
if(meas_shift_index<0)
meas_shift_index=0;
else if (meas_shift_index>MAX_MEASUREMENT_DELAY)
meas_shift_index=MAX_MEASUREMENT_DELAY;
volumetric_multiplier[FILAMENT_SENSOR_EXTRUDER_NUM] = pow((float)(100+measurement_delay[meas_shift_index])/100.0,2);
if (volumetric_multiplier[FILAMENT_SENSOR_EXTRUDER_NUM] <0.01)
volumetric_multiplier[FILAMENT_SENSOR_EXTRUDER_NUM]=0.01;
}
#endif
} }
#define PGM_RD_W(x) (short)pgm_read_word(&x) #define PGM_RD_W(x) (short)pgm_read_word(&x)
@ -697,6 +725,9 @@ static void updateTemperaturesFromRawValues()
#ifdef TEMP_SENSOR_1_AS_REDUNDANT #ifdef TEMP_SENSOR_1_AS_REDUNDANT
redundant_temperature = analog2temp(redundant_temperature_raw, 1); redundant_temperature = analog2temp(redundant_temperature_raw, 1);
#endif #endif
#ifdef FILAMENT_SENSOR && (FILWIDTH_PIN > -1) //check if a sensor is supported
filament_width_meas = analog2widthFil();
#endif
//Reset the watchdog after we know we have a temperature measurement. //Reset the watchdog after we know we have a temperature measurement.
watchdog_reset(); watchdog_reset();
@ -705,6 +736,36 @@ static void updateTemperaturesFromRawValues()
CRITICAL_SECTION_END; CRITICAL_SECTION_END;
} }
// For converting raw Filament Width to milimeters
#ifdef FILAMENT_SENSOR
float analog2widthFil() {
return current_raw_filwidth/16383.0*5.0;
//return current_raw_filwidth;
}
// For converting raw Filament Width to a ratio
int widthFil_to_size_ratio() {
float temp;
temp=filament_width_meas;
if(filament_width_meas<MEASURED_LOWER_LIMIT)
temp=filament_width_nominal; //assume sensor cut out
else if (filament_width_meas>MEASURED_UPPER_LIMIT)
temp= MEASURED_UPPER_LIMIT;
return(filament_width_nominal/temp*100);
}
#endif
void tp_init() void tp_init()
{ {
#if (MOTHERBOARD == 80) && ((TEMP_SENSOR_0==-1)||(TEMP_SENSOR_1==-1)||(TEMP_SENSOR_2==-1)||(TEMP_SENSOR_BED==-1)) #if (MOTHERBOARD == 80) && ((TEMP_SENSOR_0==-1)||(TEMP_SENSOR_1==-1)||(TEMP_SENSOR_2==-1)||(TEMP_SENSOR_BED==-1))
@ -804,6 +865,17 @@ void tp_init()
#endif #endif
#endif #endif
//Added for Filament Sensor
#ifdef FILAMENT_SENSOR
#if defined(FILWIDTH_PIN) && (FILWIDTH_PIN > -1)
#if FILWIDTH_PIN < 8
DIDR0 |= 1<<FILWIDTH_PIN;
#else
DIDR2 |= 1<<(FILWIDTH_PIN - 8);
#endif
#endif
#endif
// Use timer0 for temperature measurement // Use timer0 for temperature measurement
// Interleave temperature interrupt with millies interrupt // Interleave temperature interrupt with millies interrupt
OCR0B = 128; OCR0B = 128;
@ -1116,7 +1188,7 @@ ISR(TIMER0_COMPB_vect)
static unsigned long raw_temp_1_value = 0; static unsigned long raw_temp_1_value = 0;
static unsigned long raw_temp_2_value = 0; static unsigned long raw_temp_2_value = 0;
static unsigned long raw_temp_bed_value = 0; static unsigned long raw_temp_bed_value = 0;
static unsigned char temp_state = 8; static unsigned char temp_state = 10;
static unsigned char pwm_count = (1 << SOFT_PWM_SCALE); static unsigned char pwm_count = (1 << SOFT_PWM_SCALE);
static unsigned char soft_pwm_0; static unsigned char soft_pwm_0;
#if (EXTRUDERS > 1) || defined(HEATERS_PARALLEL) #if (EXTRUDERS > 1) || defined(HEATERS_PARALLEL)
@ -1129,6 +1201,10 @@ ISR(TIMER0_COMPB_vect)
static unsigned char soft_pwm_b; static unsigned char soft_pwm_b;
#endif #endif
#if defined(FILWIDTH_PIN) &&(FILWIDTH_PIN > -1)
static unsigned long raw_filwidth_value = 0; //added for filament width sensor
#endif
if(pwm_count == 0){ if(pwm_count == 0){
soft_pwm_0 = soft_pwm[0]; soft_pwm_0 = soft_pwm[0];
if(soft_pwm_0 > 0) { if(soft_pwm_0 > 0) {
@ -1255,10 +1331,39 @@ ISR(TIMER0_COMPB_vect)
#if defined(TEMP_2_PIN) && (TEMP_2_PIN > -1) #if defined(TEMP_2_PIN) && (TEMP_2_PIN > -1)
raw_temp_2_value += ADC; raw_temp_2_value += ADC;
#endif #endif
temp_state = 0; temp_state = 8;//change so that Filament Width is also measured
temp_count++;
break; break;
case 8: //Startup, delay initial temp reading a tiny bit so the hardware can settle. case 8: //Prepare FILWIDTH
#if defined(FILWIDTH_PIN) && (FILWIDTH_PIN> -1)
#if FILWIDTH_PIN>7
ADCSRB = 1<<MUX5;
#else
ADCSRB = 0;
#endif
ADMUX = ((1 << REFS0) | (FILWIDTH_PIN & 0x07));
ADCSRA |= 1<<ADSC; // Start conversion
#endif
lcd_buttons_update();
temp_state = 9;
break;
case 9: //Measure FILWIDTH
#if defined(FILWIDTH_PIN) &&(FILWIDTH_PIN > -1)
//raw_filwidth_value += ADC; //remove to use an IIR filter approach
if(ADC>102) //check that ADC is reading a voltage > 0.5 volts, otherwise don't take in the data.
{
raw_filwidth_value= raw_filwidth_value-(raw_filwidth_value>>7); //multipliy raw_filwidth_value by 127/128
raw_filwidth_value= raw_filwidth_value + ((unsigned long)ADC<<7); //add new ADC reading
}
#endif
temp_state = 0;
temp_count++;
break;
case 10: //Startup, delay initial temp reading a tiny bit so the hardware can settle.
temp_state = 0; temp_state = 0;
break; break;
// default: // default:
@ -1267,7 +1372,7 @@ ISR(TIMER0_COMPB_vect)
// break; // break;
} }
if(temp_count >= OVERSAMPLENR) // 8 * 16 * 1/(16000000/64/256) = 131ms. if(temp_count >= OVERSAMPLENR) // 10 * 16 * 1/(16000000/64/256) = 164ms.
{ {
if (!temp_meas_ready) //Only update the raw values if they have been read. Else we could be updating them during reading. if (!temp_meas_ready) //Only update the raw values if they have been read. Else we could be updating them during reading.
{ {
@ -1284,6 +1389,12 @@ ISR(TIMER0_COMPB_vect)
current_temperature_bed_raw = raw_temp_bed_value; current_temperature_bed_raw = raw_temp_bed_value;
} }
//Add similar code for Filament Sensor - can be read any time since IIR filtering is used
#if defined(FILWIDTH_PIN) &&(FILWIDTH_PIN > -1)
current_raw_filwidth = raw_filwidth_value>>10; //need to divide to get to 0-16384 range since we used 1/128 IIR filter approach
#endif
temp_meas_ready = true; temp_meas_ready = true;
temp_count = 0; temp_count = 0;
raw_temp_0_value = 0; raw_temp_0_value = 0;

@ -31,6 +31,14 @@
void tp_init(); //initialize the heating void tp_init(); //initialize the heating
void manage_heater(); //it is critical that this is called periodically. void manage_heater(); //it is critical that this is called periodically.
#ifdef FILAMENT_SENSOR
// For converting raw Filament Width to milimeters
float analog2widthFil();
// For converting raw Filament Width to an extrusion ratio
int widthFil_to_size_ratio();
#endif
// low level conversion routines // low level conversion routines
// do not use these routines and variables outside of temperature.cpp // do not use these routines and variables outside of temperature.cpp
extern int target_temperature[EXTRUDERS]; extern int target_temperature[EXTRUDERS];

@ -621,6 +621,75 @@ const short temptable_11[][2] PROGMEM = {
}; };
#endif #endif
#if (THERMISTORHEATER_0 == 13) || (THERMISTORHEATER_1 == 13) || (THERMISTORHEATER_2 == 13) || (THERMISTORBED == 13)
// Hisens thermistor B25/50 =3950 +/-1%
const short temptable_13[][2] PROGMEM = {
{ 22.5*OVERSAMPLENR, 300 },
{ 24.125*OVERSAMPLENR, 295 },
{ 25.875*OVERSAMPLENR, 290 },
{ 27.8125*OVERSAMPLENR, 285 },
{ 29.9375*OVERSAMPLENR, 280 },
{ 32.25*OVERSAMPLENR, 275 },
{ 34.8125*OVERSAMPLENR, 270 },
{ 37.625*OVERSAMPLENR, 265 },
{ 40.6875*OVERSAMPLENR, 260 },
{ 44.0625*OVERSAMPLENR, 255 },
{ 47.75*OVERSAMPLENR, 250 },
{ 51.8125*OVERSAMPLENR, 245 },
{ 56.3125*OVERSAMPLENR, 240 },
{ 61.25*OVERSAMPLENR, 235 },
{ 66.75*OVERSAMPLENR, 230 },
{ 72.8125*OVERSAMPLENR, 225 },
{ 79.5*OVERSAMPLENR, 220 },
{ 87*OVERSAMPLENR, 215 },
{ 95.3125*OVERSAMPLENR, 210 },
{ 104.1875*OVERSAMPLENR, 205 },
{ 112.75*OVERSAMPLENR, 200 },
{ 123.125*OVERSAMPLENR, 195 },
{ 135.75*OVERSAMPLENR, 190 },
{ 148.3125*OVERSAMPLENR, 185 },
{ 163.8125*OVERSAMPLENR, 180 },
{ 179*OVERSAMPLENR, 175 },
{ 211.125*OVERSAMPLENR, 170 },
{ 216.125*OVERSAMPLENR, 165 },
{ 236.5625*OVERSAMPLENR, 160 },
{ 258.5*OVERSAMPLENR, 155 },
{ 279.875*OVERSAMPLENR, 150 },
{ 305.375*OVERSAMPLENR, 145 },
{ 333.25*OVERSAMPLENR, 140 },
{ 362.5625*OVERSAMPLENR, 135 },
{ 393.6875*OVERSAMPLENR, 130 },
{ 425*OVERSAMPLENR, 125 },
{ 460.625*OVERSAMPLENR, 120 },
{ 495.1875*OVERSAMPLENR, 115 },
{ 530.875*OVERSAMPLENR, 110 },
{ 567.25*OVERSAMPLENR, 105 },
{ 601.625*OVERSAMPLENR, 100 },
{ 637.875*OVERSAMPLENR, 95 },
{ 674.5625*OVERSAMPLENR, 90 },
{ 710*OVERSAMPLENR, 85 },
{ 744.125*OVERSAMPLENR, 80 },
{ 775.9375*OVERSAMPLENR, 75 },
{ 806.875*OVERSAMPLENR, 70 },
{ 835.1875*OVERSAMPLENR, 65 },
{ 861.125*OVERSAMPLENR, 60 },
{ 884.375*OVERSAMPLENR, 55 },
{ 904.5625*OVERSAMPLENR, 50 },
{ 923.8125*OVERSAMPLENR, 45 },
{ 940.375*OVERSAMPLENR, 40 },
{ 954.625*OVERSAMPLENR, 35 },
{ 966.875*OVERSAMPLENR, 30 },
{ 977.0625*OVERSAMPLENR, 25 },
{ 986*OVERSAMPLENR, 20 },
{ 993.375*OVERSAMPLENR, 15 },
{ 999.5*OVERSAMPLENR, 10 },
{ 1004.5*OVERSAMPLENR, 5 },
{ 1008.5*OVERSAMPLENR, 0 }
};
#endif
#if (THERMISTORHEATER_0 == 20) || (THERMISTORHEATER_1 == 20) || (THERMISTORHEATER_2 == 20) || (THERMISTORBED == 20) // PT100 with INA826 amp on Ultimaker v2.0 electronics #if (THERMISTORHEATER_0 == 20) || (THERMISTORHEATER_1 == 20) || (THERMISTORHEATER_2 == 20) || (THERMISTORBED == 20) // PT100 with INA826 amp on Ultimaker v2.0 electronics
/* The PT100 in the Ultimaker v2.0 electronics has a high sample value for a high temperature. /* The PT100 in the Ultimaker v2.0 electronics has a high sample value for a high temperature.
This does not match the normal thermistor behaviour so we need to set the following defines */ This does not match the normal thermistor behaviour so we need to set the following defines */

@ -328,6 +328,23 @@ static void lcd_autostart_sd()
} }
#endif #endif
void lcd_set_home_offsets()
{
for(int8_t i=0; i < NUM_AXIS; i++) {
if (i != E_AXIS) {
add_homing[i] -= current_position[i];
current_position[i] = 0.0;
}
}
plan_set_position(0.0, 0.0, 0.0, current_position[E_AXIS]);
// Audio feedback
enquecommand_P(PSTR("M300 S659 P200"));
enquecommand_P(PSTR("M300 S698 P200"));
lcd_return_to_status();
}
#ifdef BABYSTEPPING #ifdef BABYSTEPPING
static void lcd_babystep_x() static void lcd_babystep_x()
{ {
@ -395,7 +412,9 @@ static void lcd_tune_menu()
START_MENU(); START_MENU();
MENU_ITEM(back, MSG_MAIN, lcd_main_menu); MENU_ITEM(back, MSG_MAIN, lcd_main_menu);
MENU_ITEM_EDIT(int3, MSG_SPEED, &feedmultiply, 10, 999); MENU_ITEM_EDIT(int3, MSG_SPEED, &feedmultiply, 10, 999);
#if TEMP_SENSOR_0 != 0
MENU_ITEM_EDIT(int3, MSG_NOZZLE, &target_temperature[0], 0, HEATER_0_MAXTEMP - 15); MENU_ITEM_EDIT(int3, MSG_NOZZLE, &target_temperature[0], 0, HEATER_0_MAXTEMP - 15);
#endif
#if TEMP_SENSOR_1 != 0 #if TEMP_SENSOR_1 != 0
MENU_ITEM_EDIT(int3, MSG_NOZZLE1, &target_temperature[1], 0, HEATER_1_MAXTEMP - 15); MENU_ITEM_EDIT(int3, MSG_NOZZLE1, &target_temperature[1], 0, HEATER_1_MAXTEMP - 15);
#endif #endif
@ -587,6 +606,7 @@ static void lcd_prepare_menu()
#endif #endif
MENU_ITEM(gcode, MSG_DISABLE_STEPPERS, PSTR("M84")); MENU_ITEM(gcode, MSG_DISABLE_STEPPERS, PSTR("M84"));
MENU_ITEM(gcode, MSG_AUTO_HOME, PSTR("G28")); MENU_ITEM(gcode, MSG_AUTO_HOME, PSTR("G28"));
MENU_ITEM(function, MSG_SET_HOME_OFFSETS, lcd_set_home_offsets);
//MENU_ITEM(gcode, MSG_SET_ORIGIN, PSTR("G92 X0 Y0 Z0")); //MENU_ITEM(gcode, MSG_SET_ORIGIN, PSTR("G92 X0 Y0 Z0"));
#if TEMP_SENSOR_0 != 0 #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_BED != 0
@ -801,7 +821,9 @@ static void lcd_control_temperature_menu()
START_MENU(); START_MENU();
MENU_ITEM(back, MSG_CONTROL, lcd_control_menu); MENU_ITEM(back, MSG_CONTROL, lcd_control_menu);
#if TEMP_SENSOR_0 != 0
MENU_ITEM_EDIT(int3, MSG_NOZZLE, &target_temperature[0], 0, HEATER_0_MAXTEMP - 15); MENU_ITEM_EDIT(int3, MSG_NOZZLE, &target_temperature[0], 0, HEATER_0_MAXTEMP - 15);
#endif
#if TEMP_SENSOR_1 != 0 #if TEMP_SENSOR_1 != 0
MENU_ITEM_EDIT(int3, MSG_NOZZLE1, &target_temperature[1], 0, HEATER_1_MAXTEMP - 15); MENU_ITEM_EDIT(int3, MSG_NOZZLE1, &target_temperature[1], 0, HEATER_1_MAXTEMP - 15);
#endif #endif
@ -812,7 +834,7 @@ static void lcd_control_temperature_menu()
MENU_ITEM_EDIT(int3, MSG_BED, &target_temperature_bed, 0, BED_MAXTEMP - 15); MENU_ITEM_EDIT(int3, MSG_BED, &target_temperature_bed, 0, BED_MAXTEMP - 15);
#endif #endif
MENU_ITEM_EDIT(int3, MSG_FAN_SPEED, &fanSpeed, 0, 255); MENU_ITEM_EDIT(int3, MSG_FAN_SPEED, &fanSpeed, 0, 255);
#ifdef AUTOTEMP #if defined AUTOTEMP && (TEMP_SENSOR_0 != 0)
MENU_ITEM_EDIT(bool, MSG_AUTOTEMP, &autotemp_enabled); MENU_ITEM_EDIT(bool, MSG_AUTOTEMP, &autotemp_enabled);
MENU_ITEM_EDIT(float3, MSG_MIN, &autotemp_min, 0, HEATER_0_MAXTEMP - 15); MENU_ITEM_EDIT(float3, MSG_MIN, &autotemp_min, 0, HEATER_0_MAXTEMP - 15);
MENU_ITEM_EDIT(float3, MSG_MAX, &autotemp_max, 0, HEATER_0_MAXTEMP - 15); MENU_ITEM_EDIT(float3, MSG_MAX, &autotemp_max, 0, HEATER_0_MAXTEMP - 15);
@ -837,7 +859,9 @@ static void lcd_control_temperature_preheat_pla_settings_menu()
START_MENU(); START_MENU();
MENU_ITEM(back, MSG_TEMPERATURE, lcd_control_temperature_menu); MENU_ITEM(back, MSG_TEMPERATURE, lcd_control_temperature_menu);
MENU_ITEM_EDIT(int3, MSG_FAN_SPEED, &plaPreheatFanSpeed, 0, 255); MENU_ITEM_EDIT(int3, MSG_FAN_SPEED, &plaPreheatFanSpeed, 0, 255);
#if TEMP_SENSOR_0 != 0
MENU_ITEM_EDIT(int3, MSG_NOZZLE, &plaPreheatHotendTemp, 0, HEATER_0_MAXTEMP - 15); MENU_ITEM_EDIT(int3, MSG_NOZZLE, &plaPreheatHotendTemp, 0, HEATER_0_MAXTEMP - 15);
#endif
#if TEMP_SENSOR_BED != 0 #if TEMP_SENSOR_BED != 0
MENU_ITEM_EDIT(int3, MSG_BED, &plaPreheatHPBTemp, 0, BED_MAXTEMP - 15); MENU_ITEM_EDIT(int3, MSG_BED, &plaPreheatHPBTemp, 0, BED_MAXTEMP - 15);
#endif #endif
@ -852,7 +876,9 @@ static void lcd_control_temperature_preheat_abs_settings_menu()
START_MENU(); START_MENU();
MENU_ITEM(back, MSG_TEMPERATURE, lcd_control_temperature_menu); MENU_ITEM(back, MSG_TEMPERATURE, lcd_control_temperature_menu);
MENU_ITEM_EDIT(int3, MSG_FAN_SPEED, &absPreheatFanSpeed, 0, 255); MENU_ITEM_EDIT(int3, MSG_FAN_SPEED, &absPreheatFanSpeed, 0, 255);
#if TEMP_SENSOR_0 != 0
MENU_ITEM_EDIT(int3, MSG_NOZZLE, &absPreheatHotendTemp, 0, HEATER_0_MAXTEMP - 15); MENU_ITEM_EDIT(int3, MSG_NOZZLE, &absPreheatHotendTemp, 0, HEATER_0_MAXTEMP - 15);
#endif
#if TEMP_SENSOR_BED != 0 #if TEMP_SENSOR_BED != 0
MENU_ITEM_EDIT(int3, MSG_BED, &absPreheatHPBTemp, 0, BED_MAXTEMP - 15); MENU_ITEM_EDIT(int3, MSG_BED, &absPreheatHPBTemp, 0, BED_MAXTEMP - 15);
#endif #endif

@ -467,7 +467,7 @@ static void lcd_implementation_status_screen()
# endif//LCD_WIDTH > 19 # endif//LCD_WIDTH > 19
lcd.setCursor(LCD_WIDTH - 8, 1); lcd.setCursor(LCD_WIDTH - 8, 1);
lcd.print('Z'); lcd.print('Z');
lcd.print(ftostr32(current_position[Z_AXIS])); lcd.print(ftostr32(current_position[Z_AXIS] + 0.00001));
#endif//LCD_HEIGHT > 2 #endif//LCD_HEIGHT > 2
#if LCD_HEIGHT > 3 #if LCD_HEIGHT > 3

@ -2,6 +2,7 @@
Marlin 3D Printer Firmware Marlin 3D Printer Firmware
========================== ==========================
[![Coverity Scan Build Status](https://scan.coverity.com/projects/2224/badge.svg)](https://scan.coverity.com/projects/2224) [![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/ErikZalm/Marlin.svg)](https://travis-ci.org/ErikZalm/Marlin)
Marlin has a GPL license because I believe in open development. Marlin has a GPL license 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. Please do not use this code in products (3D printers, CNC etc) that are closed source or are crippled by a patent.
@ -233,6 +234,10 @@ M Codes
* M400 - Finish all moves * M400 - Finish all moves
* M401 - Lower z-probe if present * M401 - Lower z-probe if present
* M402 - Raise z-probe if present * M402 - Raise z-probe if present
* M404 - N<dia in mm> Enter the nominal filament width (3mm, 1.75mm ) or will display nominal filament width without parameters
* 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 - Displays measured filament diameter
* M500 - stores paramters in EEPROM * M500 - stores paramters in EEPROM
* M501 - reads parameters from EEPROM (if you need reset them after you changed them temporarily). * M501 - reads parameters from EEPROM (if you need reset them after you changed them temporarily).
* M502 - reverts to the default "factory settings". You still need to store them in EEPROM afterwards if you want to. * M502 - reverts to the default "factory settings". You still need to store them in EEPROM afterwards if you want to.

Loading…
Cancel
Save