Merge pull request #409 from buildrob202/Marlin_v1
Implement automatic cold-end/extruder motor fan control based on nozzle temperature
This commit is contained in:
commit
b2eeebd9c3
@ -51,6 +51,9 @@
|
||||
#define MOTHERBOARD 7
|
||||
#endif
|
||||
|
||||
// This defines the number of extruders
|
||||
#define EXTRUDERS 1
|
||||
|
||||
//// The following define selects which power supply you have. Please choose the one that matches your setup
|
||||
// 1 = ATX
|
||||
// 2 = X-Box 360 203Watts (the blue wire connected to PS_ON and the red wire to VCC)
|
||||
|
@ -63,21 +63,31 @@
|
||||
//This is for controlling a fan to cool down the stepper drivers
|
||||
//it will turn on when any driver is enabled
|
||||
//and turn off after the set amount of seconds from last driver being disabled again
|
||||
//#define CONTROLLERFAN_PIN 23 //Pin used for the fan to cool controller, comment out to disable this function
|
||||
#define CONTROLLERFAN_SEC 60 //How many seconds, after all motors were disabled, the fan should run
|
||||
#define CONTROLLERFAN_PIN -1 //Pin used for the fan to cool controller (-1 to disable)
|
||||
#define CONTROLLERFAN_SECS 60 //How many seconds, after all motors were disabled, the fan should run
|
||||
#define CONTROLLERFAN_SPEED 255 // == full speed
|
||||
|
||||
// When first starting the main fan, run it at full speed for the
|
||||
// given number of milliseconds. This gets the fan spinning reliably
|
||||
// before setting a PWM value. (Does not work with software PWM for fan on Sanguinololu)
|
||||
//#define FAN_KICKSTART_TIME 100
|
||||
|
||||
// Extruder cooling fans
|
||||
// Configure fan pin outputs to automatically turn on/off when the associated
|
||||
// extruder temperature is above/below EXTRUDER_AUTO_FAN_TEMPERATURE.
|
||||
// Multiple extruders can be assigned to the same pin in which case
|
||||
// the fan will turn on when any selected extruder is above the threshold.
|
||||
#define EXTRUDER_0_AUTO_FAN_PIN -1
|
||||
#define EXTRUDER_1_AUTO_FAN_PIN -1
|
||||
#define EXTRUDER_2_AUTO_FAN_PIN -1
|
||||
#define EXTRUDER_AUTO_FAN_TEMPERATURE 50
|
||||
#define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed
|
||||
|
||||
|
||||
//===========================================================================
|
||||
//=============================Mechanical Settings===========================
|
||||
//===========================================================================
|
||||
|
||||
// This defines the number of extruders
|
||||
#define EXTRUDERS 1
|
||||
|
||||
#define ENDSTOPS_ONLY_FOR_HOMING // If defined the endstops will only be used for homing
|
||||
|
||||
|
||||
@ -210,9 +220,9 @@
|
||||
// However, THIS FEATURE IS UNSAFE!, as it will only work if interrupts are disabled. And the code could hang in an interrupt routine with interrupts disabled.
|
||||
//#define WATCHDOG_RESET_MANUAL
|
||||
#endif
|
||||
|
||||
// Enable the option to stop SD printing when hitting and endstops, needs to be enabled from the LCD menu when this option is enabled.
|
||||
//#define ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
|
||||
|
||||
// Enable the option to stop SD printing when hitting and endstops, needs to be enabled from the LCD menu when this option is enabled.
|
||||
//#define ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
|
||||
|
||||
// extruder advance constant (s2/mm3)
|
||||
//
|
||||
@ -276,7 +286,7 @@ const unsigned int dropsegments=5; //everything with less than this number of st
|
||||
#else
|
||||
#define BLOCK_BUFFER_SIZE 16 // maximize block buffer
|
||||
#endif
|
||||
|
||||
|
||||
|
||||
//The ASCII buffer for recieving from the serial:
|
||||
#define MAX_CMD_SIZE 96
|
||||
|
@ -319,7 +319,7 @@ void setup_photpin()
|
||||
void setup_powerhold()
|
||||
{
|
||||
#ifdef SUICIDE_PIN
|
||||
#if (SUICIDE_PIN> -1)
|
||||
#if (SUICIDE_PIN> 0)
|
||||
SET_OUTPUT(SUICIDE_PIN);
|
||||
WRITE(SUICIDE_PIN, HIGH);
|
||||
#endif
|
||||
@ -410,14 +410,10 @@ void setup()
|
||||
servo_init();
|
||||
|
||||
lcd_init();
|
||||
|
||||
#ifdef CONTROLLERFAN_PIN
|
||||
|
||||
#if CONTROLLERFAN_PIN > 0
|
||||
SET_OUTPUT(CONTROLLERFAN_PIN); //Set pin used for driver cooling fan
|
||||
#endif
|
||||
|
||||
#ifdef EXTRUDERFAN_PIN
|
||||
SET_OUTPUT(EXTRUDERFAN_PIN); //Set pin used for extruder cooling fan
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
|
||||
|
||||
@ -1040,6 +1036,10 @@ void process_commands()
|
||||
break;
|
||||
}
|
||||
}
|
||||
#if FAN_PIN > 0
|
||||
if (pin_number == FAN_PIN)
|
||||
fanSpeed = pin_status;
|
||||
#endif
|
||||
if (pin_number > -1)
|
||||
{
|
||||
pinMode(pin_number, OUTPUT);
|
||||
@ -2064,7 +2064,12 @@ void prepare_arc_move(char isclockwise) {
|
||||
previous_millis_cmd = millis();
|
||||
}
|
||||
|
||||
#ifdef CONTROLLERFAN_PIN
|
||||
#if CONTROLLERFAN_PIN > 0
|
||||
|
||||
#if CONTROLLERFAN_PIN == FAN_PIN
|
||||
#error "You cannot set CONTROLLERFAN_PIN equal to FAN_PIN"
|
||||
#endif
|
||||
|
||||
unsigned long lastMotor = 0; //Save the time for when a motor was turned on last
|
||||
unsigned long lastMotorCheck = 0;
|
||||
|
||||
@ -2085,35 +2090,17 @@ void controllerFan()
|
||||
{
|
||||
lastMotor = millis(); //... set time to NOW so the fan will turn on
|
||||
}
|
||||
|
||||
if ((millis() - lastMotor) >= (CONTROLLERFAN_SEC*1000UL) || lastMotor == 0) //If the last time any driver was enabled, is longer since than CONTROLLERSEC...
|
||||
|
||||
if ((millis() - lastMotor) >= (CONTROLLERFAN_SECS*1000UL) || lastMotor == 0) //If the last time any driver was enabled, is longer since than CONTROLLERSEC...
|
||||
{
|
||||
WRITE(CONTROLLERFAN_PIN, LOW); //... turn the fan off
|
||||
digitalWrite(CONTROLLERFAN_PIN, 0);
|
||||
analogWrite(CONTROLLERFAN_PIN, 0);
|
||||
}
|
||||
else
|
||||
{
|
||||
WRITE(CONTROLLERFAN_PIN, HIGH); //... turn the fan on
|
||||
}
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef EXTRUDERFAN_PIN
|
||||
unsigned long lastExtruderCheck = 0;
|
||||
|
||||
void extruderFan()
|
||||
{
|
||||
if ((millis() - lastExtruderCheck) >= 2500) //Not a time critical function, so we only check every 2500ms
|
||||
{
|
||||
lastExtruderCheck = millis();
|
||||
|
||||
if (degHotend(active_extruder) < EXTRUDERFAN_DEC)
|
||||
{
|
||||
WRITE(EXTRUDERFAN_PIN, LOW); //... turn the fan off
|
||||
}
|
||||
else
|
||||
{
|
||||
WRITE(EXTRUDERFAN_PIN, HIGH); //... turn the fan on
|
||||
// allows digital or PWM fan output to be used (see M42 handling)
|
||||
digitalWrite(CONTROLLERFAN_PIN, CONTROLLERFAN_SPEED);
|
||||
analogWrite(CONTROLLERFAN_PIN, CONTROLLERFAN_SPEED);
|
||||
}
|
||||
}
|
||||
}
|
||||
@ -2137,11 +2124,11 @@ void manage_inactivity()
|
||||
}
|
||||
}
|
||||
}
|
||||
#if( KILL_PIN>-1 )
|
||||
#if KILL_PIN > 0
|
||||
if( 0 == READ(KILL_PIN) )
|
||||
kill();
|
||||
#endif
|
||||
#ifdef CONTROLLERFAN_PIN
|
||||
#if CONTROLLERFAN_PIN > 0
|
||||
controllerFan(); //Check if fan should be turned on to cool stepper drivers down
|
||||
#endif
|
||||
#ifdef EXTRUDER_RUNOUT_PREVENT
|
||||
|
@ -69,9 +69,9 @@ volatile long endstops_stepsTotal,endstops_stepsDone;
|
||||
static volatile bool endstop_x_hit=false;
|
||||
static volatile bool endstop_y_hit=false;
|
||||
static volatile bool endstop_z_hit=false;
|
||||
#ifdef ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
|
||||
bool abort_on_endstop_hit = false;
|
||||
#endif
|
||||
#ifdef ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
|
||||
bool abort_on_endstop_hit = false;
|
||||
#endif
|
||||
|
||||
static bool old_x_min_endstop=false;
|
||||
static bool old_x_max_endstop=false;
|
||||
@ -184,20 +184,20 @@ void checkHitEndstops()
|
||||
SERIAL_ECHOPAIR(" Z:",(float)endstops_trigsteps[Z_AXIS]/axis_steps_per_unit[Z_AXIS]);
|
||||
LCD_MESSAGEPGM(MSG_ENDSTOPS_HIT "Z");
|
||||
}
|
||||
SERIAL_ECHOLN("");
|
||||
SERIAL_ECHOLN("");
|
||||
endstop_x_hit=false;
|
||||
endstop_y_hit=false;
|
||||
endstop_z_hit=false;
|
||||
#ifdef ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
|
||||
if (abort_on_endstop_hit)
|
||||
{
|
||||
endstop_z_hit=false;
|
||||
#ifdef ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
|
||||
if (abort_on_endstop_hit)
|
||||
{
|
||||
card.sdprinting = false;
|
||||
card.closefile();
|
||||
quickStop();
|
||||
quickStop();
|
||||
setTargetHotend0(0);
|
||||
setTargetHotend1(0);
|
||||
setTargetHotend2(0);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
}
|
||||
}
|
||||
@ -879,10 +879,6 @@ void st_init()
|
||||
disable_e2();
|
||||
#endif
|
||||
|
||||
#ifdef CONTROLLERFAN_PIN
|
||||
SET_OUTPUT(CONTROLLERFAN_PIN); //Set pin used for driver cooling fan
|
||||
#endif
|
||||
|
||||
// waveform generation = 0100 = CTC
|
||||
TCCR1B &= ~(1<<WGM13);
|
||||
TCCR1B |= (1<<WGM12);
|
||||
|
@ -99,8 +99,9 @@ static volatile bool temp_meas_ready = false;
|
||||
#ifdef FAN_SOFT_PWM
|
||||
static unsigned char soft_pwm_fan;
|
||||
#endif
|
||||
|
||||
|
||||
#if EXTRUDER_0_AUTO_FAN_PIN > 0 || EXTRUDER_1_AUTO_FAN_PIN > 0 || EXTRUDER_2_AUTO_FAN_PIN > 0
|
||||
static unsigned long extruder_autofan_last_check;
|
||||
#endif
|
||||
|
||||
#if EXTRUDERS > 3
|
||||
# error Unsupported number of extruders
|
||||
@ -306,6 +307,76 @@ int getHeaterPower(int heater) {
|
||||
return soft_pwm[heater];
|
||||
}
|
||||
|
||||
#if EXTRUDER_0_AUTO_FAN_PIN > 0 || EXTRUDER_1_AUTO_FAN_PIN > 0 || EXTRUDER_2_AUTO_FAN_PIN > 0
|
||||
|
||||
#if FAN_PIN > 0
|
||||
#if EXTRUDER_0_AUTO_FAN_PIN == FAN_PIN
|
||||
#error "You cannot set EXTRUDER_0_AUTO_FAN_PIN equal to FAN_PIN"
|
||||
#endif
|
||||
#if EXTRUDER_1_AUTO_FAN_PIN == FAN_PIN
|
||||
#error "You cannot set EXTRUDER_1_AUTO_FAN_PIN equal to FAN_PIN"
|
||||
#endif
|
||||
#if EXTRUDER_2_AUTO_FAN_PIN == FAN_PIN
|
||||
#error "You cannot set EXTRUDER_2_AUTO_FAN_PIN equal to FAN_PIN"
|
||||
#endif
|
||||
#endif
|
||||
|
||||
void setExtruderAutoFanState(int pin, bool state)
|
||||
{
|
||||
unsigned char newFanSpeed = (state != 0) ? EXTRUDER_AUTO_FAN_SPEED : 0;
|
||||
// this idiom allows both digital and PWM fan outputs (see M42 handling).
|
||||
pinMode(pin, OUTPUT);
|
||||
digitalWrite(pin, newFanSpeed);
|
||||
analogWrite(pin, newFanSpeed);
|
||||
}
|
||||
|
||||
void checkExtruderAutoFans()
|
||||
{
|
||||
uint8_t fanState = 0;
|
||||
|
||||
// which fan pins need to be turned on?
|
||||
#if EXTRUDER_0_AUTO_FAN_PIN > 0
|
||||
if (current_temperature[0] > EXTRUDER_AUTO_FAN_TEMPERATURE)
|
||||
fanState |= 1;
|
||||
#endif
|
||||
#if EXTRUDER_1_AUTO_FAN_PIN > 0
|
||||
if (current_temperature[1] > EXTRUDER_AUTO_FAN_TEMPERATURE)
|
||||
{
|
||||
if (EXTRUDER_1_AUTO_FAN_PIN == EXTRUDER_0_AUTO_FAN_PIN)
|
||||
fanState |= 1;
|
||||
else
|
||||
fanState |= 2;
|
||||
}
|
||||
#endif
|
||||
#if EXTRUDER_2_AUTO_FAN_PIN > 0
|
||||
if (current_temperature[2] > EXTRUDER_AUTO_FAN_TEMPERATURE)
|
||||
{
|
||||
if (EXTRUDER_2_AUTO_FAN_PIN == EXTRUDER_0_AUTO_FAN_PIN)
|
||||
fanState |= 1;
|
||||
else if (EXTRUDER_2_AUTO_FAN_PIN == EXTRUDER_1_AUTO_FAN_PIN)
|
||||
fanState |= 2;
|
||||
else
|
||||
fanState |= 4;
|
||||
}
|
||||
#endif
|
||||
|
||||
// update extruder auto fan states
|
||||
#if EXTRUDER_0_AUTO_FAN_PIN > 0
|
||||
setExtruderAutoFanState(EXTRUDER_0_AUTO_FAN_PIN, (fanState & 1) != 0);
|
||||
#endif
|
||||
#if EXTRUDER_1_AUTO_FAN_PIN > 0
|
||||
if (EXTRUDER_1_AUTO_FAN_PIN != EXTRUDER_0_AUTO_FAN_PIN)
|
||||
setExtruderAutoFanState(EXTRUDER_1_AUTO_FAN_PIN, (fanState & 2) != 0);
|
||||
#endif
|
||||
#if EXTRUDER_2_AUTO_FAN_PIN > 0
|
||||
if (EXTRUDER_2_AUTO_FAN_PIN != EXTRUDER_0_AUTO_FAN_PIN
|
||||
&& EXTRUDER_2_AUTO_FAN_PIN != EXTRUDER_1_AUTO_FAN_PIN)
|
||||
setExtruderAutoFanState(EXTRUDER_2_AUTO_FAN_PIN, (fanState & 4) != 0);
|
||||
#endif
|
||||
}
|
||||
|
||||
#endif // any extruder auto fan pins set
|
||||
|
||||
void manage_heater()
|
||||
{
|
||||
float pid_input;
|
||||
@ -398,8 +469,15 @@ void manage_heater()
|
||||
#endif
|
||||
|
||||
} // End extruder for loop
|
||||
|
||||
|
||||
#if EXTRUDER_0_AUTO_FAN_PIN > 0 || EXTRUDER_1_AUTO_FAN_PIN > 0 || EXTRUDER_2_AUTO_FAN_PIN > 0
|
||||
if(millis() - extruder_autofan_last_check > 2500) // only need to check fan state very infrequently
|
||||
{
|
||||
checkExtruderAutoFans();
|
||||
extruder_autofan_last_check = millis();
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifndef PIDTEMPBED
|
||||
if(millis() - previous_millis_bed_heater < BED_CHECK_INTERVAL)
|
||||
return;
|
||||
|
450
README.md
450
README.md
@ -1,223 +1,227 @@
|
||||
WARNING:
|
||||
--------
|
||||
THIS IS RELEASE CANDIDATE 2 FOR MARLIN 1.0.0
|
||||
|
||||
The configuration is now split in two files
|
||||
Configuration.h for the normal settings
|
||||
Configuration_adv.h for the advanced settings
|
||||
|
||||
Gen7T is not supported.
|
||||
|
||||
Quick Information
|
||||
===================
|
||||
This RepRap firmware is a mashup between <a href="https://github.com/kliment/Sprinter">Sprinter</a>, <a href="https://github.com/simen/grbl/tree">grbl</a> and many original parts.
|
||||
|
||||
Derived from Sprinter and Grbl by Erik van der Zalm.
|
||||
Sprinters lead developers are Kliment and caru.
|
||||
Grbls lead developer is Simen Svale Skogsrud. Sonney Jeon (Chamnit) improved some parts of grbl
|
||||
A fork by bkubicek for the Ultimaker was merged, and further development was aided by him.
|
||||
Some features have been added by:
|
||||
Lampmaker, Bradley Feldman, and others...
|
||||
|
||||
|
||||
Features:
|
||||
|
||||
* Interrupt based movement with real linear acceleration
|
||||
* High steprate
|
||||
* Look ahead (Keep the speed high when possible. High cornering speed)
|
||||
* Interrupt based temperature protection
|
||||
* preliminary support for Matthew Roberts advance algorithm
|
||||
For more info see: http://reprap.org/pipermail/reprap-dev/2011-May/003323.html
|
||||
* Full endstop support
|
||||
* SD Card support
|
||||
* SD Card folders (works in pronterface)
|
||||
* SD Card autostart support
|
||||
* LCD support (ideally 20x4)
|
||||
* LCD menu system for autonomous SD card printing, controlled by an click-encoder.
|
||||
* EEPROM storage of e.g. max-velocity, max-acceleration, and similar variables
|
||||
* many small but handy things originating from bkubicek's fork.
|
||||
* Arc support
|
||||
* Temperature oversampling
|
||||
* Dynamic Temperature setpointing aka "AutoTemp"
|
||||
* Support for QTMarlin, a very beta GUI for PID-tuning and velocity-acceleration testing. https://github.com/bkubicek/QTMarlin
|
||||
* Endstop trigger reporting to the host software.
|
||||
* Updated sdcardlib
|
||||
* Heater power reporting. Useful for PID monitoring.
|
||||
* PID tuning
|
||||
* CoreXY kinematics (www.corexy.com/theory.html)
|
||||
* Configurable serial port to support connection of wireless adaptors.
|
||||
|
||||
The default baudrate is 250000. This baudrate has less jitter and hence errors than the usual 115200 baud, but is less supported by drivers and host-environments.
|
||||
|
||||
|
||||
Differences and additions to the already good Sprinter firmware:
|
||||
================================================================
|
||||
|
||||
*Look-ahead:*
|
||||
|
||||
Marlin has look-ahead. While sprinter has to break and re-accelerate at each corner,
|
||||
lookahead will only decelerate and accelerate to a velocity,
|
||||
so that the change in vectorial velocity magnitude is less than the xy_jerk_velocity.
|
||||
This is only possible, if some future moves are already processed, hence the name.
|
||||
It leads to less over-deposition at corners, especially at flat angles.
|
||||
|
||||
*Arc support:*
|
||||
|
||||
Slic3r can find curves that, although broken into segments, were ment to describe an arc.
|
||||
Marlin is able to print those arcs. The advantage is the firmware can choose the resolution,
|
||||
and can perform the arc with nearly constant velocity, resulting in a nice finish.
|
||||
Also, less serial communication is needed.
|
||||
|
||||
*Temperature Oversampling:*
|
||||
|
||||
To reduce noise and make the PID-differential term more useful, 16 ADC conversion results are averaged.
|
||||
|
||||
*AutoTemp:*
|
||||
|
||||
If your gcode contains a wide spread of extruder velocities, or you realtime change the building speed, the temperature should be changed accordingly.
|
||||
Usually, higher speed requires higher temperature.
|
||||
This can now be performed by the AutoTemp function
|
||||
By calling M109 S<mintemp> T<maxtemp> F<factor> you enter the autotemp mode.
|
||||
|
||||
You can leave it by calling M109 without any F.
|
||||
If active, the maximal extruder stepper rate of all buffered moves will be calculated, and named "maxerate" [steps/sec].
|
||||
The wanted temperature then will be set to t=tempmin+factor*maxerate, while being limited between tempmin and tempmax.
|
||||
If the target temperature is set manually or by gcode to a value less then tempmin, it will be kept without change.
|
||||
Ideally, your gcode can be completely free of temperature controls, apart from a M109 S T F in the start.gcode, and a M109 S0 in the end.gcode.
|
||||
|
||||
*EEPROM:*
|
||||
|
||||
If you know your PID values, the acceleration and max-velocities of your unique machine, you can set them, and finally store them in the EEPROM.
|
||||
After each reboot, it will magically load them from EEPROM, independent what your Configuration.h says.
|
||||
|
||||
*LCD Menu:*
|
||||
|
||||
If your hardware supports it, you can build yourself a LCD-CardReader+Click+encoder combination. It will enable you to realtime tune temperatures,
|
||||
accelerations, velocities, flow rates, select and print files from the SD card, preheat, disable the steppers, and do other fancy stuff.
|
||||
One working hardware is documented here: http://www.thingiverse.com/thing:12663
|
||||
Also, with just a 20x4 or 16x2 display, useful data is shown.
|
||||
|
||||
*SD card folders:*
|
||||
|
||||
If you have an SD card reader attached to your controller, also folders work now. Listing the files in pronterface will show "/path/subpath/file.g".
|
||||
You can write to file in a subfolder by specifying a similar text using small letters in the path.
|
||||
Also, backup copies of various operating systems are hidden, as well as files not ending with ".g".
|
||||
|
||||
*SD card folders:*
|
||||
|
||||
If you place a file auto[0-9].g into the root of the sd card, it will be automatically executed if you boot the printer. The same file will be executed by selecting "Autostart" from the menu.
|
||||
First *0 will be performed, than *1 and so on. That way, you can heat up or even print automatically without user interaction.
|
||||
|
||||
*Endstop trigger reporting:*
|
||||
|
||||
If an endstop is hit while moving towards the endstop, the location at which the firmware thinks that the endstop was triggered is outputed on the serial port.
|
||||
This is useful, because the user gets a warning message.
|
||||
However, also tools like QTMarlin can use this for finding acceptable combinations of velocity+acceleration.
|
||||
|
||||
*Coding paradigm:*
|
||||
|
||||
Not relevant from a user side, but Marlin was split into thematic junks, and has tried to partially enforced private variables.
|
||||
This is intended to make it clearer, what interacts which what, and leads to a higher level of modularization.
|
||||
We think that this is a useful prestep for porting this firmware to e.g. an ARM platform in the future.
|
||||
A lot of RAM (with enabled LCD ~2200 bytes) was saved by storing char []="some message" in Program memory.
|
||||
In the serial communication, a #define based level of abstraction was enforced, so that it is clear that
|
||||
some transfer is information (usually beginning with "echo:"), an error "error:", or just normal protocol,
|
||||
necessary for backwards compatibility.
|
||||
|
||||
*Interrupt based temperature measurements:*
|
||||
|
||||
An interrupt is used to manage ADC conversions, and enforce checking for critical temperatures.
|
||||
This leads to less blocking in the heater management routine.
|
||||
|
||||
|
||||
Non-standard M-Codes, different to an old version of sprinter:
|
||||
==============================================================
|
||||
Movement:
|
||||
|
||||
* G2 - CW ARC
|
||||
* G3 - CCW ARC
|
||||
|
||||
General:
|
||||
|
||||
* M17 - Enable/Power all stepper motors. Compatibility to ReplicatorG.
|
||||
* M18 - Disable all stepper motors; same as M84.Compatibility to ReplicatorG.
|
||||
* M30 - Print time since last M109 or SD card start to serial
|
||||
* M42 - Change pin status via gcode
|
||||
* M80 - Turn on Power Supply
|
||||
* M81 - Turn off Power Supply
|
||||
* M114 - Output current position to serial port
|
||||
* M119 - Output Endstop status to serial port
|
||||
|
||||
Movement variables:
|
||||
|
||||
* M202 - Set max acceleration in units/s^2 for travel moves (M202 X1000 Y1000) Unused in Marlin!!
|
||||
* M203 - Set maximum feedrate that your machine can sustain (M203 X200 Y200 Z300 E10000) in mm/sec
|
||||
* M204 - Set default acceleration: S normal moves T filament only moves (M204 S3000 T7000) im mm/sec^2 also sets minimum segment time in ms (B20000) to prevent buffer underruns and M20 minimum feedrate
|
||||
* M206 - set home offsets. This sets the X,Y,Z coordinates of the endstops (and is added to the {X,Y,Z}_HOME_POS configuration options (and is also added to the coordinates, if any, provided to G82, as with earlier firmware)
|
||||
* M220 - set build speed mulitplying S:factor in percent ; aka "realtime tuneing in the gcode". So you can slow down if you have islands in one height-range, and speed up otherwise.
|
||||
* M221 - set the extrude multiplying S:factor in percent
|
||||
* M400 - Finish all buffered moves.
|
||||
|
||||
Temperature variables:
|
||||
* M301 - Set PID parameters P I and D
|
||||
* M302 - Allow cold extrudes
|
||||
* M303 - PID relay autotune S<temperature> sets the target temperature. (default target temperature = 150C)
|
||||
|
||||
Advance:
|
||||
|
||||
* M200 - Set filament diameter for advance
|
||||
* M205 - advanced settings: minimum travel speed S=while printing T=travel only, B=minimum segment time X= maximum xy jerk, Z=maximum Z jerk
|
||||
|
||||
EEPROM:
|
||||
|
||||
* M500 - stores paramters in EEPROM. This parameters are stored: axis_steps_per_unit, max_feedrate, max_acceleration ,acceleration,retract_acceleration,
|
||||
minimumfeedrate,mintravelfeedrate,minsegmenttime, jerk velocities, PID
|
||||
* 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.
|
||||
* M503 - print the current settings (from memory not from eeprom)
|
||||
|
||||
MISC:
|
||||
|
||||
* M240 - Trigger a camera to take a photograph
|
||||
* M999 - Restart after being stopped by error
|
||||
|
||||
Configuring and compilation:
|
||||
============================
|
||||
|
||||
Install the arduino software IDE/toolset v23 (Some configurations also work with 1.x.x)
|
||||
http://www.arduino.cc/en/Main/Software
|
||||
|
||||
For gen6/gen7 and sanguinololu the Sanguino directory in the Marlin dir needs to be copied to the arduino environment.
|
||||
copy ArduinoAddons\Arduino_x.x.x\sanguino <arduino home>\hardware\Sanguino
|
||||
|
||||
Install Ultimaker's RepG 25 build
|
||||
http://software.ultimaker.com
|
||||
For SD handling and as better substitute (apart from stl manipulation) download
|
||||
the very nice Kliment's printrun/pronterface https://github.com/kliment/Printrun
|
||||
|
||||
Copy the Ultimaker Marlin firmware
|
||||
https://github.com/ErikZalm/Marlin/tree/Marlin_v1
|
||||
(Use the download button)
|
||||
|
||||
Start the arduino IDE.
|
||||
Select Tools -> Board -> Arduino Mega 2560 or your microcontroller
|
||||
Select the correct serial port in Tools ->Serial Port
|
||||
Open Marlin.pde
|
||||
|
||||
Click the Verify/Compile button
|
||||
|
||||
Click the Upload button
|
||||
If all goes well the firmware is uploading
|
||||
|
||||
Start Ultimaker's Custom RepG 25
|
||||
Make sure Show Experimental Profiles is enabled in Preferences
|
||||
Select Sprinter as the Driver
|
||||
|
||||
Press the Connect button.
|
||||
|
||||
KNOWN ISSUES: RepG will display: Unknown: marlin x.y.z
|
||||
|
||||
That's ok. Enjoy Silky Smooth Printing.
|
||||
|
||||
|
||||
|
||||
==========================
|
||||
Marlin 3D Printer Firmware
|
||||
==========================
|
||||
|
||||
Notes:
|
||||
-----
|
||||
|
||||
The configuration is now split in two files:
|
||||
Configuration.h for the normal settings
|
||||
Configuration_adv.h for the advanced settings
|
||||
|
||||
Gen7T is not supported.
|
||||
|
||||
Quick Information
|
||||
===================
|
||||
This RepRap firmware is a mashup between <a href="https://github.com/kliment/Sprinter">Sprinter</a>, <a href="https://github.com/simen/grbl/tree">grbl</a> and many original parts.
|
||||
|
||||
Derived from Sprinter and Grbl by Erik van der Zalm.
|
||||
Sprinters lead developers are Kliment and caru.
|
||||
Grbls lead developer is Simen Svale Skogsrud. Sonney Jeon (Chamnit) improved some parts of grbl
|
||||
A fork by bkubicek for the Ultimaker was merged, and further development was aided by him.
|
||||
Some features have been added by:
|
||||
Lampmaker, Bradley Feldman, and others...
|
||||
|
||||
|
||||
Features:
|
||||
|
||||
* Interrupt based movement with real linear acceleration
|
||||
* High steprate
|
||||
* Look ahead (Keep the speed high when possible. High cornering speed)
|
||||
* Interrupt based temperature protection
|
||||
* preliminary support for Matthew Roberts advance algorithm
|
||||
For more info see: http://reprap.org/pipermail/reprap-dev/2011-May/003323.html
|
||||
* Full endstop support
|
||||
* SD Card support
|
||||
* SD Card folders (works in pronterface)
|
||||
* SD Card autostart support
|
||||
* LCD support (ideally 20x4)
|
||||
* LCD menu system for autonomous SD card printing, controlled by an click-encoder.
|
||||
* EEPROM storage of e.g. max-velocity, max-acceleration, and similar variables
|
||||
* many small but handy things originating from bkubicek's fork.
|
||||
* Arc support
|
||||
* Temperature oversampling
|
||||
* Dynamic Temperature setpointing aka "AutoTemp"
|
||||
* Support for QTMarlin, a very beta GUI for PID-tuning and velocity-acceleration testing. https://github.com/bkubicek/QTMarlin
|
||||
* Endstop trigger reporting to the host software.
|
||||
* Updated sdcardlib
|
||||
* Heater power reporting. Useful for PID monitoring.
|
||||
* PID tuning
|
||||
* CoreXY kinematics (www.corexy.com/theory.html)
|
||||
* Configurable serial port to support connection of wireless adaptors.
|
||||
* Automatic operation of extruder/cold-end cooling fans based on nozzle temperature
|
||||
|
||||
The default baudrate is 250000. This baudrate has less jitter and hence errors than the usual 115200 baud, but is less supported by drivers and host-environments.
|
||||
|
||||
|
||||
Differences and additions to the already good Sprinter firmware:
|
||||
================================================================
|
||||
|
||||
*Look-ahead:*
|
||||
|
||||
Marlin has look-ahead. While sprinter has to break and re-accelerate at each corner,
|
||||
lookahead will only decelerate and accelerate to a velocity,
|
||||
so that the change in vectorial velocity magnitude is less than the xy_jerk_velocity.
|
||||
This is only possible, if some future moves are already processed, hence the name.
|
||||
It leads to less over-deposition at corners, especially at flat angles.
|
||||
|
||||
*Arc support:*
|
||||
|
||||
Slic3r can find curves that, although broken into segments, were ment to describe an arc.
|
||||
Marlin is able to print those arcs. The advantage is the firmware can choose the resolution,
|
||||
and can perform the arc with nearly constant velocity, resulting in a nice finish.
|
||||
Also, less serial communication is needed.
|
||||
|
||||
*Temperature Oversampling:*
|
||||
|
||||
To reduce noise and make the PID-differential term more useful, 16 ADC conversion results are averaged.
|
||||
|
||||
*AutoTemp:*
|
||||
|
||||
If your gcode contains a wide spread of extruder velocities, or you realtime change the building speed, the temperature should be changed accordingly.
|
||||
Usually, higher speed requires higher temperature.
|
||||
This can now be performed by the AutoTemp function
|
||||
By calling M109 S<mintemp> T<maxtemp> F<factor> you enter the autotemp mode.
|
||||
|
||||
You can leave it by calling M109 without any F.
|
||||
If active, the maximal extruder stepper rate of all buffered moves will be calculated, and named "maxerate" [steps/sec].
|
||||
The wanted temperature then will be set to t=tempmin+factor*maxerate, while being limited between tempmin and tempmax.
|
||||
If the target temperature is set manually or by gcode to a value less then tempmin, it will be kept without change.
|
||||
Ideally, your gcode can be completely free of temperature controls, apart from a M109 S T F in the start.gcode, and a M109 S0 in the end.gcode.
|
||||
|
||||
*EEPROM:*
|
||||
|
||||
If you know your PID values, the acceleration and max-velocities of your unique machine, you can set them, and finally store them in the EEPROM.
|
||||
After each reboot, it will magically load them from EEPROM, independent what your Configuration.h says.
|
||||
|
||||
*LCD Menu:*
|
||||
|
||||
If your hardware supports it, you can build yourself a LCD-CardReader+Click+encoder combination. It will enable you to realtime tune temperatures,
|
||||
accelerations, velocities, flow rates, select and print files from the SD card, preheat, disable the steppers, and do other fancy stuff.
|
||||
One working hardware is documented here: http://www.thingiverse.com/thing:12663
|
||||
Also, with just a 20x4 or 16x2 display, useful data is shown.
|
||||
|
||||
*SD card folders:*
|
||||
|
||||
If you have an SD card reader attached to your controller, also folders work now. Listing the files in pronterface will show "/path/subpath/file.g".
|
||||
You can write to file in a subfolder by specifying a similar text using small letters in the path.
|
||||
Also, backup copies of various operating systems are hidden, as well as files not ending with ".g".
|
||||
|
||||
*SD card folders:*
|
||||
|
||||
If you place a file auto[0-9].g into the root of the sd card, it will be automatically executed if you boot the printer. The same file will be executed by selecting "Autostart" from the menu.
|
||||
First *0 will be performed, than *1 and so on. That way, you can heat up or even print automatically without user interaction.
|
||||
|
||||
*Endstop trigger reporting:*
|
||||
|
||||
If an endstop is hit while moving towards the endstop, the location at which the firmware thinks that the endstop was triggered is outputed on the serial port.
|
||||
This is useful, because the user gets a warning message.
|
||||
However, also tools like QTMarlin can use this for finding acceptable combinations of velocity+acceleration.
|
||||
|
||||
*Coding paradigm:*
|
||||
|
||||
Not relevant from a user side, but Marlin was split into thematic junks, and has tried to partially enforced private variables.
|
||||
This is intended to make it clearer, what interacts which what, and leads to a higher level of modularization.
|
||||
We think that this is a useful prestep for porting this firmware to e.g. an ARM platform in the future.
|
||||
A lot of RAM (with enabled LCD ~2200 bytes) was saved by storing char []="some message" in Program memory.
|
||||
In the serial communication, a #define based level of abstraction was enforced, so that it is clear that
|
||||
some transfer is information (usually beginning with "echo:"), an error "error:", or just normal protocol,
|
||||
necessary for backwards compatibility.
|
||||
|
||||
*Interrupt based temperature measurements:*
|
||||
|
||||
An interrupt is used to manage ADC conversions, and enforce checking for critical temperatures.
|
||||
This leads to less blocking in the heater management routine.
|
||||
|
||||
|
||||
Non-standard M-Codes, different to an old version of sprinter:
|
||||
==============================================================
|
||||
Movement:
|
||||
|
||||
* G2 - CW ARC
|
||||
* G3 - CCW ARC
|
||||
|
||||
General:
|
||||
|
||||
* M17 - Enable/Power all stepper motors. Compatibility to ReplicatorG.
|
||||
* M18 - Disable all stepper motors; same as M84.Compatibility to ReplicatorG.
|
||||
* M30 - Print time since last M109 or SD card start to serial
|
||||
* M42 - Change pin status via gcode
|
||||
* M80 - Turn on Power Supply
|
||||
* M81 - Turn off Power Supply
|
||||
* M114 - Output current position to serial port
|
||||
* M119 - Output Endstop status to serial port
|
||||
|
||||
Movement variables:
|
||||
|
||||
* M202 - Set max acceleration in units/s^2 for travel moves (M202 X1000 Y1000) Unused in Marlin!!
|
||||
* M203 - Set maximum feedrate that your machine can sustain (M203 X200 Y200 Z300 E10000) in mm/sec
|
||||
* M204 - Set default acceleration: S normal moves T filament only moves (M204 S3000 T7000) im mm/sec^2 also sets minimum segment time in ms (B20000) to prevent buffer underruns and M20 minimum feedrate
|
||||
* M206 - set home offsets. This sets the X,Y,Z coordinates of the endstops (and is added to the {X,Y,Z}_HOME_POS configuration options (and is also added to the coordinates, if any, provided to G82, as with earlier firmware)
|
||||
* M220 - set build speed mulitplying S:factor in percent ; aka "realtime tuneing in the gcode". So you can slow down if you have islands in one height-range, and speed up otherwise.
|
||||
* M221 - set the extrude multiplying S:factor in percent
|
||||
* M400 - Finish all buffered moves.
|
||||
|
||||
Temperature variables:
|
||||
* M301 - Set PID parameters P I and D
|
||||
* M302 - Allow cold extrudes
|
||||
* M303 - PID relay autotune S<temperature> sets the target temperature. (default target temperature = 150C)
|
||||
|
||||
Advance:
|
||||
|
||||
* M200 - Set filament diameter for advance
|
||||
* M205 - advanced settings: minimum travel speed S=while printing T=travel only, B=minimum segment time X= maximum xy jerk, Z=maximum Z jerk
|
||||
|
||||
EEPROM:
|
||||
|
||||
* M500 - stores paramters in EEPROM. This parameters are stored: axis_steps_per_unit, max_feedrate, max_acceleration ,acceleration,retract_acceleration,
|
||||
minimumfeedrate,mintravelfeedrate,minsegmenttime, jerk velocities, PID
|
||||
* 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.
|
||||
* M503 - print the current settings (from memory not from eeprom)
|
||||
|
||||
MISC:
|
||||
|
||||
* M240 - Trigger a camera to take a photograph
|
||||
* M999 - Restart after being stopped by error
|
||||
|
||||
Configuring and compilation:
|
||||
============================
|
||||
|
||||
Install the arduino software IDE/toolset v23 (Some configurations also work with 1.x.x)
|
||||
http://www.arduino.cc/en/Main/Software
|
||||
|
||||
For gen6/gen7 and sanguinololu the Sanguino directory in the Marlin dir needs to be copied to the arduino environment.
|
||||
copy ArduinoAddons\Arduino_x.x.x\sanguino <arduino home>\hardware\Sanguino
|
||||
|
||||
Install Ultimaker's RepG 25 build
|
||||
http://software.ultimaker.com
|
||||
For SD handling and as better substitute (apart from stl manipulation) download
|
||||
the very nice Kliment's printrun/pronterface https://github.com/kliment/Printrun
|
||||
|
||||
Copy the Ultimaker Marlin firmware
|
||||
https://github.com/ErikZalm/Marlin/tree/Marlin_v1
|
||||
(Use the download button)
|
||||
|
||||
Start the arduino IDE.
|
||||
Select Tools -> Board -> Arduino Mega 2560 or your microcontroller
|
||||
Select the correct serial port in Tools ->Serial Port
|
||||
Open Marlin.pde
|
||||
|
||||
Click the Verify/Compile button
|
||||
|
||||
Click the Upload button
|
||||
If all goes well the firmware is uploading
|
||||
|
||||
Start Ultimaker's Custom RepG 25
|
||||
Make sure Show Experimental Profiles is enabled in Preferences
|
||||
Select Sprinter as the Driver
|
||||
|
||||
Press the Connect button.
|
||||
|
||||
KNOWN ISSUES: RepG will display: Unknown: marlin x.y.z
|
||||
|
||||
That's ok. Enjoy Silky Smooth Printing.
|
||||
|
||||
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user