merge from the branch bkubicek/Marlin/zalmmerge
This commit is contained in:
parent
d7c4f0780b
commit
00674af3a8
20 changed files with 4030 additions and 3832 deletions
|
@ -1,220 +1,243 @@
|
||||||
#ifndef CONFIGURATION_H
|
#ifndef CONFIGURATION_H
|
||||||
#define CONFIGURATION_H
|
#define CONFIGURATION_H
|
||||||
|
|
||||||
//#define DEBUG_STEPS
|
//#define DEBUG_STEPS
|
||||||
|
|
||||||
// BASIC SETTINGS: select your board type, thermistor type, axis scaling, and endstop configuration
|
// BASIC SETTINGS: select your board type, thermistor type, axis scaling, and endstop configuration
|
||||||
|
|
||||||
//// The following define selects which electronics board you have. Please choose the one that matches your setup
|
//// The following define selects which electronics board you have. Please choose the one that matches your setup
|
||||||
// MEGA/RAMPS up to 1.2 = 3,
|
// MEGA/RAMPS up to 1.2 = 3,
|
||||||
// RAMPS 1.3 = 33
|
// RAMPS 1.3 = 33
|
||||||
// Gen6 = 5,
|
// Gen6 = 5,
|
||||||
// Sanguinololu 1.2 and above = 62
|
// Sanguinololu 1.2 and above = 62
|
||||||
// Ultimaker = 7,
|
// Ultimaker = 7,
|
||||||
#define MOTHERBOARD 7
|
#define MOTHERBOARD 7
|
||||||
//#define MOTHERBOARD 5
|
//#define MOTHERBOARD 5
|
||||||
|
|
||||||
|
|
||||||
//// Thermistor settings:
|
//// Thermistor settings:
|
||||||
// 1 is 100k thermistor
|
// 1 is 100k thermistor
|
||||||
// 2 is 200k thermistor
|
// 2 is 200k thermistor
|
||||||
// 3 is mendel-parts thermistor
|
// 3 is mendel-parts thermistor
|
||||||
// 4 is 10k thermistor
|
// 4 is 10k thermistor
|
||||||
// 5 is ParCan supplied 104GT-2 100K
|
// 5 is ParCan supplied 104GT-2 100K
|
||||||
// 6 is EPCOS 100k
|
// 6 is EPCOS 100k
|
||||||
// 7 is 100k Honeywell thermistor 135-104LAG-J01
|
// 7 is 100k Honeywell thermistor 135-104LAG-J01
|
||||||
#define THERMISTORHEATER_1 3
|
#define THERMISTORHEATER_1 3
|
||||||
#define THERMISTORHEATER_2 3
|
#define THERMISTORHEATER_2 3
|
||||||
#define THERMISTORBED 3
|
#define THERMISTORBED 3
|
||||||
|
|
||||||
//#define HEATER_1_USES_THERMISTOR
|
//#define HEATER_1_USES_THERMISTOR
|
||||||
//#define HEATER_2_USES_THERMISTOR
|
//#define HEATER_2_USES_THERMISTOR
|
||||||
#define HEATER_1_USES_AD595
|
#define HEATER_1_USES_AD595
|
||||||
//#define HEATER_2_USES_AD595
|
//#define HEATER_2_USES_AD595
|
||||||
|
|
||||||
// Select one of these only to define how the bed temp is read.
|
// Select one of these only to define how the bed temp is read.
|
||||||
//#define BED_USES_THERMISTOR
|
//#define BED_USES_THERMISTOR
|
||||||
//#define BED_USES_AD595
|
//#define BED_USES_AD595
|
||||||
|
|
||||||
#define HEATER_CHECK_INTERVAL 50
|
#define HEATER_CHECK_INTERVAL 50
|
||||||
#define BED_CHECK_INTERVAL 5000
|
#define BED_CHECK_INTERVAL 5000
|
||||||
|
|
||||||
|
|
||||||
//// Endstop Settings
|
//// Endstop Settings
|
||||||
#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
|
||||||
// The pullups are needed if you directly connect a mechanical endswitch between the signal and ground pins.
|
// The pullups are needed if you directly connect a mechanical endswitch between the signal and ground pins.
|
||||||
const bool ENDSTOPS_INVERTING = true; // set to true to invert the logic of the endstops.
|
const bool ENDSTOPS_INVERTING = true; // set to true to invert the logic of the endstops.
|
||||||
// For optos H21LOB set to true, for Mendel-Parts newer optos TCST2103 set to false
|
// For optos H21LOB set to true, for Mendel-Parts newer optos TCST2103 set to false
|
||||||
|
|
||||||
// This determines the communication speed of the printer
|
// This determines the communication speed of the printer
|
||||||
//#define BAUDRATE 250000
|
//#define BAUDRATE 250000
|
||||||
#define BAUDRATE 115200
|
#define BAUDRATE 115200
|
||||||
//#define BAUDRATE 230400
|
//#define BAUDRATE 230400
|
||||||
|
|
||||||
// Comment out (using // at the start of the line) to disable SD support:
|
// Comment out (using // at the start of the line) to disable SD support:
|
||||||
|
|
||||||
// #define ULTRA_LCD //any lcd
|
// #define ULTRA_LCD //any lcd
|
||||||
#define LCD_WIDTH 16
|
|
||||||
#define LCD_HEIGHT 2
|
|
||||||
|
#define ULTIPANEL
|
||||||
//#define ULTIPANEL
|
#ifdef ULTIPANEL
|
||||||
#ifdef ULTIPANEL
|
//#define NEWPANEL //enable this if you have a click-encoder panel
|
||||||
//#define NEWPANEL //enable this if you have a click-encoder panel
|
#define SDSUPPORT
|
||||||
#define SDSUPPORT
|
#define ULTRA_LCD
|
||||||
#define ULTRA_LCD
|
#define LCD_WIDTH 20
|
||||||
#define LCD_WIDTH 20
|
#define LCD_HEIGHT 4
|
||||||
#define LCD_HEIGHT 4
|
#else //no panel but just lcd
|
||||||
#endif
|
#ifdef ULTRA_LCD
|
||||||
|
#define LCD_WIDTH 16
|
||||||
|
#define LCD_HEIGHT 2
|
||||||
//#define SDSUPPORT // Enable SD Card Support in Hardware Console
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
|
|
||||||
const int dropsegments=5; //everything with this number of steps will be ignored as move
|
//#define SDSUPPORT // Enable SD Card Support in Hardware Console
|
||||||
|
|
||||||
//// ADVANCED SETTINGS - to tweak parameters
|
|
||||||
|
|
||||||
#include "thermistortables.h"
|
const int dropsegments=5; //everything with this number of steps will be ignored as move
|
||||||
|
|
||||||
// For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1
|
//// ADVANCED SETTINGS - to tweak parameters
|
||||||
#define X_ENABLE_ON 0
|
|
||||||
#define Y_ENABLE_ON 0
|
#include "thermistortables.h"
|
||||||
#define Z_ENABLE_ON 0
|
|
||||||
#define E_ENABLE_ON 0
|
// For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1
|
||||||
|
#define X_ENABLE_ON 0
|
||||||
// Disables axis when it's not being used.
|
#define Y_ENABLE_ON 0
|
||||||
#define DISABLE_X false
|
#define Z_ENABLE_ON 0
|
||||||
#define DISABLE_Y false
|
#define E_ENABLE_ON 0
|
||||||
#define DISABLE_Z false
|
|
||||||
#define DISABLE_E false
|
// Disables axis when it's not being used.
|
||||||
|
#define DISABLE_X false
|
||||||
// Inverting axis direction
|
#define DISABLE_Y false
|
||||||
#define INVERT_X_DIR true // for Mendel set to false, for Orca set to true
|
#define DISABLE_Z false
|
||||||
#define INVERT_Y_DIR false // for Mendel set to true, for Orca set to false
|
#define DISABLE_E false
|
||||||
#define INVERT_Z_DIR true // for Mendel set to false, for Orca set to true
|
|
||||||
#define INVERT_E_DIR false // for direct drive extruder v9 set to true, for geared extruder set to false
|
// Inverting axis direction
|
||||||
|
#define INVERT_X_DIR true // for Mendel set to false, for Orca set to true
|
||||||
//// ENDSTOP SETTINGS:
|
#define INVERT_Y_DIR false // for Mendel set to true, for Orca set to false
|
||||||
// Sets direction of endstops when homing; 1=MAX, -1=MIN
|
#define INVERT_Z_DIR true // for Mendel set to false, for Orca set to true
|
||||||
#define X_HOME_DIR -1
|
#define INVERT_E_DIR false // for direct drive extruder v9 set to true, for geared extruder set to false
|
||||||
#define Y_HOME_DIR -1
|
|
||||||
#define Z_HOME_DIR -1
|
//// ENDSTOP SETTINGS:
|
||||||
|
// Sets direction of endstops when homing; 1=MAX, -1=MIN
|
||||||
#define min_software_endstops false //If true, axis won't move to coordinates less than zero.
|
#define X_HOME_DIR -1
|
||||||
#define max_software_endstops false //If true, axis won't move to coordinates greater than the defined lengths below.
|
#define Y_HOME_DIR -1
|
||||||
#define X_MAX_LENGTH 210
|
#define Z_HOME_DIR -1
|
||||||
#define Y_MAX_LENGTH 210
|
|
||||||
#define Z_MAX_LENGTH 210
|
#define min_software_endstops false //If true, axis won't move to coordinates less than zero.
|
||||||
|
#define max_software_endstops false //If true, axis won't move to coordinates greater than the defined lengths below.
|
||||||
//// MOVEMENT SETTINGS
|
#define X_MAX_LENGTH 210
|
||||||
#define NUM_AXIS 4 // The axis order in all axis related arrays is X, Y, Z, E
|
#define Y_MAX_LENGTH 210
|
||||||
//note: on bernhards ultimaker 200 200 12 are working well.
|
#define Z_MAX_LENGTH 210
|
||||||
#define HOMING_FEEDRATE {50*60, 50*60, 12*60, 0} // set the homing speeds
|
|
||||||
//the followint checks if an extrusion is existent in the move. if _not_, the speed of the move is set to the maximum speed.
|
//// MOVEMENT SETTINGS
|
||||||
//!!!!!!Use only if you know that your printer works at the maximum declared speeds.
|
#define NUM_AXIS 4 // The axis order in all axis related arrays is X, Y, Z, E
|
||||||
// works around the skeinforge cool-bug. There all moves are slowed to have a minimum layer time. However slow travel moves= ooze
|
//note: on bernhards ultimaker 200 200 12 are working well.
|
||||||
#define TRAVELING_AT_MAXSPEED
|
#define HOMING_FEEDRATE {50*60, 50*60, 12*60, 0} // set the homing speeds
|
||||||
#define AXIS_RELATIVE_MODES {false, false, false, false}
|
//the followint checks if an extrusion is existent in the move. if _not_, the speed of the move is set to the maximum speed.
|
||||||
|
//!!!!!!Use only if you know that your printer works at the maximum declared speeds.
|
||||||
#define MAX_STEP_FREQUENCY 40000 // Max step frequency for Ultimaker (5000 pps / half step)
|
// works around the skeinforge cool-bug. There all moves are slowed to have a minimum layer time. However slow travel moves= ooze
|
||||||
|
#define TRAVELING_AT_MAXSPEED
|
||||||
// default settings
|
#define AXIS_RELATIVE_MODES {false, false, false, false}
|
||||||
|
|
||||||
#define DEFAULT_AXIS_STEPS_PER_UNIT {79.87220447,79.87220447,200*8/3,14} // default steps per unit for ultimaker
|
#define MAX_STEP_FREQUENCY 40000 // Max step frequency for Ultimaker (5000 pps / half step)
|
||||||
#define DEFAULT_MAX_FEEDRATE {160*60, 160*60, 10*60, 500000}
|
|
||||||
#define DEFAULT_MAX_ACCELERATION {9000,9000,150,10000} // X, Y, Z, E maximum start speed for accelerated moves. E default values are good for skeinforge 40+, for older versions raise them a lot.
|
// default settings
|
||||||
|
|
||||||
#define DEFAULT_ACCELERATION 3000 // X, Y, Z and E max acceleration in mm/s^2 for printing moves
|
#define DEFAULT_AXIS_STEPS_PER_UNIT {79.87220447,79.87220447,200*8/3,14} // default steps per unit for ultimaker
|
||||||
#define DEFAULT_RETRACT_ACCELERATION 7000 // X, Y, Z and E max acceleration in mm/s^2 for r retracts
|
#define DEFAULT_MAX_FEEDRATE {160*60, 160*60, 10*60, 500000}
|
||||||
|
#define DEFAULT_MAX_ACCELERATION {9000,9000,150,10000} // X, Y, Z, E maximum start speed for accelerated moves. E default values are good for skeinforge 40+, for older versions raise them a lot.
|
||||||
#define DEFAULT_MINIMUMFEEDRATE 10 // minimum feedrate
|
|
||||||
#define DEFAULT_MINTRAVELFEEDRATE 10
|
#define DEFAULT_ACCELERATION 3000 // X, Y, Z and E max acceleration in mm/s^2 for printing moves
|
||||||
|
#define DEFAULT_RETRACT_ACCELERATION 7000 // X, Y, Z and E max acceleration in mm/s^2 for r retracts
|
||||||
// minimum time in microseconds that a movement needs to take if the buffer is emptied. Increase this number if you see blobs while printing high speed & high detail. It will slowdown on the detailed stuff.
|
|
||||||
#define DEFAULT_MINSEGMENTTIME 20000
|
#define DEFAULT_MINIMUMFEEDRATE 10 // minimum feedrate
|
||||||
#define DEFAULT_XYJERK 30.0*60
|
#define DEFAULT_MINTRAVELFEEDRATE 10
|
||||||
#define DEFAULT_ZJERK 10.0*60
|
|
||||||
|
// minimum time in microseconds that a movement needs to take if the buffer is emptied. Increase this number if you see blobs while printing high speed & high detail. It will slowdown on the detailed stuff.
|
||||||
|
#define DEFAULT_MINSEGMENTTIME 20000
|
||||||
// The watchdog waits for the watchperiod in milliseconds whenever an M104 or M109 increases the target temperature
|
#define DEFAULT_XYJERK 30.0*60
|
||||||
//this enables the watchdog interrupt.
|
#define DEFAULT_ZJERK 10.0*60
|
||||||
#define USE_WATCHDOG
|
|
||||||
//you cannot reboot on a mega2560 due to a bug in he bootloader. Hence, you have to reset manually, and this is done hereby:
|
|
||||||
#define RESET_MANUAL
|
// The watchdog waits for the watchperiod in milliseconds whenever an M104 or M109 increases the target temperature
|
||||||
|
//this enables the watchdog interrupt.
|
||||||
#define WATCHDOG_TIMEOUT 4
|
#define USE_WATCHDOG
|
||||||
|
//you cannot reboot on a mega2560 due to a bug in he bootloader. Hence, you have to reset manually, and this is done hereby:
|
||||||
|
#define RESET_MANUAL
|
||||||
|
|
||||||
//// Experimental watchdog and minimal temp
|
#define WATCHDOG_TIMEOUT 4
|
||||||
// The watchdog waits for the watchperiod in milliseconds whenever an M104 or M109 increases the target temperature
|
|
||||||
// If the temperature has not increased at the end of that period, the target temperature is set to zero. It can be reset with another M104/M109
|
|
||||||
//#define WATCHPERIOD 5000 //5 seconds
|
|
||||||
|
//// Experimental watchdog and minimal temp
|
||||||
// Actual temperature must be close to target for this long before M109 returns success
|
// The watchdog waits for the watchperiod in milliseconds whenever an M104 or M109 increases the target temperature
|
||||||
//#define TEMP_RESIDENCY_TIME 20 // (seconds)
|
// If the temperature has not increased at the end of that period, the target temperature is set to zero. It can be reset with another M104/M109
|
||||||
//#define TEMP_HYSTERESIS 5 // (C°) range of +/- temperatures considered "close" to the target one
|
//#define WATCHPERIOD 5000 //5 seconds
|
||||||
|
|
||||||
//// The minimal temperature defines the temperature below which the heater will not be enabled
|
// Actual temperature must be close to target for this long before M109 returns success
|
||||||
#define MINTEMP 5
|
//#define TEMP_RESIDENCY_TIME 20 // (seconds)
|
||||||
#define BED_MINTEMP 5
|
//#define TEMP_HYSTERESIS 5 // (C°) range of +/- temperatures considered "close" to the target one
|
||||||
|
|
||||||
|
//// The minimal temperature defines the temperature below which the heater will not be enabled
|
||||||
// When temperature exceeds max temp, your heater will be switched off.
|
#define MINTEMP 5
|
||||||
// This feature exists to protect your hotend from overheating accidentally, but *NOT* from thermistor short/failure!
|
#define BED_MINTEMP 5
|
||||||
// You should use MINTEMP for thermistor short/failure protection.
|
|
||||||
#define MAXTEMP 275
|
|
||||||
#define BED_MAXTEMP 150
|
// When temperature exceeds max temp, your heater will be switched off.
|
||||||
|
// This feature exists to protect your hotend from overheating accidentally, but *NOT* from thermistor short/failure!
|
||||||
/// PID settings:
|
// You should use MINTEMP for thermistor short/failure protection.
|
||||||
// Uncomment the following line to enable PID support.
|
#define MAXTEMP 275
|
||||||
//#define SMOOTHING
|
#define BED_MAXTEMP 150
|
||||||
//#define SMOOTHFACTOR 5.0
|
|
||||||
//float current_raw_average=0;
|
|
||||||
|
|
||||||
#define PIDTEMP
|
|
||||||
#ifdef PIDTEMP
|
|
||||||
//#define PID_DEBUG // Sends debug data to the serial port.
|
|
||||||
//#define PID_OPENLOOP 1 // Puts PID in open loop. M104 sets the output power in %
|
|
||||||
#define PID_MAX 255 // limits current to nozzle
|
#define PIDTEMP
|
||||||
#define PID_INTEGRAL_DRIVE_MAX 255
|
#ifdef PIDTEMP
|
||||||
#define PID_dT 0.10 // 100ms sample time
|
/// PID settings:
|
||||||
#define DEFAULT_Kp 20.0
|
// Uncomment the following line to enable PID support.
|
||||||
#define DEFAULT_Ki 1.5*PID_dT
|
//#define SMOOTHING
|
||||||
#define DEFAULT_Kd 80/PID_dT
|
//#define SMOOTHFACTOR 5.0
|
||||||
#define DEFAULT_Kc 0
|
//float current_raw_average=0;
|
||||||
#endif // PIDTEMP
|
#define K1 0.95 //smoothing of the PID
|
||||||
|
//#define PID_DEBUG // Sends debug data to the serial port.
|
||||||
|
//#define PID_OPENLOOP 1 // Puts PID in open loop. M104 sets the output power in %
|
||||||
// extruder advance constant (s2/mm3)
|
#define PID_MAX 255 // limits current to nozzle
|
||||||
//
|
#define PID_INTEGRAL_DRIVE_MAX 255
|
||||||
// advance (steps) = STEPS_PER_CUBIC_MM_E * EXTUDER_ADVANCE_K * cubic mm per second ^ 2
|
#define PID_dT 0.1
|
||||||
//
|
//machine with red silicon: 1950:45 second ; with fan fully blowin 3000:47
|
||||||
// hooke's law says: force = k * distance
|
|
||||||
// bernoulli's priniciple says: v ^ 2 / 2 + g . h + pressure / density = constant
|
#define PID_CRITIAL_GAIN 3000
|
||||||
// so: v ^ 2 is proportional to number of steps we advance the extruder
|
#define PID_SWING_AT_CRITIAL 45 //seconds
|
||||||
//#define ADVANCE
|
#define PIDIADD 5
|
||||||
|
/*
|
||||||
#ifdef ADVANCE
|
//PID according to Ziegler-Nichols method
|
||||||
#define EXTRUDER_ADVANCE_K .3
|
float Kp = 0.6*PID_CRITIAL_GAIN;
|
||||||
|
float Ki =PIDIADD+2*Kp/PID_SWING_AT_CRITIAL*PID_dT;
|
||||||
#define D_FILAMENT 1.7
|
float Kd = Kp*PID_SWING_AT_CRITIAL/8./PID_dT;
|
||||||
#define STEPS_MM_E 65
|
*/
|
||||||
#define EXTRUTION_AREA (0.25 * D_FILAMENT * D_FILAMENT * 3.14159)
|
//PI according to Ziegler-Nichols method
|
||||||
#define STEPS_PER_CUBIC_MM_E (axis_steps_per_unit[E_AXIS]/ EXTRUTION_AREA)
|
#define DEFAULT_Kp (PID_CRITIAL_GAIN/2.2)
|
||||||
|
#define DEFAULT_Ki (1.2*Kp/PID_SWING_AT_CRITIAL*PID_dT)
|
||||||
#endif // ADVANCE
|
#define DEFAULT_Kd (0)
|
||||||
|
|
||||||
#if defined SDSUPPORT
|
#define PID_ADD_EXTRUSION_RATE
|
||||||
// The number of linear motions that can be in the plan at any give time.
|
#ifdef PID_ADD_EXTRUSION_RATE
|
||||||
#define BLOCK_BUFFER_SIZE 16 // SD,LCD,Buttons take more memory, block buffer needs to be smaller
|
#define DEFAULT_Kc (5) //heatingpower=Kc*(e_speed)
|
||||||
#else
|
#endif
|
||||||
#define BLOCK_BUFFER_SIZE 16 // maximize block buffer
|
#endif // PIDTEMP
|
||||||
#endif
|
|
||||||
|
// extruder advance constant (s2/mm3)
|
||||||
#ifdef SIMPLE_LCD
|
//
|
||||||
#define BLOCK_BUFFER_SIZE 16 // A little less buffer for just a simple LCD
|
// advance (steps) = STEPS_PER_CUBIC_MM_E * EXTUDER_ADVANCE_K * cubic mm per second ^ 2
|
||||||
#endif
|
//
|
||||||
|
// hooke's law says: force = k * distance
|
||||||
#endif
|
// bernoulli's priniciple says: v ^ 2 / 2 + g . h + pressure / density = constant
|
||||||
|
// so: v ^ 2 is proportional to number of steps we advance the extruder
|
||||||
|
//#define ADVANCE
|
||||||
|
|
||||||
|
#ifdef ADVANCE
|
||||||
|
#define EXTRUDER_ADVANCE_K .3
|
||||||
|
|
||||||
|
#define D_FILAMENT 1.7
|
||||||
|
#define STEPS_MM_E 65
|
||||||
|
#define EXTRUTION_AREA (0.25 * D_FILAMENT * D_FILAMENT * 3.14159)
|
||||||
|
#define STEPS_PER_CUBIC_MM_E (axis_steps_per_unit[E_AXIS]/ EXTRUTION_AREA)
|
||||||
|
|
||||||
|
#endif // ADVANCE
|
||||||
|
|
||||||
|
// THE BLOCK_BUFFER_SIZE NEEDS TO BE A POWER OF 2, e.g. 8,16,32
|
||||||
|
#if defined SDSUPPORT
|
||||||
|
// The number of linear motions that can be in the plan at any give time.
|
||||||
|
#define BLOCK_BUFFER_SIZE 16 // SD,LCD,Buttons take more memory, block buffer needs to be smaller
|
||||||
|
#else
|
||||||
|
#define BLOCK_BUFFER_SIZE 16 // maximize block buffer
|
||||||
|
#endif
|
||||||
|
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
|
@ -1,123 +1,129 @@
|
||||||
|
#ifndef __EEPROMH
|
||||||
#include "planner.h"
|
#define __EEPROMH
|
||||||
#include "temperature.h"
|
#include "planner.h"
|
||||||
|
#include "temperature.h"
|
||||||
//======================================================================================
|
#include <EEPROM.h>
|
||||||
template <class T> int EEPROM_writeAnything(int &ee, const T& value)
|
#include "Marlin.h"
|
||||||
{
|
#include "streaming.h"
|
||||||
const byte* p = (const byte*)(const void*)&value;
|
|
||||||
int i;
|
//======================================================================================
|
||||||
for (i = 0; i < sizeof(value); i++)
|
template <class T> int EEPROM_writeAnything(int &ee, const T& value)
|
||||||
EEPROM.write(ee++, *p++);
|
{
|
||||||
return i;
|
const byte* p = (const byte*)(const void*)&value;
|
||||||
}
|
int i;
|
||||||
//======================================================================================
|
for (i = 0; i < (int)sizeof(value); i++)
|
||||||
template <class T> int EEPROM_readAnything(int &ee, T& value)
|
EEPROM.write(ee++, *p++);
|
||||||
{
|
return i;
|
||||||
byte* p = (byte*)(void*)&value;
|
}
|
||||||
int i;
|
//======================================================================================
|
||||||
for (i = 0; i < sizeof(value); i++)
|
template <class T> int EEPROM_readAnything(int &ee, T& value)
|
||||||
*p++ = EEPROM.read(ee++);
|
{
|
||||||
return i;
|
byte* p = (byte*)(void*)&value;
|
||||||
}
|
int i;
|
||||||
//======================================================================================
|
for (i = 0; i < (int)sizeof(value); i++)
|
||||||
|
*p++ = EEPROM.read(ee++);
|
||||||
#define EEPROM_OFFSET 100
|
return i;
|
||||||
|
}
|
||||||
#define EEPROM_VERSION "V04" // IMPORTANT: Whenever there are changes made to the variables stored in EEPROM
|
//======================================================================================
|
||||||
// in the functions below, also increment the version number. This makes sure that
|
|
||||||
// the default values are used whenever there is a change to the data, to prevent
|
#define EEPROM_OFFSET 100
|
||||||
// wrong data being written to the variables.
|
|
||||||
// ALSO: always make sure the variables in the Store and retrieve sections are in the same order.
|
#define EEPROM_VERSION "V04" // IMPORTANT: Whenever there are changes made to the variables stored in EEPROM
|
||||||
void StoreSettings() {
|
// in the functions below, also increment the version number. This makes sure that
|
||||||
char ver[4]= "000";
|
// the default values are used whenever there is a change to the data, to prevent
|
||||||
int i=EEPROM_OFFSET;
|
// wrong data being written to the variables.
|
||||||
EEPROM_writeAnything(i,ver); // invalidate data first
|
// ALSO: always make sure the variables in the Store and retrieve sections are in the same order.
|
||||||
EEPROM_writeAnything(i,axis_steps_per_unit);
|
void StoreSettings() {
|
||||||
EEPROM_writeAnything(i,max_feedrate);
|
char ver[4]= "000";
|
||||||
EEPROM_writeAnything(i,max_acceleration_units_per_sq_second);
|
int i=EEPROM_OFFSET;
|
||||||
EEPROM_writeAnything(i,acceleration);
|
EEPROM_writeAnything(i,ver); // invalidate data first
|
||||||
EEPROM_writeAnything(i,retract_acceleration);
|
EEPROM_writeAnything(i,axis_steps_per_unit);
|
||||||
EEPROM_writeAnything(i,minimumfeedrate);
|
EEPROM_writeAnything(i,max_feedrate);
|
||||||
EEPROM_writeAnything(i,mintravelfeedrate);
|
EEPROM_writeAnything(i,max_acceleration_units_per_sq_second);
|
||||||
EEPROM_writeAnything(i,minsegmenttime);
|
EEPROM_writeAnything(i,acceleration);
|
||||||
EEPROM_writeAnything(i,max_xy_jerk);
|
EEPROM_writeAnything(i,retract_acceleration);
|
||||||
EEPROM_writeAnything(i,max_z_jerk);
|
EEPROM_writeAnything(i,minimumfeedrate);
|
||||||
#ifdef PIDTEMP
|
EEPROM_writeAnything(i,mintravelfeedrate);
|
||||||
EEPROM_writeAnything(i,Kp);
|
EEPROM_writeAnything(i,minsegmenttime);
|
||||||
EEPROM_writeAnything(i,Ki);
|
EEPROM_writeAnything(i,max_xy_jerk);
|
||||||
EEPROM_writeAnything(i,Kd);
|
EEPROM_writeAnything(i,max_z_jerk);
|
||||||
#else
|
#ifdef PIDTEMP
|
||||||
EEPROM_writeAnything(i,3000);
|
EEPROM_writeAnything(i,Kp);
|
||||||
EEPROM_writeAnything(i,0);
|
EEPROM_writeAnything(i,Ki);
|
||||||
EEPROM_writeAnything(i,0);
|
EEPROM_writeAnything(i,Kd);
|
||||||
#endif
|
#else
|
||||||
char ver2[4]=EEPROM_VERSION;
|
EEPROM_writeAnything(i,3000);
|
||||||
i=EEPROM_OFFSET;
|
EEPROM_writeAnything(i,0);
|
||||||
EEPROM_writeAnything(i,ver2); // validate data
|
EEPROM_writeAnything(i,0);
|
||||||
ECHOLN("Settings Stored");
|
#endif
|
||||||
|
char ver2[4]=EEPROM_VERSION;
|
||||||
}
|
i=EEPROM_OFFSET;
|
||||||
|
EEPROM_writeAnything(i,ver2); // validate data
|
||||||
void RetrieveSettings(bool def=false){ // if def=true, the default values will be used
|
ECHOLN("Settings Stored");
|
||||||
int i=EEPROM_OFFSET;
|
|
||||||
char stored_ver[4];
|
}
|
||||||
char ver[4]=EEPROM_VERSION;
|
|
||||||
EEPROM_readAnything(i,stored_ver); //read stored version
|
void RetrieveSettings(bool def=false){ // if def=true, the default values will be used
|
||||||
// ECHOLN("Version: [" << ver << "] Stored version: [" << stored_ver << "]");
|
int i=EEPROM_OFFSET;
|
||||||
if ((!def)&&(strncmp(ver,stored_ver,3)==0)) { // version number match
|
char stored_ver[4];
|
||||||
EEPROM_readAnything(i,axis_steps_per_unit);
|
char ver[4]=EEPROM_VERSION;
|
||||||
EEPROM_readAnything(i,max_feedrate);
|
EEPROM_readAnything(i,stored_ver); //read stored version
|
||||||
EEPROM_readAnything(i,max_acceleration_units_per_sq_second);
|
// ECHOLN("Version: [" << ver << "] Stored version: [" << stored_ver << "]");
|
||||||
EEPROM_readAnything(i,acceleration);
|
if ((!def)&&(strncmp(ver,stored_ver,3)==0)) { // version number match
|
||||||
EEPROM_readAnything(i,retract_acceleration);
|
EEPROM_readAnything(i,axis_steps_per_unit);
|
||||||
EEPROM_readAnything(i,minimumfeedrate);
|
EEPROM_readAnything(i,max_feedrate);
|
||||||
EEPROM_readAnything(i,mintravelfeedrate);
|
EEPROM_readAnything(i,max_acceleration_units_per_sq_second);
|
||||||
EEPROM_readAnything(i,minsegmenttime);
|
EEPROM_readAnything(i,acceleration);
|
||||||
EEPROM_readAnything(i,max_xy_jerk);
|
EEPROM_readAnything(i,retract_acceleration);
|
||||||
EEPROM_readAnything(i,max_z_jerk);
|
EEPROM_readAnything(i,minimumfeedrate);
|
||||||
#ifndef PIDTEMP
|
EEPROM_readAnything(i,mintravelfeedrate);
|
||||||
float Kp,Ki,Kd;
|
EEPROM_readAnything(i,minsegmenttime);
|
||||||
#endif
|
EEPROM_readAnything(i,max_xy_jerk);
|
||||||
EEPROM_readAnything(i,Kp);
|
EEPROM_readAnything(i,max_z_jerk);
|
||||||
EEPROM_readAnything(i,Ki);
|
#ifndef PIDTEMP
|
||||||
EEPROM_readAnything(i,Kd);
|
float Kp,Ki,Kd;
|
||||||
|
#endif
|
||||||
ECHOLN("Stored settings retreived:");
|
EEPROM_readAnything(i,Kp);
|
||||||
}
|
EEPROM_readAnything(i,Ki);
|
||||||
else {
|
EEPROM_readAnything(i,Kd);
|
||||||
float tmp1[]=DEFAULT_AXIS_STEPS_PER_UNIT;
|
|
||||||
float tmp2[]=DEFAULT_MAX_FEEDRATE;
|
ECHOLN("Stored settings retreived:");
|
||||||
long tmp3[]=DEFAULT_MAX_ACCELERATION;
|
}
|
||||||
for (int i=0;i<4;i++) {
|
else {
|
||||||
axis_steps_per_unit[i]=tmp1[i];
|
float tmp1[]=DEFAULT_AXIS_STEPS_PER_UNIT;
|
||||||
max_feedrate[i]=tmp2[i];
|
float tmp2[]=DEFAULT_MAX_FEEDRATE;
|
||||||
max_acceleration_units_per_sq_second[i]=tmp3[i];
|
long tmp3[]=DEFAULT_MAX_ACCELERATION;
|
||||||
}
|
for (int i=0;i<4;i++) {
|
||||||
acceleration=DEFAULT_ACCELERATION;
|
axis_steps_per_unit[i]=tmp1[i];
|
||||||
retract_acceleration=DEFAULT_RETRACT_ACCELERATION;
|
max_feedrate[i]=tmp2[i];
|
||||||
minimumfeedrate=DEFAULT_MINIMUMFEEDRATE;
|
max_acceleration_units_per_sq_second[i]=tmp3[i];
|
||||||
minsegmenttime=DEFAULT_MINSEGMENTTIME;
|
}
|
||||||
mintravelfeedrate=DEFAULT_MINTRAVELFEEDRATE;
|
acceleration=DEFAULT_ACCELERATION;
|
||||||
max_xy_jerk=DEFAULT_XYJERK;
|
retract_acceleration=DEFAULT_RETRACT_ACCELERATION;
|
||||||
max_z_jerk=DEFAULT_ZJERK;
|
minimumfeedrate=DEFAULT_MINIMUMFEEDRATE;
|
||||||
ECHOLN("Using Default settings:");
|
minsegmenttime=DEFAULT_MINSEGMENTTIME;
|
||||||
}
|
mintravelfeedrate=DEFAULT_MINTRAVELFEEDRATE;
|
||||||
ECHOLN("Steps per unit:");
|
max_xy_jerk=DEFAULT_XYJERK;
|
||||||
ECHOLN(" M92 X" <<_FLOAT(axis_steps_per_unit[0],3) << " Y" << _FLOAT(axis_steps_per_unit[1],3) << " Z" << _FLOAT(axis_steps_per_unit[2],3) << " E" << _FLOAT(axis_steps_per_unit[3],3));
|
max_z_jerk=DEFAULT_ZJERK;
|
||||||
ECHOLN("Maximum feedrates (mm/s):");
|
ECHOLN("Using Default settings:");
|
||||||
ECHOLN(" M203 X" <<_FLOAT(max_feedrate[0]/60,2)<<" Y" << _FLOAT(max_feedrate[1]/60,2) << " Z" << _FLOAT(max_feedrate[2]/60,2) << " E" << _FLOAT(max_feedrate[3]/60,2));
|
}
|
||||||
ECHOLN("Maximum Acceleration (mm/s2):");
|
ECHOLN("Steps per unit:");
|
||||||
ECHOLN(" M201 X" <<_FLOAT(max_acceleration_units_per_sq_second[0],0) << " Y" << _FLOAT(max_acceleration_units_per_sq_second[1],0) << " Z" << _FLOAT(max_acceleration_units_per_sq_second[2],0) << " E" << _FLOAT(max_acceleration_units_per_sq_second[3],0));
|
ECHOLN(" M92 X" <<_FLOAT(axis_steps_per_unit[0],3) << " Y" << _FLOAT(axis_steps_per_unit[1],3) << " Z" << _FLOAT(axis_steps_per_unit[2],3) << " E" << _FLOAT(axis_steps_per_unit[3],3));
|
||||||
ECHOLN("Acceleration: S=acceleration, T=retract acceleration");
|
ECHOLN("Maximum feedrates (mm/s):");
|
||||||
ECHOLN(" M204 S" <<_FLOAT(acceleration,2) << " T" << _FLOAT(retract_acceleration,2));
|
ECHOLN(" M203 X" <<_FLOAT(max_feedrate[0]/60,2)<<" Y" << _FLOAT(max_feedrate[1]/60,2) << " Z" << _FLOAT(max_feedrate[2]/60,2) << " E" << _FLOAT(max_feedrate[3]/60,2));
|
||||||
ECHOLN("Advanced variables: S=Min feedrate (mm/s), T=Min travel feedrate (mm/s), B=minimum segment time (ms), X=maximum xY jerk (mm/s), Z=maximum Z jerk (mm/s)");
|
ECHOLN("Maximum Acceleration (mm/s2):");
|
||||||
ECHOLN(" M205 S" <<_FLOAT(minimumfeedrate/60,2) << " T" << _FLOAT(mintravelfeedrate/60,2) << " B" << _FLOAT(minsegmenttime,2) << " X" << _FLOAT(max_xy_jerk/60,2) << " Z" << _FLOAT(max_z_jerk/60,2));
|
ECHOLN(" M201 X" <<_FLOAT(max_acceleration_units_per_sq_second[0],0) << " Y" << _FLOAT(max_acceleration_units_per_sq_second[1],0) << " Z" << _FLOAT(max_acceleration_units_per_sq_second[2],0) << " E" << _FLOAT(max_acceleration_units_per_sq_second[3],0));
|
||||||
#ifdef PIDTEMP
|
ECHOLN("Acceleration: S=acceleration, T=retract acceleration");
|
||||||
ECHOLN("PID settings:");
|
ECHOLN(" M204 S" <<_FLOAT(acceleration,2) << " T" << _FLOAT(retract_acceleration,2));
|
||||||
ECHOLN(" M301 P" << _FLOAT(Kp,3) << " I" << _FLOAT(Ki,3) << " D" << _FLOAT(Kd,3));
|
ECHOLN("Advanced variables: S=Min feedrate (mm/s), T=Min travel feedrate (mm/s), B=minimum segment time (ms), X=maximum xY jerk (mm/s), Z=maximum Z jerk (mm/s)");
|
||||||
#endif
|
ECHOLN(" M205 S" <<_FLOAT(minimumfeedrate/60,2) << " T" << _FLOAT(mintravelfeedrate/60,2) << " B" << _FLOAT(minsegmenttime,2) << " X" << _FLOAT(max_xy_jerk/60,2) << " Z" << _FLOAT(max_z_jerk/60,2));
|
||||||
|
#ifdef PIDTEMP
|
||||||
}
|
ECHOLN("PID settings:");
|
||||||
|
ECHOLN(" M301 P" << _FLOAT(Kp,3) << " I" << _FLOAT(Ki,3) << " D" << _FLOAT(Kd,3));
|
||||||
|
#endif
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
||||||
|
|
508
Marlin/Makefile
508
Marlin/Makefile
|
@ -1,274 +1,320 @@
|
||||||
|
TARGET = $(notdir $(CURDIR))
|
||||||
|
# CHANGE BELOW:
|
||||||
|
#~ INSTALL_DIR = /Applications/Arduino.app/Contents/Resources/Java
|
||||||
|
INSTALL_DIR = /home/bkubicek/software/arduino-0022
|
||||||
|
#~ PORT = /dev/cu.usbserial*
|
||||||
|
PORT = /dev/ttyACM0
|
||||||
|
|
||||||
|
# Get these values from:
|
||||||
|
# $(INSTALL_DIR)/hardware/boards.txt
|
||||||
|
# (arduino-0022/hardware/arduino/boards.txt)
|
||||||
|
# The values below are for the "Arduino Duemilanove or Nano w/ ATmega328"
|
||||||
|
# now for "Arduino Mega 2560"
|
||||||
|
UPLOAD_SPEED = 115200
|
||||||
|
UPLOAD_PROTOCOL = stk500v2
|
||||||
|
BUILD_MCU = atmega2560
|
||||||
|
BUILD_F_CPU = 16000000L
|
||||||
|
|
||||||
|
# getting undefined reference to `__cxa_pure_virtual'
|
||||||
|
#~ [http://www.arduino.cc/cgi-bin/yabb2/YaBB.pl?num=1254180518 Arduino Forum - Makefile]
|
||||||
|
#~ http://www.arduino.cc/playground/OpenBSD/CLI
|
||||||
|
#~ [http://arduino.cc/forum/index.php?topic=52041.0 A "simple" makefile for Arduino]
|
||||||
|
#~ [http://www.arduino.cc/cgi-bin/yabb2/YaBB.pl?num=1275488191 Arduino Forum - Configuring avr-gcc options in arduino IDE]
|
||||||
|
# found in /usr/lib/gcc/avr/4.3.5/cc1plus; fixed with -Wl,--gc-section
|
||||||
|
|
||||||
|
############################################################################
|
||||||
|
# Below here nothing should be changed...
|
||||||
|
|
||||||
|
ARDUINO = $(INSTALL_DIR)/hardware/arduino/cores/arduino
|
||||||
#
|
#
|
||||||
# Arduino 0022 Makefile
|
#~ AVR_TOOLS_PATH = $(INSTALL_DIR)/hardware/tools/avr/bin
|
||||||
# Uno with DOGS102 Shield
|
# in Ubuntu, avr-gcc is installed separate;
|
||||||
#
|
# only avrdude comes with the IDE
|
||||||
# written by olikraus@gmail.com
|
AVR_TOOLS_PATH = /usr/bin
|
||||||
#
|
AVR_DUDE_PATH = $(INSTALL_DIR)/hardware/tools
|
||||||
# Features:
|
|
||||||
# - boards.txt is used to derive parameters
|
|
||||||
# - All intermediate files are put into a separate directory (TMPDIRNAME)
|
|
||||||
# - Simple use: Copy Makefile into the same directory of the .pde file
|
|
||||||
#
|
|
||||||
# Limitations:
|
|
||||||
# - requires UNIX environment
|
|
||||||
# - TMPDIRNAME must be subdirectory of the current directory.
|
|
||||||
#
|
|
||||||
# Targets
|
|
||||||
# all build everything
|
|
||||||
# upload build and upload to arduino
|
|
||||||
# clean remove all temporary files (includes final hex file)
|
|
||||||
#
|
|
||||||
# History
|
|
||||||
# 001 28 Apr 2010 first release
|
|
||||||
# 002 05 Oct 2010 added 'uno'
|
|
||||||
#
|
#
|
||||||
|
SRC = $(ARDUINO)/pins_arduino.c $(ARDUINO)/wiring.c \
|
||||||
|
$(ARDUINO)/wiring_analog.c $(ARDUINO)/wiring_digital.c \
|
||||||
|
$(ARDUINO)/wiring_pulse.c \
|
||||||
|
$(ARDUINO)/wiring_shift.c $(ARDUINO)/WInterrupts.c
|
||||||
|
# added applet/$(TARGET).cpp as in IDE 0022
|
||||||
|
CXXSRC = $(ARDUINO)/HardwareSerial.cpp $(ARDUINO)/WMath.cpp \
|
||||||
|
$(ARDUINO)/Print.cpp \
|
||||||
|
$(ARDUINO)/main.cpp
|
||||||
|
# applet/$(TARGET).cpp # no need, having a rule now for applet/$(TARGET).cpp.o
|
||||||
|
# added main.cpp, as in 0022
|
||||||
|
FORMAT = ihex
|
||||||
|
|
||||||
#=== user configuration ===
|
# Name of this Makefile (used for "make depend").
|
||||||
# All ...PATH variables must have a '/' at the end
|
MAKEFILE = Makefile
|
||||||
|
|
||||||
# Board (and prozessor) information: see $(ARDUINO_PATH)hardware/arduino/boards.txt
|
# Debugging format.
|
||||||
# Some examples:
|
# Native formats for AVR-GCC's -g are stabs [default], or dwarf-2.
|
||||||
# BOARD DESCRIPTION
|
# AVR (extended) COFF requires stabs, plus an avr-objcopy run.
|
||||||
# uno Arduino Uno
|
DEBUG = stabs
|
||||||
# atmega328 Arduino Duemilanove or Nano w/ ATmega328
|
|
||||||
# diecimila Arduino Diecimila, Duemilanove, or Nano w/ ATmega168
|
|
||||||
# mega Arduino Mega
|
|
||||||
# mini Arduino Mini
|
|
||||||
# lilypad328 LilyPad Arduino w/ ATmega328
|
|
||||||
BOARD:=mega
|
|
||||||
|
|
||||||
# additional (comma separated) defines
|
OPT = 2
|
||||||
# -DDOGM128_HW board is connected to DOGM128 display
|
|
||||||
# -DDOGM132_HW board is connected to DOGM132 display
|
|
||||||
# -DDOGS102_HW board is connected to DOGS102 display
|
|
||||||
# -DDOG_REVERSE 180 degree rotation
|
|
||||||
# -DDOG_SPI_SW_ARDUINO force SW shiftOut
|
|
||||||
DEFS=-DDOGS102_HW -DDOG_DOUBLE_MEMORY -DDOG_SPI_SW_ARDUINO
|
|
||||||
|
|
||||||
# The location where the avr tools (e.g. avr-gcc) are located. Requires a '/' at the end.
|
# Place -D or -U options here
|
||||||
# Can be empty if all tools are accessable through the search path
|
#~ CDEFS = -DBUILD_F_CPU=$(BUILD_F_CPU)
|
||||||
AVR_TOOLS_PATH:=/usr/bin/
|
#~ CXXDEFS = -DBUILD_F_CPU=$(BUILD_F_CPU)
|
||||||
|
# now called DF_CPU
|
||||||
|
CDEFS = -DF_CPU=$(BUILD_F_CPU) -DARDUINO=22
|
||||||
|
CXXDEFS = -DF_CPU=$(BUILD_F_CPU) -DARDUINO=22
|
||||||
|
|
||||||
# Install path of the arduino software. Requires a '/' at the end.
|
# Place -I options here
|
||||||
ARDUINO_PATH:=/home/bkubicek/software/arduino-0022/
|
CINCS = -I$(ARDUINO) -I$(INSTALL_DIR)/libraries/LiquidCrystal/ -I$(INSTALL_DIR)/libraries/EEPROM/
|
||||||
|
CXXINCS = -I$(ARDUINO)
|
||||||
|
|
||||||
# Install path for avrdude. Requires a '/' at the end. Can be empty if avrdude is in the search path.
|
# Compiler flag to set the C Standard level.
|
||||||
AVRDUDE_PATH:=
|
# c89 - "ANSI" C
|
||||||
|
# gnu89 - c89 plus GCC extensions
|
||||||
|
# c99 - ISO C99 standard (not yet fully implemented)
|
||||||
|
# gnu99 - c99 plus GCC extensions
|
||||||
|
CSTANDARD = -std=gnu99
|
||||||
|
CDEBUG = -g$(DEBUG)
|
||||||
|
# note that typically, IDE 0022 uses -w to suppress warnings (both in cpp and c)!
|
||||||
|
CWARN = -Wall
|
||||||
|
#~ CWARN = -w
|
||||||
|
# "-Wstrict-prototypes" is valid for Ada/C/ObjC but not for C++:
|
||||||
|
CCWARN = -Wstrict-prototypes
|
||||||
|
CTUNING = -funsigned-char -funsigned-bitfields -fpack-struct -fshort-enums
|
||||||
|
#CEXTRA = -Wa,-adhlns=$(<:.c=.lst)
|
||||||
|
|
||||||
# The unix device where we can reach the arduino board
|
# to eliminate pins_ardiuno warnings:
|
||||||
# Uno: /dev/ttyACM0
|
# http://arduino.cc/pipermail/developers_arduino.cc/2010-December/004005.html
|
||||||
# Duemilanove: /dev/ttyUSB0
|
|
||||||
AVRDUDE_PORT:=/dev/ttyACM0
|
|
||||||
|
|
||||||
# List of all libaries which should be included.
|
# [http://www.arduino.cc/cgi-bin/yabb2/YaBB.pl?num=1254180518 Arduino Forum - Makefile]
|
||||||
#EXTRA_DIRS=$(ARDUINO_PATH)libraries/LiquidCrystal/
|
#~ For building the objects files "-ffunction-sections -fdata-sections" was missing
|
||||||
#EXTRA_DIRS+=$(ARDUINO_PATH)libraries/Dogm/
|
#~ and the final avr-gcc call needs "-Wl,--gc-section".
|
||||||
#EXTRA_DIRS+=/home/kraus/src/arduino/dogm128/hg/libraries/Dogm/
|
CXSECTF = -fno-exceptions -ffunction-sections -fdata-sections
|
||||||
|
CFINALF = -Wl,--gc-section
|
||||||
|
|
||||||
#=== fetch parameter from boards.txt processor parameter ===
|
CFLAGS = $(CDEBUG) $(CDEFS) $(CINCS) -O$(OPT) $(CWARN) $(CCWARN) $(CSTANDARD) $(CEXTRA)
|
||||||
# the basic idea is to get most of the information from boards.txt
|
# added CWARN also to .cpp
|
||||||
|
CXXFLAGS = $(CDEFS) $(CINCS) -O$(OPT) $(CWARN) $(CXSECTF)
|
||||||
|
#ASFLAGS = -Wa,-adhlns=$(<:.S=.lst),-gstabs
|
||||||
|
LDFLAGS = -lm
|
||||||
|
|
||||||
BOARDS_TXT:=$(ARDUINO_PATH)hardware/arduino/boards.txt
|
# Programming support using avrdude. Settings and variables.
|
||||||
|
AVRDUDE_PORT = $(PORT)
|
||||||
|
AVRDUDE_WRITE_FLASH = -U flash:w:applet/$(TARGET).hex
|
||||||
|
AVRDUDE_FLAGS = -V -F \
|
||||||
|
-p $(BUILD_MCU) -P $(AVRDUDE_PORT) -c $(UPLOAD_PROTOCOL) \
|
||||||
|
-b $(UPLOAD_SPEED) -C $(INSTALL_DIR)/hardware/tools/avrdude.conf
|
||||||
|
# -b $(UPLOAD_SPEED) -C $(INSTALL_DIR)/hardware/tools/avr/etc/avrdude.conf
|
||||||
|
|
||||||
# get the MCU value from the $(BOARD).build.mcu variable. For the atmega328 board this is atmega328p
|
# Program settings
|
||||||
MCU:=$(shell sed -n -e "s/$(BOARD).build.mcu=\(.*\)/\1/p" $(BOARDS_TXT))
|
CC = $(AVR_TOOLS_PATH)/avr-gcc
|
||||||
# get the F_CPU value from the $(BOARD).build.f_cpu variable. For the atmega328 board this is 16000000
|
CXX = $(AVR_TOOLS_PATH)/avr-g++
|
||||||
F_CPU:=$(shell sed -n -e "s/$(BOARD).build.f_cpu=\(.*\)/\1/p" $(BOARDS_TXT))
|
OBJCOPY = $(AVR_TOOLS_PATH)/avr-objcopy
|
||||||
|
OBJDUMP = $(AVR_TOOLS_PATH)/avr-objdump
|
||||||
|
AR = $(AVR_TOOLS_PATH)/avr-ar
|
||||||
|
SIZE = $(AVR_TOOLS_PATH)/avr-size
|
||||||
|
NM = $(AVR_TOOLS_PATH)/avr-nm
|
||||||
|
#~ AVRDUDE = $(AVR_TOOLS_PATH)/avrdude
|
||||||
|
AVRDUDE = $(AVR_DUDE_PATH)/avrdude
|
||||||
|
REMOVE = rm -f
|
||||||
|
MV = mv -f
|
||||||
|
|
||||||
# avrdude
|
# Define all object files.
|
||||||
# get the AVRDUDE_UPLOAD_RATE value from the $(BOARD).upload.speed variable. For the atmega328 board this is 57600
|
# NOTE: obj files will be created in respective src directories (libraries or $(INSTALL_DIR));
|
||||||
AVRDUDE_UPLOAD_RATE:=$(shell sed -n -e "s/$(BOARD).upload.speed=\(.*\)/\1/p" $(BOARDS_TXT))
|
# make clean deletes them fine
|
||||||
# get the AVRDUDE_PROGRAMMER value from the $(BOARD).upload.protocol variable. For the atmega328 board this is stk500
|
# note that srcs are in libraries or other directories;
|
||||||
# AVRDUDE_PROGRAMMER:=$(shell sed -n -e "s/$(BOARD).upload.protocol=\(.*\)/\1/p" $(BOARDS_TXT))
|
# $(CXXSRC:.cpp=.o) will cause obj files to be in same loc as src files
|
||||||
# use stk500v1, because stk500 will default to stk500v2
|
#~ OBJ = $(SRC:.c=.o) $(CXXSRC:.cpp=.o) $(ASRC:.S=.o)
|
||||||
AVRDUDE_PROGRAMMER:=stk500v1
|
# to change the output directory for object files;
|
||||||
|
# must change the obj list here!
|
||||||
|
# and then, match to corresponding rule somehow?
|
||||||
|
# or leave this - and parse in rule (auth automatic variable $(@F))?
|
||||||
|
# "Suffix Replacement"
|
||||||
|
OBJ = $(SRC:.c=.o) $(CXXSRC:.cpp=.o) $(ASRC:.S=.o)
|
||||||
|
|
||||||
#=== identify user files ===
|
# added - OBJ list, transformed into applet/
|
||||||
PDESRC:=$(shell ls *.pde)
|
OBJT = $(addprefix applet/,$(notdir $(OBJ)))
|
||||||
TARGETNAME=$(basename $(PDESRC))
|
ALLSRC = $(SRC) $(CXXSRC) $(ASRC)
|
||||||
|
|
||||||
CDIRS:=$(EXTRA_DIRS) $(addsuffix utility/,$(EXTRA_DIRS))
|
# Define all listing files.
|
||||||
CDIRS:=*.c utility/*.c $(addsuffix *.c,$(CDIRS)) $(ARDUINO_PATH)hardware/arduino/cores/arduino/*.c
|
LST = $(ASRC:.S=.lst) $(CXXSRC:.cpp=.lst) $(SRC:.c=.lst)
|
||||||
CSRC:=$(shell ls $(CDIRS) 2>/dev/null)
|
|
||||||
|
|
||||||
CCSRC:=$(shell ls *.cc 2>/dev/null)
|
# Combine all necessary flags and optional flags.
|
||||||
|
# Add target processor to flags.
|
||||||
|
ALL_CFLAGS = -mmcu=$(BUILD_MCU) -I. $(CFLAGS)
|
||||||
|
ALL_CXXFLAGS = -mmcu=$(BUILD_MCU) -I. $(CXXFLAGS)
|
||||||
|
ALL_ASFLAGS = -mmcu=$(BUILD_MCU) -I. -x assembler-with-cpp $(ASFLAGS)
|
||||||
|
|
||||||
CPPDIRS:=$(EXTRA_DIRS) $(addsuffix utility/,$(EXTRA_DIRS))
|
# depended libraries of .pde need to be added from
|
||||||
CPPDIRS:=*.cpp utility/*.cpp $(addsuffix *.cpp,$(CPPDIRS)) $(ARDUINO_PATH)hardware/arduino/cores/arduino/*.cpp
|
# $(INSTALL_DIR)/libraries (TODO: and/or ~/sketchbook/libraries)
|
||||||
CPPSRC:=$(shell ls $(CPPDIRS) 2>/dev/null)
|
# grep for 'include', test if exists, add...
|
||||||
|
# note: prefix "a real tab character" http://www.delorie.com/djgpp/doc/ug/larger/makefiles.html
|
||||||
|
# $$ to escape $ for shell;
|
||||||
|
# note: must NOT put comments # inside bash execution;
|
||||||
|
# those would get removed by make; making shell see "EOF in backquote substitution"
|
||||||
|
# echo $$ix ; \
|
||||||
|
# 'shell' twice - for each subprocess! Backtick doesn't get expanded?
|
||||||
|
GREPRES:=$(shell for ix in $(shell grep include $(TARGET).pde | sed 's/.*[<"]\(.*\).h[>"].*/\1/'); do \
|
||||||
|
if [ -d $(INSTALL_DIR)/libraries/$$ix ] ; then \
|
||||||
|
LINCS="$$LINCS -I$(INSTALL_DIR)/libraries/$$ix" ;\
|
||||||
|
fi; \
|
||||||
|
done; \
|
||||||
|
echo $$LINCS)
|
||||||
|
# append includes:
|
||||||
|
CINCS += $(GREPRES)
|
||||||
|
CXXINCS += $(GREPRES)
|
||||||
|
# append library source .cpp files too (CXXSRC)
|
||||||
|
GREPRESB:=$(shell for ix in $(shell grep include $(TARGET).pde | sed 's/.*[<"]\(.*\).h[>"].*/\1/'); do \
|
||||||
|
if [ -d $(INSTALL_DIR)/libraries/$$ix ] ; then \
|
||||||
|
CPPSRCS="$$CPPSRCS $(INSTALL_DIR)/libraries/$$ix/*.cpp" ;\
|
||||||
|
fi; \
|
||||||
|
done; \
|
||||||
|
echo $$CPPSRCS)
|
||||||
|
CXXSRC += $(GREPRESB)
|
||||||
|
# added - only CXX obj from libraries:
|
||||||
|
CXXLIBOBJ = $(GREPRESB:.cpp=.o)
|
||||||
|
|
||||||
#=== build internal variables ===
|
# Default target.
|
||||||
|
all: applet_files build sizeafter
|
||||||
|
|
||||||
# the name of the subdirectory where everything is stored
|
build: elf hex
|
||||||
TMPDIRNAME:=tmp
|
|
||||||
TMPDIRPATH:=$(TMPDIRNAME)/
|
|
||||||
|
|
||||||
AVRTOOLSPATH:=$(AVR_TOOLS_PATH)
|
applet_files: $(TARGET).pde
|
||||||
|
# Here is the "preprocessing".
|
||||||
OBJCOPY:=$(AVRTOOLSPATH)avr-objcopy
|
# It creates a .cpp file based with the same name as the .pde file.
|
||||||
OBJDUMP:=$(AVRTOOLSPATH)avr-objdump
|
# On top of the new .cpp file comes the WProgram.h header.
|
||||||
SIZE:=$(AVRTOOLSPATH)avr-size
|
# At the end there is a generic main() function attached.
|
||||||
|
# Then the .cpp file will be compiled. Errors during compile will
|
||||||
CPPSRC:=$(addprefix $(TMPDIRPATH),$(PDESRC:.pde=.cpp)) $(CPPSRC)
|
# refer to this new, automatically generated, file.
|
||||||
|
# Not the original .pde file you actually edit...
|
||||||
COBJ:=$(CSRC:.c=.o)
|
test -d applet || mkdir applet
|
||||||
CCOBJ:=$(CCSRC:.cc=.o)
|
# @ supresses printout of the cmdline itself; so only the out of echo is printed
|
||||||
CPPOBJ:=$(CPPSRC:.cpp=.o)
|
@echo ALL OBJT: $(OBJT)
|
||||||
|
@echo ALL CXXLIBOBJ: $(CXXLIBOBJ)
|
||||||
OBJFILES:=$(COBJ) $(CCOBJ) $(CPPOBJ)
|
# echo '#include "WProgram.h"' > applet/$(TARGET).cpp
|
||||||
DIRS:= $(dir $(OBJFILES))
|
@echo "#include \"WProgram.h\"\nvoid setup();\nvoid loop();\n" > applet/$(TARGET).cpp
|
||||||
|
cat $(TARGET).pde >> applet/$(TARGET).cpp
|
||||||
DEPFILES:=$(OBJFILES:.o=.d)
|
# no more need to cat main.cpp (v0022) - now it is compiled in
|
||||||
# assembler files from avr-gcc -S
|
# cat $(ARDUINO)/main.cpp >> applet/$(TARGET).cpp
|
||||||
ASSFILES:=$(OBJFILES:.o=.s)
|
|
||||||
# disassembled object files with avr-objdump -S
|
|
||||||
DISFILES:=$(OBJFILES:.o=.dis)
|
|
||||||
|
|
||||||
|
|
||||||
LIBNAME:=$(TMPDIRPATH)$(TARGETNAME).a
|
elf: applet/$(TARGET).elf
|
||||||
ELFNAME:=$(TMPDIRPATH)$(TARGETNAME).elf
|
hex: applet/$(TARGET).hex
|
||||||
HEXNAME:=$(TMPDIRPATH)$(TARGETNAME).hex
|
eep: applet/$(TARGET).eep
|
||||||
|
lss: applet/$(TARGET).lss
|
||||||
|
sym: applet/$(TARGET).sym
|
||||||
|
|
||||||
AVRDUDE_FLAGS = -V -F
|
# Program the device.
|
||||||
AVRDUDE_FLAGS += -C $(ARDUINO_PATH)/hardware/tools/avrdude.conf
|
upload: applet/$(TARGET).hex
|
||||||
AVRDUDE_FLAGS += -p $(MCU)
|
$(AVRDUDE) $(AVRDUDE_FLAGS) $(AVRDUDE_WRITE_FLASH)
|
||||||
AVRDUDE_FLAGS += -P $(AVRDUDE_PORT)
|
|
||||||
AVRDUDE_FLAGS += -c $(AVRDUDE_PROGRAMMER)
|
|
||||||
AVRDUDE_FLAGS += -b $(AVRDUDE_UPLOAD_RATE)
|
|
||||||
AVRDUDE_FLAGS += -U flash:w:$(HEXNAME)
|
|
||||||
|
|
||||||
AVRDUDE = avrdude
|
# Display size of file.
|
||||||
|
HEXSIZE = $(SIZE) --target=$(FORMAT) applet/$(TARGET).hex
|
||||||
|
ELFSIZE = $(SIZE) applet/$(TARGET).elf
|
||||||
|
sizebefore:
|
||||||
|
@if [ -f applet/$(TARGET).elf ]; then echo; echo $(MSG_SIZE_BEFORE); $(HEXSIZE); echo; fi
|
||||||
|
|
||||||
#=== predefined variable override ===
|
sizeafter:
|
||||||
# use "make -p -f/dev/null" to see the default rules and definitions
|
@if [ -f applet/$(TARGET).elf ]; then echo; echo $(MSG_SIZE_AFTER); $(HEXSIZE); echo; fi
|
||||||
|
|
||||||
# Build C and C++ flags. Include path information must be placed here
|
# Convert ELF to COFF for use in debugging / simulating in AVR Studio or VMLAB.
|
||||||
COMMON_FLAGS = -DF_CPU=$(F_CPU) -mmcu=$(MCU) $(DEFS)
|
COFFCONVERT=$(OBJCOPY) --debugging \
|
||||||
# COMMON_FLAGS += -gdwarf-2
|
--change-section-address .data-0x800000 \
|
||||||
COMMON_FLAGS += -Os
|
--change-section-address .bss-0x800000 \
|
||||||
COMMON_FLAGS += -Wall -funsigned-char -funsigned-bitfields -fpack-struct -fshort-enums
|
--change-section-address .noinit-0x800000 \
|
||||||
COMMON_FLAGS += -I.
|
--change-section-address .eeprom-0x810000
|
||||||
COMMON_FLAGS += -I$(ARDUINO_PATH)hardware/arduino/cores/arduino
|
|
||||||
COMMON_FLAGS += $(addprefix -I,$(EXTRA_DIRS))
|
|
||||||
COMMON_FLAGS += -ffunction-sections -fdata-sections -Wl,--gc-sections
|
|
||||||
COMMON_FLAGS += -Wl,--relax
|
|
||||||
COMMON_FLAGS += -mcall-prologues
|
|
||||||
|
|
||||||
CFLAGS = $(COMMON_FLAGS) -std=gnu99 -Wstrict-prototypes
|
coff: applet/$(TARGET).elf
|
||||||
CXXFLAGS = $(COMMON_FLAGS)
|
$(COFFCONVERT) -O coff-avr applet/$(TARGET).elf $(TARGET).cof
|
||||||
|
|
||||||
# Replace standard build tools by avr tools
|
extcoff: $(TARGET).elf
|
||||||
CC = $(AVRTOOLSPATH)avr-gcc
|
$(COFFCONVERT) -O coff-ext-avr applet/$(TARGET).elf $(TARGET).cof
|
||||||
CXX = $(AVRTOOLSPATH)avr-g++
|
|
||||||
AR = @$(AVRTOOLSPATH)avr-ar
|
|
||||||
|
|
||||||
|
.SUFFIXES: .elf .hex .eep .lss .sym
|
||||||
# "rm" must be able to delete a directory tree
|
|
||||||
RM = rm -rf
|
|
||||||
|
|
||||||
#=== rules ===
|
|
||||||
|
|
||||||
# add rules for the C/C++ files where the .o file is placed in the TMPDIRPATH
|
|
||||||
# reuse existing variables as far as possible
|
|
||||||
|
|
||||||
$(TMPDIRPATH)%.o: %.c
|
|
||||||
@echo compile $<
|
|
||||||
@$(COMPILE.c) $(OUTPUT_OPTION) $<
|
|
||||||
|
|
||||||
$(TMPDIRPATH)%.o: %.cc
|
|
||||||
@echo compile $<
|
|
||||||
@$(COMPILE.cc) $(OUTPUT_OPTION) $<
|
|
||||||
|
|
||||||
$(TMPDIRPATH)%.o: %.cpp
|
|
||||||
@echo compile $<
|
|
||||||
@$(COMPILE.cpp) $(OUTPUT_OPTION) $<
|
|
||||||
|
|
||||||
$(TMPDIRPATH)%.s: %.c
|
|
||||||
@$(COMPILE.c) $(OUTPUT_OPTION) -S $<
|
|
||||||
|
|
||||||
$(TMPDIRPATH)%.s: %.cc
|
|
||||||
@$(COMPILE.cc) $(OUTPUT_OPTION) -S $<
|
|
||||||
|
|
||||||
$(TMPDIRPATH)%.s: %.cpp
|
|
||||||
@$(COMPILE.cpp) $(OUTPUT_OPTION) -S $<
|
|
||||||
|
|
||||||
$(TMPDIRPATH)%.dis: $(TMPDIRPATH)%.o
|
|
||||||
@$(OBJDUMP) -S $< > $@
|
|
||||||
|
|
||||||
.SUFFIXES: .elf .hex .pde
|
|
||||||
|
|
||||||
.elf.hex:
|
.elf.hex:
|
||||||
@$(OBJCOPY) -O ihex -R .eeprom $< $@
|
$(OBJCOPY) -O $(FORMAT) -R .eeprom $< $@
|
||||||
|
|
||||||
$(TMPDIRPATH)%.cpp: %.pde
|
|
||||||
@cat $(ARDUINO_PATH)hardware/arduino/cores/arduino/main.cpp > $@
|
|
||||||
@cat $< >> $@
|
|
||||||
@echo >> $@
|
|
||||||
@echo 'extern "C" void __cxa_pure_virtual() { while (1); }' >> $@
|
|
||||||
|
|
||||||
|
.elf.eep:
|
||||||
|
-$(OBJCOPY) -j .eeprom --set-section-flags=.eeprom="alloc,load" \
|
||||||
|
--change-section-lma .eeprom=0 -O $(FORMAT) $< $@
|
||||||
|
|
||||||
.PHONY: all
|
# Create extended listing file from ELF output file.
|
||||||
all: tmpdir $(HEXNAME) assemblersource showsize
|
.elf.lss:
|
||||||
ls -al $(HEXNAME) $(ELFNAME)
|
$(OBJDUMP) -h -S $< > $@
|
||||||
|
|
||||||
$(ELFNAME): $(LIBNAME)($(addprefix $(TMPDIRPATH),$(OBJFILES)))
|
# Create a symbol table from ELF output file.
|
||||||
$(LINK.o) $(COMMON_FLAGS) $(LIBNAME) $(LOADLIBES) $(LDLIBS) -o $@
|
.elf.sym:
|
||||||
|
$(NM) -n $< > $@
|
||||||
|
|
||||||
$(LIBNAME)(): $(addprefix $(TMPDIRPATH),$(OBJFILES))
|
# Link: create ELF output file from library.
|
||||||
|
# NOTE: applet/$(TARGET).cpp.o MUST BE BEFORE applet/core.a
|
||||||
|
# in the dependency list, so its rule runs first!
|
||||||
|
applet/$(TARGET).elf: $(TARGET).pde applet/$(TARGET).cpp.o applet/core.a
|
||||||
|
# $(CC) $(ALL_CFLAGS) -o $@ applet/$(TARGET).cpp -L. applet/core.a $(LDFLAGS)
|
||||||
|
# changed as in IDE v0022: link cpp obj files
|
||||||
|
@echo $$(tput bold)$$(tput setaf 2) $(CC) $$(tput sgr0) $(ALL_CFLAGS) $(CFINALF) -o $@ applet/$(TARGET).cpp.o $(CXXOBJ) -L. applet/core.a $(LDFLAGS)
|
||||||
|
@$(CC) $(ALL_CFLAGS) $(CFINALF) -o $@ applet/$(TARGET).cpp.o $(CXXOBJ) -L. applet/core.a $(LDFLAGS)
|
||||||
|
|
||||||
#=== create temp directory ===
|
# added: cpp.o depends on cpp (and .pde which generates it)
|
||||||
# not really required, because it will be also created during the dependency handling
|
# $< "first item in the dependencies list"; $@ "left side of the :"; $^ "right side of the :"
|
||||||
.PHONY: tmpdir
|
# http://www.cs.colby.edu/maxwell/courses/tutorials/maketutor/
|
||||||
tmpdir:
|
applet/$(TARGET).cpp.o: applet/$(TARGET).cpp
|
||||||
@test -d $(TMPDIRPATH) || mkdir $(TMPDIRPATH)
|
@echo $$(tput bold) $(CXX) $$(tput sgr0) -c $(ALL_CXXFLAGS) $< -o $@
|
||||||
|
@$(CXX) -c $(ALL_CXXFLAGS) $< -o $@
|
||||||
|
|
||||||
#=== create assembler files for each C/C++ file ===
|
#~ applet/core.a: $(OBJ)
|
||||||
.PHONY: assemblersource
|
#~ @for i in $(OBJ); do echo $(AR) rcs applet/core.a $$i; $(AR) rcs applet/core.a $$i; done
|
||||||
assemblersource: $(addprefix $(TMPDIRPATH),$(ASSFILES)) $(addprefix $(TMPDIRPATH),$(DISFILES))
|
|
||||||
|
|
||||||
|
applet/core.a: $(OBJT)
|
||||||
|
@for i in $(OBJT); do echo $(AR) rcs applet/core.a $$i; $(AR) rcs applet/core.a $$i; done
|
||||||
|
|
||||||
#=== show the section sizes of the ELF file ===
|
# iterate through OBJ to find the original location; then build depending on source extension
|
||||||
.PHONY: showsize
|
# TODO: add handling of assembler files
|
||||||
showsize: $(ELFNAME)
|
applet/%.o:
|
||||||
$(SIZE) $<
|
@for iob in $(OBJ); do \
|
||||||
|
if [ "`basename $$iob`" = "`basename $@`" ]; then \
|
||||||
|
for ios in $(ALLSRC); do \
|
||||||
|
if [ "$${iob%%.*}" = "$${ios%%.*}" ]; then \
|
||||||
|
case $${ios##*.} in \
|
||||||
|
"cpp") \
|
||||||
|
echo "$$(tput bold)$$(tput setaf 1) $(CXX) $$(tput sgr0) -c $(ALL_CXXFLAGS) $$ios -o $@"; \
|
||||||
|
$(CXX) -c $(ALL_CXXFLAGS) $$ios -o $@;; \
|
||||||
|
"c") \
|
||||||
|
echo "$$(tput bold)$$(tput setaf 1) $(CC) $$(tput sgr0) -c $(ALL_CFLAGS) $$ios -o $@"; \
|
||||||
|
$(CC) -c $(ALL_CFLAGS) $$ios -o $@;; \
|
||||||
|
esac; \
|
||||||
|
fi; \
|
||||||
|
done; \
|
||||||
|
fi; \
|
||||||
|
done;
|
||||||
|
|
||||||
#=== clean up target ===
|
#~ # Compile: create object files from C++ source files.
|
||||||
# this is simple: the TMPDIRPATH is removed
|
#~ .cpp.o:
|
||||||
.PHONY: clean
|
#~ $(CXX) -c $(ALL_CXXFLAGS) $< -o $@
|
||||||
|
|
||||||
|
#~ # Compile: create object files from C source files.
|
||||||
|
#~ .c.o:
|
||||||
|
#~ $(CC) -c $(ALL_CFLAGS) $< -o $@
|
||||||
|
|
||||||
|
#~ # Compile: create assembler files from C source files.
|
||||||
|
#~ .c.s:
|
||||||
|
#~ $(CC) -S $(ALL_CFLAGS) $< -o $@
|
||||||
|
|
||||||
|
#~ # Assemble: create object files from assembler source files.
|
||||||
|
#~ .S.o:
|
||||||
|
#~ $(CC) -c $(ALL_ASFLAGS) $< -o $@
|
||||||
|
|
||||||
|
#~ # Automatic dependencies
|
||||||
|
#~ %.d: %.c
|
||||||
|
#~ $(CC) -M $(ALL_CFLAGS) $< | sed "s;$(notdir $*).o:;$*.o $*.d:;" > $@
|
||||||
|
|
||||||
|
#~ %.d: %.cpp
|
||||||
|
#~ $(CXX) -M $(ALL_CXXFLAGS) $< | sed "s;$(notdir $*).o:;$*.o $*.d:;" > $@
|
||||||
|
|
||||||
|
# Target: clean project.
|
||||||
clean:
|
clean:
|
||||||
$(RM) $(TMPDIRPATH)
|
$(REMOVE) applet/$(TARGET).hex applet/$(TARGET).eep applet/$(TARGET).cof applet/$(TARGET).elf \
|
||||||
|
applet/$(TARGET).map applet/$(TARGET).sym applet/$(TARGET).lss applet/core.a \
|
||||||
# Program the device.
|
$(OBJT) applet/$(TARGET).cpp.o \
|
||||||
# step 1: reset the arduino board with the stty command
|
$(OBJ) $(LST) $(SRC:.c=.s) $(SRC:.c=.d) $(CXXSRC:.cpp=.s) $(CXXSRC:.cpp=.d)
|
||||||
# step 2: user avrdude to upload the software
|
|
||||||
.PHONY: upload
|
|
||||||
upload: $(HEXNAME)
|
|
||||||
stty -F $(AVRDUDE_PORT) hupcl
|
|
||||||
$(AVRDUDE) $(AVRDUDE_FLAGS)
|
|
||||||
|
|
||||||
|
|
||||||
# === dependency handling ===
|
|
||||||
# From the gnu make manual (section 4.14, Generating Prerequisites Automatically)
|
|
||||||
# Additionally (because this will be the first executed rule) TMPDIRPATH is created here.
|
|
||||||
# Instead of "sed" the "echo" command is used
|
|
||||||
# cd $(TMPDIRPATH); mkdir -p $(DIRS) 2> /dev/null; cd ..
|
|
||||||
DEPACTION=test -d $(TMPDIRPATH) || mkdir $(TMPDIRPATH);\
|
|
||||||
mkdir -p $(addprefix $(TMPDIRPATH),$(DIRS));\
|
|
||||||
set -e; echo -n $@ $(dir $@) > $@; $(CC) -MM $(COMMON_FLAGS) $< >> $@
|
|
||||||
|
|
||||||
|
|
||||||
$(TMPDIRPATH)%.d: %.c
|
|
||||||
@$(DEPACTION)
|
|
||||||
|
|
||||||
$(TMPDIRPATH)%.d: %.cc
|
|
||||||
@$(DEPACTION)
|
|
||||||
|
|
||||||
|
|
||||||
$(TMPDIRPATH)%.d: %.cpp
|
|
||||||
@$(DEPACTION)
|
|
||||||
|
|
||||||
# Include dependency files. If a .d file is missing, a warning is created and the .d file is created
|
|
||||||
# This warning is not a problem (gnu make manual, section 3.3 Including Other Makefiles)
|
|
||||||
-include $(addprefix $(TMPDIRPATH),$(DEPFILES))
|
|
||||||
|
|
||||||
|
|
||||||
|
.PHONY: all build elf hex eep lss sym program coff extcoff clean applet_files sizebefore sizeafter
|
||||||
|
|
165
Marlin/Marlin.h
165
Marlin/Marlin.h
|
@ -1,83 +1,82 @@
|
||||||
#ifndef __MARLINH
|
#ifndef __MARLINH
|
||||||
#define __MARLINH
|
#define __MARLINH
|
||||||
|
|
||||||
// Tonokip RepRap firmware rewrite based off of Hydra-mmm firmware.
|
// Tonokip RepRap firmware rewrite based off of Hydra-mmm firmware.
|
||||||
// Licence: GPL
|
// Licence: GPL
|
||||||
#include <WProgram.h>
|
#include <WProgram.h>
|
||||||
#include "fastio.h"
|
#include "fastio.h"
|
||||||
|
|
||||||
|
|
||||||
#define ECHO(x) Serial << "echo: " << x;
|
#define ECHO(x) Serial << "echo: " << x;
|
||||||
#define ECHOLN(x) Serial << "echo: "<<x<<endl;
|
#define ECHOLN(x) Serial << "echo: "<<x<<endl;
|
||||||
|
|
||||||
void get_command();
|
void get_command();
|
||||||
void process_commands();
|
void process_commands();
|
||||||
|
|
||||||
void manage_inactivity(byte debug);
|
void manage_inactivity(byte debug);
|
||||||
|
|
||||||
#if X_ENABLE_PIN > -1
|
#if X_ENABLE_PIN > -1
|
||||||
#define enable_x() WRITE(X_ENABLE_PIN, X_ENABLE_ON)
|
#define enable_x() WRITE(X_ENABLE_PIN, X_ENABLE_ON)
|
||||||
#define disable_x() WRITE(X_ENABLE_PIN,!X_ENABLE_ON)
|
#define disable_x() WRITE(X_ENABLE_PIN,!X_ENABLE_ON)
|
||||||
#else
|
#else
|
||||||
#define enable_x() ;
|
#define enable_x() ;
|
||||||
#define disable_x() ;
|
#define disable_x() ;
|
||||||
#endif
|
#endif
|
||||||
#if Y_ENABLE_PIN > -1
|
#if Y_ENABLE_PIN > -1
|
||||||
#define enable_y() WRITE(Y_ENABLE_PIN, Y_ENABLE_ON)
|
#define enable_y() WRITE(Y_ENABLE_PIN, Y_ENABLE_ON)
|
||||||
#define disable_y() WRITE(Y_ENABLE_PIN,!Y_ENABLE_ON)
|
#define disable_y() WRITE(Y_ENABLE_PIN,!Y_ENABLE_ON)
|
||||||
#else
|
#else
|
||||||
#define enable_y() ;
|
#define enable_y() ;
|
||||||
#define disable_y() ;
|
#define disable_y() ;
|
||||||
#endif
|
#endif
|
||||||
#if Z_ENABLE_PIN > -1
|
#if Z_ENABLE_PIN > -1
|
||||||
#define enable_z() WRITE(Z_ENABLE_PIN, Z_ENABLE_ON)
|
#define enable_z() WRITE(Z_ENABLE_PIN, Z_ENABLE_ON)
|
||||||
#define disable_z() WRITE(Z_ENABLE_PIN,!Z_ENABLE_ON)
|
#define disable_z() WRITE(Z_ENABLE_PIN,!Z_ENABLE_ON)
|
||||||
#else
|
#else
|
||||||
#define enable_z() ;
|
#define enable_z() ;
|
||||||
#define disable_z() ;
|
#define disable_z() ;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if E_ENABLE_PIN > -1
|
#if E_ENABLE_PIN > -1
|
||||||
|
|
||||||
#define enable_e() WRITE(E_ENABLE_PIN, E_ENABLE_ON)
|
#define enable_e() WRITE(E_ENABLE_PIN, E_ENABLE_ON)
|
||||||
#define disable_e() WRITE(E_ENABLE_PIN,!E_ENABLE_ON)
|
#define disable_e() WRITE(E_ENABLE_PIN,!E_ENABLE_ON)
|
||||||
|
|
||||||
#else
|
#else
|
||||||
#define enable_e() ;
|
#define enable_e() ;
|
||||||
#define disable_e() ;
|
#define disable_e() ;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#define X_AXIS 0
|
#define X_AXIS 0
|
||||||
#define Y_AXIS 1
|
#define Y_AXIS 1
|
||||||
#define Z_AXIS 2
|
#define Z_AXIS 2
|
||||||
#define E_AXIS 3
|
#define E_AXIS 3
|
||||||
|
|
||||||
void FlushSerialRequestResend();
|
void FlushSerialRequestResend();
|
||||||
void ClearToSend();
|
void ClearToSend();
|
||||||
|
|
||||||
void get_coordinates();
|
void get_coordinates();
|
||||||
void prepare_move();
|
void prepare_move();
|
||||||
void kill(byte debug);
|
void kill();
|
||||||
|
|
||||||
//void check_axes_activity();
|
//void check_axes_activity();
|
||||||
//void plan_init();
|
//void plan_init();
|
||||||
//void st_init();
|
//void st_init();
|
||||||
//void tp_init();
|
//void tp_init();
|
||||||
//void plan_buffer_line(float x, float y, float z, float e, float feed_rate);
|
//void plan_buffer_line(float x, float y, float z, float e, float feed_rate);
|
||||||
//void plan_set_position(float x, float y, float z, float e);
|
//void plan_set_position(float x, float y, float z, float e);
|
||||||
//void st_wake_up();
|
//void st_wake_up();
|
||||||
//void st_synchronize();
|
//void st_synchronize();
|
||||||
void enquecommand(const char *cmd);
|
void enquecommand(const char *cmd);
|
||||||
void wd_reset();
|
|
||||||
|
|
||||||
#ifndef CRITICAL_SECTION_START
|
#ifndef CRITICAL_SECTION_START
|
||||||
#define CRITICAL_SECTION_START unsigned char _sreg = SREG; cli();
|
#define CRITICAL_SECTION_START unsigned char _sreg = SREG; cli();
|
||||||
#define CRITICAL_SECTION_END SREG = _sreg;
|
#define CRITICAL_SECTION_END SREG = _sreg;
|
||||||
#endif //CRITICAL_SECTION_START
|
#endif //CRITICAL_SECTION_START
|
||||||
|
|
||||||
extern float homing_feedrate[];
|
extern float homing_feedrate[];
|
||||||
extern bool axis_relative_modes[];
|
extern bool axis_relative_modes[];
|
||||||
|
|
||||||
void manage_inactivity(byte debug);
|
void wd_reset() ;
|
||||||
|
#endif
|
||||||
#endif
|
|
||||||
|
|
2466
Marlin/Marlin.pde
2466
Marlin/Marlin.pde
|
@ -1,1233 +1,1233 @@
|
||||||
/*
|
/*
|
||||||
Reprap firmware based on Sprinter and grbl.
|
Reprap firmware based on Sprinter and grbl.
|
||||||
Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||||
|
|
||||||
This program is free software: you can redistribute it and/or modify
|
This program is free software: you can redistribute it and/or modify
|
||||||
it under the terms of the GNU General Public License as published by
|
it under the terms of the GNU General Public License as published by
|
||||||
the Free Software Foundation, either version 3 of the License, or
|
the Free Software Foundation, either version 3 of the License, or
|
||||||
(at your option) any later version.
|
(at your option) any later version.
|
||||||
|
|
||||||
This program is distributed in the hope that it will be useful,
|
This program is distributed in the hope that it will be useful,
|
||||||
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
GNU General Public License for more details.
|
GNU General Public License for more details.
|
||||||
|
|
||||||
You should have received a copy of the GNU General Public License
|
You should have received a copy of the GNU General Public License
|
||||||
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
*/
|
*/
|
||||||
|
|
||||||
/*
|
/*
|
||||||
This firmware is a mashup between Sprinter and grbl.
|
This firmware is a mashup between Sprinter and grbl.
|
||||||
(https://github.com/kliment/Sprinter)
|
(https://github.com/kliment/Sprinter)
|
||||||
(https://github.com/simen/grbl/tree)
|
(https://github.com/simen/grbl/tree)
|
||||||
|
|
||||||
It has preliminary support for Matthew Roberts advance algorithm
|
It has preliminary support for Matthew Roberts advance algorithm
|
||||||
http://reprap.org/pipermail/reprap-dev/2011-May/003323.html
|
http://reprap.org/pipermail/reprap-dev/2011-May/003323.html
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#include <EEPROM.h>
|
#include "EEPROMwrite.h"
|
||||||
#include "fastio.h"
|
#include "fastio.h"
|
||||||
#include "Configuration.h"
|
#include "Configuration.h"
|
||||||
#include "pins.h"
|
#include "pins.h"
|
||||||
#include "Marlin.h"
|
#include "Marlin.h"
|
||||||
#include "ultralcd.h"
|
#include "ultralcd.h"
|
||||||
#include "streaming.h"
|
#include "streaming.h"
|
||||||
#include "planner.h"
|
#include "planner.h"
|
||||||
#include "stepper.h"
|
#include "stepper.h"
|
||||||
#include "temperature.h"
|
#include "temperature.h"
|
||||||
|
|
||||||
#ifdef SIMPLE_LCD
|
#ifdef SIMPLE_LCD
|
||||||
#include "Simplelcd.h"
|
#include "Simplelcd.h"
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
char version_string[] = "1.0.0 Alpha 1";
|
char version_string[] = "1.0.0 Alpha 1";
|
||||||
|
|
||||||
#ifdef SDSUPPORT
|
#ifdef SDSUPPORT
|
||||||
#include "SdFat.h"
|
#include "SdFat.h"
|
||||||
#endif //SDSUPPORT
|
#endif //SDSUPPORT
|
||||||
|
|
||||||
|
|
||||||
// look here for descriptions of gcodes: http://linuxcnc.org/handbook/gcode/g-code.html
|
// look here for descriptions of gcodes: http://linuxcnc.org/handbook/gcode/g-code.html
|
||||||
// http://objects.reprap.org/wiki/Mendel_User_Manual:_RepRapGCodes
|
// http://objects.reprap.org/wiki/Mendel_User_Manual:_RepRapGCodes
|
||||||
|
|
||||||
//Implemented Codes
|
//Implemented Codes
|
||||||
//-------------------
|
//-------------------
|
||||||
// G0 -> G1
|
// G0 -> G1
|
||||||
// G1 - Coordinated Movement X Y Z E
|
// G1 - Coordinated Movement X Y Z E
|
||||||
// G4 - Dwell S<seconds> or P<milliseconds>
|
// G4 - Dwell S<seconds> or P<milliseconds>
|
||||||
// G28 - Home all Axis
|
// G28 - Home all Axis
|
||||||
// G90 - Use Absolute Coordinates
|
// G90 - Use Absolute Coordinates
|
||||||
// G91 - Use Relative Coordinates
|
// G91 - Use Relative Coordinates
|
||||||
// G92 - Set current position to cordinates given
|
// G92 - Set current position to cordinates given
|
||||||
|
|
||||||
//RepRap M Codes
|
//RepRap M Codes
|
||||||
// M104 - Set extruder target temp
|
// M104 - Set extruder target temp
|
||||||
// M105 - Read current temp
|
// M105 - Read current temp
|
||||||
// M106 - Fan on
|
// M106 - Fan on
|
||||||
// M107 - Fan off
|
// M107 - Fan off
|
||||||
// M109 - Wait for extruder current temp to reach target temp.
|
// M109 - Wait for extruder current temp to reach target temp.
|
||||||
// M114 - Display current position
|
// M114 - Display current position
|
||||||
|
|
||||||
//Custom M Codes
|
//Custom M Codes
|
||||||
// M20 - List SD card
|
// M20 - List SD card
|
||||||
// M21 - Init SD card
|
// M21 - Init SD card
|
||||||
// M22 - Release SD card
|
// M22 - Release SD card
|
||||||
// M23 - Select SD file (M23 filename.g)
|
// M23 - Select SD file (M23 filename.g)
|
||||||
// M24 - Start/resume SD print
|
// M24 - Start/resume SD print
|
||||||
// M25 - Pause SD print
|
// M25 - Pause SD print
|
||||||
// M26 - Set SD position in bytes (M26 S12345)
|
// M26 - Set SD position in bytes (M26 S12345)
|
||||||
// M27 - Report SD print status
|
// M27 - Report SD print status
|
||||||
// M28 - Start SD write (M28 filename.g)
|
// M28 - Start SD write (M28 filename.g)
|
||||||
// M29 - Stop SD write
|
// M29 - Stop SD write
|
||||||
// M42 - Change pin status via gcode
|
// M42 - Change pin status via gcode
|
||||||
// M80 - Turn on Power Supply
|
// M80 - Turn on Power Supply
|
||||||
// M81 - Turn off Power Supply
|
// M81 - Turn off Power Supply
|
||||||
// M82 - Set E codes absolute (default)
|
// M82 - Set E codes absolute (default)
|
||||||
// M83 - Set E codes relative while in Absolute Coordinates (G90) mode
|
// M83 - Set E codes relative while in Absolute Coordinates (G90) mode
|
||||||
// M84 - Disable steppers until next move,
|
// M84 - Disable steppers until next move,
|
||||||
// or use S<seconds> to specify an inactivity timeout, after which the steppers will be disabled. S0 to disable the timeout.
|
// or use S<seconds> to specify an inactivity timeout, after which the steppers will be disabled. S0 to disable the timeout.
|
||||||
// M85 - Set inactivity shutdown timer with parameter S<seconds>. To disable set zero (default)
|
// M85 - Set inactivity shutdown timer with parameter S<seconds>. To disable set zero (default)
|
||||||
// M92 - Set axis_steps_per_unit - same syntax as G92
|
// M92 - Set axis_steps_per_unit - same syntax as G92
|
||||||
// M115 - Capabilities string
|
// M115 - Capabilities string
|
||||||
// M140 - Set bed target temp
|
// M140 - Set bed target temp
|
||||||
// M190 - Wait for bed current temp to reach target temp.
|
// M190 - Wait for bed current temp to reach target temp.
|
||||||
// M200 - Set filament diameter
|
// M200 - Set filament diameter
|
||||||
// M201 - Set max acceleration in units/s^2 for print moves (M201 X1000 Y1000)
|
// M201 - Set max acceleration in units/s^2 for print moves (M201 X1000 Y1000)
|
||||||
// M202 - Set max acceleration in units/s^2 for travel moves (M202 X1000 Y1000) Unused in Marlin!!
|
// 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
|
// 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
|
// 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
|
||||||
// M205 - advanced settings: minimum travel speed S=while printing T=travel only, B=minimum segment time X= maximum xy jerk, Z=maximum Z jerk
|
// M205 - advanced settings: minimum travel speed S=while printing T=travel only, B=minimum segment time X= maximum xy jerk, Z=maximum Z jerk
|
||||||
// M220 - set speed factor override percentage S:factor in percent
|
// M220 - set speed factor override percentage S:factor in percent
|
||||||
// M301 - Set PID parameters P I and D
|
// M301 - Set PID parameters P I and D
|
||||||
// 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). D
|
// M501 - reads parameters from EEPROM (if you need reset them after you changed them temporarily). D
|
||||||
// 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.
|
||||||
|
|
||||||
//Stepper Movement Variables
|
//Stepper Movement Variables
|
||||||
|
|
||||||
char axis_codes[NUM_AXIS] = {
|
char axis_codes[NUM_AXIS] = {
|
||||||
'X', 'Y', 'Z', 'E'};
|
'X', 'Y', 'Z', 'E'};
|
||||||
float destination[NUM_AXIS] = {
|
float destination[NUM_AXIS] = {
|
||||||
0.0, 0.0, 0.0, 0.0};
|
0.0, 0.0, 0.0, 0.0};
|
||||||
float current_position[NUM_AXIS] = {
|
float current_position[NUM_AXIS] = {
|
||||||
0.0, 0.0, 0.0, 0.0};
|
0.0, 0.0, 0.0, 0.0};
|
||||||
bool home_all_axis = true;
|
bool home_all_axis = true;
|
||||||
float feedrate = 1500.0, next_feedrate, saved_feedrate;
|
float feedrate = 1500.0, next_feedrate, saved_feedrate;
|
||||||
long gcode_N, gcode_LastN;
|
long gcode_N, gcode_LastN;
|
||||||
|
|
||||||
float homing_feedrate[] = HOMING_FEEDRATE;
|
float homing_feedrate[] = HOMING_FEEDRATE;
|
||||||
bool axis_relative_modes[] = AXIS_RELATIVE_MODES;
|
bool axis_relative_modes[] = AXIS_RELATIVE_MODES;
|
||||||
|
|
||||||
bool relative_mode = false; //Determines Absolute or Relative Coordinates
|
bool relative_mode = false; //Determines Absolute or Relative Coordinates
|
||||||
bool relative_mode_e = false; //Determines Absolute or Relative E Codes while in Absolute Coordinates mode. E is always relative in Relative Coordinates mode.
|
bool relative_mode_e = false; //Determines Absolute or Relative E Codes while in Absolute Coordinates mode. E is always relative in Relative Coordinates mode.
|
||||||
|
|
||||||
uint8_t fanpwm=0;
|
uint8_t fanpwm=0;
|
||||||
|
|
||||||
volatile int feedmultiply=100; //100->1 200->2
|
volatile int feedmultiply=100; //100->1 200->2
|
||||||
int saved_feedmultiply;
|
int saved_feedmultiply;
|
||||||
volatile bool feedmultiplychanged=false;
|
volatile bool feedmultiplychanged=false;
|
||||||
// comm variables
|
// comm variables
|
||||||
#define MAX_CMD_SIZE 96
|
#define MAX_CMD_SIZE 96
|
||||||
#define BUFSIZE 4
|
#define BUFSIZE 4
|
||||||
char cmdbuffer[BUFSIZE][MAX_CMD_SIZE];
|
char cmdbuffer[BUFSIZE][MAX_CMD_SIZE];
|
||||||
bool fromsd[BUFSIZE];
|
bool fromsd[BUFSIZE];
|
||||||
int bufindr = 0;
|
int bufindr = 0;
|
||||||
int bufindw = 0;
|
int bufindw = 0;
|
||||||
int buflen = 0;
|
int buflen = 0;
|
||||||
int i = 0;
|
int i = 0;
|
||||||
char serial_char;
|
char serial_char;
|
||||||
int serial_count = 0;
|
int serial_count = 0;
|
||||||
boolean comment_mode = false;
|
boolean comment_mode = false;
|
||||||
char *strchr_pointer; // just a pointer to find chars in the cmd string like X, Y, Z, E, etc
|
char *strchr_pointer; // just a pointer to find chars in the cmd string like X, Y, Z, E, etc
|
||||||
extern float HeaterPower;
|
extern float HeaterPower;
|
||||||
|
|
||||||
#include "EEPROM.h"
|
#include "EEPROM.h"
|
||||||
|
|
||||||
const int sensitive_pins[] = SENSITIVE_PINS; // Sensitive pin list for M42
|
const int sensitive_pins[] = SENSITIVE_PINS; // Sensitive pin list for M42
|
||||||
|
|
||||||
float tt = 0, bt = 0;
|
float tt = 0, bt = 0;
|
||||||
#ifdef WATCHPERIOD
|
#ifdef WATCHPERIOD
|
||||||
int watch_raw = -1000;
|
int watch_raw = -1000;
|
||||||
unsigned long watchmillis = 0;
|
unsigned long watchmillis = 0;
|
||||||
#endif //WATCHPERIOD
|
#endif //WATCHPERIOD
|
||||||
|
|
||||||
//Inactivity shutdown variables
|
//Inactivity shutdown variables
|
||||||
unsigned long previous_millis_cmd = 0;
|
unsigned long previous_millis_cmd = 0;
|
||||||
unsigned long max_inactive_time = 0;
|
unsigned long max_inactive_time = 0;
|
||||||
unsigned long stepper_inactive_time = 0;
|
unsigned long stepper_inactive_time = 0;
|
||||||
|
|
||||||
unsigned long starttime=0;
|
unsigned long starttime=0;
|
||||||
unsigned long stoptime=0;
|
unsigned long stoptime=0;
|
||||||
#ifdef SDSUPPORT
|
#ifdef SDSUPPORT
|
||||||
Sd2Card card;
|
Sd2Card card;
|
||||||
SdVolume volume;
|
SdVolume volume;
|
||||||
SdFile root;
|
SdFile root;
|
||||||
SdFile file;
|
SdFile file;
|
||||||
uint32_t filesize = 0;
|
uint32_t filesize = 0;
|
||||||
uint32_t sdpos = 0;
|
uint32_t sdpos = 0;
|
||||||
bool sdmode = false;
|
bool sdmode = false;
|
||||||
bool sdactive = false;
|
bool sdactive = false;
|
||||||
bool savetosd = false;
|
bool savetosd = false;
|
||||||
int16_t n;
|
int16_t n;
|
||||||
long autostart_atmillis=0;
|
unsigned long autostart_atmillis=0;
|
||||||
|
|
||||||
void initsd(){
|
void initsd(){
|
||||||
sdactive = false;
|
sdactive = false;
|
||||||
#if SDSS >- 1
|
#if SDSS >- 1
|
||||||
if(root.isOpen())
|
if(root.isOpen())
|
||||||
root.close();
|
root.close();
|
||||||
if (!card.init(SPI_FULL_SPEED,SDSS)){
|
if (!card.init(SPI_FULL_SPEED,SDSS)){
|
||||||
//if (!card.init(SPI_HALF_SPEED,SDSS))
|
//if (!card.init(SPI_HALF_SPEED,SDSS))
|
||||||
Serial.println("SD init fail");
|
Serial.println("SD init fail");
|
||||||
}
|
}
|
||||||
else if (!volume.init(&card))
|
else if (!volume.init(&card))
|
||||||
Serial.println("volume.init failed");
|
Serial.println("volume.init failed");
|
||||||
else if (!root.openRoot(&volume))
|
else if (!root.openRoot(&volume))
|
||||||
Serial.println("openRoot failed");
|
Serial.println("openRoot failed");
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
sdactive = true;
|
sdactive = true;
|
||||||
Serial.println("SD card ok");
|
Serial.println("SD card ok");
|
||||||
}
|
}
|
||||||
#endif //SDSS
|
#endif //SDSS
|
||||||
}
|
}
|
||||||
|
|
||||||
void quickinitsd(){
|
void quickinitsd(){
|
||||||
sdactive=false;
|
sdactive=false;
|
||||||
autostart_atmillis=millis()+5000;
|
autostart_atmillis=millis()+5000;
|
||||||
}
|
}
|
||||||
|
|
||||||
inline void write_command(char *buf){
|
inline void write_command(char *buf){
|
||||||
char* begin = buf;
|
char* begin = buf;
|
||||||
char* npos = 0;
|
char* npos = 0;
|
||||||
char* end = buf + strlen(buf) - 1;
|
char* end = buf + strlen(buf) - 1;
|
||||||
|
|
||||||
file.writeError = false;
|
file.writeError = false;
|
||||||
if((npos = strchr(buf, 'N')) != NULL){
|
if((npos = strchr(buf, 'N')) != NULL){
|
||||||
begin = strchr(npos, ' ') + 1;
|
begin = strchr(npos, ' ') + 1;
|
||||||
end = strchr(npos, '*') - 1;
|
end = strchr(npos, '*') - 1;
|
||||||
}
|
}
|
||||||
end[1] = '\r';
|
end[1] = '\r';
|
||||||
end[2] = '\n';
|
end[2] = '\n';
|
||||||
end[3] = '\0';
|
end[3] = '\0';
|
||||||
//Serial.println(begin);
|
//Serial.println(begin);
|
||||||
file.write(begin);
|
file.write(begin);
|
||||||
if (file.writeError){
|
if (file.writeError){
|
||||||
Serial.println("error writing to file");
|
Serial.println("error writing to file");
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
#endif //SDSUPPORT
|
#endif //SDSUPPORT
|
||||||
|
|
||||||
|
|
||||||
///adds an command to the main command buffer
|
///adds an command to the main command buffer
|
||||||
void enquecommand(const char *cmd)
|
void enquecommand(const char *cmd)
|
||||||
{
|
{
|
||||||
if(buflen < BUFSIZE)
|
if(buflen < BUFSIZE)
|
||||||
{
|
{
|
||||||
//this is dangerous if a mixing of serial and this happsens
|
//this is dangerous if a mixing of serial and this happsens
|
||||||
strcpy(&(cmdbuffer[bufindw][0]),cmd);
|
strcpy(&(cmdbuffer[bufindw][0]),cmd);
|
||||||
Serial.print("en:");Serial.println(cmdbuffer[bufindw]);
|
Serial.print("en:");Serial.println(cmdbuffer[bufindw]);
|
||||||
bufindw= (bufindw + 1)%BUFSIZE;
|
bufindw= (bufindw + 1)%BUFSIZE;
|
||||||
buflen += 1;
|
buflen += 1;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void setup()
|
void setup()
|
||||||
{
|
{
|
||||||
|
|
||||||
Serial.begin(BAUDRATE);
|
Serial.begin(BAUDRATE);
|
||||||
ECHOLN("Marlin "<<version_string);
|
ECHOLN("Marlin "<<version_string);
|
||||||
Serial.println("start");
|
Serial.println("start");
|
||||||
#if defined FANCY_LCD || defined SIMPLE_LCD
|
#if defined FANCY_LCD || defined SIMPLE_LCD
|
||||||
lcd_init();
|
lcd_init();
|
||||||
#endif
|
#endif
|
||||||
for(int i = 0; i < BUFSIZE; i++){
|
for(int i = 0; i < BUFSIZE; i++){
|
||||||
fromsd[i] = false;
|
fromsd[i] = false;
|
||||||
}
|
}
|
||||||
|
|
||||||
RetrieveSettings(); // loads data from EEPROM if available
|
RetrieveSettings(); // loads data from EEPROM if available
|
||||||
|
|
||||||
|
|
||||||
for(int i=0; i < NUM_AXIS; i++){
|
for(int i=0; i < NUM_AXIS; i++){
|
||||||
axis_steps_per_sqr_second[i] = max_acceleration_units_per_sq_second[i] * axis_steps_per_unit[i];
|
axis_steps_per_sqr_second[i] = max_acceleration_units_per_sq_second[i] * axis_steps_per_unit[i];
|
||||||
}
|
}
|
||||||
|
|
||||||
#ifdef SDSUPPORT
|
#ifdef SDSUPPORT
|
||||||
//power to SD reader
|
//power to SD reader
|
||||||
#if SDPOWER > -1
|
#if SDPOWER > -1
|
||||||
SET_OUTPUT(SDPOWER);
|
SET_OUTPUT(SDPOWER);
|
||||||
WRITE(SDPOWER,HIGH);
|
WRITE(SDPOWER,HIGH);
|
||||||
#endif //SDPOWER
|
#endif //SDPOWER
|
||||||
quickinitsd();
|
quickinitsd();
|
||||||
|
|
||||||
#endif //SDSUPPORT
|
#endif //SDSUPPORT
|
||||||
plan_init(); // Initialize planner;
|
plan_init(); // Initialize planner;
|
||||||
st_init(); // Initialize stepper;
|
st_init(); // Initialize stepper;
|
||||||
tp_init(); // Initialize temperature loop
|
tp_init(); // Initialize temperature loop
|
||||||
//checkautostart();
|
//checkautostart();
|
||||||
}
|
}
|
||||||
|
|
||||||
#ifdef SDSUPPORT
|
#ifdef SDSUPPORT
|
||||||
bool autostart_stilltocheck=true;
|
bool autostart_stilltocheck=true;
|
||||||
|
|
||||||
|
|
||||||
void checkautostart(bool force)
|
void checkautostart(bool force)
|
||||||
{
|
{
|
||||||
//this is to delay autostart and hence the initialisaiton of the sd card to some seconds after the normal init, so the device is available quick after a reset
|
//this is to delay autostart and hence the initialisaiton of the sd card to some seconds after the normal init, so the device is available quick after a reset
|
||||||
if(!force)
|
if(!force)
|
||||||
{
|
{
|
||||||
if(!autostart_stilltocheck)
|
if(!autostart_stilltocheck)
|
||||||
return;
|
return;
|
||||||
if(autostart_atmillis<millis())
|
if(autostart_atmillis<millis())
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
autostart_stilltocheck=false;
|
autostart_stilltocheck=false;
|
||||||
if(!sdactive)
|
if(!sdactive)
|
||||||
{
|
{
|
||||||
initsd();
|
initsd();
|
||||||
if(!sdactive) //fail
|
if(!sdactive) //fail
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
static int lastnr=0;
|
static int lastnr=0;
|
||||||
char autoname[30];
|
char autoname[30];
|
||||||
sprintf(autoname,"auto%i.g",lastnr);
|
sprintf(autoname,"auto%i.g",lastnr);
|
||||||
for(int i=0;i<strlen(autoname);i++)
|
for(int i=0;i<(int)strlen(autoname);i++)
|
||||||
autoname[i]=tolower(autoname[i]);
|
autoname[i]=tolower(autoname[i]);
|
||||||
dir_t p;
|
dir_t p;
|
||||||
|
|
||||||
root.rewind();
|
root.rewind();
|
||||||
char filename[11];
|
//char filename[11];
|
||||||
int cnt=0;
|
//int cnt=0;
|
||||||
|
|
||||||
bool found=false;
|
bool found=false;
|
||||||
while (root.readDir(p) > 0)
|
while (root.readDir(p) > 0)
|
||||||
{
|
{
|
||||||
for(int i=0;i<strlen((char*)p.name);i++)
|
for(int i=0;i<(int)strlen((char*)p.name);i++)
|
||||||
p.name[i]=tolower(p.name[i]);
|
p.name[i]=tolower(p.name[i]);
|
||||||
//Serial.print((char*)p.name);
|
//Serial.print((char*)p.name);
|
||||||
//Serial.print(" ");
|
//Serial.print(" ");
|
||||||
//Serial.println(autoname);
|
//Serial.println(autoname);
|
||||||
if(p.name[9]!='~') //skip safety copies
|
if(p.name[9]!='~') //skip safety copies
|
||||||
if(strncmp((char*)p.name,autoname,5)==0)
|
if(strncmp((char*)p.name,autoname,5)==0)
|
||||||
{
|
{
|
||||||
char cmd[30];
|
char cmd[30];
|
||||||
|
|
||||||
sprintf(cmd,"M23 %s",autoname);
|
sprintf(cmd,"M23 %s",autoname);
|
||||||
//sprintf(cmd,"M115");
|
//sprintf(cmd,"M115");
|
||||||
//enquecommand("G92 Z0");
|
//enquecommand("G92 Z0");
|
||||||
//enquecommand("G1 Z10 F2000");
|
//enquecommand("G1 Z10 F2000");
|
||||||
//enquecommand("G28 X-105 Y-105");
|
//enquecommand("G28 X-105 Y-105");
|
||||||
enquecommand(cmd);
|
enquecommand(cmd);
|
||||||
enquecommand("M24");
|
enquecommand("M24");
|
||||||
found=true;
|
found=true;
|
||||||
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
if(!found)
|
if(!found)
|
||||||
lastnr=-1;
|
lastnr=-1;
|
||||||
else
|
else
|
||||||
lastnr++;
|
lastnr++;
|
||||||
|
|
||||||
}
|
}
|
||||||
#else
|
#else
|
||||||
|
|
||||||
inline void checkautostart(bool x)
|
inline void checkautostart(bool x)
|
||||||
{
|
{
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
||||||
void loop()
|
void loop()
|
||||||
{
|
{
|
||||||
if(buflen<3)
|
if(buflen<3)
|
||||||
get_command();
|
get_command();
|
||||||
checkautostart(false);
|
checkautostart(false);
|
||||||
if(buflen)
|
if(buflen)
|
||||||
{
|
{
|
||||||
#ifdef SDSUPPORT
|
#ifdef SDSUPPORT
|
||||||
if(savetosd){
|
if(savetosd){
|
||||||
if(strstr(cmdbuffer[bufindr],"M29") == NULL){
|
if(strstr(cmdbuffer[bufindr],"M29") == NULL){
|
||||||
write_command(cmdbuffer[bufindr]);
|
write_command(cmdbuffer[bufindr]);
|
||||||
Serial.println("ok");
|
Serial.println("ok");
|
||||||
}
|
}
|
||||||
else{
|
else{
|
||||||
file.sync();
|
file.sync();
|
||||||
file.close();
|
file.close();
|
||||||
savetosd = false;
|
savetosd = false;
|
||||||
Serial.println("Done saving file.");
|
Serial.println("Done saving file.");
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
else{
|
else{
|
||||||
process_commands();
|
process_commands();
|
||||||
}
|
}
|
||||||
#else
|
#else
|
||||||
process_commands();
|
process_commands();
|
||||||
#endif //SDSUPPORT
|
#endif //SDSUPPORT
|
||||||
buflen = (buflen-1);
|
buflen = (buflen-1);
|
||||||
bufindr = (bufindr + 1)%BUFSIZE;
|
bufindr = (bufindr + 1)%BUFSIZE;
|
||||||
}
|
}
|
||||||
//check heater every n milliseconds
|
//check heater every n milliseconds
|
||||||
manage_heater();
|
manage_heater();
|
||||||
manage_inactivity(1);
|
manage_inactivity(1);
|
||||||
LCD_STATUS;
|
LCD_STATUS;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
inline void get_command()
|
inline void get_command()
|
||||||
{
|
{
|
||||||
while( Serial.available() > 0 && buflen < BUFSIZE) {
|
while( Serial.available() > 0 && buflen < BUFSIZE) {
|
||||||
serial_char = Serial.read();
|
serial_char = Serial.read();
|
||||||
if(serial_char == '\n' || serial_char == '\r' || serial_char == ':' || serial_count >= (MAX_CMD_SIZE - 1) )
|
if(serial_char == '\n' || serial_char == '\r' || serial_char == ':' || serial_count >= (MAX_CMD_SIZE - 1) )
|
||||||
{
|
{
|
||||||
if(!serial_count) return; //if empty line
|
if(!serial_count) return; //if empty line
|
||||||
cmdbuffer[bufindw][serial_count] = 0; //terminate string
|
cmdbuffer[bufindw][serial_count] = 0; //terminate string
|
||||||
if(!comment_mode){
|
if(!comment_mode){
|
||||||
fromsd[bufindw] = false;
|
fromsd[bufindw] = false;
|
||||||
if(strstr(cmdbuffer[bufindw], "N") != NULL)
|
if(strstr(cmdbuffer[bufindw], "N") != NULL)
|
||||||
{
|
{
|
||||||
strchr_pointer = strchr(cmdbuffer[bufindw], 'N');
|
strchr_pointer = strchr(cmdbuffer[bufindw], 'N');
|
||||||
gcode_N = (strtol(&cmdbuffer[bufindw][strchr_pointer - cmdbuffer[bufindw] + 1], NULL, 10));
|
gcode_N = (strtol(&cmdbuffer[bufindw][strchr_pointer - cmdbuffer[bufindw] + 1], NULL, 10));
|
||||||
if(gcode_N != gcode_LastN+1 && (strstr(cmdbuffer[bufindw], "M110") == NULL) ) {
|
if(gcode_N != gcode_LastN+1 && (strstr(cmdbuffer[bufindw], "M110") == NULL) ) {
|
||||||
Serial.print("Serial Error: Line Number is not Last Line Number+1, Last Line:");
|
Serial.print("Serial Error: Line Number is not Last Line Number+1, Last Line:");
|
||||||
Serial.println(gcode_LastN);
|
Serial.println(gcode_LastN);
|
||||||
//Serial.println(gcode_N);
|
//Serial.println(gcode_N);
|
||||||
FlushSerialRequestResend();
|
FlushSerialRequestResend();
|
||||||
serial_count = 0;
|
serial_count = 0;
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
if(strstr(cmdbuffer[bufindw], "*") != NULL)
|
if(strstr(cmdbuffer[bufindw], "*") != NULL)
|
||||||
{
|
{
|
||||||
byte checksum = 0;
|
byte checksum = 0;
|
||||||
byte count = 0;
|
byte count = 0;
|
||||||
while(cmdbuffer[bufindw][count] != '*') checksum = checksum^cmdbuffer[bufindw][count++];
|
while(cmdbuffer[bufindw][count] != '*') checksum = checksum^cmdbuffer[bufindw][count++];
|
||||||
strchr_pointer = strchr(cmdbuffer[bufindw], '*');
|
strchr_pointer = strchr(cmdbuffer[bufindw], '*');
|
||||||
|
|
||||||
if( (int)(strtod(&cmdbuffer[bufindw][strchr_pointer - cmdbuffer[bufindw] + 1], NULL)) != checksum) {
|
if( (int)(strtod(&cmdbuffer[bufindw][strchr_pointer - cmdbuffer[bufindw] + 1], NULL)) != checksum) {
|
||||||
Serial.print("Error: checksum mismatch, Last Line:");
|
Serial.print("Error: checksum mismatch, Last Line:");
|
||||||
Serial.println(gcode_LastN);
|
Serial.println(gcode_LastN);
|
||||||
FlushSerialRequestResend();
|
FlushSerialRequestResend();
|
||||||
serial_count = 0;
|
serial_count = 0;
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
//if no errors, continue parsing
|
//if no errors, continue parsing
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
Serial.print("Error: No Checksum with line number, Last Line:");
|
Serial.print("Error: No Checksum with line number, Last Line:");
|
||||||
Serial.println(gcode_LastN);
|
Serial.println(gcode_LastN);
|
||||||
FlushSerialRequestResend();
|
FlushSerialRequestResend();
|
||||||
serial_count = 0;
|
serial_count = 0;
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
gcode_LastN = gcode_N;
|
gcode_LastN = gcode_N;
|
||||||
//if no errors, continue parsing
|
//if no errors, continue parsing
|
||||||
}
|
}
|
||||||
else // if we don't receive 'N' but still see '*'
|
else // if we don't receive 'N' but still see '*'
|
||||||
{
|
{
|
||||||
if((strstr(cmdbuffer[bufindw], "*") != NULL))
|
if((strstr(cmdbuffer[bufindw], "*") != NULL))
|
||||||
{
|
{
|
||||||
Serial.print("Error: No Line Number with checksum, Last Line:");
|
Serial.print("Error: No Line Number with checksum, Last Line:");
|
||||||
Serial.println(gcode_LastN);
|
Serial.println(gcode_LastN);
|
||||||
serial_count = 0;
|
serial_count = 0;
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
if((strstr(cmdbuffer[bufindw], "G") != NULL)){
|
if((strstr(cmdbuffer[bufindw], "G") != NULL)){
|
||||||
strchr_pointer = strchr(cmdbuffer[bufindw], 'G');
|
strchr_pointer = strchr(cmdbuffer[bufindw], 'G');
|
||||||
switch((int)((strtod(&cmdbuffer[bufindw][strchr_pointer - cmdbuffer[bufindw] + 1], NULL)))){
|
switch((int)((strtod(&cmdbuffer[bufindw][strchr_pointer - cmdbuffer[bufindw] + 1], NULL)))){
|
||||||
case 0:
|
case 0:
|
||||||
case 1:
|
case 1:
|
||||||
#ifdef SDSUPPORT
|
#ifdef SDSUPPORT
|
||||||
if(savetosd)
|
if(savetosd)
|
||||||
break;
|
break;
|
||||||
#endif //SDSUPPORT
|
#endif //SDSUPPORT
|
||||||
Serial.println("ok");
|
Serial.println("ok");
|
||||||
break;
|
break;
|
||||||
default:
|
default:
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
bufindw = (bufindw + 1)%BUFSIZE;
|
bufindw = (bufindw + 1)%BUFSIZE;
|
||||||
buflen += 1;
|
buflen += 1;
|
||||||
|
|
||||||
}
|
}
|
||||||
comment_mode = false; //for new command
|
comment_mode = false; //for new command
|
||||||
serial_count = 0; //clear buffer
|
serial_count = 0; //clear buffer
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
if(serial_char == ';') comment_mode = true;
|
if(serial_char == ';') comment_mode = true;
|
||||||
if(!comment_mode) cmdbuffer[bufindw][serial_count++] = serial_char;
|
if(!comment_mode) cmdbuffer[bufindw][serial_count++] = serial_char;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
#ifdef SDSUPPORT
|
#ifdef SDSUPPORT
|
||||||
if(!sdmode || serial_count!=0){
|
if(!sdmode || serial_count!=0){
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
while( filesize > sdpos && buflen < BUFSIZE) {
|
while( filesize > sdpos && buflen < BUFSIZE) {
|
||||||
n = file.read();
|
n = file.read();
|
||||||
serial_char = (char)n;
|
serial_char = (char)n;
|
||||||
if(serial_char == '\n' || serial_char == '\r' || serial_char == ':' || serial_count >= (MAX_CMD_SIZE - 1) || n == -1)
|
if(serial_char == '\n' || serial_char == '\r' || serial_char == ':' || serial_count >= (MAX_CMD_SIZE - 1) || n == -1)
|
||||||
{
|
{
|
||||||
sdpos = file.curPosition();
|
sdpos = file.curPosition();
|
||||||
if(sdpos >= filesize){
|
if(sdpos >= filesize){
|
||||||
sdmode = false;
|
sdmode = false;
|
||||||
Serial.println("Done printing file");
|
Serial.println("Done printing file");
|
||||||
stoptime=millis();
|
stoptime=millis();
|
||||||
char time[30];
|
char time[30];
|
||||||
unsigned long t=(stoptime-starttime)/1000;
|
unsigned long t=(stoptime-starttime)/1000;
|
||||||
int sec,min;
|
int sec,min;
|
||||||
min=t/60;
|
min=t/60;
|
||||||
sec=t%60;
|
sec=t%60;
|
||||||
sprintf(time,"%i min, %i sec",min,sec);
|
sprintf(time,"%i min, %i sec",min,sec);
|
||||||
Serial.println(time);
|
Serial.println(time);
|
||||||
LCD_MESSAGE(time);
|
LCD_MESSAGE(time);
|
||||||
checkautostart(true);
|
checkautostart(true);
|
||||||
}
|
}
|
||||||
if(!serial_count) return; //if empty line
|
if(!serial_count) return; //if empty line
|
||||||
cmdbuffer[bufindw][serial_count] = 0; //terminate string
|
cmdbuffer[bufindw][serial_count] = 0; //terminate string
|
||||||
if(!comment_mode){
|
if(!comment_mode){
|
||||||
fromsd[bufindw] = true;
|
fromsd[bufindw] = true;
|
||||||
buflen += 1;
|
buflen += 1;
|
||||||
bufindw = (bufindw + 1)%BUFSIZE;
|
bufindw = (bufindw + 1)%BUFSIZE;
|
||||||
}
|
}
|
||||||
comment_mode = false; //for new command
|
comment_mode = false; //for new command
|
||||||
serial_count = 0; //clear buffer
|
serial_count = 0; //clear buffer
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
if(serial_char == ';') comment_mode = true;
|
if(serial_char == ';') comment_mode = true;
|
||||||
if(!comment_mode) cmdbuffer[bufindw][serial_count++] = serial_char;
|
if(!comment_mode) cmdbuffer[bufindw][serial_count++] = serial_char;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
#endif //SDSUPPORT
|
#endif //SDSUPPORT
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
inline float code_value() {
|
inline float code_value() {
|
||||||
return (strtod(&cmdbuffer[bufindr][strchr_pointer - cmdbuffer[bufindr] + 1], NULL));
|
return (strtod(&cmdbuffer[bufindr][strchr_pointer - cmdbuffer[bufindr] + 1], NULL));
|
||||||
}
|
}
|
||||||
inline long code_value_long() {
|
inline long code_value_long() {
|
||||||
return (strtol(&cmdbuffer[bufindr][strchr_pointer - cmdbuffer[bufindr] + 1], NULL, 10));
|
return (strtol(&cmdbuffer[bufindr][strchr_pointer - cmdbuffer[bufindr] + 1], NULL, 10));
|
||||||
}
|
}
|
||||||
inline bool code_seen(char code_string[]) {
|
inline bool code_seen(char code_string[]) {
|
||||||
return (strstr(cmdbuffer[bufindr], code_string) != NULL);
|
return (strstr(cmdbuffer[bufindr], code_string) != NULL);
|
||||||
} //Return True if the string was found
|
} //Return True if the string was found
|
||||||
|
|
||||||
inline bool code_seen(char code)
|
inline bool code_seen(char code)
|
||||||
{
|
{
|
||||||
strchr_pointer = strchr(cmdbuffer[bufindr], code);
|
strchr_pointer = strchr(cmdbuffer[bufindr], code);
|
||||||
return (strchr_pointer != NULL); //Return True if a character was found
|
return (strchr_pointer != NULL); //Return True if a character was found
|
||||||
}
|
}
|
||||||
|
|
||||||
inline void process_commands()
|
inline void process_commands()
|
||||||
{
|
{
|
||||||
unsigned long codenum; //throw away variable
|
unsigned long codenum; //throw away variable
|
||||||
char *starpos = NULL;
|
char *starpos = NULL;
|
||||||
|
|
||||||
if(code_seen('G'))
|
if(code_seen('G'))
|
||||||
{
|
{
|
||||||
switch((int)code_value())
|
switch((int)code_value())
|
||||||
{
|
{
|
||||||
case 0: // G0 -> G1
|
case 0: // G0 -> G1
|
||||||
case 1: // G1
|
case 1: // G1
|
||||||
get_coordinates(); // For X Y Z E F
|
get_coordinates(); // For X Y Z E F
|
||||||
prepare_move();
|
prepare_move();
|
||||||
previous_millis_cmd = millis();
|
previous_millis_cmd = millis();
|
||||||
//ClearToSend();
|
//ClearToSend();
|
||||||
return;
|
return;
|
||||||
//break;
|
//break;
|
||||||
case 4: // G4 dwell
|
case 4: // G4 dwell
|
||||||
codenum = 0;
|
codenum = 0;
|
||||||
if(code_seen('P')) codenum = code_value(); // milliseconds to wait
|
if(code_seen('P')) codenum = code_value(); // milliseconds to wait
|
||||||
if(code_seen('S')) codenum = code_value() * 1000; // seconds to wait
|
if(code_seen('S')) codenum = code_value() * 1000; // seconds to wait
|
||||||
codenum += millis(); // keep track of when we started waiting
|
codenum += millis(); // keep track of when we started waiting
|
||||||
while(millis() < codenum ){
|
while(millis() < codenum ){
|
||||||
manage_heater();
|
manage_heater();
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
case 28: //G28 Home all Axis one at a time
|
case 28: //G28 Home all Axis one at a time
|
||||||
saved_feedrate = feedrate;
|
saved_feedrate = feedrate;
|
||||||
saved_feedmultiply = feedmultiply;
|
saved_feedmultiply = feedmultiply;
|
||||||
feedmultiply = 100;
|
feedmultiply = 100;
|
||||||
|
|
||||||
for(int i=0; i < NUM_AXIS; i++) {
|
for(int i=0; i < NUM_AXIS; i++) {
|
||||||
destination[i] = current_position[i];
|
destination[i] = current_position[i];
|
||||||
}
|
}
|
||||||
feedrate = 0.0;
|
feedrate = 0.0;
|
||||||
|
|
||||||
home_all_axis = !((code_seen(axis_codes[0])) || (code_seen(axis_codes[1])) || (code_seen(axis_codes[2])));
|
home_all_axis = !((code_seen(axis_codes[0])) || (code_seen(axis_codes[1])) || (code_seen(axis_codes[2])));
|
||||||
|
|
||||||
if((home_all_axis) || (code_seen(axis_codes[X_AXIS]))) {
|
if((home_all_axis) || (code_seen(axis_codes[X_AXIS]))) {
|
||||||
if ((X_MIN_PIN > -1 && X_HOME_DIR==-1) || (X_MAX_PIN > -1 && X_HOME_DIR==1)){
|
if ((X_MIN_PIN > -1 && X_HOME_DIR==-1) || (X_MAX_PIN > -1 && X_HOME_DIR==1)){
|
||||||
// st_synchronize();
|
// st_synchronize();
|
||||||
current_position[X_AXIS] = 0;
|
current_position[X_AXIS] = 0;
|
||||||
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]);
|
||||||
destination[X_AXIS] = 1.5 * X_MAX_LENGTH * X_HOME_DIR;
|
destination[X_AXIS] = 1.5 * X_MAX_LENGTH * X_HOME_DIR;
|
||||||
feedrate = homing_feedrate[X_AXIS];
|
feedrate = homing_feedrate[X_AXIS];
|
||||||
prepare_move();
|
prepare_move();
|
||||||
|
|
||||||
// st_synchronize();
|
// st_synchronize();
|
||||||
current_position[X_AXIS] = 0;
|
current_position[X_AXIS] = 0;
|
||||||
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]);
|
||||||
destination[X_AXIS] = -5 * X_HOME_DIR;
|
destination[X_AXIS] = -5 * X_HOME_DIR;
|
||||||
prepare_move();
|
prepare_move();
|
||||||
|
|
||||||
// st_synchronize();
|
// st_synchronize();
|
||||||
destination[X_AXIS] = 10 * X_HOME_DIR;
|
destination[X_AXIS] = 10 * X_HOME_DIR;
|
||||||
feedrate = homing_feedrate[X_AXIS]/2 ;
|
feedrate = homing_feedrate[X_AXIS]/2 ;
|
||||||
prepare_move();
|
prepare_move();
|
||||||
|
|
||||||
// st_synchronize();
|
// st_synchronize();
|
||||||
current_position[X_AXIS] = (X_HOME_DIR == -1) ? 0 : X_MAX_LENGTH;
|
current_position[X_AXIS] = (X_HOME_DIR == -1) ? 0 : X_MAX_LENGTH;
|
||||||
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]);
|
||||||
destination[X_AXIS] = current_position[X_AXIS];
|
destination[X_AXIS] = current_position[X_AXIS];
|
||||||
feedrate = 0.0;
|
feedrate = 0.0;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
if((home_all_axis) || (code_seen(axis_codes[Y_AXIS]))) {
|
if((home_all_axis) || (code_seen(axis_codes[Y_AXIS]))) {
|
||||||
if ((Y_MIN_PIN > -1 && Y_HOME_DIR==-1) || (Y_MAX_PIN > -1 && Y_HOME_DIR==1)){
|
if ((Y_MIN_PIN > -1 && Y_HOME_DIR==-1) || (Y_MAX_PIN > -1 && Y_HOME_DIR==1)){
|
||||||
current_position[Y_AXIS] = 0;
|
current_position[Y_AXIS] = 0;
|
||||||
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]);
|
||||||
destination[Y_AXIS] = 1.5 * Y_MAX_LENGTH * Y_HOME_DIR;
|
destination[Y_AXIS] = 1.5 * Y_MAX_LENGTH * Y_HOME_DIR;
|
||||||
feedrate = homing_feedrate[Y_AXIS];
|
feedrate = homing_feedrate[Y_AXIS];
|
||||||
prepare_move();
|
prepare_move();
|
||||||
// st_synchronize();
|
// st_synchronize();
|
||||||
|
|
||||||
current_position[Y_AXIS] = 0;
|
current_position[Y_AXIS] = 0;
|
||||||
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]);
|
||||||
destination[Y_AXIS] = -5 * Y_HOME_DIR;
|
destination[Y_AXIS] = -5 * Y_HOME_DIR;
|
||||||
prepare_move();
|
prepare_move();
|
||||||
// st_synchronize();
|
// st_synchronize();
|
||||||
|
|
||||||
destination[Y_AXIS] = 10 * Y_HOME_DIR;
|
destination[Y_AXIS] = 10 * Y_HOME_DIR;
|
||||||
feedrate = homing_feedrate[Y_AXIS]/2;
|
feedrate = homing_feedrate[Y_AXIS]/2;
|
||||||
prepare_move();
|
prepare_move();
|
||||||
// st_synchronize();
|
// st_synchronize();
|
||||||
|
|
||||||
current_position[Y_AXIS] = (Y_HOME_DIR == -1) ? 0 : Y_MAX_LENGTH;
|
current_position[Y_AXIS] = (Y_HOME_DIR == -1) ? 0 : Y_MAX_LENGTH;
|
||||||
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]);
|
||||||
destination[Y_AXIS] = current_position[Y_AXIS];
|
destination[Y_AXIS] = current_position[Y_AXIS];
|
||||||
feedrate = 0.0;
|
feedrate = 0.0;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
if((home_all_axis) || (code_seen(axis_codes[Z_AXIS]))) {
|
if((home_all_axis) || (code_seen(axis_codes[Z_AXIS]))) {
|
||||||
if ((Z_MIN_PIN > -1 && Z_HOME_DIR==-1) || (Z_MAX_PIN > -1 && Z_HOME_DIR==1)){
|
if ((Z_MIN_PIN > -1 && Z_HOME_DIR==-1) || (Z_MAX_PIN > -1 && Z_HOME_DIR==1)){
|
||||||
current_position[Z_AXIS] = 0;
|
current_position[Z_AXIS] = 0;
|
||||||
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]);
|
||||||
destination[Z_AXIS] = 1.5 * Z_MAX_LENGTH * Z_HOME_DIR;
|
destination[Z_AXIS] = 1.5 * Z_MAX_LENGTH * Z_HOME_DIR;
|
||||||
feedrate = homing_feedrate[Z_AXIS];
|
feedrate = homing_feedrate[Z_AXIS];
|
||||||
prepare_move();
|
prepare_move();
|
||||||
// st_synchronize();
|
// st_synchronize();
|
||||||
|
|
||||||
current_position[Z_AXIS] = 0;
|
current_position[Z_AXIS] = 0;
|
||||||
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]);
|
||||||
destination[Z_AXIS] = -2 * Z_HOME_DIR;
|
destination[Z_AXIS] = -2 * Z_HOME_DIR;
|
||||||
prepare_move();
|
prepare_move();
|
||||||
// st_synchronize();
|
// st_synchronize();
|
||||||
|
|
||||||
destination[Z_AXIS] = 3 * Z_HOME_DIR;
|
destination[Z_AXIS] = 3 * Z_HOME_DIR;
|
||||||
feedrate = homing_feedrate[Z_AXIS]/2;
|
feedrate = homing_feedrate[Z_AXIS]/2;
|
||||||
prepare_move();
|
prepare_move();
|
||||||
// st_synchronize();
|
// st_synchronize();
|
||||||
|
|
||||||
current_position[Z_AXIS] = (Z_HOME_DIR == -1) ? 0 : Z_MAX_LENGTH;
|
current_position[Z_AXIS] = (Z_HOME_DIR == -1) ? 0 : Z_MAX_LENGTH;
|
||||||
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]);
|
||||||
destination[Z_AXIS] = current_position[Z_AXIS];
|
destination[Z_AXIS] = current_position[Z_AXIS];
|
||||||
feedrate = 0.0;
|
feedrate = 0.0;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
feedrate = saved_feedrate;
|
feedrate = saved_feedrate;
|
||||||
feedmultiply = saved_feedmultiply;
|
feedmultiply = saved_feedmultiply;
|
||||||
previous_millis_cmd = millis();
|
previous_millis_cmd = millis();
|
||||||
break;
|
break;
|
||||||
case 90: // G90
|
case 90: // G90
|
||||||
relative_mode = false;
|
relative_mode = false;
|
||||||
break;
|
break;
|
||||||
case 91: // G91
|
case 91: // G91
|
||||||
relative_mode = true;
|
relative_mode = true;
|
||||||
break;
|
break;
|
||||||
case 92: // G92
|
case 92: // G92
|
||||||
if(!code_seen(axis_codes[E_AXIS]))
|
if(!code_seen(axis_codes[E_AXIS]))
|
||||||
st_synchronize();
|
st_synchronize();
|
||||||
for(int i=0; i < NUM_AXIS; i++) {
|
for(int i=0; i < NUM_AXIS; i++) {
|
||||||
if(code_seen(axis_codes[i])) current_position[i] = code_value();
|
if(code_seen(axis_codes[i])) current_position[i] = code_value();
|
||||||
}
|
}
|
||||||
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]);
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
else if(code_seen('M'))
|
else if(code_seen('M'))
|
||||||
{
|
{
|
||||||
|
|
||||||
switch( (int)code_value() )
|
switch( (int)code_value() )
|
||||||
{
|
{
|
||||||
#ifdef SDSUPPORT
|
#ifdef SDSUPPORT
|
||||||
|
|
||||||
case 20: // M20 - list SD card
|
case 20: // M20 - list SD card
|
||||||
Serial.println("Begin file list");
|
Serial.println("Begin file list");
|
||||||
root.ls();
|
root.ls();
|
||||||
Serial.println("End file list");
|
Serial.println("End file list");
|
||||||
break;
|
break;
|
||||||
case 21: // M21 - init SD card
|
case 21: // M21 - init SD card
|
||||||
sdmode = false;
|
sdmode = false;
|
||||||
initsd();
|
initsd();
|
||||||
break;
|
break;
|
||||||
case 22: //M22 - release SD card
|
case 22: //M22 - release SD card
|
||||||
sdmode = false;
|
sdmode = false;
|
||||||
sdactive = false;
|
sdactive = false;
|
||||||
break;
|
break;
|
||||||
case 23: //M23 - Select file
|
case 23: //M23 - Select file
|
||||||
if(sdactive){
|
if(sdactive){
|
||||||
sdmode = false;
|
sdmode = false;
|
||||||
file.close();
|
file.close();
|
||||||
starpos = (strchr(strchr_pointer + 4,'*'));
|
starpos = (strchr(strchr_pointer + 4,'*'));
|
||||||
if(starpos!=NULL)
|
if(starpos!=NULL)
|
||||||
*(starpos-1)='\0';
|
*(starpos-1)='\0';
|
||||||
if (file.open(&root, strchr_pointer + 4, O_READ)) {
|
if (file.open(&root, strchr_pointer + 4, O_READ)) {
|
||||||
Serial.print("File opened:");
|
Serial.print("File opened:");
|
||||||
Serial.print(strchr_pointer + 4);
|
Serial.print(strchr_pointer + 4);
|
||||||
Serial.print(" Size:");
|
Serial.print(" Size:");
|
||||||
Serial.println(file.fileSize());
|
Serial.println(file.fileSize());
|
||||||
sdpos = 0;
|
sdpos = 0;
|
||||||
filesize = file.fileSize();
|
filesize = file.fileSize();
|
||||||
Serial.println("File selected");
|
Serial.println("File selected");
|
||||||
}
|
}
|
||||||
else{
|
else{
|
||||||
Serial.println("file.open failed");
|
Serial.println("file.open failed");
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
case 24: //M24 - Start SD print
|
case 24: //M24 - Start SD print
|
||||||
if(sdactive){
|
if(sdactive){
|
||||||
sdmode = true;
|
sdmode = true;
|
||||||
starttime=millis();
|
starttime=millis();
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
case 25: //M25 - Pause SD print
|
case 25: //M25 - Pause SD print
|
||||||
if(sdmode){
|
if(sdmode){
|
||||||
sdmode = false;
|
sdmode = false;
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
case 26: //M26 - Set SD index
|
case 26: //M26 - Set SD index
|
||||||
if(sdactive && code_seen('S')){
|
if(sdactive && code_seen('S')){
|
||||||
sdpos = code_value_long();
|
sdpos = code_value_long();
|
||||||
file.seekSet(sdpos);
|
file.seekSet(sdpos);
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
case 27: //M27 - Get SD status
|
case 27: //M27 - Get SD status
|
||||||
if(sdactive){
|
if(sdactive){
|
||||||
Serial.print("SD printing byte ");
|
Serial.print("SD printing byte ");
|
||||||
Serial.print(sdpos);
|
Serial.print(sdpos);
|
||||||
Serial.print("/");
|
Serial.print("/");
|
||||||
Serial.println(filesize);
|
Serial.println(filesize);
|
||||||
}
|
}
|
||||||
else{
|
else{
|
||||||
Serial.println("Not SD printing");
|
Serial.println("Not SD printing");
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
case 28: //M28 - Start SD write
|
case 28: //M28 - Start SD write
|
||||||
if(sdactive){
|
if(sdactive){
|
||||||
char* npos = 0;
|
char* npos = 0;
|
||||||
file.close();
|
file.close();
|
||||||
sdmode = false;
|
sdmode = false;
|
||||||
starpos = (strchr(strchr_pointer + 4,'*'));
|
starpos = (strchr(strchr_pointer + 4,'*'));
|
||||||
if(starpos != NULL){
|
if(starpos != NULL){
|
||||||
npos = strchr(cmdbuffer[bufindr], 'N');
|
npos = strchr(cmdbuffer[bufindr], 'N');
|
||||||
strchr_pointer = strchr(npos,' ') + 1;
|
strchr_pointer = strchr(npos,' ') + 1;
|
||||||
*(starpos-1) = '\0';
|
*(starpos-1) = '\0';
|
||||||
}
|
}
|
||||||
if (!file.open(&root, strchr_pointer+4, O_CREAT | O_APPEND | O_WRITE | O_TRUNC))
|
if (!file.open(&root, strchr_pointer+4, O_CREAT | O_APPEND | O_WRITE | O_TRUNC))
|
||||||
{
|
{
|
||||||
Serial.print("open failed, File: ");
|
Serial.print("open failed, File: ");
|
||||||
Serial.print(strchr_pointer + 4);
|
Serial.print(strchr_pointer + 4);
|
||||||
Serial.print(".");
|
Serial.print(".");
|
||||||
}
|
}
|
||||||
else{
|
else{
|
||||||
savetosd = true;
|
savetosd = true;
|
||||||
Serial.print("Writing to file: ");
|
Serial.print("Writing to file: ");
|
||||||
Serial.println(strchr_pointer + 4);
|
Serial.println(strchr_pointer + 4);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
case 29: //M29 - Stop SD write
|
case 29: //M29 - Stop SD write
|
||||||
//processed in write to file routine above
|
//processed in write to file routine above
|
||||||
//savetosd = false;
|
//savetosd = false;
|
||||||
break;
|
break;
|
||||||
case 30:
|
case 30:
|
||||||
{
|
{
|
||||||
stoptime=millis();
|
stoptime=millis();
|
||||||
char time[30];
|
char time[30];
|
||||||
unsigned long t=(stoptime-starttime)/1000;
|
unsigned long t=(stoptime-starttime)/1000;
|
||||||
int sec,min;
|
int sec,min;
|
||||||
min=t/60;
|
min=t/60;
|
||||||
sec=t%60;
|
sec=t%60;
|
||||||
sprintf(time,"%i min, %i sec",min,sec);
|
sprintf(time,"%i min, %i sec",min,sec);
|
||||||
Serial.println(time);
|
Serial.println(time);
|
||||||
LCD_MESSAGE(time);
|
LCD_MESSAGE(time);
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
#endif //SDSUPPORT
|
#endif //SDSUPPORT
|
||||||
case 42: //M42 -Change pin status via gcode
|
case 42: //M42 -Change pin status via gcode
|
||||||
if (code_seen('S'))
|
if (code_seen('S'))
|
||||||
{
|
{
|
||||||
int pin_status = code_value();
|
int pin_status = code_value();
|
||||||
if (code_seen('P') && pin_status >= 0 && pin_status <= 255)
|
if (code_seen('P') && pin_status >= 0 && pin_status <= 255)
|
||||||
{
|
{
|
||||||
int pin_number = code_value();
|
int pin_number = code_value();
|
||||||
for(int i = 0; i < sizeof(sensitive_pins); i++)
|
for(int i = 0; i < (int)sizeof(sensitive_pins); i++)
|
||||||
{
|
{
|
||||||
if (sensitive_pins[i] == pin_number)
|
if (sensitive_pins[i] == pin_number)
|
||||||
{
|
{
|
||||||
pin_number = -1;
|
pin_number = -1;
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
if (pin_number > -1)
|
if (pin_number > -1)
|
||||||
{
|
{
|
||||||
pinMode(pin_number, OUTPUT);
|
pinMode(pin_number, OUTPUT);
|
||||||
digitalWrite(pin_number, pin_status);
|
digitalWrite(pin_number, pin_status);
|
||||||
analogWrite(pin_number, pin_status);
|
analogWrite(pin_number, pin_status);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
case 104: // M104
|
case 104: // M104
|
||||||
if (code_seen('S')) target_raw[0] = temp2analog(code_value());
|
if (code_seen('S')) target_raw[TEMPSENSOR_HOTEND] = temp2analog(code_value());
|
||||||
#ifdef PIDTEMP
|
#ifdef PIDTEMP
|
||||||
pid_setpoint = code_value();
|
pid_setpoint = code_value();
|
||||||
#endif //PIDTEM
|
#endif //PIDTEM
|
||||||
#ifdef WATCHPERIOD
|
#ifdef WATCHPERIOD
|
||||||
if(target_raw[0] > current_raw[0]){
|
if(target_raw[TEMPSENSOR_HOTEND] > current_raw[TEMPSENSOR_HOTEND]){
|
||||||
watchmillis = max(1,millis());
|
watchmillis = max(1,millis());
|
||||||
watch_raw = current_raw[0];
|
watch_raw[TEMPSENSOR_HOTEND] = current_raw[TEMPSENSOR_HOTEND];
|
||||||
}else{
|
}else{
|
||||||
watchmillis = 0;
|
watchmillis = 0;
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
break;
|
break;
|
||||||
case 140: // M140 set bed temp
|
case 140: // M140 set bed temp
|
||||||
if (code_seen('S')) target_raw[1] = temp2analogBed(code_value());
|
if (code_seen('S')) target_raw[TEMPSENSOR_BED] = temp2analogBed(code_value());
|
||||||
break;
|
break;
|
||||||
case 105: // M105
|
case 105: // M105
|
||||||
#if (TEMP_0_PIN > -1) || defined (HEATER_USES_AD595)
|
#if (TEMP_0_PIN > -1) || defined (HEATER_USES_AD595)
|
||||||
tt = analog2temp(current_raw[0]);
|
tt = analog2temp(current_raw[TEMPSENSOR_HOTEND]);
|
||||||
#endif
|
#endif
|
||||||
#if TEMP_1_PIN > -1
|
#if TEMP_1_PIN > -1
|
||||||
bt = analog2tempBed(current_raw[1]);
|
bt = analog2tempBed(current_raw[TEMPSENSOR_BED]);
|
||||||
#endif
|
#endif
|
||||||
#if (TEMP_0_PIN > -1) || defined (HEATER_USES_AD595)
|
#if (TEMP_0_PIN > -1) || defined (HEATER_USES_AD595)
|
||||||
Serial.print("ok T:");
|
Serial.print("ok T:");
|
||||||
Serial.print(tt);
|
Serial.print(tt);
|
||||||
// Serial.print(", raw:");
|
// Serial.print(", raw:");
|
||||||
// Serial.print(current_raw);
|
// Serial.print(current_raw);
|
||||||
#if TEMP_1_PIN > -1
|
#if TEMP_1_PIN > -1
|
||||||
#ifdef PIDTEMP
|
#ifdef PIDTEMP
|
||||||
Serial.print(" B:");
|
Serial.print(" B:");
|
||||||
#if TEMP_1_PIN > -1
|
#if TEMP_1_PIN > -1
|
||||||
Serial.println(bt);
|
Serial.println(bt);
|
||||||
#else
|
#else
|
||||||
Serial.println(HeaterPower);
|
Serial.println(HeaterPower);
|
||||||
#endif
|
#endif
|
||||||
#else
|
#else
|
||||||
Serial.println();
|
Serial.println();
|
||||||
#endif
|
#endif
|
||||||
#else
|
#else
|
||||||
Serial.println();
|
Serial.println();
|
||||||
#endif
|
#endif
|
||||||
#else
|
#else
|
||||||
Serial.println("No thermistors - no temp");
|
Serial.println("No thermistors - no temp");
|
||||||
#endif
|
#endif
|
||||||
return;
|
return;
|
||||||
//break;
|
//break;
|
||||||
case 109: {// M109 - Wait for extruder heater to reach target.
|
case 109: {// M109 - Wait for extruder heater to reach target.
|
||||||
LCD_MESSAGE("Heating...");
|
LCD_MESSAGE("Heating...");
|
||||||
if (code_seen('S')) target_raw[0] = temp2analog(code_value());
|
if (code_seen('S')) target_raw[TEMPSENSOR_HOTEND] = temp2analog(code_value());
|
||||||
#ifdef PIDTEMP
|
#ifdef PIDTEMP
|
||||||
pid_setpoint = code_value();
|
pid_setpoint = code_value();
|
||||||
#endif //PIDTEM
|
#endif //PIDTEM
|
||||||
#ifdef WATCHPERIOD
|
#ifdef WATCHPERIOD
|
||||||
if(target_raw[0]>current_raw[0]) {
|
if(target_raw[TEMPSENSOR_HOTEND]>current_raw[TEMPSENSOR_HOTEND]){
|
||||||
watchmillis = max(1,millis());
|
watchmillis = max(1,millis());
|
||||||
watch_raw = current_raw[0];
|
watch_raw[TEMPSENSOR_HOTEND] = current_raw[TEMPSENSOR_HOTEND];
|
||||||
} else {
|
} else {
|
||||||
watchmillis = 0;
|
watchmillis = 0;
|
||||||
}
|
}
|
||||||
#endif //WATCHPERIOD
|
#endif //WATCHPERIOD
|
||||||
codenum = millis();
|
codenum = millis();
|
||||||
|
|
||||||
/* See if we are heating up or cooling down */
|
/* See if we are heating up or cooling down */
|
||||||
bool target_direction = (current_raw[0] < target_raw[0]); // true if heating, false if cooling
|
bool target_direction = (current_raw[0] < target_raw[0]); // true if heating, false if cooling
|
||||||
|
|
||||||
#ifdef TEMP_RESIDENCY_TIME
|
#ifdef TEMP_RESIDENCY_TIME
|
||||||
long residencyStart;
|
long residencyStart;
|
||||||
residencyStart = -1;
|
residencyStart = -1;
|
||||||
/* continue to loop until we have reached the target temp
|
/* continue to loop until we have reached the target temp
|
||||||
_and_ until TEMP_RESIDENCY_TIME hasn't passed since we reached it */
|
_and_ until TEMP_RESIDENCY_TIME hasn't passed since we reached it */
|
||||||
while((target_direction ? (current_raw[0] < target_raw[0]) : (current_raw[0] > target_raw[0])) ||
|
while((target_direction ? (current_raw[0] < target_raw[0]) : (current_raw[0] > target_raw[0])) ||
|
||||||
(residencyStart > -1 && (millis() - residencyStart) < TEMP_RESIDENCY_TIME*1000) ) {
|
(residencyStart > -1 && (millis() - residencyStart) < TEMP_RESIDENCY_TIME*1000) ) {
|
||||||
#else
|
#else
|
||||||
while ( target_direction ? (current_raw[0] < target_raw[0]) : (current_raw[0] > target_raw[0]) ) {
|
while ( target_direction ? (current_raw[0] < target_raw[0]) : (current_raw[0] > target_raw[0]) ) {
|
||||||
#endif //TEMP_RESIDENCY_TIME
|
#endif //TEMP_RESIDENCY_TIME
|
||||||
if( (millis() - codenum) > 1000 ) { //Print Temp Reading every 1 second while heating up/cooling down
|
if( (millis() - codenum) > 1000 ) { //Print Temp Reading every 1 second while heating up/cooling down
|
||||||
Serial.print("T:");
|
Serial.print("T:");
|
||||||
Serial.println( analog2temp(current_raw[0]) );
|
Serial.println( analog2temp(current_raw[TEMPSENSOR_HOTEND]) );
|
||||||
codenum = millis();
|
codenum = millis();
|
||||||
}
|
}
|
||||||
manage_heater();
|
manage_heater();
|
||||||
LCD_STATUS;
|
LCD_STATUS;
|
||||||
#ifdef TEMP_RESIDENCY_TIME
|
#ifdef TEMP_RESIDENCY_TIME
|
||||||
/* start/restart the TEMP_RESIDENCY_TIME timer whenever we reach target temp for the first time
|
/* start/restart the TEMP_RESIDENCY_TIME timer whenever we reach target temp for the first time
|
||||||
or when current temp falls outside the hysteresis after target temp was reached */
|
or when current temp falls outside the hysteresis after target temp was reached */
|
||||||
if ((residencyStart == -1 && target_direction && current_raw[0] >= target_raw[0]) ||
|
if ((residencyStart == -1 && target_direction && current_raw[0] >= target_raw[0]) ||
|
||||||
(residencyStart == -1 && !target_direction && current_raw[0] <= target_raw[0]) ||
|
(residencyStart == -1 && !target_direction && current_raw[0] <= target_raw[0]) ||
|
||||||
(residencyStart > -1 && labs(analog2temp(current_raw[0]) - analog2temp(target_raw[0])) > TEMP_HYSTERESIS) ) {
|
(residencyStart > -1 && labs(analog2temp(current_raw[0]) - analog2temp(target_raw[0])) > TEMP_HYSTERESIS) ) {
|
||||||
residencyStart = millis();
|
residencyStart = millis();
|
||||||
}
|
}
|
||||||
#endif //TEMP_RESIDENCY_TIME
|
#endif //TEMP_RESIDENCY_TIME
|
||||||
}
|
}
|
||||||
LCD_MESSAGE("Marlin ready.");
|
LCD_MESSAGE("Marlin ready.");
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
case 190: // M190 - Wait bed for heater to reach target.
|
case 190: // M190 - Wait bed for heater to reach target.
|
||||||
#if TEMP_1_PIN > -1
|
#if TEMP_1_PIN > -1
|
||||||
if (code_seen('S')) target_raw[1] = temp2analog(code_value());
|
if (code_seen('S')) target_raw[TEMPSENSOR_BED] = temp2analog(code_value());
|
||||||
codenum = millis();
|
codenum = millis();
|
||||||
while(current_raw[1] < target_raw[1])
|
while(current_raw[TEMPSENSOR_BED] < target_raw[TEMPSENSOR_BED])
|
||||||
{
|
{
|
||||||
if( (millis()-codenum) > 1000 ) //Print Temp Reading every 1 second while heating up.
|
if( (millis()-codenum) > 1000 ) //Print Temp Reading every 1 second while heating up.
|
||||||
{
|
{
|
||||||
float tt=analog2temp(current_raw[0]);
|
float tt=analog2temp(current_raw[TEMPSENSOR_HOTEND]);
|
||||||
Serial.print("T:");
|
Serial.print("T:");
|
||||||
Serial.println( tt );
|
Serial.println( tt );
|
||||||
Serial.print("ok T:");
|
Serial.print("ok T:");
|
||||||
Serial.print( tt );
|
Serial.print( tt );
|
||||||
Serial.print(" B:");
|
Serial.print(" B:");
|
||||||
Serial.println( analog2temp(current_raw[1]) );
|
Serial.println( analog2temp(current_raw[TEMPSENSOR_BED]) );
|
||||||
codenum = millis();
|
codenum = millis();
|
||||||
}
|
}
|
||||||
manage_heater();
|
manage_heater();
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
break;
|
break;
|
||||||
#if FAN_PIN > -1
|
#if FAN_PIN > -1
|
||||||
case 106: //M106 Fan On
|
case 106: //M106 Fan On
|
||||||
if (code_seen('S')){
|
if (code_seen('S')){
|
||||||
WRITE(FAN_PIN,HIGH);
|
WRITE(FAN_PIN,HIGH);
|
||||||
fanpwm=constrain(code_value(),0,255);
|
fanpwm=constrain(code_value(),0,255);
|
||||||
analogWrite(FAN_PIN, fanpwm);
|
analogWrite(FAN_PIN, fanpwm);
|
||||||
}
|
}
|
||||||
else {
|
else {
|
||||||
WRITE(FAN_PIN,HIGH);
|
WRITE(FAN_PIN,HIGH);
|
||||||
fanpwm=255;
|
fanpwm=255;
|
||||||
analogWrite(FAN_PIN, fanpwm);
|
analogWrite(FAN_PIN, fanpwm);
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
case 107: //M107 Fan Off
|
case 107: //M107 Fan Off
|
||||||
WRITE(FAN_PIN,LOW);
|
WRITE(FAN_PIN,LOW);
|
||||||
analogWrite(FAN_PIN, 0);
|
analogWrite(FAN_PIN, 0);
|
||||||
break;
|
break;
|
||||||
#endif
|
#endif
|
||||||
#if (PS_ON_PIN > -1)
|
#if (PS_ON_PIN > -1)
|
||||||
case 80: // M80 - ATX Power On
|
case 80: // M80 - ATX Power On
|
||||||
SET_OUTPUT(PS_ON_PIN); //GND
|
SET_OUTPUT(PS_ON_PIN); //GND
|
||||||
break;
|
break;
|
||||||
case 81: // M81 - ATX Power Off
|
case 81: // M81 - ATX Power Off
|
||||||
SET_INPUT(PS_ON_PIN); //Floating
|
SET_INPUT(PS_ON_PIN); //Floating
|
||||||
break;
|
break;
|
||||||
#endif
|
#endif
|
||||||
case 82:
|
case 82:
|
||||||
axis_relative_modes[3] = false;
|
axis_relative_modes[3] = false;
|
||||||
break;
|
break;
|
||||||
case 83:
|
case 83:
|
||||||
axis_relative_modes[3] = true;
|
axis_relative_modes[3] = true;
|
||||||
break;
|
break;
|
||||||
case 18:
|
case 18:
|
||||||
case 84:
|
case 84:
|
||||||
if(code_seen('S')){
|
if(code_seen('S')){
|
||||||
stepper_inactive_time = code_value() * 1000;
|
stepper_inactive_time = code_value() * 1000;
|
||||||
}
|
}
|
||||||
else{
|
else{
|
||||||
st_synchronize();
|
st_synchronize();
|
||||||
disable_x();
|
disable_x();
|
||||||
disable_y();
|
disable_y();
|
||||||
disable_z();
|
disable_z();
|
||||||
disable_e();
|
disable_e();
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
case 85: // M85
|
case 85: // M85
|
||||||
code_seen('S');
|
code_seen('S');
|
||||||
max_inactive_time = code_value() * 1000;
|
max_inactive_time = code_value() * 1000;
|
||||||
break;
|
break;
|
||||||
case 92: // M92
|
case 92: // M92
|
||||||
for(int i=0; i < NUM_AXIS; i++) {
|
for(int i=0; i < NUM_AXIS; i++) {
|
||||||
if(code_seen(axis_codes[i])) axis_steps_per_unit[i] = code_value();
|
if(code_seen(axis_codes[i])) axis_steps_per_unit[i] = code_value();
|
||||||
}
|
}
|
||||||
|
|
||||||
break;
|
break;
|
||||||
case 115: // M115
|
case 115: // M115
|
||||||
Serial.println("FIRMWARE_NAME:Sprinter/grbl mashup for gen6 FIRMWARE_URL:http://www.mendel-parts.com PROTOCOL_VERSION:1.0 MACHINE_TYPE:Mendel EXTRUDER_COUNT:1");
|
Serial.println("FIRMWARE_NAME:Sprinter/grbl mashup for gen6 FIRMWARE_URL:http://www.mendel-parts.com PROTOCOL_VERSION:1.0 MACHINE_TYPE:Mendel EXTRUDER_COUNT:1");
|
||||||
break;
|
break;
|
||||||
case 114: // M114
|
case 114: // M114
|
||||||
Serial.print("X:");
|
Serial.print("X:");
|
||||||
Serial.print(current_position[X_AXIS]);
|
Serial.print(current_position[X_AXIS]);
|
||||||
Serial.print("Y:");
|
Serial.print("Y:");
|
||||||
Serial.print(current_position[Y_AXIS]);
|
Serial.print(current_position[Y_AXIS]);
|
||||||
Serial.print("Z:");
|
Serial.print("Z:");
|
||||||
Serial.print(current_position[Z_AXIS]);
|
Serial.print(current_position[Z_AXIS]);
|
||||||
Serial.print("E:");
|
Serial.print("E:");
|
||||||
Serial.print(current_position[E_AXIS]);
|
Serial.print(current_position[E_AXIS]);
|
||||||
#ifdef DEBUG_STEPS
|
#ifdef DEBUG_STEPS
|
||||||
Serial.print(" Count X:");
|
Serial.print(" Count X:");
|
||||||
Serial.print(float(count_position[X_AXIS])/axis_steps_per_unit[X_AXIS]);
|
Serial.print(float(count_position[X_AXIS])/axis_steps_per_unit[X_AXIS]);
|
||||||
Serial.print("Y:");
|
Serial.print("Y:");
|
||||||
Serial.print(float(count_position[Y_AXIS])/axis_steps_per_unit[Y_AXIS]);
|
Serial.print(float(count_position[Y_AXIS])/axis_steps_per_unit[Y_AXIS]);
|
||||||
Serial.print("Z:");
|
Serial.print("Z:");
|
||||||
Serial.println(float(count_position[Z_AXIS])/axis_steps_per_unit[Z_AXIS]);
|
Serial.println(float(count_position[Z_AXIS])/axis_steps_per_unit[Z_AXIS]);
|
||||||
#endif
|
#endif
|
||||||
Serial.println("");
|
Serial.println("");
|
||||||
break;
|
break;
|
||||||
case 119: // M119
|
case 119: // M119
|
||||||
#if (X_MIN_PIN > -1)
|
#if (X_MIN_PIN > -1)
|
||||||
Serial.print("x_min:");
|
Serial.print("x_min:");
|
||||||
Serial.print((READ(X_MIN_PIN)^ENDSTOPS_INVERTING)?"H ":"L ");
|
Serial.print((READ(X_MIN_PIN)^ENDSTOPS_INVERTING)?"H ":"L ");
|
||||||
#endif
|
#endif
|
||||||
#if (X_MAX_PIN > -1)
|
#if (X_MAX_PIN > -1)
|
||||||
Serial.print("x_max:");
|
Serial.print("x_max:");
|
||||||
Serial.print((READ(X_MAX_PIN)^ENDSTOPS_INVERTING)?"H ":"L ");
|
Serial.print((READ(X_MAX_PIN)^ENDSTOPS_INVERTING)?"H ":"L ");
|
||||||
#endif
|
#endif
|
||||||
#if (Y_MIN_PIN > -1)
|
#if (Y_MIN_PIN > -1)
|
||||||
Serial.print("y_min:");
|
Serial.print("y_min:");
|
||||||
Serial.print((READ(Y_MIN_PIN)^ENDSTOPS_INVERTING)?"H ":"L ");
|
Serial.print((READ(Y_MIN_PIN)^ENDSTOPS_INVERTING)?"H ":"L ");
|
||||||
#endif
|
#endif
|
||||||
#if (Y_MAX_PIN > -1)
|
#if (Y_MAX_PIN > -1)
|
||||||
Serial.print("y_max:");
|
Serial.print("y_max:");
|
||||||
Serial.print((READ(Y_MAX_PIN)^ENDSTOPS_INVERTING)?"H ":"L ");
|
Serial.print((READ(Y_MAX_PIN)^ENDSTOPS_INVERTING)?"H ":"L ");
|
||||||
#endif
|
#endif
|
||||||
#if (Z_MIN_PIN > -1)
|
#if (Z_MIN_PIN > -1)
|
||||||
Serial.print("z_min:");
|
Serial.print("z_min:");
|
||||||
Serial.print((READ(Z_MIN_PIN)^ENDSTOPS_INVERTING)?"H ":"L ");
|
Serial.print((READ(Z_MIN_PIN)^ENDSTOPS_INVERTING)?"H ":"L ");
|
||||||
#endif
|
#endif
|
||||||
#if (Z_MAX_PIN > -1)
|
#if (Z_MAX_PIN > -1)
|
||||||
Serial.print("z_max:");
|
Serial.print("z_max:");
|
||||||
Serial.print((READ(Z_MAX_PIN)^ENDSTOPS_INVERTING)?"H ":"L ");
|
Serial.print((READ(Z_MAX_PIN)^ENDSTOPS_INVERTING)?"H ":"L ");
|
||||||
#endif
|
#endif
|
||||||
Serial.println("");
|
Serial.println("");
|
||||||
break;
|
break;
|
||||||
//TODO: update for all axis, use for loop
|
//TODO: update for all axis, use for loop
|
||||||
case 201: // M201
|
case 201: // M201
|
||||||
for(int i=0; i < NUM_AXIS; i++) {
|
for(int i=0; i < NUM_AXIS; i++) {
|
||||||
if(code_seen(axis_codes[i])) axis_steps_per_sqr_second[i] = code_value() * axis_steps_per_unit[i];
|
if(code_seen(axis_codes[i])) axis_steps_per_sqr_second[i] = code_value() * axis_steps_per_unit[i];
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
#if 0 // Not used for Sprinter/grbl gen6
|
#if 0 // Not used for Sprinter/grbl gen6
|
||||||
case 202: // M202
|
case 202: // M202
|
||||||
for(int i=0; i < NUM_AXIS; i++) {
|
for(int i=0; i < NUM_AXIS; i++) {
|
||||||
if(code_seen(axis_codes[i])) axis_travel_steps_per_sqr_second[i] = code_value() * axis_steps_per_unit[i];
|
if(code_seen(axis_codes[i])) axis_travel_steps_per_sqr_second[i] = code_value() * axis_steps_per_unit[i];
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
#endif
|
#endif
|
||||||
case 203: // M203 max feedrate mm/sec
|
case 203: // M203 max feedrate mm/sec
|
||||||
for(int i=0; i < NUM_AXIS; i++) {
|
for(int i=0; i < NUM_AXIS; i++) {
|
||||||
if(code_seen(axis_codes[i])) max_feedrate[i] = code_value()*60 ;
|
if(code_seen(axis_codes[i])) max_feedrate[i] = code_value()*60 ;
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
case 204: // M204 acclereration S normal moves T filmanent only moves
|
case 204: // M204 acclereration S normal moves T filmanent only moves
|
||||||
{
|
{
|
||||||
if(code_seen('S')) acceleration = code_value() ;
|
if(code_seen('S')) acceleration = code_value() ;
|
||||||
if(code_seen('T')) retract_acceleration = code_value() ;
|
if(code_seen('T')) retract_acceleration = code_value() ;
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
case 205: //M205 advanced settings: minimum travel speed S=while printing T=travel only, B=minimum segment time X= maximum xy jerk, Z=maximum Z jerk
|
case 205: //M205 advanced settings: minimum travel speed S=while printing T=travel only, B=minimum segment time X= maximum xy jerk, Z=maximum Z jerk
|
||||||
{
|
{
|
||||||
if(code_seen('S')) minimumfeedrate = code_value()*60 ;
|
if(code_seen('S')) minimumfeedrate = code_value()*60 ;
|
||||||
if(code_seen('T')) mintravelfeedrate = code_value()*60 ;
|
if(code_seen('T')) mintravelfeedrate = code_value()*60 ;
|
||||||
if(code_seen('B')) minsegmenttime = code_value() ;
|
if(code_seen('B')) minsegmenttime = code_value() ;
|
||||||
if(code_seen('X')) max_xy_jerk = code_value()*60 ;
|
if(code_seen('X')) max_xy_jerk = code_value()*60 ;
|
||||||
if(code_seen('Z')) max_z_jerk = code_value()*60 ;
|
if(code_seen('Z')) max_z_jerk = code_value()*60 ;
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
case 220: // M220 S<factor in percent>- set speed factor override percentage
|
case 220: // M220 S<factor in percent>- set speed factor override percentage
|
||||||
{
|
{
|
||||||
if(code_seen('S'))
|
if(code_seen('S'))
|
||||||
{
|
{
|
||||||
feedmultiply = code_value() ;
|
feedmultiply = code_value() ;
|
||||||
feedmultiplychanged=true;
|
feedmultiplychanged=true;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
#ifdef PIDTEMP
|
#ifdef PIDTEMP
|
||||||
case 301: // M301
|
case 301: // M301
|
||||||
if(code_seen('P')) Kp = code_value();
|
if(code_seen('P')) Kp = code_value();
|
||||||
if(code_seen('I')) Ki = code_value()*PID_dT;
|
if(code_seen('I')) Ki = code_value()*PID_dT;
|
||||||
if(code_seen('D')) Kd = code_value()/PID_dT;
|
if(code_seen('D')) Kd = code_value()/PID_dT;
|
||||||
// ECHOLN("Kp "<<_FLOAT(Kp,2));
|
// ECHOLN("Kp "<<_FLOAT(Kp,2));
|
||||||
// ECHOLN("Ki "<<_FLOAT(Ki/PID_dT,2));
|
// ECHOLN("Ki "<<_FLOAT(Ki/PID_dT,2));
|
||||||
// ECHOLN("Kd "<<_FLOAT(Kd*PID_dT,2));
|
// ECHOLN("Kd "<<_FLOAT(Kd*PID_dT,2));
|
||||||
|
|
||||||
// temp_iState_min = 0.0;
|
// temp_iState_min = 0.0;
|
||||||
// if (Ki!=0) {
|
// if (Ki!=0) {
|
||||||
// temp_iState_max = PID_INTEGRAL_DRIVE_MAX / (Ki/100.0);
|
// temp_iState_max = PID_INTEGRAL_DRIVE_MAX / (Ki/100.0);
|
||||||
// }
|
// }
|
||||||
// else temp_iState_max = 1.0e10;
|
// else temp_iState_max = 1.0e10;
|
||||||
break;
|
break;
|
||||||
#endif //PIDTEMP
|
#endif //PIDTEMP
|
||||||
case 500: // Store settings in EEPROM
|
case 500: // Store settings in EEPROM
|
||||||
{
|
{
|
||||||
StoreSettings();
|
StoreSettings();
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
case 501: // Read settings from EEPROM
|
case 501: // Read settings from EEPROM
|
||||||
{
|
{
|
||||||
RetrieveSettings();
|
RetrieveSettings();
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
case 502: // Revert to default settings
|
case 502: // Revert to default settings
|
||||||
{
|
{
|
||||||
RetrieveSettings(true);
|
RetrieveSettings(true);
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
else{
|
else{
|
||||||
Serial.println("Unknown command:");
|
Serial.println("Unknown command:");
|
||||||
Serial.println(cmdbuffer[bufindr]);
|
Serial.println(cmdbuffer[bufindr]);
|
||||||
}
|
}
|
||||||
|
|
||||||
ClearToSend();
|
ClearToSend();
|
||||||
}
|
}
|
||||||
|
|
||||||
void FlushSerialRequestResend()
|
void FlushSerialRequestResend()
|
||||||
{
|
{
|
||||||
//char cmdbuffer[bufindr][100]="Resend:";
|
//char cmdbuffer[bufindr][100]="Resend:";
|
||||||
Serial.flush();
|
Serial.flush();
|
||||||
Serial.print("Resend:");
|
Serial.print("Resend:");
|
||||||
Serial.println(gcode_LastN + 1);
|
Serial.println(gcode_LastN + 1);
|
||||||
ClearToSend();
|
ClearToSend();
|
||||||
}
|
}
|
||||||
|
|
||||||
void ClearToSend()
|
void ClearToSend()
|
||||||
{
|
{
|
||||||
previous_millis_cmd = millis();
|
previous_millis_cmd = millis();
|
||||||
#ifdef SDSUPPORT
|
#ifdef SDSUPPORT
|
||||||
if(fromsd[bufindr])
|
if(fromsd[bufindr])
|
||||||
return;
|
return;
|
||||||
#endif //SDSUPPORT
|
#endif //SDSUPPORT
|
||||||
Serial.println("ok");
|
Serial.println("ok");
|
||||||
}
|
}
|
||||||
|
|
||||||
inline void get_coordinates()
|
inline void get_coordinates()
|
||||||
{
|
{
|
||||||
for(int i=0; i < NUM_AXIS; i++) {
|
for(int i=0; i < NUM_AXIS; i++) {
|
||||||
if(code_seen(axis_codes[i])) destination[i] = (float)code_value() + (axis_relative_modes[i] || relative_mode)*current_position[i];
|
if(code_seen(axis_codes[i])) destination[i] = (float)code_value() + (axis_relative_modes[i] || relative_mode)*current_position[i];
|
||||||
else destination[i] = current_position[i]; //Are these else lines really needed?
|
else destination[i] = current_position[i]; //Are these else lines really needed?
|
||||||
}
|
}
|
||||||
if(code_seen('F')) {
|
if(code_seen('F')) {
|
||||||
next_feedrate = code_value();
|
next_feedrate = code_value();
|
||||||
if(next_feedrate > 0.0) feedrate = next_feedrate;
|
if(next_feedrate > 0.0) feedrate = next_feedrate;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void prepare_move()
|
void prepare_move()
|
||||||
{
|
{
|
||||||
plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate*feedmultiply/60.0/100.0);
|
plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate*feedmultiply/60.0/100.0);
|
||||||
for(int i=0; i < NUM_AXIS; i++) {
|
for(int i=0; i < NUM_AXIS; i++) {
|
||||||
current_position[i] = destination[i];
|
current_position[i] = destination[i];
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
#ifdef USE_WATCHDOG
|
#ifdef USE_WATCHDOG
|
||||||
|
|
||||||
#include <avr/wdt.h>
|
#include <avr/wdt.h>
|
||||||
#include <avr/interrupt.h>
|
#include <avr/interrupt.h>
|
||||||
|
|
||||||
volatile uint8_t timeout_seconds=0;
|
volatile uint8_t timeout_seconds=0;
|
||||||
|
|
||||||
void(* ctrlaltdelete) (void) = 0;
|
void(* ctrlaltdelete) (void) = 0;
|
||||||
|
|
||||||
ISR(WDT_vect) { //Watchdog timer interrupt, called if main program blocks >1sec
|
ISR(WDT_vect) { //Watchdog timer interrupt, called if main program blocks >1sec
|
||||||
if(timeout_seconds++ >= WATCHDOG_TIMEOUT)
|
if(timeout_seconds++ >= WATCHDOG_TIMEOUT)
|
||||||
{
|
{
|
||||||
kill();
|
kill();
|
||||||
#ifdef RESET_MANUAL
|
#ifdef RESET_MANUAL
|
||||||
LCD_MESSAGE("Please Reset!");
|
LCD_MESSAGE("Please Reset!");
|
||||||
ECHOLN("echo_: Something is wrong, please turn off the printer.");
|
ECHOLN("echo_: Something is wrong, please turn off the printer.");
|
||||||
#else
|
#else
|
||||||
LCD_MESSAGE("Timeout, resetting!");
|
LCD_MESSAGE("Timeout, resetting!");
|
||||||
#endif
|
#endif
|
||||||
//disable watchdog, it will survife reboot.
|
//disable watchdog, it will survife reboot.
|
||||||
WDTCSR |= (1<<WDCE) | (1<<WDE);
|
WDTCSR |= (1<<WDCE) | (1<<WDE);
|
||||||
WDTCSR = 0;
|
WDTCSR = 0;
|
||||||
#ifdef RESET_MANUAL
|
#ifdef RESET_MANUAL
|
||||||
while(1); //wait for user or serial reset
|
while(1); //wait for user or serial reset
|
||||||
#else
|
#else
|
||||||
ctrlaltdelete();
|
ctrlaltdelete();
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
/// intialise watch dog with a 1 sec interrupt time
|
/// intialise watch dog with a 1 sec interrupt time
|
||||||
void wd_init() {
|
void wd_init() {
|
||||||
WDTCSR = (1<<WDCE )|(1<<WDE ); //allow changes
|
WDTCSR = (1<<WDCE )|(1<<WDE ); //allow changes
|
||||||
WDTCSR = (1<<WDIF)|(1<<WDIE)| (1<<WDCE )|(1<<WDE )| (1<<WDP2 )|(1<<WDP1)|(0<<WDP0);
|
WDTCSR = (1<<WDIF)|(1<<WDIE)| (1<<WDCE )|(1<<WDE )| (1<<WDP2 )|(1<<WDP1)|(0<<WDP0);
|
||||||
}
|
}
|
||||||
|
|
||||||
/// reset watchdog. MUST be called every 1s after init or avr will reset.
|
/// reset watchdog. MUST be called every 1s after init or avr will reset.
|
||||||
void wd_reset() {
|
void wd_reset() {
|
||||||
wdt_reset();
|
wdt_reset();
|
||||||
timeout_seconds=0; //reset counter for resets
|
timeout_seconds=0; //reset counter for resets
|
||||||
}
|
}
|
||||||
#endif /* USE_WATCHDOG */
|
#endif /* USE_WATCHDOG */
|
||||||
|
|
||||||
|
|
||||||
inline void kill()
|
inline void kill()
|
||||||
{
|
{
|
||||||
#if TEMP_0_PIN > -1
|
#if TEMP_0_PIN > -1
|
||||||
target_raw[0]=0;
|
target_raw[0]=0;
|
||||||
#if HEATER_0_PIN > -1
|
#if HEATER_0_PIN > -1
|
||||||
WRITE(HEATER_0_PIN,LOW);
|
WRITE(HEATER_0_PIN,LOW);
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
#if TEMP_1_PIN > -1
|
#if TEMP_1_PIN > -1
|
||||||
target_raw[1]=0;
|
target_raw[1]=0;
|
||||||
#if HEATER_1_PIN > -1
|
#if HEATER_1_PIN > -1
|
||||||
WRITE(HEATER_1_PIN,LOW);
|
WRITE(HEATER_1_PIN,LOW);
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
#if TEMP_2_PIN > -1
|
#if TEMP_2_PIN > -1
|
||||||
target_raw[2]=0;
|
target_raw[2]=0;
|
||||||
#if HEATER_2_PIN > -1
|
#if HEATER_2_PIN > -1
|
||||||
WRITE(HEATER_2_PIN,LOW);
|
WRITE(HEATER_2_PIN,LOW);
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
disable_x();
|
disable_x();
|
||||||
disable_y();
|
disable_y();
|
||||||
disable_z();
|
disable_z();
|
||||||
disable_e();
|
disable_e();
|
||||||
|
|
||||||
if(PS_ON_PIN > -1) pinMode(PS_ON_PIN,INPUT);
|
if(PS_ON_PIN > -1) pinMode(PS_ON_PIN,INPUT);
|
||||||
Serial.println("!! Printer halted. kill() called!!");
|
Serial.println("!! Printer halted. kill() called!!");
|
||||||
while(1); // Wait for reset
|
while(1); // Wait for reset
|
||||||
}
|
}
|
||||||
|
|
||||||
void manage_inactivity(byte debug) {
|
void manage_inactivity(byte debug) {
|
||||||
if( (millis()-previous_millis_cmd) > max_inactive_time ) if(max_inactive_time) kill();
|
if( (millis()-previous_millis_cmd) > max_inactive_time ) if(max_inactive_time) kill();
|
||||||
if( (millis()-previous_millis_cmd) > stepper_inactive_time ) if(stepper_inactive_time) {
|
if( (millis()-previous_millis_cmd) > stepper_inactive_time ) if(stepper_inactive_time) {
|
||||||
disable_x();
|
disable_x();
|
||||||
disable_y();
|
disable_y();
|
||||||
disable_z();
|
disable_z();
|
||||||
disable_e();
|
disable_e();
|
||||||
}
|
}
|
||||||
check_axes_activity();
|
check_axes_activity();
|
||||||
}
|
}
|
||||||
|
|
|
@ -24,12 +24,12 @@
|
||||||
*/
|
*/
|
||||||
|
|
||||||
/// Read a pin
|
/// Read a pin
|
||||||
#define _READ(IO) ((bool)(DIO ## IO ## _RPORT & MASK(DIO ## IO ## _PIN)))
|
#define _READ(IO) ((bool)(DIO ## IO ## _RPORT & MASK(DIO ## IO ## _PIN)))
|
||||||
/// write to a pin
|
/// write to a pin
|
||||||
#define _WRITE(IO, v) do { if (v) {DIO ## IO ## _WPORT |= MASK(DIO ## IO ## _PIN); } else {DIO ## IO ## _WPORT &= ~MASK(DIO ## IO ## _PIN); }; } while (0)
|
#define _WRITE(IO, v) do { if (v) {DIO ## IO ## _WPORT |= MASK(DIO ## IO ## _PIN); } else {DIO ## IO ## _WPORT &= ~MASK(DIO ## IO ## _PIN); }; } while (0)
|
||||||
//#define _WRITE(IO, v) do { #if (DIO ## IO ## _WPORT >= 0x100) CRITICAL_SECTION_START; if (v) {DIO ## IO ## _WPORT |= MASK(DIO ## IO ## _PIN); } else {DIO ## IO ## _WPORT &= ~MASK(DIO ## IO ## _PIN); };#if (DIO ## IO ## _WPORT >= 0x100) CRITICAL_SECTION_END; } while (0)
|
//#define _WRITE(IO, v) do { #if (DIO ## IO ## _WPORT >= 0x100) CRITICAL_SECTION_START; if (v) {DIO ## IO ## _WPORT |= MASK(DIO ## IO ## _PIN); } else {DIO ## IO ## _WPORT &= ~MASK(DIO ## IO ## _PIN); };#if (DIO ## IO ## _WPORT >= 0x100) CRITICAL_SECTION_END; } while (0)
|
||||||
/// toggle a pin
|
/// toggle a pin
|
||||||
#define _TOGGLE(IO) do {DIO ## IO ## _RPORT = MASK(DIO ## IO ## _PIN); } while (0)
|
#define _TOGGLE(IO) do {DIO ## IO ## _RPORT = MASK(DIO ## IO ## _PIN); } while (0)
|
||||||
|
|
||||||
/// set pin as input
|
/// set pin as input
|
||||||
#define _SET_INPUT(IO) do {DIO ## IO ## _DDR &= ~MASK(DIO ## IO ## _PIN); } while (0)
|
#define _SET_INPUT(IO) do {DIO ## IO ## _DDR &= ~MASK(DIO ## IO ## _PIN); } while (0)
|
||||||
|
@ -2556,4 +2556,4 @@ pins
|
||||||
#error pins for this chip not defined in arduino.h! If you write an appropriate pin definition and have this firmware work on your chip, please submit a pull request
|
#error pins for this chip not defined in arduino.h! If you write an appropriate pin definition and have this firmware work on your chip, please submit a pull request
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#endif /* _ARDUINO_H */
|
#endif /* _ARDUINO_H */
|
||||||
|
|
10
Marlin/lcd.h
10
Marlin/lcd.h
|
@ -1,10 +0,0 @@
|
||||||
#ifndef __LCDH
|
|
||||||
#define __LCDH
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
#endif
|
|
|
@ -1 +0,0 @@
|
||||||
|
|
|
@ -381,13 +381,6 @@ void check_axes_activity() {
|
||||||
// calculation the caller must also provide the physical length of the line in millimeters.
|
// calculation the caller must also provide the physical length of the line in millimeters.
|
||||||
void plan_buffer_line(float x, float y, float z, float e, float feed_rate) {
|
void plan_buffer_line(float x, float y, float z, float e, float feed_rate) {
|
||||||
|
|
||||||
// The target position of the tool in absolute steps
|
|
||||||
// Calculate target position in absolute steps
|
|
||||||
long target[4];
|
|
||||||
target[X_AXIS] = lround(x*axis_steps_per_unit[X_AXIS]);
|
|
||||||
target[Y_AXIS] = lround(y*axis_steps_per_unit[Y_AXIS]);
|
|
||||||
target[Z_AXIS] = lround(z*axis_steps_per_unit[Z_AXIS]);
|
|
||||||
target[E_AXIS] = lround(e*axis_steps_per_unit[E_AXIS]);
|
|
||||||
|
|
||||||
// Calculate the buffer head after we push this byte
|
// Calculate the buffer head after we push this byte
|
||||||
int next_buffer_head = (block_buffer_head + 1) & (BLOCK_BUFFER_SIZE - 1);
|
int next_buffer_head = (block_buffer_head + 1) & (BLOCK_BUFFER_SIZE - 1);
|
||||||
|
@ -400,6 +393,15 @@ void plan_buffer_line(float x, float y, float z, float e, float feed_rate) {
|
||||||
LCD_STATUS;
|
LCD_STATUS;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// The target position of the tool in absolute steps
|
||||||
|
// Calculate target position in absolute steps
|
||||||
|
//this should be done after the wait, because otherwise a M92 code within the gcode disrupts this calculation somehow
|
||||||
|
long target[4];
|
||||||
|
target[X_AXIS] = lround(x*axis_steps_per_unit[X_AXIS]);
|
||||||
|
target[Y_AXIS] = lround(y*axis_steps_per_unit[Y_AXIS]);
|
||||||
|
target[Z_AXIS] = lround(z*axis_steps_per_unit[Z_AXIS]);
|
||||||
|
target[E_AXIS] = lround(e*axis_steps_per_unit[E_AXIS]);
|
||||||
|
|
||||||
// Prepare to set up new block
|
// Prepare to set up new block
|
||||||
block_t *block = &block_buffer[block_buffer_head];
|
block_t *block = &block_buffer[block_buffer_head];
|
||||||
|
|
||||||
|
@ -433,7 +435,7 @@ void plan_buffer_line(float x, float y, float z, float e, float feed_rate) {
|
||||||
unsigned long microseconds;
|
unsigned long microseconds;
|
||||||
|
|
||||||
if (block->steps_e == 0) {
|
if (block->steps_e == 0) {
|
||||||
if(feed_rate<mintravelfeedrate) feed_rate=mintravelfeedrate;
|
if(feed_rate<mintravelfeedrate) feed_rate=mintravelfeedrate;
|
||||||
}
|
}
|
||||||
else {
|
else {
|
||||||
if(feed_rate<minimumfeedrate) feed_rate=minimumfeedrate;
|
if(feed_rate<minimumfeedrate) feed_rate=minimumfeedrate;
|
||||||
|
|
182
Marlin/planner.h
182
Marlin/planner.h
|
@ -1,90 +1,92 @@
|
||||||
/*
|
/*
|
||||||
planner.h - buffers movement commands and manages the acceleration profile plan
|
planner.h - buffers movement commands and manages the acceleration profile plan
|
||||||
Part of Grbl
|
Part of Grbl
|
||||||
|
|
||||||
Copyright (c) 2009-2011 Simen Svale Skogsrud
|
Copyright (c) 2009-2011 Simen Svale Skogsrud
|
||||||
|
|
||||||
Grbl is free software: you can redistribute it and/or modify
|
Grbl is free software: you can redistribute it and/or modify
|
||||||
it under the terms of the GNU General Public License as published by
|
it under the terms of the GNU General Public License as published by
|
||||||
the Free Software Foundation, either version 3 of the License, or
|
the Free Software Foundation, either version 3 of the License, or
|
||||||
(at your option) any later version.
|
(at your option) any later version.
|
||||||
|
|
||||||
Grbl is distributed in the hope that it will be useful,
|
Grbl is distributed in the hope that it will be useful,
|
||||||
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
GNU General Public License for more details.
|
GNU General Public License for more details.
|
||||||
|
|
||||||
You should have received a copy of the GNU General Public License
|
You should have received a copy of the GNU General Public License
|
||||||
along with Grbl. If not, see <http://www.gnu.org/licenses/>.
|
along with Grbl. If not, see <http://www.gnu.org/licenses/>.
|
||||||
*/
|
*/
|
||||||
|
|
||||||
// This module is to be considered a sub-module of stepper.c. Please don't include
|
// This module is to be considered a sub-module of stepper.c. Please don't include
|
||||||
// this file from any other module.
|
// this file from any other module.
|
||||||
|
|
||||||
#ifndef planner_h
|
#ifndef planner_h
|
||||||
#define planner_h
|
#define planner_h
|
||||||
|
|
||||||
// This struct is used when buffering the setup for each linear movement "nominal" values are as specified in
|
#include "Configuration.h"
|
||||||
// the source g-code and may never actually be reached if acceleration management is active.
|
|
||||||
typedef struct {
|
// This struct is used when buffering the setup for each linear movement "nominal" values are as specified in
|
||||||
// Fields used by the bresenham algorithm for tracing the line
|
// the source g-code and may never actually be reached if acceleration management is active.
|
||||||
long steps_x, steps_y, steps_z, steps_e; // Step count along each axis
|
typedef struct {
|
||||||
long step_event_count; // The number of step events required to complete this block
|
// Fields used by the bresenham algorithm for tracing the line
|
||||||
volatile long accelerate_until; // The index of the step event on which to stop acceleration
|
long steps_x, steps_y, steps_z, steps_e; // Step count along each axis
|
||||||
volatile long decelerate_after; // The index of the step event on which to start decelerating
|
long step_event_count; // The number of step events required to complete this block
|
||||||
volatile long acceleration_rate; // The acceleration rate used for acceleration calculation
|
volatile long accelerate_until; // The index of the step event on which to stop acceleration
|
||||||
unsigned char direction_bits; // The direction bit set for this block (refers to *_DIRECTION_BIT in config.h)
|
volatile long decelerate_after; // The index of the step event on which to start decelerating
|
||||||
#ifdef ADVANCE
|
volatile long acceleration_rate; // The acceleration rate used for acceleration calculation
|
||||||
long advance_rate;
|
unsigned char direction_bits; // The direction bit set for this block (refers to *_DIRECTION_BIT in config.h)
|
||||||
volatile long initial_advance;
|
#ifdef ADVANCE
|
||||||
volatile long final_advance;
|
long advance_rate;
|
||||||
float advance;
|
volatile long initial_advance;
|
||||||
#endif
|
volatile long final_advance;
|
||||||
|
float advance;
|
||||||
// Fields used by the motion planner to manage acceleration
|
#endif
|
||||||
float speed_x, speed_y, speed_z, speed_e; // Nominal mm/minute for each axis
|
|
||||||
float nominal_speed; // The nominal speed for this block in mm/min
|
// Fields used by the motion planner to manage acceleration
|
||||||
float millimeters; // The total travel of this block in mm
|
float speed_x, speed_y, speed_z, speed_e; // Nominal mm/minute for each axis
|
||||||
float entry_speed;
|
float nominal_speed; // The nominal speed for this block in mm/min
|
||||||
float acceleration; // acceleration mm/sec^2
|
float millimeters; // The total travel of this block in mm
|
||||||
|
float entry_speed;
|
||||||
// Settings for the trapezoid generator
|
float acceleration; // acceleration mm/sec^2
|
||||||
long nominal_rate; // The nominal step rate for this block in step_events/sec
|
|
||||||
volatile long initial_rate; // The jerk-adjusted step rate at start of block
|
// Settings for the trapezoid generator
|
||||||
volatile long final_rate; // The minimal rate at exit
|
long nominal_rate; // The nominal step rate for this block in step_events/sec
|
||||||
long acceleration_st; // acceleration steps/sec^2
|
volatile long initial_rate; // The jerk-adjusted step rate at start of block
|
||||||
volatile char busy;
|
volatile long final_rate; // The minimal rate at exit
|
||||||
} block_t;
|
long acceleration_st; // acceleration steps/sec^2
|
||||||
|
volatile char busy;
|
||||||
// Initialize the motion plan subsystem
|
} block_t;
|
||||||
void plan_init();
|
|
||||||
|
// Initialize the motion plan subsystem
|
||||||
// Add a new linear movement to the buffer. x, y and z is the signed, absolute target position in
|
void plan_init();
|
||||||
// millimaters. Feed rate specifies the speed of the motion.
|
|
||||||
void plan_buffer_line(float x, float y, float z, float e, float feed_rate);
|
// Add a new linear movement to the buffer. x, y and z is the signed, absolute target position in
|
||||||
|
// millimaters. Feed rate specifies the speed of the motion.
|
||||||
// Set position. Used for G92 instructions.
|
void plan_buffer_line(float x, float y, float z, float e, float feed_rate);
|
||||||
void plan_set_position(float x, float y, float z, float e);
|
|
||||||
|
// Set position. Used for G92 instructions.
|
||||||
// Called when the current block is no longer needed. Discards the block and makes the memory
|
void plan_set_position(float x, float y, float z, float e);
|
||||||
// availible for new blocks.
|
|
||||||
void plan_discard_current_block();
|
// Called when the current block is no longer needed. Discards the block and makes the memory
|
||||||
|
// availible for new blocks.
|
||||||
// Gets the current block. Returns NULL if buffer empty
|
void plan_discard_current_block();
|
||||||
block_t *plan_get_current_block();
|
|
||||||
|
// Gets the current block. Returns NULL if buffer empty
|
||||||
void check_axes_activity();
|
block_t *plan_get_current_block();
|
||||||
|
|
||||||
extern unsigned long minsegmenttime;
|
void check_axes_activity();
|
||||||
extern float max_feedrate[4]; // set the max speeds
|
|
||||||
extern float axis_steps_per_unit[4];
|
extern unsigned long minsegmenttime;
|
||||||
extern long max_acceleration_units_per_sq_second[4]; // Use M201 to override by software
|
extern float max_feedrate[4]; // set the max speeds
|
||||||
extern float minimumfeedrate;
|
extern float axis_steps_per_unit[4];
|
||||||
extern float acceleration; // Normal acceleration mm/s^2 THIS IS THE DEFAULT ACCELERATION for all moves. M204 SXXXX
|
extern long max_acceleration_units_per_sq_second[4]; // Use M201 to override by software
|
||||||
extern float retract_acceleration; // mm/s^2 filament pull-pack and push-forward while standing still in the other axis M204 TXXXX
|
extern float minimumfeedrate;
|
||||||
extern float max_xy_jerk; //speed than can be stopped at once, if i understand correctly.
|
extern float acceleration; // Normal acceleration mm/s^2 THIS IS THE DEFAULT ACCELERATION for all moves. M204 SXXXX
|
||||||
extern float max_z_jerk;
|
extern float retract_acceleration; // mm/s^2 filament pull-pack and push-forward while standing still in the other axis M204 TXXXX
|
||||||
extern float mintravelfeedrate;
|
extern float max_xy_jerk; //speed than can be stopped at once, if i understand correctly.
|
||||||
extern unsigned long axis_steps_per_sqr_second[NUM_AXIS];
|
extern float max_z_jerk;
|
||||||
|
extern float mintravelfeedrate;
|
||||||
#endif
|
extern unsigned long axis_steps_per_sqr_second[NUM_AXIS];
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
|
@ -115,7 +115,7 @@ asm volatile ( \
|
||||||
#define ENABLE_STEPPER_DRIVER_INTERRUPT() TIMSK1 |= (1<<OCIE1A)
|
#define ENABLE_STEPPER_DRIVER_INTERRUPT() TIMSK1 |= (1<<OCIE1A)
|
||||||
#define DISABLE_STEPPER_DRIVER_INTERRUPT() TIMSK1 &= ~(1<<OCIE1A)
|
#define DISABLE_STEPPER_DRIVER_INTERRUPT() TIMSK1 &= ~(1<<OCIE1A)
|
||||||
|
|
||||||
static block_t *current_block; // A pointer to the block currently being traced
|
block_t *current_block; // A pointer to the block currently being traced
|
||||||
|
|
||||||
// Variables used by The Stepper Driver Interrupt
|
// Variables used by The Stepper Driver Interrupt
|
||||||
static unsigned char out_bits; // The next stepping-bits to be output
|
static unsigned char out_bits; // The next stepping-bits to be output
|
||||||
|
|
|
@ -1,40 +1,44 @@
|
||||||
/*
|
/*
|
||||||
stepper.h - stepper motor driver: executes motion plans of planner.c using the stepper motors
|
stepper.h - stepper motor driver: executes motion plans of planner.c using the stepper motors
|
||||||
Part of Grbl
|
Part of Grbl
|
||||||
|
|
||||||
Copyright (c) 2009-2011 Simen Svale Skogsrud
|
Copyright (c) 2009-2011 Simen Svale Skogsrud
|
||||||
|
|
||||||
Grbl is free software: you can redistribute it and/or modify
|
Grbl is free software: you can redistribute it and/or modify
|
||||||
it under the terms of the GNU General Public License as published by
|
it under the terms of the GNU General Public License as published by
|
||||||
the Free Software Foundation, either version 3 of the License, or
|
the Free Software Foundation, either version 3 of the License, or
|
||||||
(at your option) any later version.
|
(at your option) any later version.
|
||||||
|
|
||||||
Grbl is distributed in the hope that it will be useful,
|
Grbl is distributed in the hope that it will be useful,
|
||||||
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
GNU General Public License for more details.
|
GNU General Public License for more details.
|
||||||
|
|
||||||
You should have received a copy of the GNU General Public License
|
You should have received a copy of the GNU General Public License
|
||||||
along with Grbl. If not, see <http://www.gnu.org/licenses/>.
|
along with Grbl. If not, see <http://www.gnu.org/licenses/>.
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#ifndef stepper_h
|
#ifndef stepper_h
|
||||||
#define stepper_h
|
#define stepper_h
|
||||||
// Initialize and start the stepper motor subsystem
|
|
||||||
void st_init();
|
#include "planner.h"
|
||||||
|
|
||||||
// Block until all buffered steps are executed
|
// Initialize and start the stepper motor subsystem
|
||||||
void st_synchronize();
|
void st_init();
|
||||||
|
|
||||||
// The stepper subsystem goes to sleep when it runs out of things to execute. Call this
|
// Block until all buffered steps are executed
|
||||||
// to notify the subsystem that it is time to go to work.
|
void st_synchronize();
|
||||||
void st_wake_up();
|
|
||||||
|
// The stepper subsystem goes to sleep when it runs out of things to execute. Call this
|
||||||
// if DEBUG_STEPS is enabled, M114 can be used to compare two methods of determining the X,Y,Z position of the printer.
|
// to notify the subsystem that it is time to go to work.
|
||||||
// for debugging purposes only, should be disabled by default
|
void st_wake_up();
|
||||||
#ifdef DEBUG_STEPS
|
|
||||||
extern volatile long count_position[NUM_AXIS];
|
// if DEBUG_STEPS is enabled, M114 can be used to compare two methods of determining the X,Y,Z position of the printer.
|
||||||
extern volatile int count_direction[NUM_AXIS];
|
// for debugging purposes only, should be disabled by default
|
||||||
#endif
|
#ifdef DEBUG_STEPS
|
||||||
|
extern volatile long count_position[NUM_AXIS];
|
||||||
#endif
|
extern volatile int count_direction[NUM_AXIS];
|
||||||
|
#endif
|
||||||
|
|
||||||
|
extern block_t *current_block; // A pointer to the block currently being traced
|
||||||
|
#endif
|
||||||
|
|
|
@ -90,14 +90,15 @@ void manage_heater()
|
||||||
|
|
||||||
float pid_input;
|
float pid_input;
|
||||||
float pid_output;
|
float pid_output;
|
||||||
if(temp_meas_ready == true) {
|
if(temp_meas_ready != true) //better readability
|
||||||
|
return;
|
||||||
|
|
||||||
CRITICAL_SECTION_START;
|
CRITICAL_SECTION_START;
|
||||||
temp_meas_ready = false;
|
temp_meas_ready = false;
|
||||||
CRITICAL_SECTION_END;
|
CRITICAL_SECTION_END;
|
||||||
|
|
||||||
#ifdef PIDTEMP
|
#ifdef PIDTEMP
|
||||||
pid_input = analog2temp(current_raw[0]);
|
pid_input = analog2temp(current_raw[TEMPSENSOR_HOTEND]);
|
||||||
|
|
||||||
#ifndef PID_OPENLOOP
|
#ifndef PID_OPENLOOP
|
||||||
pid_error = pid_setpoint - pid_input;
|
pid_error = pid_setpoint - pid_input;
|
||||||
|
@ -118,10 +119,13 @@ CRITICAL_SECTION_END;
|
||||||
temp_iState += pid_error;
|
temp_iState += pid_error;
|
||||||
temp_iState = constrain(temp_iState, temp_iState_min, temp_iState_max);
|
temp_iState = constrain(temp_iState, temp_iState_min, temp_iState_max);
|
||||||
iTerm = Ki * temp_iState;
|
iTerm = Ki * temp_iState;
|
||||||
#define K1 0.95
|
//K1 defined in Configuration.h in the PID settings
|
||||||
#define K2 (1.0-K1)
|
#define K2 (1.0-K1)
|
||||||
dTerm = (Kd * (pid_input - temp_dState))*K2 + (K1 * dTerm);
|
dTerm = (Kd * (pid_input - temp_dState))*K2 + (K1 * dTerm);
|
||||||
temp_dState = pid_input;
|
temp_dState = pid_input;
|
||||||
|
#ifdef PID_ADD_EXTRUSION_RATE
|
||||||
|
pTerm+=Kc*current_block->speed_e; //additional heating if extrusion speed is high
|
||||||
|
#endif
|
||||||
pid_output = constrain(pTerm + iTerm - dTerm, 0, PID_MAX);
|
pid_output = constrain(pTerm + iTerm - dTerm, 0, PID_MAX);
|
||||||
}
|
}
|
||||||
#endif //PID_OPENLOOP
|
#endif //PID_OPENLOOP
|
||||||
|
@ -157,7 +161,7 @@ CRITICAL_SECTION_END;
|
||||||
previous_millis_bed_heater = millis();
|
previous_millis_bed_heater = millis();
|
||||||
|
|
||||||
#if TEMP_1_PIN > -1
|
#if TEMP_1_PIN > -1
|
||||||
if(current_raw[1] >= target_raw[1])
|
if(current_raw[TEMPSENSOR_BED] >= target_raw[TEMPSENSOR_BED])
|
||||||
{
|
{
|
||||||
WRITE(HEATER_1_PIN,LOW);
|
WRITE(HEATER_1_PIN,LOW);
|
||||||
}
|
}
|
||||||
|
@ -167,7 +171,6 @@ CRITICAL_SECTION_END;
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
}
|
|
||||||
|
|
||||||
// Takes hot end temperature value as input and returns corresponding raw value.
|
// Takes hot end temperature value as input and returns corresponding raw value.
|
||||||
// For a thermistor, it uses the RepRap thermistor temp table.
|
// For a thermistor, it uses the RepRap thermistor temp table.
|
||||||
|
@ -428,15 +431,15 @@ ISR(TIMER0_COMPB_vect)
|
||||||
raw_temp_2_value = 0;
|
raw_temp_2_value = 0;
|
||||||
#ifdef MAXTEMP
|
#ifdef MAXTEMP
|
||||||
#if (HEATER_0_PIN > -1)
|
#if (HEATER_0_PIN > -1)
|
||||||
if(current_raw[0] >= maxttemp) {
|
if(current_raw[TEMPSENSOR_HOTEND] >= maxttemp) {
|
||||||
target_raw[0] = 0;
|
target_raw[TEMPSENSOR_HOTEND] = 0;
|
||||||
analogWrite(HEATER_0_PIN, 0);
|
analogWrite(HEATER_0_PIN, 0);
|
||||||
Serial.println("!! Temperature extruder 0 switched off. MAXTEMP triggered !!");
|
Serial.println("!! Temperature extruder 0 switched off. MAXTEMP triggered !!");
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
#if (HEATER_2_PIN > -1)
|
#if (HEATER_2_PIN > -1)
|
||||||
if(current_raw[2] >= maxttemp) {
|
if(current_raw[TEMPSENSOR_AUX] >= maxttemp) {
|
||||||
target_raw[2] = 0;
|
target_raw[TEMPSENSOR_AUX] = 0;
|
||||||
analogWrite(HEATER_2_PIN, 0);
|
analogWrite(HEATER_2_PIN, 0);
|
||||||
Serial.println("!! Temperature extruder 1 switched off. MAXTEMP triggered !!");
|
Serial.println("!! Temperature extruder 1 switched off. MAXTEMP triggered !!");
|
||||||
}
|
}
|
||||||
|
@ -444,15 +447,15 @@ ISR(TIMER0_COMPB_vect)
|
||||||
#endif //MAXTEMP
|
#endif //MAXTEMP
|
||||||
#ifdef MINTEMP
|
#ifdef MINTEMP
|
||||||
#if (HEATER_0_PIN > -1)
|
#if (HEATER_0_PIN > -1)
|
||||||
if(current_raw[0] <= minttemp) {
|
if(current_raw[TEMPSENSOR_HOTEND] <= minttemp) {
|
||||||
target_raw[0] = 0;
|
target_raw[TEMPSENSOR_HOTEND] = 0;
|
||||||
analogWrite(HEATER_0_PIN, 0);
|
analogWrite(HEATER_0_PIN, 0);
|
||||||
Serial.println("!! Temperature extruder 0 switched off. MINTEMP triggered !!");
|
Serial.println("!! Temperature extruder 0 switched off. MINTEMP triggered !!");
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
#if (HEATER_2_PIN > -1)
|
#if (HEATER_2_PIN > -1)
|
||||||
if(current_raw[2] <= minttemp) {
|
if(current_raw[TEMPSENSOR_AUX] <= minttemp) {
|
||||||
target_raw[2] = 0;
|
target_raw[TEMPSENSOR_AUX] = 0;
|
||||||
analogWrite(HEATER_2_PIN, 0);
|
analogWrite(HEATER_2_PIN, 0);
|
||||||
Serial.println("!! Temperature extruder 1 switched off. MINTEMP triggered !!");
|
Serial.println("!! Temperature extruder 1 switched off. MINTEMP triggered !!");
|
||||||
}
|
}
|
||||||
|
|
|
@ -1,55 +1,58 @@
|
||||||
/*
|
/*
|
||||||
temperature.h - temperature controller
|
temperature.h - temperature controller
|
||||||
Part of Marlin
|
Part of Marlin
|
||||||
|
|
||||||
Copyright (c) 2011 Erik van der Zalm
|
Copyright (c) 2011 Erik van der Zalm
|
||||||
|
|
||||||
Grbl is free software: you can redistribute it and/or modify
|
Grbl is free software: you can redistribute it and/or modify
|
||||||
it under the terms of the GNU General Public License as published by
|
it under the terms of the GNU General Public License as published by
|
||||||
the Free Software Foundation, either version 3 of the License, or
|
the Free Software Foundation, either version 3 of the License, or
|
||||||
(at your option) any later version.
|
(at your option) any later version.
|
||||||
|
|
||||||
Grbl is distributed in the hope that it will be useful,
|
Grbl is distributed in the hope that it will be useful,
|
||||||
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
GNU General Public License for more details.
|
GNU General Public License for more details.
|
||||||
|
|
||||||
You should have received a copy of the GNU General Public License
|
You should have received a copy of the GNU General Public License
|
||||||
along with Grbl. If not, see <http://www.gnu.org/licenses/>.
|
along with Grbl. If not, see <http://www.gnu.org/licenses/>.
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#ifndef temperature_h
|
#ifndef temperature_h
|
||||||
#define temperature_h
|
#define temperature_h
|
||||||
|
|
||||||
void manage_inactivity(byte debug);
|
#include "Marlin.h"
|
||||||
|
#ifdef PID_ADD_EXTRUSION_RATE
|
||||||
void tp_init();
|
#include "stepper.h"
|
||||||
void manage_heater();
|
#endif
|
||||||
//int temp2analogu(int celsius, const short table[][2], int numtemps);
|
void tp_init();
|
||||||
//float analog2tempu(int raw, const short table[][2], int numtemps);
|
void manage_heater();
|
||||||
float temp2analog(int celsius);
|
//int temp2analogu(int celsius, const short table[][2], int numtemps);
|
||||||
float temp2analogBed(int celsius);
|
//float analog2tempu(int raw, const short table[][2], int numtemps);
|
||||||
float analog2temp(int raw);
|
float temp2analog(int celsius);
|
||||||
float analog2tempBed(int raw);
|
float temp2analogBed(int celsius);
|
||||||
|
float analog2temp(int raw);
|
||||||
#ifdef HEATER_USES_THERMISTOR
|
float analog2tempBed(int raw);
|
||||||
#define HEATERSOURCE 1
|
|
||||||
#endif
|
#ifdef HEATER_USES_THERMISTOR
|
||||||
#ifdef BED_USES_THERMISTOR
|
#define HEATERSOURCE 1
|
||||||
#define BEDSOURCE 1
|
#endif
|
||||||
#endif
|
#ifdef BED_USES_THERMISTOR
|
||||||
|
#define BEDSOURCE 1
|
||||||
//#define temp2analogh( c ) temp2analogu((c),temptable,NUMTEMPS)
|
#endif
|
||||||
//#define analog2temp( c ) analog2tempu((c),temptable,NUMTEMPS
|
|
||||||
|
//#define temp2analogh( c ) temp2analogu((c),temptable,NUMTEMPS)
|
||||||
|
//#define analog2temp( c ) analog2tempu((c),temptable,NUMTEMPS
|
||||||
extern float Kp;
|
|
||||||
extern float Ki;
|
|
||||||
extern float Kd;
|
extern float Kp;
|
||||||
extern float Kc;
|
extern float Ki;
|
||||||
|
extern float Kd;
|
||||||
extern int target_raw[3];
|
extern float Kc;
|
||||||
extern int current_raw[3];
|
|
||||||
extern double pid_setpoint;
|
enum {TEMPSENSOR_HOTEND=0,TEMPSENSOR_BED=1, TEMPSENSOR_AUX=2};
|
||||||
|
extern int target_raw[3];
|
||||||
#endif
|
extern int current_raw[3];
|
||||||
|
extern double pid_setpoint;
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
|
@ -7,67 +7,67 @@
|
||||||
|
|
||||||
#define NUMTEMPS_1 61
|
#define NUMTEMPS_1 61
|
||||||
const short temptable_1[NUMTEMPS_1][2] = {
|
const short temptable_1[NUMTEMPS_1][2] = {
|
||||||
{ 23*OVERSAMPLENR , 300 },
|
{ 23*OVERSAMPLENR , 300 },
|
||||||
{ 25*OVERSAMPLENR , 295 },
|
{ 25*OVERSAMPLENR , 295 },
|
||||||
{ 27*OVERSAMPLENR , 290 },
|
{ 27*OVERSAMPLENR , 290 },
|
||||||
{ 28*OVERSAMPLENR , 285 },
|
{ 28*OVERSAMPLENR , 285 },
|
||||||
{ 31*OVERSAMPLENR , 280 },
|
{ 31*OVERSAMPLENR , 280 },
|
||||||
{ 33*OVERSAMPLENR , 275 },
|
{ 33*OVERSAMPLENR , 275 },
|
||||||
{ 35*OVERSAMPLENR , 270 },
|
{ 35*OVERSAMPLENR , 270 },
|
||||||
{ 38*OVERSAMPLENR , 265 },
|
{ 38*OVERSAMPLENR , 265 },
|
||||||
{ 41*OVERSAMPLENR , 260 },
|
{ 41*OVERSAMPLENR , 260 },
|
||||||
{ 44*OVERSAMPLENR , 255 },
|
{ 44*OVERSAMPLENR , 255 },
|
||||||
{ 48*OVERSAMPLENR , 250 },
|
{ 48*OVERSAMPLENR , 250 },
|
||||||
{ 52*OVERSAMPLENR , 245 },
|
{ 52*OVERSAMPLENR , 245 },
|
||||||
{ 56*OVERSAMPLENR , 240 },
|
{ 56*OVERSAMPLENR , 240 },
|
||||||
{ 61*OVERSAMPLENR , 235 },
|
{ 61*OVERSAMPLENR , 235 },
|
||||||
{ 66*OVERSAMPLENR , 230 },
|
{ 66*OVERSAMPLENR , 230 },
|
||||||
{ 71*OVERSAMPLENR , 225 },
|
{ 71*OVERSAMPLENR , 225 },
|
||||||
{ 78*OVERSAMPLENR , 220 },
|
{ 78*OVERSAMPLENR , 220 },
|
||||||
{ 84*OVERSAMPLENR , 215 },
|
{ 84*OVERSAMPLENR , 215 },
|
||||||
{ 92*OVERSAMPLENR , 210 },
|
{ 92*OVERSAMPLENR , 210 },
|
||||||
{ 100*OVERSAMPLENR , 205 },
|
{ 100*OVERSAMPLENR , 205 },
|
||||||
{ 109*OVERSAMPLENR , 200 },
|
{ 109*OVERSAMPLENR , 200 },
|
||||||
{ 120*OVERSAMPLENR , 195 },
|
{ 120*OVERSAMPLENR , 195 },
|
||||||
{ 131*OVERSAMPLENR , 190 },
|
{ 131*OVERSAMPLENR , 190 },
|
||||||
{ 143*OVERSAMPLENR , 185 },
|
{ 143*OVERSAMPLENR , 185 },
|
||||||
{ 156*OVERSAMPLENR , 180 },
|
{ 156*OVERSAMPLENR , 180 },
|
||||||
{ 171*OVERSAMPLENR , 175 },
|
{ 171*OVERSAMPLENR , 175 },
|
||||||
{ 187*OVERSAMPLENR , 170 },
|
{ 187*OVERSAMPLENR , 170 },
|
||||||
{ 205*OVERSAMPLENR , 165 },
|
{ 205*OVERSAMPLENR , 165 },
|
||||||
{ 224*OVERSAMPLENR , 160 },
|
{ 224*OVERSAMPLENR , 160 },
|
||||||
{ 245*OVERSAMPLENR , 155 },
|
{ 245*OVERSAMPLENR , 155 },
|
||||||
{ 268*OVERSAMPLENR , 150 },
|
{ 268*OVERSAMPLENR , 150 },
|
||||||
{ 293*OVERSAMPLENR , 145 },
|
{ 293*OVERSAMPLENR , 145 },
|
||||||
{ 320*OVERSAMPLENR , 140 },
|
{ 320*OVERSAMPLENR , 140 },
|
||||||
{ 348*OVERSAMPLENR , 135 },
|
{ 348*OVERSAMPLENR , 135 },
|
||||||
{ 379*OVERSAMPLENR , 130 },
|
{ 379*OVERSAMPLENR , 130 },
|
||||||
{ 411*OVERSAMPLENR , 125 },
|
{ 411*OVERSAMPLENR , 125 },
|
||||||
{ 445*OVERSAMPLENR , 120 },
|
{ 445*OVERSAMPLENR , 120 },
|
||||||
{ 480*OVERSAMPLENR , 115 },
|
{ 480*OVERSAMPLENR , 115 },
|
||||||
{ 516*OVERSAMPLENR , 110 },
|
{ 516*OVERSAMPLENR , 110 },
|
||||||
{ 553*OVERSAMPLENR , 105 },
|
{ 553*OVERSAMPLENR , 105 },
|
||||||
{ 591*OVERSAMPLENR , 100 },
|
{ 591*OVERSAMPLENR , 100 },
|
||||||
{ 628*OVERSAMPLENR , 95 },
|
{ 628*OVERSAMPLENR , 95 },
|
||||||
{ 665*OVERSAMPLENR , 90 },
|
{ 665*OVERSAMPLENR , 90 },
|
||||||
{ 702*OVERSAMPLENR , 85 },
|
{ 702*OVERSAMPLENR , 85 },
|
||||||
{ 737*OVERSAMPLENR , 80 },
|
{ 737*OVERSAMPLENR , 80 },
|
||||||
{ 770*OVERSAMPLENR , 75 },
|
{ 770*OVERSAMPLENR , 75 },
|
||||||
{ 801*OVERSAMPLENR , 70 },
|
{ 801*OVERSAMPLENR , 70 },
|
||||||
{ 830*OVERSAMPLENR , 65 },
|
{ 830*OVERSAMPLENR , 65 },
|
||||||
{ 857*OVERSAMPLENR , 60 },
|
{ 857*OVERSAMPLENR , 60 },
|
||||||
{ 881*OVERSAMPLENR , 55 },
|
{ 881*OVERSAMPLENR , 55 },
|
||||||
{ 903*OVERSAMPLENR , 50 },
|
{ 903*OVERSAMPLENR , 50 },
|
||||||
{ 922*OVERSAMPLENR , 45 },
|
{ 922*OVERSAMPLENR , 45 },
|
||||||
{ 939*OVERSAMPLENR , 40 },
|
{ 939*OVERSAMPLENR , 40 },
|
||||||
{ 954*OVERSAMPLENR , 35 },
|
{ 954*OVERSAMPLENR , 35 },
|
||||||
{ 966*OVERSAMPLENR , 30 },
|
{ 966*OVERSAMPLENR , 30 },
|
||||||
{ 977*OVERSAMPLENR , 25 },
|
{ 977*OVERSAMPLENR , 25 },
|
||||||
{ 985*OVERSAMPLENR , 20 },
|
{ 985*OVERSAMPLENR , 20 },
|
||||||
{ 993*OVERSAMPLENR , 15 },
|
{ 993*OVERSAMPLENR , 15 },
|
||||||
{ 999*OVERSAMPLENR , 10 },
|
{ 999*OVERSAMPLENR , 10 },
|
||||||
{ 1004*OVERSAMPLENR , 5 },
|
{ 1004*OVERSAMPLENR , 5 },
|
||||||
{ 1008*OVERSAMPLENR , 0 } //safety
|
{ 1008*OVERSAMPLENR , 0 } //safety
|
||||||
};
|
};
|
||||||
#endif
|
#endif
|
||||||
#if (THERMISTORHEATER_1 == 2) || (THERMISTORHEATER_2 == 2) || (THERMISTORBED == 2) //200k bed thermistor
|
#if (THERMISTORHEATER_1 == 2) || (THERMISTORHEATER_2 == 2) || (THERMISTORBED == 2) //200k bed thermistor
|
||||||
|
@ -100,35 +100,35 @@ const short temptable_2[NUMTEMPS_2][2] = {
|
||||||
#if (THERMISTORHEATER_1 == 3) || (THERMISTORHEATER_2 == 3) || (THERMISTORBED == 3) //mendel-parts
|
#if (THERMISTORHEATER_1 == 3) || (THERMISTORHEATER_2 == 3) || (THERMISTORBED == 3) //mendel-parts
|
||||||
#define NUMTEMPS_3 28
|
#define NUMTEMPS_3 28
|
||||||
const short temptable_3[NUMTEMPS_3][2] = {
|
const short temptable_3[NUMTEMPS_3][2] = {
|
||||||
{1*OVERSAMPLENR,864},
|
{1*OVERSAMPLENR,864},
|
||||||
{21*OVERSAMPLENR,300},
|
{21*OVERSAMPLENR,300},
|
||||||
{25*OVERSAMPLENR,290},
|
{25*OVERSAMPLENR,290},
|
||||||
{29*OVERSAMPLENR,280},
|
{29*OVERSAMPLENR,280},
|
||||||
{33*OVERSAMPLENR,270},
|
{33*OVERSAMPLENR,270},
|
||||||
{39*OVERSAMPLENR,260},
|
{39*OVERSAMPLENR,260},
|
||||||
{46*OVERSAMPLENR,250},
|
{46*OVERSAMPLENR,250},
|
||||||
{54*OVERSAMPLENR,240},
|
{54*OVERSAMPLENR,240},
|
||||||
{64*OVERSAMPLENR,230},
|
{64*OVERSAMPLENR,230},
|
||||||
{75*OVERSAMPLENR,220},
|
{75*OVERSAMPLENR,220},
|
||||||
{90*OVERSAMPLENR,210},
|
{90*OVERSAMPLENR,210},
|
||||||
{107*OVERSAMPLENR,200},
|
{107*OVERSAMPLENR,200},
|
||||||
{128*OVERSAMPLENR,190},
|
{128*OVERSAMPLENR,190},
|
||||||
{154*OVERSAMPLENR,180},
|
{154*OVERSAMPLENR,180},
|
||||||
{184*OVERSAMPLENR,170},
|
{184*OVERSAMPLENR,170},
|
||||||
{221*OVERSAMPLENR,160},
|
{221*OVERSAMPLENR,160},
|
||||||
{265*OVERSAMPLENR,150},
|
{265*OVERSAMPLENR,150},
|
||||||
{316*OVERSAMPLENR,140},
|
{316*OVERSAMPLENR,140},
|
||||||
{375*OVERSAMPLENR,130},
|
{375*OVERSAMPLENR,130},
|
||||||
{441*OVERSAMPLENR,120},
|
{441*OVERSAMPLENR,120},
|
||||||
{513*OVERSAMPLENR,110},
|
{513*OVERSAMPLENR,110},
|
||||||
{588*OVERSAMPLENR,100},
|
{588*OVERSAMPLENR,100},
|
||||||
{734*OVERSAMPLENR,80},
|
{734*OVERSAMPLENR,80},
|
||||||
{856*OVERSAMPLENR,60},
|
{856*OVERSAMPLENR,60},
|
||||||
{938*OVERSAMPLENR,40},
|
{938*OVERSAMPLENR,40},
|
||||||
{986*OVERSAMPLENR,20},
|
{986*OVERSAMPLENR,20},
|
||||||
{1008*OVERSAMPLENR,0},
|
{1008*OVERSAMPLENR,0},
|
||||||
{1018*OVERSAMPLENR,-20}
|
{1018*OVERSAMPLENR,-20}
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
#if (THERMISTORHEATER_1 == 4) || (THERMISTORHEATER_2 == 4) || (THERMISTORBED == 4) //10k thermistor
|
#if (THERMISTORHEATER_1 == 4) || (THERMISTORHEATER_2 == 4) || (THERMISTORBED == 4) //10k thermistor
|
||||||
|
|
|
@ -153,4 +153,4 @@
|
||||||
#define BLOCK ;
|
#define BLOCK ;
|
||||||
#endif
|
#endif
|
||||||
#endif //ULTRALCD
|
#endif //ULTRALCD
|
||||||
|
|
||||||
|
|
3186
Marlin/ultralcd.pde
3186
Marlin/ultralcd.pde
|
@ -1,1593 +1,1593 @@
|
||||||
#include "ultralcd.h"
|
#include "ultralcd.h"
|
||||||
|
|
||||||
|
|
||||||
#ifdef ULTRA_LCD
|
#ifdef ULTRA_LCD
|
||||||
extern volatile int feedmultiply;
|
extern volatile int feedmultiply;
|
||||||
extern long position[4];
|
extern long position[4];
|
||||||
|
|
||||||
char messagetext[LCD_WIDTH]="";
|
char messagetext[LCD_WIDTH]="";
|
||||||
|
|
||||||
#include <LiquidCrystal.h>
|
#include <LiquidCrystal.h>
|
||||||
LiquidCrystal lcd(LCD_PINS_RS, LCD_PINS_ENABLE, LCD_PINS_D4, LCD_PINS_D5,LCD_PINS_D6,LCD_PINS_D7); //RS,Enable,D4,D5,D6,D7
|
LiquidCrystal lcd(LCD_PINS_RS, LCD_PINS_ENABLE, LCD_PINS_D4, LCD_PINS_D5,LCD_PINS_D6,LCD_PINS_D7); //RS,Enable,D4,D5,D6,D7
|
||||||
|
|
||||||
unsigned long previous_millis_lcd=0;
|
unsigned long previous_millis_lcd=0;
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
volatile char buttons=0; //the last checked buttons in a bit array.
|
volatile char buttons=0; //the last checked buttons in a bit array.
|
||||||
int encoderpos=0;
|
int encoderpos=0;
|
||||||
short lastenc=0;
|
short lastenc=0;
|
||||||
#ifdef NEWPANEL
|
#ifdef NEWPANEL
|
||||||
long blocking=0;
|
long blocking=0;
|
||||||
#else
|
#else
|
||||||
long blocking[8]={0,0,0,0,0,0,0,0};
|
long blocking[8]={0,0,0,0,0,0,0,0};
|
||||||
#endif
|
#endif
|
||||||
MainMenu menu;
|
MainMenu menu;
|
||||||
|
|
||||||
void lcd_status(const char* message)
|
void lcd_status(const char* message)
|
||||||
{
|
{
|
||||||
strncpy(messagetext,message,LCD_WIDTH);
|
strncpy(messagetext,message,LCD_WIDTH);
|
||||||
}
|
}
|
||||||
|
|
||||||
void clear()
|
void clear()
|
||||||
{
|
{
|
||||||
//lcd.setCursor(0,0);
|
//lcd.setCursor(0,0);
|
||||||
lcd.clear();
|
lcd.clear();
|
||||||
//delay(1);
|
//delay(1);
|
||||||
// lcd.begin(LCD_WIDTH,LCD_HEIGHT);
|
// lcd.begin(LCD_WIDTH,LCD_HEIGHT);
|
||||||
//lcd_init();
|
//lcd_init();
|
||||||
}
|
}
|
||||||
long previous_millis_buttons=0;
|
long previous_millis_buttons=0;
|
||||||
|
|
||||||
void lcd_init()
|
void lcd_init()
|
||||||
{
|
{
|
||||||
//beep();
|
//beep();
|
||||||
byte Degree[8] =
|
byte Degree[8] =
|
||||||
{
|
{
|
||||||
B01100,
|
B01100,
|
||||||
B10010,
|
B10010,
|
||||||
B10010,
|
B10010,
|
||||||
B01100,
|
B01100,
|
||||||
B00000,
|
B00000,
|
||||||
B00000,
|
B00000,
|
||||||
B00000,
|
B00000,
|
||||||
B00000
|
B00000
|
||||||
};
|
};
|
||||||
byte Thermometer[8] =
|
byte Thermometer[8] =
|
||||||
{
|
{
|
||||||
B00100,
|
B00100,
|
||||||
B01010,
|
B01010,
|
||||||
B01010,
|
B01010,
|
||||||
B01010,
|
B01010,
|
||||||
B01010,
|
B01010,
|
||||||
B10001,
|
B10001,
|
||||||
B10001,
|
B10001,
|
||||||
B01110
|
B01110
|
||||||
};
|
};
|
||||||
byte uplevel[8]={0x04, 0x0e, 0x1f, 0x04, 0x1c, 0x00, 0x00, 0x00};//thanks joris
|
byte uplevel[8]={0x04, 0x0e, 0x1f, 0x04, 0x1c, 0x00, 0x00, 0x00};//thanks joris
|
||||||
byte refresh[8]={0x00, 0x06, 0x19, 0x18, 0x03, 0x13, 0x0c, 0x00}; //thanks joris
|
byte refresh[8]={0x00, 0x06, 0x19, 0x18, 0x03, 0x13, 0x0c, 0x00}; //thanks joris
|
||||||
lcd.begin(LCD_WIDTH, LCD_HEIGHT);
|
lcd.begin(LCD_WIDTH, LCD_HEIGHT);
|
||||||
lcd.createChar(1,Degree);
|
lcd.createChar(1,Degree);
|
||||||
lcd.createChar(2,Thermometer);
|
lcd.createChar(2,Thermometer);
|
||||||
lcd.createChar(3,uplevel);
|
lcd.createChar(3,uplevel);
|
||||||
lcd.createChar(4,refresh);
|
lcd.createChar(4,refresh);
|
||||||
LCD_MESSAGE(fillto(LCD_WIDTH,"UltiMarlin ready."));
|
LCD_MESSAGE(fillto(LCD_WIDTH,"UltiMarlin ready."));
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
void beep()
|
void beep()
|
||||||
{
|
{
|
||||||
//return;
|
//return;
|
||||||
#ifdef ULTIPANEL
|
#ifdef ULTIPANEL
|
||||||
pinMode(BEEPER,OUTPUT);
|
pinMode(BEEPER,OUTPUT);
|
||||||
for(int i=0;i<20;i++){
|
for(int i=0;i<20;i++){
|
||||||
WRITE(BEEPER,HIGH);
|
WRITE(BEEPER,HIGH);
|
||||||
delay(5);
|
delay(5);
|
||||||
WRITE(BEEPER,LOW);
|
WRITE(BEEPER,LOW);
|
||||||
delay(5);
|
delay(5);
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
void beepshort()
|
void beepshort()
|
||||||
{
|
{
|
||||||
//return;
|
//return;
|
||||||
#ifdef ULTIPANEL
|
#ifdef ULTIPANEL
|
||||||
pinMode(BEEPER,OUTPUT);
|
pinMode(BEEPER,OUTPUT);
|
||||||
for(int i=0;i<10;i++){
|
for(int i=0;i<10;i++){
|
||||||
WRITE(BEEPER,HIGH);
|
WRITE(BEEPER,HIGH);
|
||||||
delay(3);
|
delay(3);
|
||||||
WRITE(BEEPER,LOW);
|
WRITE(BEEPER,LOW);
|
||||||
delay(3);
|
delay(3);
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
void lcd_status()
|
void lcd_status()
|
||||||
{
|
{
|
||||||
#ifdef ULTIPANEL
|
#ifdef ULTIPANEL
|
||||||
static uint8_t oldbuttons=0;
|
static uint8_t oldbuttons=0;
|
||||||
static long previous_millis_buttons=0;
|
static long previous_millis_buttons=0;
|
||||||
static long previous_lcdinit=0;
|
static long previous_lcdinit=0;
|
||||||
// buttons_check(); // Done in temperature interrupt
|
// buttons_check(); // Done in temperature interrupt
|
||||||
//previous_millis_buttons=millis();
|
//previous_millis_buttons=millis();
|
||||||
|
|
||||||
if((buttons==oldbuttons) && ((millis() - previous_millis_lcd) < LCD_UPDATE_INTERVAL) )
|
if((buttons==oldbuttons) && ((millis() - previous_millis_lcd) < LCD_UPDATE_INTERVAL) )
|
||||||
return;
|
return;
|
||||||
oldbuttons=buttons;
|
oldbuttons=buttons;
|
||||||
#else
|
#else
|
||||||
|
|
||||||
if(((millis() - previous_millis_lcd) < LCD_UPDATE_INTERVAL) )
|
if(((millis() - previous_millis_lcd) < LCD_UPDATE_INTERVAL) )
|
||||||
return;
|
return;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
previous_millis_lcd=millis();
|
previous_millis_lcd=millis();
|
||||||
menu.update();
|
menu.update();
|
||||||
}
|
}
|
||||||
#ifdef ULTIPANEL
|
#ifdef ULTIPANEL
|
||||||
void buttons_init()
|
void buttons_init()
|
||||||
{
|
{
|
||||||
#ifdef NEWPANEL
|
#ifdef NEWPANEL
|
||||||
pinMode(BTN_EN1,INPUT);
|
pinMode(BTN_EN1,INPUT);
|
||||||
pinMode(BTN_EN2,INPUT);
|
pinMode(BTN_EN2,INPUT);
|
||||||
pinMode(BTN_ENC,INPUT);
|
pinMode(BTN_ENC,INPUT);
|
||||||
pinMode(SDCARDDETECT,INPUT);
|
pinMode(SDCARDDETECT,INPUT);
|
||||||
WRITE(BTN_EN1,HIGH);
|
WRITE(BTN_EN1,HIGH);
|
||||||
WRITE(BTN_EN2,HIGH);
|
WRITE(BTN_EN2,HIGH);
|
||||||
WRITE(BTN_ENC,HIGH);
|
WRITE(BTN_ENC,HIGH);
|
||||||
WRITE(SDCARDDETECT,HIGH);
|
WRITE(SDCARDDETECT,HIGH);
|
||||||
#else
|
#else
|
||||||
pinMode(SHIFT_CLK,OUTPUT);
|
pinMode(SHIFT_CLK,OUTPUT);
|
||||||
pinMode(SHIFT_LD,OUTPUT);
|
pinMode(SHIFT_LD,OUTPUT);
|
||||||
pinMode(SHIFT_EN,OUTPUT);
|
pinMode(SHIFT_EN,OUTPUT);
|
||||||
pinMode(SHIFT_OUT,INPUT);
|
pinMode(SHIFT_OUT,INPUT);
|
||||||
WRITE(SHIFT_OUT,HIGH);
|
WRITE(SHIFT_OUT,HIGH);
|
||||||
WRITE(SHIFT_LD,HIGH);
|
WRITE(SHIFT_LD,HIGH);
|
||||||
WRITE(SHIFT_EN,LOW);
|
WRITE(SHIFT_EN,LOW);
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
void buttons_check()
|
void buttons_check()
|
||||||
{
|
{
|
||||||
// volatile static bool busy=false;
|
// volatile static bool busy=false;
|
||||||
// if(busy)
|
// if(busy)
|
||||||
// return;
|
// return;
|
||||||
// busy=true;
|
// busy=true;
|
||||||
|
|
||||||
#ifdef NEWPANEL
|
#ifdef NEWPANEL
|
||||||
uint8_t newbutton=0;
|
uint8_t newbutton=0;
|
||||||
if(READ(BTN_EN1)==0) newbutton|=EN_A;
|
if(READ(BTN_EN1)==0) newbutton|=EN_A;
|
||||||
if(READ(BTN_EN2)==0) newbutton|=EN_B;
|
if(READ(BTN_EN2)==0) newbutton|=EN_B;
|
||||||
if((blocking<millis()) &&(READ(BTN_ENC)==0))
|
if((blocking<millis()) &&(READ(BTN_ENC)==0))
|
||||||
newbutton|=EN_C;
|
newbutton|=EN_C;
|
||||||
buttons=newbutton;
|
buttons=newbutton;
|
||||||
#else
|
#else
|
||||||
//read it from the shift register
|
//read it from the shift register
|
||||||
uint8_t newbutton=0;
|
uint8_t newbutton=0;
|
||||||
WRITE(SHIFT_LD,LOW);
|
WRITE(SHIFT_LD,LOW);
|
||||||
WRITE(SHIFT_LD,HIGH);
|
WRITE(SHIFT_LD,HIGH);
|
||||||
unsigned char tmp_buttons=0;
|
unsigned char tmp_buttons=0;
|
||||||
for(unsigned char i=0;i<8;i++)
|
for(unsigned char i=0;i<8;i++)
|
||||||
{
|
{
|
||||||
newbutton = newbutton>>1;
|
newbutton = newbutton>>1;
|
||||||
if(READ(SHIFT_OUT))
|
if(READ(SHIFT_OUT))
|
||||||
newbutton|=(1<<7);
|
newbutton|=(1<<7);
|
||||||
WRITE(SHIFT_CLK,HIGH);
|
WRITE(SHIFT_CLK,HIGH);
|
||||||
WRITE(SHIFT_CLK,LOW);
|
WRITE(SHIFT_CLK,LOW);
|
||||||
}
|
}
|
||||||
buttons=~newbutton; //invert it, because a pressed switch produces a logical 0
|
buttons=~newbutton; //invert it, because a pressed switch produces a logical 0
|
||||||
#endif
|
#endif
|
||||||
char enc=0;
|
char enc=0;
|
||||||
if(buttons&EN_A)
|
if(buttons&EN_A)
|
||||||
enc|=(1<<0);
|
enc|=(1<<0);
|
||||||
if(buttons&EN_B)
|
if(buttons&EN_B)
|
||||||
enc|=(1<<1);
|
enc|=(1<<1);
|
||||||
if(enc!=lastenc)
|
if(enc!=lastenc)
|
||||||
{
|
{
|
||||||
switch(enc)
|
switch(enc)
|
||||||
{
|
{
|
||||||
case encrot0:
|
case encrot0:
|
||||||
if(lastenc==encrot3)
|
if(lastenc==encrot3)
|
||||||
encoderpos++;
|
encoderpos++;
|
||||||
else if(lastenc==encrot1)
|
else if(lastenc==encrot1)
|
||||||
encoderpos--;
|
encoderpos--;
|
||||||
break;
|
break;
|
||||||
case encrot1:
|
case encrot1:
|
||||||
if(lastenc==encrot0)
|
if(lastenc==encrot0)
|
||||||
encoderpos++;
|
encoderpos++;
|
||||||
else if(lastenc==encrot2)
|
else if(lastenc==encrot2)
|
||||||
encoderpos--;
|
encoderpos--;
|
||||||
break;
|
break;
|
||||||
case encrot2:
|
case encrot2:
|
||||||
if(lastenc==encrot1)
|
if(lastenc==encrot1)
|
||||||
encoderpos++;
|
encoderpos++;
|
||||||
else if(lastenc==encrot3)
|
else if(lastenc==encrot3)
|
||||||
encoderpos--;
|
encoderpos--;
|
||||||
break;
|
break;
|
||||||
case encrot3:
|
case encrot3:
|
||||||
if(lastenc==encrot2)
|
if(lastenc==encrot2)
|
||||||
encoderpos++;
|
encoderpos++;
|
||||||
else if(lastenc==encrot0)
|
else if(lastenc==encrot0)
|
||||||
encoderpos--;
|
encoderpos--;
|
||||||
break;
|
break;
|
||||||
default:
|
default:
|
||||||
;
|
;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
lastenc=enc;
|
lastenc=enc;
|
||||||
// busy=false;
|
// busy=false;
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
MainMenu::MainMenu()
|
MainMenu::MainMenu()
|
||||||
{
|
{
|
||||||
status=Main_Status;
|
status=Main_Status;
|
||||||
displayStartingRow=0;
|
displayStartingRow=0;
|
||||||
activeline=0;
|
activeline=0;
|
||||||
force_lcd_update=true;
|
force_lcd_update=true;
|
||||||
#ifdef ULTIPANEL
|
#ifdef ULTIPANEL
|
||||||
buttons_init();
|
buttons_init();
|
||||||
#endif
|
#endif
|
||||||
lcd_init();
|
lcd_init();
|
||||||
linechanging=false;
|
linechanging=false;
|
||||||
}
|
}
|
||||||
|
|
||||||
extern volatile bool feedmultiplychanged;
|
extern volatile bool feedmultiplychanged;
|
||||||
|
|
||||||
void MainMenu::showStatus()
|
void MainMenu::showStatus()
|
||||||
{
|
{
|
||||||
#if LCD_HEIGHT==4
|
#if LCD_HEIGHT==4
|
||||||
static int oldcurrentraw=-1;
|
static int oldcurrentraw=-1;
|
||||||
static int oldtargetraw=-1;
|
static int oldtargetraw=-1;
|
||||||
//force_lcd_update=true;
|
//force_lcd_update=true;
|
||||||
if(force_lcd_update||feedmultiplychanged) //initial display of content
|
if(force_lcd_update||feedmultiplychanged) //initial display of content
|
||||||
{
|
{
|
||||||
feedmultiplychanged=false;
|
feedmultiplychanged=false;
|
||||||
encoderpos=feedmultiply;
|
encoderpos=feedmultiply;
|
||||||
clear();
|
clear();
|
||||||
lcd.setCursor(0,0);lcd.print("\002123/567\001 ");
|
lcd.setCursor(0,0);lcd.print("\002123/567\001 ");
|
||||||
#if defined BED_USES_THERMISTOR || defined BED_USES_AD595
|
#if defined BED_USES_THERMISTOR || defined BED_USES_AD595
|
||||||
lcd.setCursor(10,0);lcd.print("B123/567\001 ");
|
lcd.setCursor(10,0);lcd.print("B123/567\001 ");
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
if((abs(current_raw[0]-oldcurrentraw)>3)||force_lcd_update)
|
if((abs(current_raw[TEMPSENSOR_HOTEND]-oldcurrentraw)>3)||force_lcd_update)
|
||||||
{
|
{
|
||||||
lcd.setCursor(1,0);
|
lcd.setCursor(1,0);
|
||||||
lcd.print(ftostr3(analog2temp(current_raw[0])));
|
lcd.print(ftostr3(analog2temp(current_raw[TEMPSENSOR_HOTEND])));
|
||||||
oldcurrentraw=current_raw[0];
|
oldcurrentraw=current_raw[TEMPSENSOR_HOTEND];
|
||||||
}
|
}
|
||||||
if((target_raw[0]!=oldtargetraw)||force_lcd_update)
|
if((target_raw[TEMPSENSOR_HOTEND]!=oldtargetraw)||force_lcd_update)
|
||||||
{
|
{
|
||||||
lcd.setCursor(5,0);
|
lcd.setCursor(5,0);
|
||||||
lcd.print(ftostr3(analog2temp(target_raw[0])));
|
lcd.print(ftostr3(analog2temp(target_raw[TEMPSENSOR_HOTEND])));
|
||||||
oldtargetraw=target_raw[0];
|
oldtargetraw=target_raw[TEMPSENSOR_HOTEND];
|
||||||
}
|
}
|
||||||
#if defined BED_USES_THERMISTOR || defined BED_USES_AD595
|
#if defined BED_USES_THERMISTOR || defined BED_USES_AD595
|
||||||
static int oldcurrentbedraw=-1;
|
static int oldcurrentbedraw=-1;
|
||||||
static int oldtargetbedraw=-1;
|
static int oldtargetbedraw=-1;
|
||||||
if((current_bed_raw!=oldcurrentbedraw)||force_lcd_update)
|
if((current_bed_raw!=oldcurrentbedraw)||force_lcd_update)
|
||||||
{
|
{
|
||||||
lcd.setCursor(1,0);
|
lcd.setCursor(1,0);
|
||||||
lcd.print(ftostr3(analog2temp(current_bed_raw)));
|
lcd.print(ftostr3(analog2temp(current_bed_raw)));
|
||||||
oldcurrentraw=current_raw[1];
|
oldcurrentraw=current_raw[TEMPSENSOR_BED];
|
||||||
}
|
}
|
||||||
if((target_bed_raw!=oldtargebedtraw)||force_lcd_update)
|
if((target_bed_raw!=oldtargebedtraw)||force_lcd_update)
|
||||||
{
|
{
|
||||||
lcd.setCursor(5,0);
|
lcd.setCursor(5,0);
|
||||||
lcd.print(ftostr3(analog2temp(target_bed_raw)));
|
lcd.print(ftostr3(analog2temp(target_bed_raw)));
|
||||||
oldtargetraw=target_bed_raw;
|
oldtargetraw=target_bed_raw;
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
//starttime=2;
|
//starttime=2;
|
||||||
static uint16_t oldtime=0;
|
static uint16_t oldtime=0;
|
||||||
if(starttime!=0)
|
if(starttime!=0)
|
||||||
{
|
{
|
||||||
lcd.setCursor(0,1);
|
lcd.setCursor(0,1);
|
||||||
uint16_t time=millis()/60000-starttime/60000;
|
uint16_t time=millis()/60000-starttime/60000;
|
||||||
|
|
||||||
if(starttime!=oldtime)
|
if(starttime!=oldtime)
|
||||||
{
|
{
|
||||||
lcd.print(itostr2(time/60));lcd.print("h ");lcd.print(itostr2(time%60));lcd.print("m");
|
lcd.print(itostr2(time/60));lcd.print("h ");lcd.print(itostr2(time%60));lcd.print("m");
|
||||||
oldtime=time;
|
oldtime=time;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
static int oldzpos=0;
|
static int oldzpos=0;
|
||||||
int currentz=current_position[2]*10;
|
int currentz=current_position[2]*10;
|
||||||
if((currentz!=oldzpos)||force_lcd_update)
|
if((currentz!=oldzpos)||force_lcd_update)
|
||||||
{
|
{
|
||||||
lcd.setCursor(10,1);
|
lcd.setCursor(10,1);
|
||||||
lcd.print("Z:");lcd.print(itostr31(currentz));
|
lcd.print("Z:");lcd.print(itostr31(currentz));
|
||||||
oldzpos=currentz;
|
oldzpos=currentz;
|
||||||
}
|
}
|
||||||
static int oldfeedmultiply=0;
|
static int oldfeedmultiply=0;
|
||||||
int curfeedmultiply=feedmultiply;
|
int curfeedmultiply=feedmultiply;
|
||||||
if(encoderpos!=curfeedmultiply||force_lcd_update)
|
if(encoderpos!=curfeedmultiply||force_lcd_update)
|
||||||
{
|
{
|
||||||
curfeedmultiply=encoderpos;
|
curfeedmultiply=encoderpos;
|
||||||
if(curfeedmultiply<10)
|
if(curfeedmultiply<10)
|
||||||
curfeedmultiply=10;
|
curfeedmultiply=10;
|
||||||
if(curfeedmultiply>999)
|
if(curfeedmultiply>999)
|
||||||
curfeedmultiply=999;
|
curfeedmultiply=999;
|
||||||
feedmultiply=curfeedmultiply;
|
feedmultiply=curfeedmultiply;
|
||||||
encoderpos=curfeedmultiply;
|
encoderpos=curfeedmultiply;
|
||||||
}
|
}
|
||||||
if((curfeedmultiply!=oldfeedmultiply)||force_lcd_update)
|
if((curfeedmultiply!=oldfeedmultiply)||force_lcd_update)
|
||||||
{
|
{
|
||||||
oldfeedmultiply=curfeedmultiply;
|
oldfeedmultiply=curfeedmultiply;
|
||||||
lcd.setCursor(0,2);
|
lcd.setCursor(0,2);
|
||||||
lcd.print(itostr3(curfeedmultiply));lcd.print("% ");
|
lcd.print(itostr3(curfeedmultiply));lcd.print("% ");
|
||||||
}
|
}
|
||||||
if(messagetext[0]!='\0')
|
if(messagetext[0]!='\0')
|
||||||
{
|
{
|
||||||
lcd.setCursor(0,LCD_HEIGHT-1);
|
lcd.setCursor(0,LCD_HEIGHT-1);
|
||||||
lcd.print(fillto(LCD_WIDTH,messagetext));
|
lcd.print(fillto(LCD_WIDTH,messagetext));
|
||||||
messagetext[0]='\0';
|
messagetext[0]='\0';
|
||||||
}
|
}
|
||||||
#else //smaller LCDS----------------------------------
|
#else //smaller LCDS----------------------------------
|
||||||
static int oldcurrentraw=-1;
|
static int oldcurrentraw=-1;
|
||||||
static int oldtargetraw=-1;
|
static int oldtargetraw=-1;
|
||||||
if(force_lcd_update) //initial display of content
|
if(force_lcd_update) //initial display of content
|
||||||
{
|
{
|
||||||
encoderpos=feedmultiply;
|
encoderpos=feedmultiply;
|
||||||
lcd.setCursor(0,0);lcd.print("\002123/567\001 ");
|
lcd.setCursor(0,0);lcd.print("\002123/567\001 ");
|
||||||
#if defined BED_USES_THERMISTOR || defined BED_USES_AD595
|
#if defined BED_USES_THERMISTOR || defined BED_USES_AD595
|
||||||
lcd.setCursor(10,0);lcd.print("B123/567\001 ");
|
lcd.setCursor(10,0);lcd.print("B123/567\001 ");
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
if((abs(current_raw[0]-oldcurrentraw)>3)||force_lcd_update)
|
if((abs(current_raw[TEMPSENSOR_HOTEND]-oldcurrentraw)>3)||force_lcd_update)
|
||||||
{
|
{
|
||||||
lcd.setCursor(1,0);
|
lcd.setCursor(1,0);
|
||||||
lcd.print(ftostr3(analog2temp(current_raw[0])));
|
lcd.print(ftostr3(analog2temp(current_raw[TEMPSENSOR_HOTEND])));
|
||||||
oldcurrentraw=current_raw[0];
|
oldcurrentraw=current_raw[TEMPSENSOR_HOTEND];
|
||||||
}
|
}
|
||||||
if((target_raw[0]!=oldtargetraw)||force_lcd_update)
|
if((target_raw[TEMPSENSOR_HOTEND]!=oldtargetraw)||force_lcd_update)
|
||||||
{
|
{
|
||||||
lcd.setCursor(5,0);
|
lcd.setCursor(5,0);
|
||||||
lcd.print(ftostr3(analog2temp(target_raw[0])));
|
lcd.print(ftostr3(analog2temp(target_raw[TEMPSENSOR_HOTEND])));
|
||||||
oldtargetraw=target_raw[0];
|
oldtargetraw=target_raw[TEMPSENSOR_HOTEND];
|
||||||
}
|
}
|
||||||
|
|
||||||
if(messagetext[0]!='\0')
|
if(messagetext[0]!='\0')
|
||||||
{
|
{
|
||||||
lcd.setCursor(0,LCD_HEIGHT-1);
|
lcd.setCursor(0,LCD_HEIGHT-1);
|
||||||
lcd.print(fillto(LCD_WIDTH,messagetext));
|
lcd.print(fillto(LCD_WIDTH,messagetext));
|
||||||
messagetext[0]='\0';
|
messagetext[0]='\0';
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
enum {ItemP_exit, ItemP_home, ItemP_origin, ItemP_preheat, ItemP_extrude, ItemP_disstep};
|
enum {ItemP_exit, ItemP_home, ItemP_origin, ItemP_preheat, ItemP_extrude, ItemP_disstep};
|
||||||
|
|
||||||
void MainMenu::showPrepare()
|
void MainMenu::showPrepare()
|
||||||
{
|
{
|
||||||
uint8_t line=0;
|
uint8_t line=0;
|
||||||
if(lastlineoffset!=lineoffset)
|
if(lastlineoffset!=lineoffset)
|
||||||
{
|
{
|
||||||
force_lcd_update=true;
|
force_lcd_update=true;
|
||||||
clear();
|
clear();
|
||||||
}
|
}
|
||||||
for(uint8_t i=lineoffset;i<lineoffset+LCD_HEIGHT;i++)
|
for(uint8_t i=lineoffset;i<lineoffset+LCD_HEIGHT;i++)
|
||||||
{
|
{
|
||||||
//Serial.println((int)(line-lineoffset));
|
//Serial.println((int)(line-lineoffset));
|
||||||
switch(i)
|
switch(i)
|
||||||
{
|
{
|
||||||
case ItemP_exit:
|
case ItemP_exit:
|
||||||
{
|
{
|
||||||
if(force_lcd_update)
|
if(force_lcd_update)
|
||||||
{
|
{
|
||||||
lcd.setCursor(0,line);lcd.print(" Prepare");
|
lcd.setCursor(0,line);lcd.print(" Prepare");
|
||||||
}
|
}
|
||||||
if((activeline==line) && CLICKED)
|
if((activeline==line) && CLICKED)
|
||||||
{
|
{
|
||||||
BLOCK
|
BLOCK
|
||||||
status=Main_Menu;
|
status=Main_Menu;
|
||||||
beepshort();
|
beepshort();
|
||||||
}
|
}
|
||||||
}break;
|
}break;
|
||||||
case ItemP_home:
|
case ItemP_home:
|
||||||
{
|
{
|
||||||
if(force_lcd_update)
|
if(force_lcd_update)
|
||||||
{
|
{
|
||||||
lcd.setCursor(0,line);lcd.print(" Auto Home");
|
lcd.setCursor(0,line);lcd.print(" Auto Home");
|
||||||
}
|
}
|
||||||
if((activeline==line) && CLICKED)
|
if((activeline==line) && CLICKED)
|
||||||
{
|
{
|
||||||
BLOCK
|
BLOCK
|
||||||
enquecommand("G28 X-105 Y-105 Z0");
|
enquecommand("G28 X-105 Y-105 Z0");
|
||||||
beepshort();
|
beepshort();
|
||||||
}
|
}
|
||||||
}break;
|
}break;
|
||||||
case ItemP_origin:
|
case ItemP_origin:
|
||||||
{
|
{
|
||||||
if(force_lcd_update)
|
if(force_lcd_update)
|
||||||
{
|
{
|
||||||
lcd.setCursor(0,line);lcd.print(" Set Origin");
|
lcd.setCursor(0,line);lcd.print(" Set Origin");
|
||||||
|
|
||||||
}
|
}
|
||||||
if((activeline==line) && CLICKED)
|
if((activeline==line) && CLICKED)
|
||||||
{
|
{
|
||||||
BLOCK
|
BLOCK
|
||||||
enquecommand("G92 X0 Y0 Z0");
|
enquecommand("G92 X0 Y0 Z0");
|
||||||
beepshort();
|
beepshort();
|
||||||
}
|
}
|
||||||
}break;
|
}break;
|
||||||
case ItemP_preheat:
|
case ItemP_preheat:
|
||||||
{
|
{
|
||||||
if(force_lcd_update)
|
if(force_lcd_update)
|
||||||
{
|
{
|
||||||
lcd.setCursor(0,line);lcd.print(" Preheat");
|
lcd.setCursor(0,line);lcd.print(" Preheat");
|
||||||
}
|
}
|
||||||
if((activeline==line) && CLICKED)
|
if((activeline==line) && CLICKED)
|
||||||
{
|
{
|
||||||
BLOCK
|
BLOCK
|
||||||
target_raw[0] = temp2analog(170);
|
target_raw[TEMPSENSOR_HOTEND] = temp2analog(170);
|
||||||
beepshort();
|
beepshort();
|
||||||
}
|
}
|
||||||
}break;
|
}break;
|
||||||
case ItemP_extrude:
|
case ItemP_extrude:
|
||||||
{
|
{
|
||||||
if(force_lcd_update)
|
if(force_lcd_update)
|
||||||
{
|
{
|
||||||
lcd.setCursor(0,line);lcd.print(" Extrude");
|
lcd.setCursor(0,line);lcd.print(" Extrude");
|
||||||
}
|
}
|
||||||
if((activeline==line) && CLICKED)
|
if((activeline==line) && CLICKED)
|
||||||
{
|
{
|
||||||
BLOCK
|
BLOCK
|
||||||
enquecommand("G92 E0");
|
enquecommand("G92 E0");
|
||||||
enquecommand("G1 F700 E50");
|
enquecommand("G1 F700 E50");
|
||||||
beepshort();
|
beepshort();
|
||||||
}
|
}
|
||||||
}break;
|
}break;
|
||||||
case ItemP_disstep:
|
case ItemP_disstep:
|
||||||
{
|
{
|
||||||
if(force_lcd_update)
|
if(force_lcd_update)
|
||||||
{
|
{
|
||||||
lcd.setCursor(0,line);lcd.print(" Disable Steppers");
|
lcd.setCursor(0,line);lcd.print(" Disable Steppers");
|
||||||
}
|
}
|
||||||
if((activeline==line) && CLICKED)
|
if((activeline==line) && CLICKED)
|
||||||
{
|
{
|
||||||
BLOCK
|
BLOCK
|
||||||
enquecommand("M84");
|
enquecommand("M84");
|
||||||
beepshort();
|
beepshort();
|
||||||
}
|
}
|
||||||
}break;
|
}break;
|
||||||
default:
|
default:
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
line++;
|
line++;
|
||||||
}
|
}
|
||||||
lastlineoffset=lineoffset;
|
lastlineoffset=lineoffset;
|
||||||
if((encoderpos/lcdslow!=lastencoderpos/lcdslow)||force_lcd_update)
|
if((encoderpos/lcdslow!=lastencoderpos/lcdslow)||force_lcd_update)
|
||||||
{
|
{
|
||||||
|
|
||||||
lcd.setCursor(0,activeline);lcd.print((activeline+lineoffset)?' ':' ');
|
lcd.setCursor(0,activeline);lcd.print((activeline+lineoffset)?' ':' ');
|
||||||
|
|
||||||
if(encoderpos<0)
|
if(encoderpos<0)
|
||||||
{
|
{
|
||||||
lineoffset--;
|
lineoffset--;
|
||||||
if(lineoffset<0)
|
if(lineoffset<0)
|
||||||
lineoffset=0;
|
lineoffset=0;
|
||||||
encoderpos=0;
|
encoderpos=0;
|
||||||
force_lcd_update=true;
|
force_lcd_update=true;
|
||||||
}
|
}
|
||||||
if(encoderpos/lcdslow>3)
|
if(encoderpos/lcdslow>3)
|
||||||
{
|
{
|
||||||
lineoffset++;
|
lineoffset++;
|
||||||
encoderpos=3*lcdslow;
|
encoderpos=3*lcdslow;
|
||||||
if(lineoffset>(ItemP_disstep+1-LCD_HEIGHT))
|
if(lineoffset>(ItemP_disstep+1-LCD_HEIGHT))
|
||||||
lineoffset=ItemP_disstep+1-LCD_HEIGHT;
|
lineoffset=ItemP_disstep+1-LCD_HEIGHT;
|
||||||
force_lcd_update=true;
|
force_lcd_update=true;
|
||||||
}
|
}
|
||||||
//encoderpos=encoderpos%LCD_HEIGHT;
|
//encoderpos=encoderpos%LCD_HEIGHT;
|
||||||
lastencoderpos=encoderpos;
|
lastencoderpos=encoderpos;
|
||||||
activeline=encoderpos/lcdslow;
|
activeline=encoderpos/lcdslow;
|
||||||
lcd.setCursor(0,activeline);lcd.print((activeline+lineoffset)?'>':'\003');
|
lcd.setCursor(0,activeline);lcd.print((activeline+lineoffset)?'>':'\003');
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
enum {
|
enum {
|
||||||
ItemC_exit, ItemC_nozzle,
|
ItemC_exit, ItemC_nozzle,
|
||||||
ItemC_PID_P,ItemC_PID_I,ItemC_PID_D,ItemC_PID_C,
|
ItemC_PID_P,ItemC_PID_I,ItemC_PID_D,ItemC_PID_C,
|
||||||
ItemC_fan,
|
ItemC_fan,
|
||||||
ItemC_acc, ItemC_xyjerk,
|
ItemC_acc, ItemC_xyjerk,
|
||||||
ItemC_vmaxx, ItemC_vmaxy, ItemC_vmaxz, ItemC_vmaxe,
|
ItemC_vmaxx, ItemC_vmaxy, ItemC_vmaxz, ItemC_vmaxe,
|
||||||
ItemC_vtravmin,ItemC_vmin,
|
ItemC_vtravmin,ItemC_vmin,
|
||||||
ItemC_amaxx, ItemC_amaxy, ItemC_amaxz, ItemC_amaxe,
|
ItemC_amaxx, ItemC_amaxy, ItemC_amaxz, ItemC_amaxe,
|
||||||
ItemC_aret,ItemC_esteps, ItemC_store, ItemC_load,ItemC_failsafe
|
ItemC_aret,ItemC_esteps, ItemC_store, ItemC_load,ItemC_failsafe
|
||||||
};
|
};
|
||||||
|
|
||||||
void MainMenu::showControl()
|
void MainMenu::showControl()
|
||||||
{
|
{
|
||||||
uint8_t line=0;
|
uint8_t line=0;
|
||||||
if((lastlineoffset!=lineoffset)||force_lcd_update)
|
if((lastlineoffset!=lineoffset)||force_lcd_update)
|
||||||
{
|
{
|
||||||
force_lcd_update=true;
|
force_lcd_update=true;
|
||||||
clear();
|
clear();
|
||||||
}
|
}
|
||||||
for(uint8_t i=lineoffset;i<lineoffset+LCD_HEIGHT;i++)
|
for(uint8_t i=lineoffset;i<lineoffset+LCD_HEIGHT;i++)
|
||||||
{
|
{
|
||||||
switch(i)
|
switch(i)
|
||||||
{
|
{
|
||||||
case ItemC_exit:
|
case ItemC_exit:
|
||||||
{
|
{
|
||||||
if(force_lcd_update)
|
if(force_lcd_update)
|
||||||
{
|
{
|
||||||
lcd.setCursor(0,line);lcd.print(" Control");
|
lcd.setCursor(0,line);lcd.print(" Control");
|
||||||
}
|
}
|
||||||
if((activeline==line) && CLICKED)
|
if((activeline==line) && CLICKED)
|
||||||
{
|
{
|
||||||
BLOCK
|
BLOCK
|
||||||
status=Main_Menu;
|
status=Main_Menu;
|
||||||
beepshort();
|
beepshort();
|
||||||
}
|
}
|
||||||
}break;
|
}break;
|
||||||
case ItemC_nozzle:
|
case ItemC_nozzle:
|
||||||
{
|
{
|
||||||
if(force_lcd_update)
|
if(force_lcd_update)
|
||||||
{
|
{
|
||||||
lcd.setCursor(0,line);lcd.print(" \002Nozzle:");
|
lcd.setCursor(0,line);lcd.print(" \002Nozzle:");
|
||||||
lcd.setCursor(13,line);lcd.print(ftostr3(analog2temp(target_raw[0])));
|
lcd.setCursor(13,line);lcd.print(ftostr3(analog2temp(target_raw[TEMPSENSOR_HOTEND])));
|
||||||
}
|
}
|
||||||
|
|
||||||
if((activeline==line) )
|
if((activeline==line) )
|
||||||
{
|
{
|
||||||
if(CLICKED)
|
if(CLICKED)
|
||||||
{
|
{
|
||||||
linechanging=!linechanging;
|
linechanging=!linechanging;
|
||||||
if(linechanging)
|
if(linechanging)
|
||||||
{
|
{
|
||||||
encoderpos=(int)analog2temp(target_raw[0]);
|
encoderpos=(int)analog2temp(target_raw[TEMPSENSOR_HOTEND]);
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
target_raw[0] = temp2analog(encoderpos);
|
target_raw[TEMPSENSOR_HOTEND] = temp2analog(encoderpos);
|
||||||
encoderpos=activeline*lcdslow;
|
encoderpos=activeline*lcdslow;
|
||||||
beepshort();
|
beepshort();
|
||||||
}
|
}
|
||||||
BLOCK;
|
BLOCK;
|
||||||
}
|
}
|
||||||
if(linechanging)
|
if(linechanging)
|
||||||
{
|
{
|
||||||
if(encoderpos<0) encoderpos=0;
|
if(encoderpos<0) encoderpos=0;
|
||||||
if(encoderpos>260) encoderpos=260;
|
if(encoderpos>260) encoderpos=260;
|
||||||
lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));
|
lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}break;
|
}break;
|
||||||
|
|
||||||
case ItemC_fan:
|
case ItemC_fan:
|
||||||
{
|
{
|
||||||
if(force_lcd_update)
|
if(force_lcd_update)
|
||||||
{
|
{
|
||||||
lcd.setCursor(0,line);lcd.print(" Fan speed:");
|
lcd.setCursor(0,line);lcd.print(" Fan speed:");
|
||||||
lcd.setCursor(13,line);lcd.print(ftostr3(fanpwm));
|
lcd.setCursor(13,line);lcd.print(ftostr3(fanpwm));
|
||||||
}
|
}
|
||||||
|
|
||||||
if((activeline==line) )
|
if((activeline==line) )
|
||||||
{
|
{
|
||||||
if(CLICKED) //nalogWrite(FAN_PIN, fanpwm);
|
if(CLICKED) //nalogWrite(FAN_PIN, fanpwm);
|
||||||
{
|
{
|
||||||
linechanging=!linechanging;
|
linechanging=!linechanging;
|
||||||
if(linechanging)
|
if(linechanging)
|
||||||
{
|
{
|
||||||
encoderpos=fanpwm;
|
encoderpos=fanpwm;
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
fanpwm = constrain(encoderpos,0,255);
|
fanpwm = constrain(encoderpos,0,255);
|
||||||
encoderpos=fanpwm;
|
encoderpos=fanpwm;
|
||||||
analogWrite(FAN_PIN, fanpwm);
|
analogWrite(FAN_PIN, fanpwm);
|
||||||
|
|
||||||
beepshort();
|
beepshort();
|
||||||
}
|
}
|
||||||
BLOCK;
|
BLOCK;
|
||||||
}
|
}
|
||||||
if(linechanging)
|
if(linechanging)
|
||||||
{
|
{
|
||||||
if(encoderpos<0) encoderpos=0;
|
if(encoderpos<0) encoderpos=0;
|
||||||
if(encoderpos>255) encoderpos=255;
|
if(encoderpos>255) encoderpos=255;
|
||||||
fanpwm=encoderpos;
|
fanpwm=encoderpos;
|
||||||
analogWrite(FAN_PIN, fanpwm);
|
analogWrite(FAN_PIN, fanpwm);
|
||||||
lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));
|
lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}break;
|
}break;
|
||||||
case ItemC_acc:
|
case ItemC_acc:
|
||||||
{
|
{
|
||||||
if(force_lcd_update)
|
if(force_lcd_update)
|
||||||
{
|
{
|
||||||
lcd.setCursor(0,line);lcd.print(" Acc:");
|
lcd.setCursor(0,line);lcd.print(" Acc:");
|
||||||
lcd.setCursor(13,line);lcd.print(itostr3(acceleration/100));lcd.print("00");
|
lcd.setCursor(13,line);lcd.print(itostr3(acceleration/100));lcd.print("00");
|
||||||
}
|
}
|
||||||
|
|
||||||
if((activeline==line) )
|
if((activeline==line) )
|
||||||
{
|
{
|
||||||
if(CLICKED)
|
if(CLICKED)
|
||||||
{
|
{
|
||||||
linechanging=!linechanging;
|
linechanging=!linechanging;
|
||||||
if(linechanging)
|
if(linechanging)
|
||||||
{
|
{
|
||||||
encoderpos=(int)acceleration/100;
|
encoderpos=(int)acceleration/100;
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
acceleration= encoderpos*100;
|
acceleration= encoderpos*100;
|
||||||
encoderpos=activeline*lcdslow;
|
encoderpos=activeline*lcdslow;
|
||||||
}
|
}
|
||||||
BLOCK;
|
BLOCK;
|
||||||
beepshort();
|
beepshort();
|
||||||
}
|
}
|
||||||
if(linechanging)
|
if(linechanging)
|
||||||
{
|
{
|
||||||
if(encoderpos<5) encoderpos=5;
|
if(encoderpos<5) encoderpos=5;
|
||||||
if(encoderpos>990) encoderpos=990;
|
if(encoderpos>990) encoderpos=990;
|
||||||
lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));lcd.print("00");
|
lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));lcd.print("00");
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}break;
|
}break;
|
||||||
case ItemC_xyjerk: //max_xy_jerk
|
case ItemC_xyjerk: //max_xy_jerk
|
||||||
{
|
{
|
||||||
if(force_lcd_update)
|
if(force_lcd_update)
|
||||||
{
|
{
|
||||||
lcd.setCursor(0,line);lcd.print(" Vxy-jerk: ");
|
lcd.setCursor(0,line);lcd.print(" Vxy-jerk: ");
|
||||||
lcd.setCursor(13,line);lcd.print(itostr3(max_xy_jerk/60));
|
lcd.setCursor(13,line);lcd.print(itostr3(max_xy_jerk/60));
|
||||||
}
|
}
|
||||||
|
|
||||||
if((activeline==line) )
|
if((activeline==line) )
|
||||||
{
|
{
|
||||||
if(CLICKED)
|
if(CLICKED)
|
||||||
{
|
{
|
||||||
linechanging=!linechanging;
|
linechanging=!linechanging;
|
||||||
if(linechanging)
|
if(linechanging)
|
||||||
{
|
{
|
||||||
encoderpos=(int)max_xy_jerk/60;
|
encoderpos=(int)max_xy_jerk/60;
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
max_xy_jerk= encoderpos*60;
|
max_xy_jerk= encoderpos*60;
|
||||||
encoderpos=activeline*lcdslow;
|
encoderpos=activeline*lcdslow;
|
||||||
|
|
||||||
}
|
}
|
||||||
BLOCK;
|
BLOCK;
|
||||||
beepshort();
|
beepshort();
|
||||||
}
|
}
|
||||||
if(linechanging)
|
if(linechanging)
|
||||||
{
|
{
|
||||||
if(encoderpos<1) encoderpos=1;
|
if(encoderpos<1) encoderpos=1;
|
||||||
if(encoderpos>990) encoderpos=990;
|
if(encoderpos>990) encoderpos=990;
|
||||||
lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));
|
lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}break;
|
}break;
|
||||||
case ItemC_PID_P:
|
case ItemC_PID_P:
|
||||||
{
|
{
|
||||||
if(force_lcd_update)
|
if(force_lcd_update)
|
||||||
{
|
{
|
||||||
lcd.setCursor(0,line);lcd.print(" PID-P: ");
|
lcd.setCursor(0,line);lcd.print(" PID-P: ");
|
||||||
lcd.setCursor(13,line);lcd.print(itostr4(Kp));
|
lcd.setCursor(13,line);lcd.print(itostr4(Kp));
|
||||||
}
|
}
|
||||||
|
|
||||||
if((activeline==line) )
|
if((activeline==line) )
|
||||||
{
|
{
|
||||||
if(CLICKED)
|
if(CLICKED)
|
||||||
{
|
{
|
||||||
linechanging=!linechanging;
|
linechanging=!linechanging;
|
||||||
if(linechanging)
|
if(linechanging)
|
||||||
{
|
{
|
||||||
encoderpos=(int)Kp/5;
|
encoderpos=(int)Kp/5;
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
Kp= encoderpos*5;
|
Kp= encoderpos*5;
|
||||||
encoderpos=activeline*lcdslow;
|
encoderpos=activeline*lcdslow;
|
||||||
|
|
||||||
}
|
}
|
||||||
BLOCK;
|
BLOCK;
|
||||||
beepshort();
|
beepshort();
|
||||||
}
|
}
|
||||||
if(linechanging)
|
if(linechanging)
|
||||||
{
|
{
|
||||||
if(encoderpos<1) encoderpos=1;
|
if(encoderpos<1) encoderpos=1;
|
||||||
if(encoderpos>9990/5) encoderpos=9990/5;
|
if(encoderpos>9990/5) encoderpos=9990/5;
|
||||||
lcd.setCursor(13,line);lcd.print(itostr4(encoderpos*5));
|
lcd.setCursor(13,line);lcd.print(itostr4(encoderpos*5));
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}break;
|
}break;
|
||||||
case ItemC_PID_I:
|
case ItemC_PID_I:
|
||||||
{
|
{
|
||||||
if(force_lcd_update)
|
if(force_lcd_update)
|
||||||
{
|
{
|
||||||
lcd.setCursor(0,line);lcd.print(" PID-I: ");
|
lcd.setCursor(0,line);lcd.print(" PID-I: ");
|
||||||
lcd.setCursor(13,line);lcd.print(ftostr51(Ki));
|
lcd.setCursor(13,line);lcd.print(ftostr51(Ki));
|
||||||
}
|
}
|
||||||
|
|
||||||
if((activeline==line) )
|
if((activeline==line) )
|
||||||
{
|
{
|
||||||
if(CLICKED)
|
if(CLICKED)
|
||||||
{
|
{
|
||||||
linechanging=!linechanging;
|
linechanging=!linechanging;
|
||||||
if(linechanging)
|
if(linechanging)
|
||||||
{
|
{
|
||||||
encoderpos=(int)(Ki*10);
|
encoderpos=(int)(Ki*10);
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
Ki= encoderpos/10.;
|
Ki= encoderpos/10.;
|
||||||
encoderpos=activeline*lcdslow;
|
encoderpos=activeline*lcdslow;
|
||||||
|
|
||||||
}
|
}
|
||||||
BLOCK;
|
BLOCK;
|
||||||
beepshort();
|
beepshort();
|
||||||
}
|
}
|
||||||
if(linechanging)
|
if(linechanging)
|
||||||
{
|
{
|
||||||
if(encoderpos<0) encoderpos=0;
|
if(encoderpos<0) encoderpos=0;
|
||||||
if(encoderpos>9990) encoderpos=9990;
|
if(encoderpos>9990) encoderpos=9990;
|
||||||
lcd.setCursor(13,line);lcd.print(ftostr51(encoderpos/10.));
|
lcd.setCursor(13,line);lcd.print(ftostr51(encoderpos/10.));
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}break;
|
}break;
|
||||||
case ItemC_PID_D:
|
case ItemC_PID_D:
|
||||||
{
|
{
|
||||||
if(force_lcd_update)
|
if(force_lcd_update)
|
||||||
{
|
{
|
||||||
lcd.setCursor(0,line);lcd.print(" PID-D: ");
|
lcd.setCursor(0,line);lcd.print(" PID-D: ");
|
||||||
lcd.setCursor(13,line);lcd.print(itostr4(Kd));
|
lcd.setCursor(13,line);lcd.print(itostr4(Kd));
|
||||||
}
|
}
|
||||||
|
|
||||||
if((activeline==line) )
|
if((activeline==line) )
|
||||||
{
|
{
|
||||||
if(CLICKED)
|
if(CLICKED)
|
||||||
{
|
{
|
||||||
linechanging=!linechanging;
|
linechanging=!linechanging;
|
||||||
if(linechanging)
|
if(linechanging)
|
||||||
{
|
{
|
||||||
encoderpos=(int)Kd/5;
|
encoderpos=(int)Kd/5;
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
Kd= encoderpos*5;
|
Kd= encoderpos*5;
|
||||||
encoderpos=activeline*lcdslow;
|
encoderpos=activeline*lcdslow;
|
||||||
|
|
||||||
}
|
}
|
||||||
BLOCK;
|
BLOCK;
|
||||||
beepshort();
|
beepshort();
|
||||||
}
|
}
|
||||||
if(linechanging)
|
if(linechanging)
|
||||||
{
|
{
|
||||||
if(encoderpos<0) encoderpos=0;
|
if(encoderpos<0) encoderpos=0;
|
||||||
if(encoderpos>9990/5) encoderpos=9990/5;
|
if(encoderpos>9990/5) encoderpos=9990/5;
|
||||||
lcd.setCursor(13,line);lcd.print(itostr4(encoderpos*5));
|
lcd.setCursor(13,line);lcd.print(itostr4(encoderpos*5));
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}break;
|
}break;
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
case ItemC_PID_C:
|
case ItemC_PID_C:
|
||||||
{
|
{
|
||||||
if(force_lcd_update)
|
if(force_lcd_update)
|
||||||
{
|
{
|
||||||
lcd.setCursor(0,line);lcd.print(" PID-C: ");
|
lcd.setCursor(0,line);lcd.print(" PID-C: ");
|
||||||
lcd.setCursor(13,line);lcd.print(itostr3(Kc));
|
lcd.setCursor(13,line);lcd.print(itostr3(Kc));
|
||||||
}
|
}
|
||||||
|
|
||||||
if((activeline==line) )
|
if((activeline==line) )
|
||||||
{
|
{
|
||||||
if(CLICKED)
|
if(CLICKED)
|
||||||
{
|
{
|
||||||
linechanging=!linechanging;
|
linechanging=!linechanging;
|
||||||
if(linechanging)
|
if(linechanging)
|
||||||
{
|
{
|
||||||
encoderpos=(int)Kc;
|
encoderpos=(int)Kc;
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
Kc= encoderpos;
|
Kc= encoderpos;
|
||||||
encoderpos=activeline*lcdslow;
|
encoderpos=activeline*lcdslow;
|
||||||
|
|
||||||
}
|
}
|
||||||
BLOCK;
|
BLOCK;
|
||||||
beepshort();
|
beepshort();
|
||||||
}
|
}
|
||||||
if(linechanging)
|
if(linechanging)
|
||||||
{
|
{
|
||||||
if(encoderpos<0) encoderpos=0;
|
if(encoderpos<0) encoderpos=0;
|
||||||
if(encoderpos>990) encoderpos=990;
|
if(encoderpos>990) encoderpos=990;
|
||||||
lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));
|
lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}break;
|
}break;
|
||||||
case ItemC_vmaxx:
|
case ItemC_vmaxx:
|
||||||
case ItemC_vmaxy:
|
case ItemC_vmaxy:
|
||||||
case ItemC_vmaxz:
|
case ItemC_vmaxz:
|
||||||
case ItemC_vmaxe:
|
case ItemC_vmaxe:
|
||||||
{
|
{
|
||||||
if(force_lcd_update)
|
if(force_lcd_update)
|
||||||
{
|
{
|
||||||
lcd.setCursor(0,line);lcd.print(" Vmax ");
|
lcd.setCursor(0,line);lcd.print(" Vmax ");
|
||||||
if(i==ItemC_vmaxx)lcd.print("x:");
|
if(i==ItemC_vmaxx)lcd.print("x:");
|
||||||
if(i==ItemC_vmaxy)lcd.print("y:");
|
if(i==ItemC_vmaxy)lcd.print("y:");
|
||||||
if(i==ItemC_vmaxz)lcd.print("z:");
|
if(i==ItemC_vmaxz)lcd.print("z:");
|
||||||
if(i==ItemC_vmaxe)lcd.print("e:");
|
if(i==ItemC_vmaxe)lcd.print("e:");
|
||||||
lcd.setCursor(13,line);lcd.print(itostr3(max_feedrate[i-ItemC_vmaxx]/60));
|
lcd.setCursor(13,line);lcd.print(itostr3(max_feedrate[i-ItemC_vmaxx]/60));
|
||||||
}
|
}
|
||||||
|
|
||||||
if((activeline==line) )
|
if((activeline==line) )
|
||||||
{
|
{
|
||||||
if(CLICKED)
|
if(CLICKED)
|
||||||
{
|
{
|
||||||
linechanging=!linechanging;
|
linechanging=!linechanging;
|
||||||
if(linechanging)
|
if(linechanging)
|
||||||
{
|
{
|
||||||
encoderpos=(int)max_feedrate[i-ItemC_vmaxx]/60;
|
encoderpos=(int)max_feedrate[i-ItemC_vmaxx]/60;
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
max_feedrate[i-ItemC_vmaxx]= encoderpos*60;
|
max_feedrate[i-ItemC_vmaxx]= encoderpos*60;
|
||||||
encoderpos=activeline*lcdslow;
|
encoderpos=activeline*lcdslow;
|
||||||
|
|
||||||
}
|
}
|
||||||
BLOCK;
|
BLOCK;
|
||||||
beepshort();
|
beepshort();
|
||||||
}
|
}
|
||||||
if(linechanging)
|
if(linechanging)
|
||||||
{
|
{
|
||||||
if(encoderpos<1) encoderpos=1;
|
if(encoderpos<1) encoderpos=1;
|
||||||
if(encoderpos>990) encoderpos=990;
|
if(encoderpos>990) encoderpos=990;
|
||||||
lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));
|
lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}break;
|
}break;
|
||||||
|
|
||||||
case ItemC_vmin:
|
case ItemC_vmin:
|
||||||
{
|
{
|
||||||
if(force_lcd_update)
|
if(force_lcd_update)
|
||||||
{
|
{
|
||||||
lcd.setCursor(0,line);lcd.print(" Vmin:");
|
lcd.setCursor(0,line);lcd.print(" Vmin:");
|
||||||
lcd.setCursor(13,line);lcd.print(itostr3(minimumfeedrate/60));
|
lcd.setCursor(13,line);lcd.print(itostr3(minimumfeedrate/60));
|
||||||
}
|
}
|
||||||
|
|
||||||
if((activeline==line) )
|
if((activeline==line) )
|
||||||
{
|
{
|
||||||
if(CLICKED)
|
if(CLICKED)
|
||||||
{
|
{
|
||||||
linechanging=!linechanging;
|
linechanging=!linechanging;
|
||||||
if(linechanging)
|
if(linechanging)
|
||||||
{
|
{
|
||||||
encoderpos=(int)(minimumfeedrate/60.);
|
encoderpos=(int)(minimumfeedrate/60.);
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
minimumfeedrate= encoderpos*60;
|
minimumfeedrate= encoderpos*60;
|
||||||
encoderpos=activeline*lcdslow;
|
encoderpos=activeline*lcdslow;
|
||||||
|
|
||||||
}
|
}
|
||||||
BLOCK;
|
BLOCK;
|
||||||
beepshort();
|
beepshort();
|
||||||
}
|
}
|
||||||
if(linechanging)
|
if(linechanging)
|
||||||
{
|
{
|
||||||
if(encoderpos<0) encoderpos=0;
|
if(encoderpos<0) encoderpos=0;
|
||||||
if(encoderpos>990) encoderpos=990;
|
if(encoderpos>990) encoderpos=990;
|
||||||
lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));
|
lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}break;
|
}break;
|
||||||
case ItemC_vtravmin:
|
case ItemC_vtravmin:
|
||||||
{
|
{
|
||||||
if(force_lcd_update)
|
if(force_lcd_update)
|
||||||
{
|
{
|
||||||
lcd.setCursor(0,line);lcd.print(" VTrav min:");
|
lcd.setCursor(0,line);lcd.print(" VTrav min:");
|
||||||
lcd.setCursor(13,line);lcd.print(itostr3(mintravelfeedrate/60));
|
lcd.setCursor(13,line);lcd.print(itostr3(mintravelfeedrate/60));
|
||||||
}
|
}
|
||||||
|
|
||||||
if((activeline==line) )
|
if((activeline==line) )
|
||||||
{
|
{
|
||||||
if(CLICKED)
|
if(CLICKED)
|
||||||
{
|
{
|
||||||
linechanging=!linechanging;
|
linechanging=!linechanging;
|
||||||
if(linechanging)
|
if(linechanging)
|
||||||
{
|
{
|
||||||
encoderpos=(int)mintravelfeedrate/60;
|
encoderpos=(int)mintravelfeedrate/60;
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
mintravelfeedrate= encoderpos*60;
|
mintravelfeedrate= encoderpos*60;
|
||||||
encoderpos=activeline*lcdslow;
|
encoderpos=activeline*lcdslow;
|
||||||
|
|
||||||
}
|
}
|
||||||
BLOCK;
|
BLOCK;
|
||||||
beepshort();
|
beepshort();
|
||||||
}
|
}
|
||||||
if(linechanging)
|
if(linechanging)
|
||||||
{
|
{
|
||||||
if(encoderpos<0) encoderpos=0;
|
if(encoderpos<0) encoderpos=0;
|
||||||
if(encoderpos>990) encoderpos=990;
|
if(encoderpos>990) encoderpos=990;
|
||||||
lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));
|
lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}break;
|
}break;
|
||||||
|
|
||||||
case ItemC_amaxx:
|
case ItemC_amaxx:
|
||||||
case ItemC_amaxy:
|
case ItemC_amaxy:
|
||||||
case ItemC_amaxz:
|
case ItemC_amaxz:
|
||||||
case ItemC_amaxe:
|
case ItemC_amaxe:
|
||||||
{
|
{
|
||||||
if(force_lcd_update)
|
if(force_lcd_update)
|
||||||
{
|
{
|
||||||
lcd.setCursor(0,line);lcd.print(" Amax ");
|
lcd.setCursor(0,line);lcd.print(" Amax ");
|
||||||
if(i==ItemC_amaxx)lcd.print("x:");
|
if(i==ItemC_amaxx)lcd.print("x:");
|
||||||
if(i==ItemC_amaxy)lcd.print("y:");
|
if(i==ItemC_amaxy)lcd.print("y:");
|
||||||
if(i==ItemC_amaxz)lcd.print("z:");
|
if(i==ItemC_amaxz)lcd.print("z:");
|
||||||
if(i==ItemC_amaxe)lcd.print("e:");
|
if(i==ItemC_amaxe)lcd.print("e:");
|
||||||
lcd.setCursor(13,line);lcd.print(itostr3(max_acceleration_units_per_sq_second[i-ItemC_amaxx]/100));lcd.print("00");
|
lcd.setCursor(13,line);lcd.print(itostr3(max_acceleration_units_per_sq_second[i-ItemC_amaxx]/100));lcd.print("00");
|
||||||
}
|
}
|
||||||
|
|
||||||
if((activeline==line) )
|
if((activeline==line) )
|
||||||
{
|
{
|
||||||
if(CLICKED)
|
if(CLICKED)
|
||||||
{
|
{
|
||||||
linechanging=!linechanging;
|
linechanging=!linechanging;
|
||||||
if(linechanging)
|
if(linechanging)
|
||||||
{
|
{
|
||||||
encoderpos=(int)max_acceleration_units_per_sq_second[i-ItemC_amaxx]/100;
|
encoderpos=(int)max_acceleration_units_per_sq_second[i-ItemC_amaxx]/100;
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
max_acceleration_units_per_sq_second[i-ItemC_amaxx]= encoderpos*100;
|
max_acceleration_units_per_sq_second[i-ItemC_amaxx]= encoderpos*100;
|
||||||
encoderpos=activeline*lcdslow;
|
encoderpos=activeline*lcdslow;
|
||||||
}
|
}
|
||||||
BLOCK;
|
BLOCK;
|
||||||
beepshort();
|
beepshort();
|
||||||
}
|
}
|
||||||
if(linechanging)
|
if(linechanging)
|
||||||
{
|
{
|
||||||
if(encoderpos<1) encoderpos=1;
|
if(encoderpos<1) encoderpos=1;
|
||||||
if(encoderpos>990) encoderpos=990;
|
if(encoderpos>990) encoderpos=990;
|
||||||
lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));lcd.print("00");
|
lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));lcd.print("00");
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}break;
|
}break;
|
||||||
case ItemC_aret://float retract_acceleration = 7000;
|
case ItemC_aret://float retract_acceleration = 7000;
|
||||||
{
|
{
|
||||||
if(force_lcd_update)
|
if(force_lcd_update)
|
||||||
{
|
{
|
||||||
lcd.setCursor(0,line);lcd.print(" A-retract:");
|
lcd.setCursor(0,line);lcd.print(" A-retract:");
|
||||||
lcd.setCursor(13,line);lcd.print(ftostr3(retract_acceleration/100));lcd.print("00");
|
lcd.setCursor(13,line);lcd.print(ftostr3(retract_acceleration/100));lcd.print("00");
|
||||||
}
|
}
|
||||||
|
|
||||||
if((activeline==line) )
|
if((activeline==line) )
|
||||||
{
|
{
|
||||||
if(CLICKED)
|
if(CLICKED)
|
||||||
{
|
{
|
||||||
linechanging=!linechanging;
|
linechanging=!linechanging;
|
||||||
if(linechanging)
|
if(linechanging)
|
||||||
{
|
{
|
||||||
encoderpos=(int)retract_acceleration/100;
|
encoderpos=(int)retract_acceleration/100;
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
retract_acceleration= encoderpos*100;
|
retract_acceleration= encoderpos*100;
|
||||||
encoderpos=activeline*lcdslow;
|
encoderpos=activeline*lcdslow;
|
||||||
|
|
||||||
}
|
}
|
||||||
BLOCK;
|
BLOCK;
|
||||||
beepshort();
|
beepshort();
|
||||||
}
|
}
|
||||||
if(linechanging)
|
if(linechanging)
|
||||||
{
|
{
|
||||||
if(encoderpos<10) encoderpos=10;
|
if(encoderpos<10) encoderpos=10;
|
||||||
if(encoderpos>990) encoderpos=990;
|
if(encoderpos>990) encoderpos=990;
|
||||||
lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));lcd.print("00");
|
lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));lcd.print("00");
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}break;
|
}break;
|
||||||
case ItemC_esteps://axis_steps_per_unit[i] = code_value();
|
case ItemC_esteps://axis_steps_per_unit[i] = code_value();
|
||||||
{
|
{
|
||||||
if(force_lcd_update)
|
if(force_lcd_update)
|
||||||
{
|
{
|
||||||
lcd.setCursor(0,line);lcd.print(" Esteps/mm:");
|
lcd.setCursor(0,line);lcd.print(" Esteps/mm:");
|
||||||
lcd.setCursor(13,line);lcd.print(itostr4(axis_steps_per_unit[3]));
|
lcd.setCursor(13,line);lcd.print(itostr4(axis_steps_per_unit[3]));
|
||||||
}
|
}
|
||||||
|
|
||||||
if((activeline==line) )
|
if((activeline==line) )
|
||||||
{
|
{
|
||||||
if(CLICKED)
|
if(CLICKED)
|
||||||
{
|
{
|
||||||
linechanging=!linechanging;
|
linechanging=!linechanging;
|
||||||
if(linechanging)
|
if(linechanging)
|
||||||
{
|
{
|
||||||
encoderpos=(int)axis_steps_per_unit[3];
|
encoderpos=(int)axis_steps_per_unit[3];
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
float factor=float(encoderpos)/float(axis_steps_per_unit[3]);
|
float factor=float(encoderpos)/float(axis_steps_per_unit[3]);
|
||||||
position[E_AXIS]=lround(position[E_AXIS]*factor);
|
position[E_AXIS]=lround(position[E_AXIS]*factor);
|
||||||
//current_position[3]*=factor;
|
//current_position[3]*=factor;
|
||||||
axis_steps_per_unit[E_AXIS]= encoderpos;
|
axis_steps_per_unit[E_AXIS]= encoderpos;
|
||||||
encoderpos=activeline*lcdslow;
|
encoderpos=activeline*lcdslow;
|
||||||
|
|
||||||
}
|
}
|
||||||
BLOCK;
|
BLOCK;
|
||||||
beepshort();
|
beepshort();
|
||||||
}
|
}
|
||||||
if(linechanging)
|
if(linechanging)
|
||||||
{
|
{
|
||||||
if(encoderpos<5) encoderpos=5;
|
if(encoderpos<5) encoderpos=5;
|
||||||
if(encoderpos>9999) encoderpos=9999;
|
if(encoderpos>9999) encoderpos=9999;
|
||||||
lcd.setCursor(13,line);lcd.print(itostr4(encoderpos));
|
lcd.setCursor(13,line);lcd.print(itostr4(encoderpos));
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}break;
|
}break;
|
||||||
case ItemC_store:
|
case ItemC_store:
|
||||||
{
|
{
|
||||||
if(force_lcd_update)
|
if(force_lcd_update)
|
||||||
{
|
{
|
||||||
lcd.setCursor(0,line);lcd.print(" Store EPROM");
|
lcd.setCursor(0,line);lcd.print(" Store EPROM");
|
||||||
}
|
}
|
||||||
if((activeline==line) && CLICKED)
|
if((activeline==line) && CLICKED)
|
||||||
{
|
{
|
||||||
//enquecommand("M84");
|
//enquecommand("M84");
|
||||||
beepshort();
|
beepshort();
|
||||||
BLOCK;
|
BLOCK;
|
||||||
StoreSettings();
|
StoreSettings();
|
||||||
}
|
}
|
||||||
}break;
|
}break;
|
||||||
case ItemC_load:
|
case ItemC_load:
|
||||||
{
|
{
|
||||||
if(force_lcd_update)
|
if(force_lcd_update)
|
||||||
{
|
{
|
||||||
lcd.setCursor(0,line);lcd.print(" Load EPROM");
|
lcd.setCursor(0,line);lcd.print(" Load EPROM");
|
||||||
}
|
}
|
||||||
if((activeline==line) && CLICKED)
|
if((activeline==line) && CLICKED)
|
||||||
{
|
{
|
||||||
//enquecommand("M84");
|
//enquecommand("M84");
|
||||||
beepshort();
|
beepshort();
|
||||||
BLOCK;
|
BLOCK;
|
||||||
RetrieveSettings();
|
RetrieveSettings();
|
||||||
}
|
}
|
||||||
}break;
|
}break;
|
||||||
case ItemC_failsafe:
|
case ItemC_failsafe:
|
||||||
{
|
{
|
||||||
if(force_lcd_update)
|
if(force_lcd_update)
|
||||||
{
|
{
|
||||||
lcd.setCursor(0,line);lcd.print(" Restore Failsafe");
|
lcd.setCursor(0,line);lcd.print(" Restore Failsafe");
|
||||||
}
|
}
|
||||||
if((activeline==line) && CLICKED)
|
if((activeline==line) && CLICKED)
|
||||||
{
|
{
|
||||||
//enquecommand("M84");
|
//enquecommand("M84");
|
||||||
beepshort();
|
beepshort();
|
||||||
BLOCK;
|
BLOCK;
|
||||||
RetrieveSettings(true);
|
RetrieveSettings(true);
|
||||||
}
|
}
|
||||||
}break;
|
}break;
|
||||||
default:
|
default:
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
line++;
|
line++;
|
||||||
}
|
}
|
||||||
lastlineoffset=lineoffset;
|
lastlineoffset=lineoffset;
|
||||||
|
|
||||||
if(!linechanging && ((encoderpos/lcdslow!=lastencoderpos/lcdslow)||force_lcd_update))
|
if(!linechanging && ((encoderpos/lcdslow!=lastencoderpos/lcdslow)||force_lcd_update))
|
||||||
{
|
{
|
||||||
|
|
||||||
lcd.setCursor(0,activeline);lcd.print((activeline+lineoffset)?' ':' ');
|
lcd.setCursor(0,activeline);lcd.print((activeline+lineoffset)?' ':' ');
|
||||||
|
|
||||||
if(encoderpos<0)
|
if(encoderpos<0)
|
||||||
{
|
{
|
||||||
lineoffset--;
|
lineoffset--;
|
||||||
if(lineoffset<0)
|
if(lineoffset<0)
|
||||||
lineoffset=0;
|
lineoffset=0;
|
||||||
encoderpos=0;
|
encoderpos=0;
|
||||||
force_lcd_update=true;
|
force_lcd_update=true;
|
||||||
}
|
}
|
||||||
if(encoderpos/lcdslow>3)
|
if(encoderpos/lcdslow>3)
|
||||||
{
|
{
|
||||||
lineoffset++;
|
lineoffset++;
|
||||||
encoderpos=3*lcdslow;
|
encoderpos=3*lcdslow;
|
||||||
if(lineoffset>(ItemC_failsafe+1-LCD_HEIGHT))
|
if(lineoffset>(ItemC_failsafe+1-LCD_HEIGHT))
|
||||||
lineoffset=ItemC_failsafe+1-LCD_HEIGHT;
|
lineoffset=ItemC_failsafe+1-LCD_HEIGHT;
|
||||||
force_lcd_update=true;
|
force_lcd_update=true;
|
||||||
}
|
}
|
||||||
//encoderpos=encoderpos%LCD_HEIGHT;
|
//encoderpos=encoderpos%LCD_HEIGHT;
|
||||||
lastencoderpos=encoderpos;
|
lastencoderpos=encoderpos;
|
||||||
activeline=encoderpos/lcdslow;
|
activeline=encoderpos/lcdslow;
|
||||||
if(activeline>3) activeline=3;
|
if(activeline>3) activeline=3;
|
||||||
lcd.setCursor(0,activeline);lcd.print((activeline+lineoffset)?'>':'\003');
|
lcd.setCursor(0,activeline);lcd.print((activeline+lineoffset)?'>':'\003');
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
#include "SdFat.h"
|
#include "SdFat.h"
|
||||||
|
|
||||||
void MainMenu::getfilename(const uint8_t nr)
|
void MainMenu::getfilename(const uint8_t nr)
|
||||||
{
|
{
|
||||||
#ifdef SDSUPPORT
|
#ifdef SDSUPPORT
|
||||||
dir_t p;
|
dir_t p;
|
||||||
root.rewind();
|
root.rewind();
|
||||||
uint8_t cnt=0;
|
uint8_t cnt=0;
|
||||||
filename[0]='\0';
|
filename[0]='\0';
|
||||||
while (root.readDir(p) > 0)
|
while (root.readDir(p) > 0)
|
||||||
{
|
{
|
||||||
if (p.name[0] == DIR_NAME_FREE) break;
|
if (p.name[0] == DIR_NAME_FREE) break;
|
||||||
if (p.name[0] == DIR_NAME_DELETED || p.name[0] == '.'|| p.name[0] == '_') continue;
|
if (p.name[0] == DIR_NAME_DELETED || p.name[0] == '.'|| p.name[0] == '_') continue;
|
||||||
if (!DIR_IS_FILE_OR_SUBDIR(&p)) continue;
|
if (!DIR_IS_FILE_OR_SUBDIR(&p)) continue;
|
||||||
if(p.name[8]!='G') continue;
|
if(p.name[8]!='G') continue;
|
||||||
if(p.name[9]=='~') continue;
|
if(p.name[9]=='~') continue;
|
||||||
if(cnt++!=nr) continue;
|
if(cnt++!=nr) continue;
|
||||||
//Serial.println((char*)p.name);
|
//Serial.println((char*)p.name);
|
||||||
uint8_t writepos=0;
|
uint8_t writepos=0;
|
||||||
for (uint8_t i = 0; i < 11; i++)
|
for (uint8_t i = 0; i < 11; i++)
|
||||||
{
|
{
|
||||||
if (p.name[i] == ' ') continue;
|
if (p.name[i] == ' ') continue;
|
||||||
if (i == 8) {
|
if (i == 8) {
|
||||||
filename[writepos++]='.';
|
filename[writepos++]='.';
|
||||||
}
|
}
|
||||||
filename[writepos++]=p.name[i];
|
filename[writepos++]=p.name[i];
|
||||||
}
|
}
|
||||||
filename[writepos++]=0;
|
filename[writepos++]=0;
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
uint8_t getnrfilenames()
|
uint8_t getnrfilenames()
|
||||||
{
|
{
|
||||||
#ifdef SDSUPPORT
|
#ifdef SDSUPPORT
|
||||||
dir_t p;
|
dir_t p;
|
||||||
root.rewind();
|
root.rewind();
|
||||||
uint8_t cnt=0;
|
uint8_t cnt=0;
|
||||||
while (root.readDir(p) > 0)
|
while (root.readDir(p) > 0)
|
||||||
{
|
{
|
||||||
if (p.name[0] == DIR_NAME_FREE) break;
|
if (p.name[0] == DIR_NAME_FREE) break;
|
||||||
if (p.name[0] == DIR_NAME_DELETED || p.name[0] == '.'|| p.name[0] == '_') continue;
|
if (p.name[0] == DIR_NAME_DELETED || p.name[0] == '.'|| p.name[0] == '_') continue;
|
||||||
if (!DIR_IS_FILE_OR_SUBDIR(&p)) continue;
|
if (!DIR_IS_FILE_OR_SUBDIR(&p)) continue;
|
||||||
if(p.name[8]!='G') continue;
|
if(p.name[8]!='G') continue;
|
||||||
if(p.name[9]=='~') continue;
|
if(p.name[9]=='~') continue;
|
||||||
cnt++;
|
cnt++;
|
||||||
}
|
}
|
||||||
return cnt;
|
return cnt;
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
void MainMenu::showSD()
|
void MainMenu::showSD()
|
||||||
{
|
{
|
||||||
|
|
||||||
#ifdef SDSUPPORT
|
#ifdef SDSUPPORT
|
||||||
uint8_t line=0;
|
uint8_t line=0;
|
||||||
|
|
||||||
if(lastlineoffset!=lineoffset)
|
if(lastlineoffset!=lineoffset)
|
||||||
{
|
{
|
||||||
force_lcd_update=true;
|
force_lcd_update=true;
|
||||||
}
|
}
|
||||||
static uint8_t nrfiles=0;
|
static uint8_t nrfiles=0;
|
||||||
if(force_lcd_update)
|
if(force_lcd_update)
|
||||||
{
|
{
|
||||||
clear();
|
clear();
|
||||||
if(sdactive)
|
if(sdactive)
|
||||||
{
|
{
|
||||||
nrfiles=getnrfilenames();
|
nrfiles=getnrfilenames();
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
nrfiles=0;
|
nrfiles=0;
|
||||||
lineoffset=0;
|
lineoffset=0;
|
||||||
}
|
}
|
||||||
//Serial.print("Nr files:"); Serial.println((int)nrfiles);
|
//Serial.print("Nr files:"); Serial.println((int)nrfiles);
|
||||||
}
|
}
|
||||||
|
|
||||||
for(int8_t i=lineoffset;i<lineoffset+LCD_HEIGHT;i++)
|
for(int8_t i=lineoffset;i<lineoffset+LCD_HEIGHT;i++)
|
||||||
{
|
{
|
||||||
switch(i)
|
switch(i)
|
||||||
{
|
{
|
||||||
case 0:
|
case 0:
|
||||||
{
|
{
|
||||||
if(force_lcd_update)
|
if(force_lcd_update)
|
||||||
{
|
{
|
||||||
lcd.setCursor(0,line);lcd.print(" File");
|
lcd.setCursor(0,line);lcd.print(" File");
|
||||||
}
|
}
|
||||||
if((activeline==line) && CLICKED)
|
if((activeline==line) && CLICKED)
|
||||||
{
|
{
|
||||||
BLOCK
|
BLOCK
|
||||||
status=Main_Menu;
|
status=Main_Menu;
|
||||||
beepshort();
|
beepshort();
|
||||||
}
|
}
|
||||||
}break;
|
}break;
|
||||||
case 1:
|
case 1:
|
||||||
{
|
{
|
||||||
if(force_lcd_update)
|
if(force_lcd_update)
|
||||||
{
|
{
|
||||||
lcd.setCursor(0,line);
|
lcd.setCursor(0,line);
|
||||||
#ifdef CARDINSERTED
|
#ifdef CARDINSERTED
|
||||||
if(CARDINSERTED)
|
if(CARDINSERTED)
|
||||||
#else
|
#else
|
||||||
if(true)
|
if(true)
|
||||||
#endif
|
#endif
|
||||||
{
|
{
|
||||||
lcd.print(" \004Refresh");
|
lcd.print(" \004Refresh");
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
lcd.print(" \004Insert Card");
|
lcd.print(" \004Insert Card");
|
||||||
}
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
if((activeline==line) && CLICKED)
|
if((activeline==line) && CLICKED)
|
||||||
{
|
{
|
||||||
BLOCK;
|
BLOCK;
|
||||||
beepshort();
|
beepshort();
|
||||||
initsd();
|
initsd();
|
||||||
force_lcd_update=true;
|
force_lcd_update=true;
|
||||||
nrfiles=getnrfilenames();
|
nrfiles=getnrfilenames();
|
||||||
}
|
}
|
||||||
}break;
|
}break;
|
||||||
default:
|
default:
|
||||||
{
|
{
|
||||||
if(i-2<nrfiles)
|
if(i-2<nrfiles)
|
||||||
{
|
{
|
||||||
if(force_lcd_update)
|
if(force_lcd_update)
|
||||||
{
|
{
|
||||||
getfilename(i-2);
|
getfilename(i-2);
|
||||||
//Serial.print("Filenr:");Serial.println(i-2);
|
//Serial.print("Filenr:");Serial.println(i-2);
|
||||||
lcd.setCursor(0,line);lcd.print(" ");lcd.print(filename);
|
lcd.setCursor(0,line);lcd.print(" ");lcd.print(filename);
|
||||||
}
|
}
|
||||||
if((activeline==line) && CLICKED)
|
if((activeline==line) && CLICKED)
|
||||||
{
|
{
|
||||||
BLOCK
|
BLOCK
|
||||||
getfilename(i-2);
|
getfilename(i-2);
|
||||||
char cmd[30];
|
char cmd[30];
|
||||||
for(int i=0;i<strlen(filename);i++)
|
for(int i=0;i<strlen(filename);i++)
|
||||||
filename[i]=tolower(filename[i]);
|
filename[i]=tolower(filename[i]);
|
||||||
sprintf(cmd,"M23 %s",filename);
|
sprintf(cmd,"M23 %s",filename);
|
||||||
//sprintf(cmd,"M115");
|
//sprintf(cmd,"M115");
|
||||||
enquecommand(cmd);
|
enquecommand(cmd);
|
||||||
enquecommand("M24");
|
enquecommand("M24");
|
||||||
beep();
|
beep();
|
||||||
status=Main_Status;
|
status=Main_Status;
|
||||||
lcd_status(filename);
|
lcd_status(filename);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
line++;
|
line++;
|
||||||
}
|
}
|
||||||
lastlineoffset=lineoffset;
|
lastlineoffset=lineoffset;
|
||||||
if((encoderpos!=lastencoderpos)||force_lcd_update)
|
if((encoderpos!=lastencoderpos)||force_lcd_update)
|
||||||
{
|
{
|
||||||
|
|
||||||
lcd.setCursor(0,activeline);lcd.print((activeline+lineoffset)?' ':' ');
|
lcd.setCursor(0,activeline);lcd.print((activeline+lineoffset)?' ':' ');
|
||||||
|
|
||||||
if(encoderpos<0)
|
if(encoderpos<0)
|
||||||
{
|
{
|
||||||
lineoffset--;
|
lineoffset--;
|
||||||
if(lineoffset<0)
|
if(lineoffset<0)
|
||||||
lineoffset=0;
|
lineoffset=0;
|
||||||
encoderpos=0;
|
encoderpos=0;
|
||||||
force_lcd_update=true;
|
force_lcd_update=true;
|
||||||
}
|
}
|
||||||
if(encoderpos/lcdslow>3)
|
if(encoderpos/lcdslow>3)
|
||||||
{
|
{
|
||||||
lineoffset++;
|
lineoffset++;
|
||||||
encoderpos=3*lcdslow;
|
encoderpos=3*lcdslow;
|
||||||
if(lineoffset>(1+nrfiles+1-LCD_HEIGHT))
|
if(lineoffset>(1+nrfiles+1-LCD_HEIGHT))
|
||||||
lineoffset=1+nrfiles+1-LCD_HEIGHT;
|
lineoffset=1+nrfiles+1-LCD_HEIGHT;
|
||||||
force_lcd_update=true;
|
force_lcd_update=true;
|
||||||
|
|
||||||
}
|
}
|
||||||
lastencoderpos=encoderpos;
|
lastencoderpos=encoderpos;
|
||||||
activeline=encoderpos;
|
activeline=encoderpos;
|
||||||
if(activeline>3)
|
if(activeline>3)
|
||||||
{
|
{
|
||||||
activeline=3;
|
activeline=3;
|
||||||
}
|
}
|
||||||
if(activeline<0)
|
if(activeline<0)
|
||||||
{
|
{
|
||||||
activeline=0;
|
activeline=0;
|
||||||
}
|
}
|
||||||
if(activeline>1+nrfiles) activeline=1+nrfiles;
|
if(activeline>1+nrfiles) activeline=1+nrfiles;
|
||||||
if(lineoffset>1+nrfiles) lineoffset=1+nrfiles;
|
if(lineoffset>1+nrfiles) lineoffset=1+nrfiles;
|
||||||
lcd.setCursor(0,activeline);lcd.print((activeline+lineoffset)?'>':'\003');
|
lcd.setCursor(0,activeline);lcd.print((activeline+lineoffset)?'>':'\003');
|
||||||
|
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
enum {ItemM_watch, ItemM_prepare, ItemM_control, ItemM_file };
|
enum {ItemM_watch, ItemM_prepare, ItemM_control, ItemM_file };
|
||||||
void MainMenu::showMainMenu()
|
void MainMenu::showMainMenu()
|
||||||
{
|
{
|
||||||
//if(int(encoderpos/lcdslow)!=int(lastencoderpos/lcdslow))
|
//if(int(encoderpos/lcdslow)!=int(lastencoderpos/lcdslow))
|
||||||
// force_lcd_update=true;
|
// force_lcd_update=true;
|
||||||
#ifndef ULTIPANEL
|
#ifndef ULTIPANEL
|
||||||
force_lcd_update=false;
|
force_lcd_update=false;
|
||||||
#endif
|
#endif
|
||||||
//Serial.println((int)activeline);
|
//Serial.println((int)activeline);
|
||||||
if(force_lcd_update)
|
if(force_lcd_update)
|
||||||
clear();
|
clear();
|
||||||
for(short line=0;line<LCD_HEIGHT;line++)
|
for(short line=0;line<LCD_HEIGHT;line++)
|
||||||
{
|
{
|
||||||
switch(line)
|
switch(line)
|
||||||
{
|
{
|
||||||
case ItemM_watch:
|
case ItemM_watch:
|
||||||
{
|
{
|
||||||
if(force_lcd_update) {lcd.setCursor(0,line);lcd.print(" Watch \x7E");}
|
if(force_lcd_update) {lcd.setCursor(0,line);lcd.print(" Watch \x7E");}
|
||||||
if((activeline==line)&&CLICKED)
|
if((activeline==line)&&CLICKED)
|
||||||
{
|
{
|
||||||
BLOCK;
|
BLOCK;
|
||||||
beepshort();
|
beepshort();
|
||||||
status=Main_Status;
|
status=Main_Status;
|
||||||
}
|
}
|
||||||
} break;
|
} break;
|
||||||
case ItemM_prepare:
|
case ItemM_prepare:
|
||||||
{
|
{
|
||||||
if(force_lcd_update) {lcd.setCursor(0,line);lcd.print(" Prepare \x7E");}
|
if(force_lcd_update) {lcd.setCursor(0,line);lcd.print(" Prepare \x7E");}
|
||||||
if((activeline==line)&&CLICKED)
|
if((activeline==line)&&CLICKED)
|
||||||
{
|
{
|
||||||
BLOCK;
|
BLOCK;
|
||||||
status=Main_Prepare;
|
status=Main_Prepare;
|
||||||
beepshort();
|
beepshort();
|
||||||
}
|
}
|
||||||
} break;
|
} break;
|
||||||
|
|
||||||
case ItemM_control:
|
case ItemM_control:
|
||||||
{
|
{
|
||||||
if(force_lcd_update) {lcd.setCursor(0,line);lcd.print(" Control \x7E");}
|
if(force_lcd_update) {lcd.setCursor(0,line);lcd.print(" Control \x7E");}
|
||||||
if((activeline==line)&&CLICKED)
|
if((activeline==line)&&CLICKED)
|
||||||
{
|
{
|
||||||
BLOCK;
|
BLOCK;
|
||||||
status=Main_Control;
|
status=Main_Control;
|
||||||
beepshort();
|
beepshort();
|
||||||
}
|
}
|
||||||
}break;
|
}break;
|
||||||
#ifdef SDSUPPORT
|
#ifdef SDSUPPORT
|
||||||
case ItemM_file:
|
case ItemM_file:
|
||||||
{
|
{
|
||||||
if(force_lcd_update)
|
if(force_lcd_update)
|
||||||
{
|
{
|
||||||
lcd.setCursor(0,line);
|
lcd.setCursor(0,line);
|
||||||
#ifdef CARDINSERTED
|
#ifdef CARDINSERTED
|
||||||
if(CARDINSERTED)
|
if(CARDINSERTED)
|
||||||
#else
|
#else
|
||||||
if(true)
|
if(true)
|
||||||
#endif
|
#endif
|
||||||
{
|
{
|
||||||
if(sdmode)
|
if(sdmode)
|
||||||
lcd.print(" Stop Print \x7E");
|
lcd.print(" Stop Print \x7E");
|
||||||
else
|
else
|
||||||
lcd.print(" Card Menu \x7E");
|
lcd.print(" Card Menu \x7E");
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
lcd.print(" No Card");
|
lcd.print(" No Card");
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
#ifdef CARDINSERTED
|
#ifdef CARDINSERTED
|
||||||
if(CARDINSERTED)
|
if(CARDINSERTED)
|
||||||
#endif
|
#endif
|
||||||
if((activeline==line)&&CLICKED)
|
if((activeline==line)&&CLICKED)
|
||||||
{
|
{
|
||||||
sdmode = false;
|
sdmode = false;
|
||||||
BLOCK;
|
BLOCK;
|
||||||
status=Main_SD;
|
status=Main_SD;
|
||||||
beepshort();
|
beepshort();
|
||||||
}
|
}
|
||||||
}break;
|
}break;
|
||||||
#endif
|
#endif
|
||||||
default:
|
default:
|
||||||
Serial.println('NEVER say never');
|
Serial.println('NEVER say never');
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
if(activeline<0) activeline=0;
|
if(activeline<0) activeline=0;
|
||||||
if(activeline>=LCD_HEIGHT) activeline=LCD_HEIGHT-1;
|
if(activeline>=LCD_HEIGHT) activeline=LCD_HEIGHT-1;
|
||||||
if((encoderpos!=lastencoderpos)||force_lcd_update)
|
if((encoderpos!=lastencoderpos)||force_lcd_update)
|
||||||
{
|
{
|
||||||
lcd.setCursor(0,activeline);lcd.print(activeline?' ':' ');
|
lcd.setCursor(0,activeline);lcd.print(activeline?' ':' ');
|
||||||
if(encoderpos<0) encoderpos=0;
|
if(encoderpos<0) encoderpos=0;
|
||||||
if(encoderpos>3*lcdslow) encoderpos=3*lcdslow;
|
if(encoderpos>3*lcdslow) encoderpos=3*lcdslow;
|
||||||
activeline=abs(encoderpos/lcdslow)%LCD_HEIGHT;
|
activeline=abs(encoderpos/lcdslow)%LCD_HEIGHT;
|
||||||
if(activeline<0) activeline=0;
|
if(activeline<0) activeline=0;
|
||||||
if(activeline>=LCD_HEIGHT) activeline=LCD_HEIGHT-1;
|
if(activeline>=LCD_HEIGHT) activeline=LCD_HEIGHT-1;
|
||||||
lastencoderpos=encoderpos;
|
lastencoderpos=encoderpos;
|
||||||
lcd.setCursor(0,activeline);lcd.print(activeline?'>':'\003');
|
lcd.setCursor(0,activeline);lcd.print(activeline?'>':'\003');
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void MainMenu::update()
|
void MainMenu::update()
|
||||||
{
|
{
|
||||||
static MainStatus oldstatus=Main_Menu; //init automatically causes foce_lcd_update=true
|
static MainStatus oldstatus=Main_Menu; //init automatically causes foce_lcd_update=true
|
||||||
static long timeoutToStatus=0;
|
static long timeoutToStatus=0;
|
||||||
static bool oldcardstatus=false;
|
static bool oldcardstatus=false;
|
||||||
#ifdef CARDINSERTED
|
#ifdef CARDINSERTED
|
||||||
if((CARDINSERTED != oldcardstatus))
|
if((CARDINSERTED != oldcardstatus))
|
||||||
{
|
{
|
||||||
force_lcd_update=true;
|
force_lcd_update=true;
|
||||||
oldcardstatus=CARDINSERTED;
|
oldcardstatus=CARDINSERTED;
|
||||||
//Serial.println("SD CHANGE");
|
//Serial.println("SD CHANGE");
|
||||||
if(CARDINSERTED)
|
if(CARDINSERTED)
|
||||||
{
|
{
|
||||||
initsd();
|
initsd();
|
||||||
lcd_status("Card inserted");
|
lcd_status("Card inserted");
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
sdactive=false;
|
sdactive=false;
|
||||||
lcd_status("Card removed");
|
lcd_status("Card removed");
|
||||||
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
if(status!=oldstatus)
|
if(status!=oldstatus)
|
||||||
{
|
{
|
||||||
//Serial.println(status);
|
//Serial.println(status);
|
||||||
//clear();
|
//clear();
|
||||||
force_lcd_update=true;
|
force_lcd_update=true;
|
||||||
encoderpos=0;
|
encoderpos=0;
|
||||||
lineoffset=0;
|
lineoffset=0;
|
||||||
|
|
||||||
oldstatus=status;
|
oldstatus=status;
|
||||||
}
|
}
|
||||||
if( (encoderpos!=lastencoderpos) || CLICKED)
|
if( (encoderpos!=lastencoderpos) || CLICKED)
|
||||||
timeoutToStatus=millis()+STATUSTIMEOUT;
|
timeoutToStatus=millis()+STATUSTIMEOUT;
|
||||||
|
|
||||||
switch(status)
|
switch(status)
|
||||||
{
|
{
|
||||||
case Main_Status:
|
case Main_Status:
|
||||||
{
|
{
|
||||||
showStatus();
|
showStatus();
|
||||||
if(CLICKED)
|
if(CLICKED)
|
||||||
{
|
{
|
||||||
linechanging=false;
|
linechanging=false;
|
||||||
BLOCK
|
BLOCK
|
||||||
status=Main_Menu;
|
status=Main_Menu;
|
||||||
timeoutToStatus=millis()+STATUSTIMEOUT;
|
timeoutToStatus=millis()+STATUSTIMEOUT;
|
||||||
}
|
}
|
||||||
}break;
|
}break;
|
||||||
case Main_Menu:
|
case Main_Menu:
|
||||||
{
|
{
|
||||||
showMainMenu();
|
showMainMenu();
|
||||||
linechanging=false;
|
linechanging=false;
|
||||||
}break;
|
}break;
|
||||||
case Main_Prepare:
|
case Main_Prepare:
|
||||||
{
|
{
|
||||||
showPrepare();
|
showPrepare();
|
||||||
}break;
|
}break;
|
||||||
case Main_Control:
|
case Main_Control:
|
||||||
{
|
{
|
||||||
showControl();
|
showControl();
|
||||||
}break;
|
}break;
|
||||||
case Main_SD:
|
case Main_SD:
|
||||||
{
|
{
|
||||||
showSD();
|
showSD();
|
||||||
}break;
|
}break;
|
||||||
}
|
}
|
||||||
|
|
||||||
if(timeoutToStatus<millis())
|
if(timeoutToStatus<millis())
|
||||||
status=Main_Status;
|
status=Main_Status;
|
||||||
force_lcd_update=false;
|
force_lcd_update=false;
|
||||||
lastencoderpos=encoderpos;
|
lastencoderpos=encoderpos;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
//return for string conversion routines
|
//return for string conversion routines
|
||||||
char conv[8];
|
char conv[8];
|
||||||
|
|
||||||
/// convert float to string with +123.4 format
|
/// convert float to string with +123.4 format
|
||||||
char *ftostr3(const float &x)
|
char *ftostr3(const float &x)
|
||||||
{
|
{
|
||||||
//sprintf(conv,"%5.1f",x);
|
//sprintf(conv,"%5.1f",x);
|
||||||
int xx=x;
|
int xx=x;
|
||||||
conv[0]=(xx/100)%10+'0';
|
conv[0]=(xx/100)%10+'0';
|
||||||
conv[1]=(xx/10)%10+'0';
|
conv[1]=(xx/10)%10+'0';
|
||||||
conv[2]=(xx)%10+'0';
|
conv[2]=(xx)%10+'0';
|
||||||
conv[3]=0;
|
conv[3]=0;
|
||||||
return conv;
|
return conv;
|
||||||
}
|
}
|
||||||
char *itostr2(const uint8_t &x)
|
char *itostr2(const uint8_t &x)
|
||||||
{
|
{
|
||||||
//sprintf(conv,"%5.1f",x);
|
//sprintf(conv,"%5.1f",x);
|
||||||
int xx=x;
|
int xx=x;
|
||||||
conv[0]=(xx/10)%10+'0';
|
conv[0]=(xx/10)%10+'0';
|
||||||
conv[1]=(xx)%10+'0';
|
conv[1]=(xx)%10+'0';
|
||||||
conv[2]=0;
|
conv[2]=0;
|
||||||
return conv;
|
return conv;
|
||||||
}
|
}
|
||||||
/// convert float to string with +123.4 format
|
/// convert float to string with +123.4 format
|
||||||
char *ftostr31(const float &x)
|
char *ftostr31(const float &x)
|
||||||
{
|
{
|
||||||
//sprintf(conv,"%5.1f",x);
|
//sprintf(conv,"%5.1f",x);
|
||||||
int xx=x*10;
|
int xx=x*10;
|
||||||
conv[0]=(xx>=0)?'+':'-';
|
conv[0]=(xx>=0)?'+':'-';
|
||||||
xx=abs(xx);
|
xx=abs(xx);
|
||||||
conv[1]=(xx/1000)%10+'0';
|
conv[1]=(xx/1000)%10+'0';
|
||||||
conv[2]=(xx/100)%10+'0';
|
conv[2]=(xx/100)%10+'0';
|
||||||
conv[3]=(xx/10)%10+'0';
|
conv[3]=(xx/10)%10+'0';
|
||||||
conv[4]='.';
|
conv[4]='.';
|
||||||
conv[5]=(xx)%10+'0';
|
conv[5]=(xx)%10+'0';
|
||||||
conv[6]=0;
|
conv[6]=0;
|
||||||
return conv;
|
return conv;
|
||||||
}
|
}
|
||||||
|
|
||||||
char *itostr31(const int &xx)
|
char *itostr31(const int &xx)
|
||||||
{
|
{
|
||||||
//sprintf(conv,"%5.1f",x);
|
//sprintf(conv,"%5.1f",x);
|
||||||
conv[0]=(xx>=0)?'+':'-';
|
conv[0]=(xx>=0)?'+':'-';
|
||||||
conv[1]=(xx/1000)%10+'0';
|
conv[1]=(xx/1000)%10+'0';
|
||||||
conv[2]=(xx/100)%10+'0';
|
conv[2]=(xx/100)%10+'0';
|
||||||
conv[3]=(xx/10)%10+'0';
|
conv[3]=(xx/10)%10+'0';
|
||||||
conv[4]='.';
|
conv[4]='.';
|
||||||
conv[5]=(xx)%10+'0';
|
conv[5]=(xx)%10+'0';
|
||||||
conv[6]=0;
|
conv[6]=0;
|
||||||
return conv;
|
return conv;
|
||||||
}
|
}
|
||||||
char *itostr3(const int &xx)
|
char *itostr3(const int &xx)
|
||||||
{
|
{
|
||||||
conv[0]=(xx/100)%10+'0';
|
conv[0]=(xx/100)%10+'0';
|
||||||
conv[1]=(xx/10)%10+'0';
|
conv[1]=(xx/10)%10+'0';
|
||||||
conv[2]=(xx)%10+'0';
|
conv[2]=(xx)%10+'0';
|
||||||
conv[3]=0;
|
conv[3]=0;
|
||||||
return conv;
|
return conv;
|
||||||
}
|
}
|
||||||
|
|
||||||
char *itostr4(const int &xx)
|
char *itostr4(const int &xx)
|
||||||
{
|
{
|
||||||
conv[0]=(xx/1000)%10+'0';
|
conv[0]=(xx/1000)%10+'0';
|
||||||
conv[1]=(xx/100)%10+'0';
|
conv[1]=(xx/100)%10+'0';
|
||||||
conv[2]=(xx/10)%10+'0';
|
conv[2]=(xx/10)%10+'0';
|
||||||
conv[3]=(xx)%10+'0';
|
conv[3]=(xx)%10+'0';
|
||||||
conv[4]=0;
|
conv[4]=0;
|
||||||
return conv;
|
return conv;
|
||||||
}
|
}
|
||||||
|
|
||||||
/// convert float to string with +1234.5 format
|
/// convert float to string with +1234.5 format
|
||||||
char *ftostr51(const float &x)
|
char *ftostr51(const float &x)
|
||||||
{
|
{
|
||||||
int xx=x*10;
|
int xx=x*10;
|
||||||
conv[0]=(xx>=0)?'+':'-';
|
conv[0]=(xx>=0)?'+':'-';
|
||||||
xx=abs(xx);
|
xx=abs(xx);
|
||||||
conv[1]=(xx/10000)%10+'0';
|
conv[1]=(xx/10000)%10+'0';
|
||||||
conv[2]=(xx/1000)%10+'0';
|
conv[2]=(xx/1000)%10+'0';
|
||||||
conv[3]=(xx/100)%10+'0';
|
conv[3]=(xx/100)%10+'0';
|
||||||
conv[4]=(xx/10)%10+'0';
|
conv[4]=(xx/10)%10+'0';
|
||||||
conv[5]='.';
|
conv[5]='.';
|
||||||
conv[6]=(xx)%10+'0';
|
conv[6]=(xx)%10+'0';
|
||||||
conv[7]=0;
|
conv[7]=0;
|
||||||
return conv;
|
return conv;
|
||||||
}
|
}
|
||||||
|
|
||||||
char *fillto(int8_t n,char *c)
|
char *fillto(int8_t n,char *c)
|
||||||
{
|
{
|
||||||
static char ret[25];
|
static char ret[25];
|
||||||
bool endfound=false;
|
bool endfound=false;
|
||||||
for(int8_t i=0;i<n;i++)
|
for(int8_t i=0;i<n;i++)
|
||||||
{
|
{
|
||||||
ret[i]=c[i];
|
ret[i]=c[i];
|
||||||
if(c[i]==0)
|
if(c[i]==0)
|
||||||
{
|
{
|
||||||
endfound=true;
|
endfound=true;
|
||||||
}
|
}
|
||||||
if(endfound)
|
if(endfound)
|
||||||
{
|
{
|
||||||
ret[i]=' ';
|
ret[i]=' ';
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
ret[n]=0;
|
ret[n]=0;
|
||||||
return ret;
|
return ret;
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
#else
|
#else
|
||||||
inline void lcd_status() {};
|
inline void lcd_status() {};
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
64
README
64
README
|
@ -1,7 +1,14 @@
|
||||||
This firmware is a mashup between Sprinter, grbl and many original parts.
|
This RepRap firmware is a mashup between Sprinter, grbl and many original parts.
|
||||||
(https://github.com/kliment/Sprinter)
|
(https://github.com/kliment/Sprinter)
|
||||||
(https://github.com/simen/grbl/tree)
|
(https://github.com/simen/grbl/tree)
|
||||||
|
|
||||||
|
Derived from Sprinter and Grbl by Erik van der Zalm.
|
||||||
|
Sprinters lead developers are Kliment and caru.
|
||||||
|
Grbls lead developer is Simen Svale Skogsrud.
|
||||||
|
It has been adapted to the Ultimaker Printer by:
|
||||||
|
Bernhard Kubicek, Matthijs Keuper, Bradley Feldman, and others...
|
||||||
|
|
||||||
|
|
||||||
Features:
|
Features:
|
||||||
- Interrupt based movement with real linear acceleration
|
- Interrupt based movement with real linear acceleration
|
||||||
- High steprate
|
- High steprate
|
||||||
|
@ -9,62 +16,49 @@ Features:
|
||||||
- Interrupt based temperature protection
|
- Interrupt based temperature protection
|
||||||
- preliminary support for Matthew Roberts advance algorithm
|
- preliminary support for Matthew Roberts advance algorithm
|
||||||
For more info see: http://reprap.org/pipermail/reprap-dev/2011-May/003323.html
|
For more info see: http://reprap.org/pipermail/reprap-dev/2011-May/003323.html
|
||||||
|
- Full endstop support
|
||||||
|
- Simple LCD support (16x2)
|
||||||
|
- SD Card support
|
||||||
|
- Provisions for Bernhard Kubicek's new hardware control console and 20x4 lcd
|
||||||
|
|
||||||
This firmware is optimized for gen6 electronics.
|
This firmware is optimized for Ultimaker's gen6 electronics (including the Ultimaker 1.5.x daughterboard and Arduino Mega 2560).
|
||||||
|
|
||||||
|
The default baudrate is 115200.
|
||||||
|
|
||||||
The default baudrate is 250000.
|
|
||||||
This gives less communication errors then regular baudrates.
|
|
||||||
|
|
||||||
========================================================================================
|
========================================================================================
|
||||||
|
|
||||||
Configuring and compilation
|
Configuring and compilation
|
||||||
|
|
||||||
|
|
||||||
Install the arduino software version 0018
|
Install the latest arduino software IDE/toolset (currently 0022)
|
||||||
http://www.arduino.cc/en/Main/Software
|
http://www.arduino.cc/en/Main/Software
|
||||||
|
|
||||||
Install the sanguino software, version 0018
|
Install Ultimaker's RepG 25 build
|
||||||
http://sanguino.cc/useit
|
http://software.ultimaker.com
|
||||||
|
(or alternatively install Kliment's printrun/pronterface https://github.com/kliment/Printrun_)
|
||||||
|
|
||||||
Install pronterface
|
Copy the Ultimaker Marlin firmware
|
||||||
https://github.com/kliment/Printrun
|
https:/github.com/bkubicek/Marlin
|
||||||
|
|
||||||
Copy the Marlin firmware
|
|
||||||
https:/github.com/ErikZalm/Marlin
|
|
||||||
(Use the download button)
|
(Use the download button)
|
||||||
|
|
||||||
Start the arduino IDE.
|
Start the arduino IDE.
|
||||||
Select Tools -> Board -> Sanguino
|
Select Tools -> Board -> Arduino Mega 2560
|
||||||
Select the correct serial port in Tools ->Serial Port
|
Select the correct serial port in Tools ->Serial Port
|
||||||
Open Marlin.pde
|
Open Marlin.pde
|
||||||
|
|
||||||
Change the printer specific setting in Configuration.h to the correct values.
|
Click the Verify/Compile button
|
||||||
|
|
||||||
The following values are the most important:
|
|
||||||
- float axis_steps_per_unit[].... // Set the correct steps / mm in the corresponding field
|
|
||||||
- const bool ENDSTOPS_INVERTING = false; // Change if only positive moves are executed
|
|
||||||
- #define INVERT_x_DIR true // Change if the motor direction is wrong
|
|
||||||
|
|
||||||
Click the Upload button
|
Click the Upload button
|
||||||
If all goes well the firmware is uploading
|
If all goes well the firmware is uploading
|
||||||
|
|
||||||
Start pronterface
|
Start Ultimaker's Custom RepG 25
|
||||||
|
Make sure Show Experimental Profiles is enabled in Preferences
|
||||||
Select the correct Serial Port. Type 250000 in the baudrate field.
|
Select Sprinter as the Driver
|
||||||
Press the Connect button
|
|
||||||
|
|
||||||
===============================================================================================
|
|
||||||
Known issues
|
|
||||||
|
|
||||||
On some systems we get compilation errors.
|
|
||||||
|
|
||||||
This is caused by the "wiring_serial.c" and "wiring.c".
|
|
||||||
The simple fix is to delete these files but this may have a performance impact.
|
|
||||||
|
|
||||||
The best workaround is to move these files to sanguino directory.
|
|
||||||
(".../arduino-0018/hardware/Sanguino/cores/arduino/" on windows systems)
|
|
||||||
|
|
||||||
|
|
||||||
|
Press the Connect button.
|
||||||
|
|
||||||
|
KNOWN ISSUES: RepG will display: Unknown: marlin x.y.z
|
||||||
|
|
||||||
|
That's ok. Enjoy Silky Smooth Printing.
|
||||||
|
|
||||||
|
|
69
README.md
Normal file
69
README.md
Normal file
|
@ -0,0 +1,69 @@
|
||||||
|
WARNING: THIS IN A PROCESS OF HEAVY OVERWORKING.
|
||||||
|
DO NOT USE THIS ON YOUR MACHINE UNTIL FURTHER NOTICE!!!
|
||||||
|
|
||||||
|
===========================================
|
||||||
|
|
||||||
|
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.
|
||||||
|
Some features have been added by and configuration has been added by:
|
||||||
|
Bernhard Kubicek, Matthijs Keuper, 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
|
||||||
|
- Simple LCD support (16x2)
|
||||||
|
- SD Card support
|
||||||
|
- Provisions for Bernhard Kubicek's new hardware control console and 20x4 lcd
|
||||||
|
|
||||||
|
This firmware is optimized for Ultimaker's gen6 electronics (including the Ultimaker 1.5.x daughterboard and Arduino Mega 2560).
|
||||||
|
|
||||||
|
The default baudrate is 115200.
|
||||||
|
|
||||||
|
|
||||||
|
========================================================================================
|
||||||
|
|
||||||
|
Configuring and compilation
|
||||||
|
|
||||||
|
|
||||||
|
Install the latest arduino software IDE/toolset (currently 0022)
|
||||||
|
http://www.arduino.cc/en/Main/Software
|
||||||
|
|
||||||
|
Install Ultimaker's RepG 25 build
|
||||||
|
http://software.ultimaker.com
|
||||||
|
(or alternatively install Kliment's printrun/pronterface https://github.com/kliment/Printrun_)
|
||||||
|
|
||||||
|
Copy the Ultimaker Marlin firmware
|
||||||
|
https:/github.com/bkubicek/Marlin
|
||||||
|
(Use the download button)
|
||||||
|
|
||||||
|
Start the arduino IDE.
|
||||||
|
Select Tools -> Board -> Arduino Mega 2560
|
||||||
|
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.
|
||||||
|
|
||||||
|
|
||||||
|
|
58
merging still needs.txt
Normal file
58
merging still needs.txt
Normal file
|
@ -0,0 +1,58 @@
|
||||||
|
files to compare manually:
|
||||||
|
planner.cpp
|
||||||
|
stepper.cpp
|
||||||
|
temperature.cpp
|
||||||
|
|
||||||
|
---
|
||||||
|
things that changed:
|
||||||
|
* planner.cpp
|
||||||
|
estimate_acc_distance now works with floats.
|
||||||
|
in calculate_trapezoid:for_block
|
||||||
|
long acceleration_rate=(long)((float)acceleration*8.388608) is gone
|
||||||
|
so is block_>acceleration_rate
|
||||||
|
void planner_reverse_pass:
|
||||||
|
some stuff I don't understand right now changed
|
||||||
|
in planner_forward_pass:
|
||||||
|
done: BLOCK_BUFFER_SIZE is now necessarily power of 2 (aka 8 16, 32). Inportant to document this somewhere.
|
||||||
|
no more inline in void plan_discard_current_block()
|
||||||
|
no more inline in plan_get_current_block()
|
||||||
|
in plan_buffer_line(...)
|
||||||
|
the long target[4]; and calculations of thoose should go after the while(block_buffer_tail==..). if the axis_steps_per_unit are changed from the gcode (M92) the calculation for the currently planned buffer move will be corrupt, because Target is calculated with one value, and the stuff afterwards with another. At least this solved the problem I had with the M92 E* changes in the code. Very sure about this, I took me 20min to find this as the solution for the bug I was hunting.
|
||||||
|
around if(feed_rate<minimumfeedrate) this only should be done if it is not a pure extrusion. I think there is a bug right now.
|
||||||
|
~line 447 blockcount=
|
||||||
|
not sure if this also works if the difference is negative, as it would happen if the ringbuffer runs over the end and start at 0.
|
||||||
|
~line 507 tmp_aceleration. not sure whats going on, but a lot changed.
|
||||||
|
|
||||||
|
|
||||||
|
* stepper.cpp
|
||||||
|
~214: if (busy) should be a echoln, maybe
|
||||||
|
~331: great, The Z_M_PIN checks are in :)
|
||||||
|
|
||||||
|
*temperature.cpp
|
||||||
|
done: enum for heater, bed,
|
||||||
|
manage_heater() is seriously different.
|
||||||
|
done: if tem_meas_ready ==true->!true+return?
|
||||||
|
done #define K1 0.95 maybe in the configuration.h?
|
||||||
|
semi-done: PID-C checking needed. Untested but added.
|
||||||
|
----
|
||||||
|
|
||||||
|
still needed to finish the merge, before testin!
|
||||||
|
|
||||||
|
manage_heater
|
||||||
|
ISR
|
||||||
|
movement planner
|
||||||
|
|
||||||
|
TODO:
|
||||||
|
|
||||||
|
remove traveling at maxpseed
|
||||||
|
remove Simplelcd
|
||||||
|
|
||||||
|
remove DEBUG_STEPS?
|
||||||
|
|
||||||
|
block_t
|
||||||
|
pid_dt ->0.1 whats the changes to the PID, checking needed
|
||||||
|
|
||||||
|
|
||||||
|
----
|
||||||
|
second merge saturday morning:
|
||||||
|
done: PID_dt->0.1
|
Reference in a new issue