Merge branch 'Marlin_v1', remote-tracking branch 'origin/Marlin_v1' into Marlin_v1

This commit is contained in:
Erik van der Zalm 2011-12-04 19:54:43 +01:00
commit 95a0b28acb
14 changed files with 536 additions and 470 deletions

View file

@ -214,6 +214,7 @@ const bool Z_ENDSTOPS_INVERTING = true; // set to true to invert the logic of th
#define X_HOME_RETRACT_MM 5 #define X_HOME_RETRACT_MM 5
#define Y_HOME_RETRACT_MM 5 #define Y_HOME_RETRACT_MM 5
#define Z_HOME_RETRACT_MM 1 #define Z_HOME_RETRACT_MM 1
#define QUICK_HOME //if this is defined, if both x and y are to be homed, a diagonal move will be performed initially.
#define AXIS_RELATIVE_MODES {false, false, false, false} #define AXIS_RELATIVE_MODES {false, false, false, false}

View file

@ -16,7 +16,6 @@
#include "Configuration.h" #include "Configuration.h"
#include "MarlinSerial.h" #include "MarlinSerial.h"
#define FORCE_INLINE __attribute__((always_inline)) inline #define FORCE_INLINE __attribute__((always_inline)) inline
//#define SERIAL_ECHO(x) Serial << "echo: " << x; //#define SERIAL_ECHO(x) Serial << "echo: " << x;
//#define SERIAL_ECHOLN(x) Serial << "echo: "<<x<<endl; //#define SERIAL_ECHOLN(x) Serial << "echo: "<<x<<endl;
@ -25,15 +24,25 @@
//#define SERIAL_PROTOCOL(x) Serial << x; //#define SERIAL_PROTOCOL(x) Serial << x;
//#define SERIAL_PROTOCOLLN(x) Serial << x<<endl; //#define SERIAL_PROTOCOLLN(x) Serial << x<<endl;
//this is a unfinsihed attemp to removes a lot of warning messages, see:
// http://www.avrfreaks.net/index.php?name=PNphpBB2&file=printview&t=57011
//typedef char prog_char PROGMEM;
// //#define PSTR (s ) ((const PROGMEM char *)(s))
// //# define MYPGM(s) (__extension__({static prog_char __c[] = (s); &__c[0];}))
// //#define MYPGM(s) ((const prog_char *g PROGMEM=s))
// //#define MYPGM(s) PSTR(s)
#define MYPGM(s) (__extension__({static char __c[] __attribute__((__progmem__)) = (s); &__c[0];})) //This is the normal behaviour
//#define MYPGM(s) (__extension__({static prog_char __c[] = (s); &__c[0];})) //this does not work but hides the warnings
#define SERIAL_PROTOCOL(x) MSerial.print(x); #define SERIAL_PROTOCOL(x) MSerial.print(x);
#define SERIAL_PROTOCOLPGM(x) serialprintPGM(PSTR(x)); #define SERIAL_PROTOCOLPGM(x) serialprintPGM(MYPGM(x));
#define SERIAL_PROTOCOLLN(x) {MSerial.print(x);MSerial.write('\n');} #define SERIAL_PROTOCOLLN(x) {MSerial.print(x);MSerial.write('\n');}
#define SERIAL_PROTOCOLLNPGM(x) {serialprintPGM(PSTR(x));MSerial.write('\n');} #define SERIAL_PROTOCOLLNPGM(x) {serialprintPGM(MYPGM(x));MSerial.write('\n');}
const char errormagic[] PROGMEM ="Error:";
const char echomagic[] PROGMEM ="echo:"; const prog_char errormagic[] PROGMEM ="Error:";
const prog_char echomagic[] PROGMEM ="echo:";
#define SERIAL_ERROR_START serialprintPGM(errormagic); #define SERIAL_ERROR_START serialprintPGM(errormagic);
#define SERIAL_ERROR(x) SERIAL_PROTOCOL(x) #define SERIAL_ERROR(x) SERIAL_PROTOCOL(x)
#define SERIAL_ERRORPGM(x) SERIAL_PROTOCOLPGM(x) #define SERIAL_ERRORPGM(x) SERIAL_PROTOCOLPGM(x)
@ -50,7 +59,7 @@ const char echomagic[] PROGMEM ="echo:";
//things to write to serial from Programmemory. saves 400 to 2k of RAM. //things to write to serial from Programmemory. saves 400 to 2k of RAM.
#define SerialprintPGM(x) serialprintPGM(PSTR(x)) #define SerialprintPGM(x) serialprintPGM(MYPGM(x))
FORCE_INLINE void serialprintPGM(const char *str) FORCE_INLINE void serialprintPGM(const char *str)
{ {
char ch=pgm_read_byte(str); char ch=pgm_read_byte(str);

View file

@ -167,7 +167,8 @@ static char *strchr_pointer; // just a pointer to find chars in the cmd string l
const int sensitive_pins[] = SENSITIVE_PINS; // Sensitive pin list for M42 const int sensitive_pins[] = SENSITIVE_PINS; // Sensitive pin list for M42
static float tt = 0, bt = 0; //static float tt = 0;
//static float bt = 0;
//Inactivity shutdown variables //Inactivity shutdown variables
static unsigned long previous_millis_cmd = 0; static unsigned long previous_millis_cmd = 0;
@ -532,7 +533,7 @@ FORCE_INLINE void process_commands()
} }
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])));
#ifdef QUICK_HOME
if( code_seen(axis_codes[0]) && code_seen(axis_codes[1]) ) //first diagonal move if( code_seen(axis_codes[0]) && code_seen(axis_codes[1]) ) //first diagonal move
{ {
current_position[X_AXIS] = 0; current_position[Y_AXIS] = 0; current_position[X_AXIS] = 0; current_position[Y_AXIS] = 0;
@ -545,6 +546,7 @@ FORCE_INLINE void process_commands()
prepare_move(); prepare_move();
current_position[X_AXIS] = 0; current_position[Y_AXIS] = 0; current_position[X_AXIS] = 0; current_position[Y_AXIS] = 0;
} }
#endif
if((home_all_axis) || (code_seen(axis_codes[X_AXIS]))) if((home_all_axis) || (code_seen(axis_codes[X_AXIS])))
{ {
@ -669,6 +671,7 @@ FORCE_INLINE void process_commands()
SERIAL_ECHO_START; SERIAL_ECHO_START;
SERIAL_ECHOLN(time); SERIAL_ECHOLN(time);
LCD_MESSAGE(time); LCD_MESSAGE(time);
autotempShutdown();
} }
break; break;
case 42: //M42 -Change pin status via gcode case 42: //M42 -Change pin status via gcode

View file

@ -20,6 +20,7 @@
Modified 28 September 2010 by Mark Sproul Modified 28 September 2010 by Mark Sproul
*/ */
#include <stdlib.h> #include <stdlib.h>
#include <stdio.h> #include <stdio.h>
#include <string.h> #include <string.h>

View file

@ -120,7 +120,7 @@ class MarlinSerial //: public Stream
FORCE_INLINE void print(const String &s) FORCE_INLINE void print(const String &s)
{ {
for (int i = 0; i < s.length(); i++) { for (int i = 0; i < (int)s.length(); i++) {
write(s[i]); write(s[i]);
} }
} }

View file

@ -59,7 +59,7 @@ private:
LsAction lsAction; //stored for recursion. LsAction lsAction; //stored for recursion.
int16_t nrFiles; //counter for the files in the current directory and recycled as position counter for getting the nrFiles'th name in the directory. int16_t nrFiles; //counter for the files in the current directory and recycled as position counter for getting the nrFiles'th name in the directory.
char* diveDirName; char* diveDirName;
void lsDive(char *prepend,SdFile parent); void lsDive(const char *prepend,SdFile parent);
}; };

View file

@ -40,7 +40,7 @@ char *createFilename(char *buffer,const dir_t &p) //buffer>12characters
} }
void CardReader::lsDive(char *prepend,SdFile parent) void CardReader::lsDive(const char *prepend,SdFile parent)
{ {
dir_t p; dir_t p;
uint8_t cnt=0; uint8_t cnt=0;
@ -436,5 +436,6 @@ void CardReader::printingHasFinished()
{ {
finishAndDisableSteppers(); finishAndDisableSteppers();
} }
autotempShutdown();
} }
#endif //SDSUPPORT #endif //SDSUPPORT

View file

@ -91,7 +91,7 @@ static float previous_nominal_speed; // Nominal speed of previous path line segm
#ifdef AUTOTEMP #ifdef AUTOTEMP
float autotemp_max=250; float autotemp_max=250;
float autotemp_min=210; float autotemp_min=210;
float autotemp_factor=1; float autotemp_factor=0.1;
bool autotemp_enabled=false; bool autotemp_enabled=false;
#endif #endif
@ -107,10 +107,12 @@ volatile unsigned char block_buffer_tail; // Index of the block to pro
//=============================private variables ============================ //=============================private variables ============================
//=========================================================================== //===========================================================================
// Used for the frequency limit #ifdef XY_FREQUENCY_LIMIT
static unsigned char old_direction_bits = 0; // Old direction bits. Used for speed calculations // Used for the frequency limit
static long x_segment_time[3]={0,0,0}; // Segment times (in us). Used for speed calculations static unsigned char old_direction_bits = 0; // Old direction bits. Used for speed calculations
static long y_segment_time[3]={0,0,0}; static long x_segment_time[3]={0,0,0}; // Segment times (in us). Used for speed calculations
static long y_segment_time[3]={0,0,0};
#endif
// Returns the index of the next block in the ring buffer // Returns the index of the next block in the ring buffer
// NOTE: Removed modulo (%) operator, which uses an expensive divide and multiplication. // NOTE: Removed modulo (%) operator, which uses an expensive divide and multiplication.
@ -254,7 +256,7 @@ void planner_reverse_pass_kernel(block_t *previous, block_t *current, block_t *n
// planner_recalculate() needs to go over the current plan twice. Once in reverse and once forward. This // planner_recalculate() needs to go over the current plan twice. Once in reverse and once forward. This
// implements the reverse pass. // implements the reverse pass.
void planner_reverse_pass() { void planner_reverse_pass() {
char block_index = block_buffer_head; uint8_t block_index = block_buffer_head;
if(((block_buffer_head-block_buffer_tail + BLOCK_BUFFER_SIZE) & (BLOCK_BUFFER_SIZE - 1)) > 3) { if(((block_buffer_head-block_buffer_tail + BLOCK_BUFFER_SIZE) & (BLOCK_BUFFER_SIZE - 1)) > 3) {
block_index = (block_buffer_head - 3) & (BLOCK_BUFFER_SIZE - 1); block_index = (block_buffer_head - 3) & (BLOCK_BUFFER_SIZE - 1);
block_t *block[3] = { NULL, NULL, NULL }; block_t *block[3] = { NULL, NULL, NULL };
@ -293,7 +295,7 @@ void planner_forward_pass_kernel(block_t *previous, block_t *current, block_t *n
// planner_recalculate() needs to go over the current plan twice. Once in reverse and once forward. This // planner_recalculate() needs to go over the current plan twice. Once in reverse and once forward. This
// implements the forward pass. // implements the forward pass.
void planner_forward_pass() { void planner_forward_pass() {
char block_index = block_buffer_tail; uint8_t block_index = block_buffer_tail;
block_t *block[3] = { NULL, NULL, NULL }; block_t *block[3] = { NULL, NULL, NULL };
while(block_index != block_buffer_head) { while(block_index != block_buffer_head) {
@ -383,7 +385,7 @@ void getHighESpeed()
return; //do nothing return; //do nothing
float high=0; float high=0;
char block_index = block_buffer_tail; uint8_t block_index = block_buffer_tail;
while(block_index != block_buffer_head) { while(block_index != block_buffer_head) {
float se=block_buffer[block_index].steps_e/float(block_buffer[block_index].step_event_count)*block_buffer[block_index].nominal_rate; float se=block_buffer[block_index].steps_e/float(block_buffer[block_index].step_event_count)*block_buffer[block_index].nominal_rate;
@ -422,7 +424,7 @@ void check_axes_activity() {
block_t *block; block_t *block;
if(block_buffer_tail != block_buffer_head) { if(block_buffer_tail != block_buffer_head) {
char block_index = block_buffer_tail; uint8_t block_index = block_buffer_tail;
while(block_index != block_buffer_head) { while(block_index != block_buffer_head) {
block = &block_buffer[block_index]; block = &block_buffer[block_index];
if(block->steps_x != 0) x_active++; if(block->steps_x != 0) x_active++;
@ -518,8 +520,7 @@ void plan_buffer_line(const float &x, const float &y, const float &z, const floa
block->nominal_speed = block->millimeters * inverse_second; // (mm/sec) Always > 0 block->nominal_speed = block->millimeters * inverse_second; // (mm/sec) Always > 0
block->nominal_rate = ceil(block->step_event_count * inverse_second); // (step/sec) Always > 0 block->nominal_rate = ceil(block->step_event_count * inverse_second); // (step/sec) Always > 0
// segment time im micro seconds
long segment_time = lround(1000000.0/inverse_second);
if (block->steps_e == 0) { if (block->steps_e == 0) {
@ -537,6 +538,8 @@ void plan_buffer_line(const float &x, const float &y, const float &z, const floa
#endif #endif
/* /*
// segment time im micro seconds
long segment_time = lround(1000000.0/inverse_second);
if ((blockcount>0) && (blockcount < (BLOCK_BUFFER_SIZE - 4))) { if ((blockcount>0) && (blockcount < (BLOCK_BUFFER_SIZE - 4))) {
if (segment_time<minsegmenttime) { // buffer is draining, add extra time. The amount of time added increases if the buffer is still emptied more. if (segment_time<minsegmenttime) { // buffer is draining, add extra time. The amount of time added increases if the buffer is still emptied more.
segment_time=segment_time+lround(2*(minsegmenttime-segment_time)/blockcount); segment_time=segment_time+lround(2*(minsegmenttime-segment_time)/blockcount);

View file

@ -21,6 +21,7 @@
/* The timer calculations of this module informed by the 'RepRap cartesian firmware' by Zack Smith /* The timer calculations of this module informed by the 'RepRap cartesian firmware' by Zack Smith
and Philipp Tiefenbacher. */ and Philipp Tiefenbacher. */
#include "stepper.h" #include "stepper.h"
#include "Configuration.h" #include "Configuration.h"
#include "Marlin.h" #include "Marlin.h"
@ -454,7 +455,7 @@ ISR(TIMER1_COMPA_vect)
// Calculare new timer value // Calculare new timer value
unsigned short timer; unsigned short timer;
unsigned short step_rate; unsigned short step_rate;
if (step_events_completed <= current_block->accelerate_until) { if (step_events_completed <= (unsigned long int)current_block->accelerate_until) {
MultiU24X24toH16(acc_step_rate, acceleration_time, current_block->acceleration_rate); MultiU24X24toH16(acc_step_rate, acceleration_time, current_block->acceleration_rate);
acc_step_rate += current_block->initial_rate; acc_step_rate += current_block->initial_rate;
@ -478,7 +479,7 @@ ISR(TIMER1_COMPA_vect)
#endif #endif
} }
else if (step_events_completed > current_block->decelerate_after) { else if (step_events_completed > (unsigned long int)current_block->decelerate_after) {
MultiU24X24toH16(step_rate, deceleration_time, current_block->acceleration_rate); MultiU24X24toH16(step_rate, deceleration_time, current_block->acceleration_rate);
if(step_rate > acc_step_rate) { // Check step_rate stays positive if(step_rate > acc_step_rate) { // Check step_rate stays positive
@ -695,7 +696,7 @@ void st_set_e_position(const long &e)
CRITICAL_SECTION_END; CRITICAL_SECTION_END;
} }
long st_get_position(char axis) long st_get_position(uint8_t axis)
{ {
long count_pos; long count_pos;
CRITICAL_SECTION_START; CRITICAL_SECTION_START;

View file

@ -34,7 +34,7 @@ void st_set_position(const long &x, const long &y, const long &z, const long &e)
void st_set_e_position(const long &e); void st_set_e_position(const long &e);
// Get current position in steps // Get current position in steps
long st_get_position(char axis); long st_get_position(uint8_t axis);
// The stepper subsystem goes to sleep when it runs out of things to execute. Call this // The stepper subsystem goes to sleep when it runs out of things to execute. Call this
// to notify the subsystem that it is time to go to work. // to notify the subsystem that it is time to go to work.

View file

@ -67,7 +67,8 @@ int heatingtarget_raw[3]= {0, 0, 0};
//=========================================================================== //===========================================================================
static bool temp_meas_ready = false; static bool temp_meas_ready = false;
static unsigned long previous_millis_heater, previous_millis_bed_heater; static unsigned long previous_millis_bed_heater;
//static unsigned long previous_millis_heater;
#ifdef PIDTEMP #ifdef PIDTEMP
//static cannot be external: //static cannot be external:
@ -80,8 +81,8 @@ static unsigned long previous_millis_heater, previous_millis_bed_heater;
static float pid_error; static float pid_error;
static float temp_iState_min; static float temp_iState_min;
static float temp_iState_max; static float temp_iState_max;
static float pid_input; // static float pid_input;
static float pid_output; // static float pid_output;
static bool pid_reset; static bool pid_reset;
#endif //PIDTEMP #endif //PIDTEMP
@ -94,8 +95,8 @@ static unsigned long previous_millis_heater, previous_millis_bed_heater;
// Init min and max temp with extreme values to prevent false errors during startup // Init min and max temp with extreme values to prevent false errors during startup
static int minttemp_0 = 0; static int minttemp_0 = 0;
static int maxttemp_0 = 16383; static int maxttemp_0 = 16383;
static int minttemp_1 = 0; //static int minttemp_1 = 0;
static int maxttemp_1 = 16383; //static int maxttemp_1 = 16383;
static int bed_minttemp = 0; static int bed_minttemp = 0;
static int bed_maxttemp = 16383; static int bed_maxttemp = 16383;
@ -268,7 +269,10 @@ int temp2analogBed(int celsius) {
return (1023 * OVERSAMPLENR) - raw; return (1023 * OVERSAMPLENR) - raw;
#elif defined BED_USES_AD595 #elif defined BED_USES_AD595
return lround(celsius * (1024.0 * OVERSAMPLENR/ (5.0 * 100.0) ) ); return lround(celsius * (1024.0 * OVERSAMPLENR/ (5.0 * 100.0) ) );
#else
#warning No heater-type defined for the bed.
#endif #endif
return 0;
} }
// Derived from RepRap FiveD extruder::getTemperature() // Derived from RepRap FiveD extruder::getTemperature()
@ -296,6 +300,8 @@ float analog2temp(int raw) {
return celsius; return celsius;
#elif defined HEATER_0_USES_AD595 #elif defined HEATER_0_USES_AD595
return raw * ((5.0 * 100.0) / 1024.0) / OVERSAMPLENR; return raw * ((5.0 * 100.0) / 1024.0) / OVERSAMPLENR;
#else
#error PLEASE DEFINE HEATER TYPE
#endif #endif
} }
@ -328,7 +334,10 @@ float analog2tempBed(int raw) {
#elif defined BED_USES_AD595 #elif defined BED_USES_AD595
return raw * ((5.0 * 100.0) / 1024.0) / OVERSAMPLENR; return raw * ((5.0 * 100.0) / 1024.0) / OVERSAMPLENR;
#else
#warning No heater-type defined for the bed.
#endif #endif
return 0;
} }
void tp_init() void tp_init()

View file

@ -86,7 +86,7 @@ FORCE_INLINE void setTargetHotend0(const float &celsius)
#endif //PIDTEMP #endif //PIDTEMP
}; };
FORCE_INLINE void setTargetHotend1(const float &celsius) { target_raw[TEMPSENSOR_HOTEND_1]=temp2analog(celsius);}; FORCE_INLINE void setTargetHotend1(const float &celsius) { target_raw[TEMPSENSOR_HOTEND_1]=temp2analog(celsius);};
FORCE_INLINE float setTargetHotend(const float &celcius, uint8_t extruder){ FORCE_INLINE void setTargetHotend(const float &celcius, uint8_t extruder){
if(extruder == 0) setTargetHotend0(celcius); if(extruder == 0) setTargetHotend0(celcius);
if(extruder == 1) setTargetHotend1(celcius); if(extruder == 1) setTargetHotend1(celcius);
}; };
@ -94,20 +94,32 @@ FORCE_INLINE void setTargetBed(const float &celsius) { target_raw[TEMPSENSO
FORCE_INLINE bool isHeatingHotend0() {return heatingtarget_raw[TEMPSENSOR_HOTEND_0] > current_raw[TEMPSENSOR_HOTEND_0];}; FORCE_INLINE bool isHeatingHotend0() {return heatingtarget_raw[TEMPSENSOR_HOTEND_0] > current_raw[TEMPSENSOR_HOTEND_0];};
FORCE_INLINE bool isHeatingHotend1() {return target_raw[TEMPSENSOR_HOTEND_1] > current_raw[TEMPSENSOR_HOTEND_1];}; FORCE_INLINE bool isHeatingHotend1() {return target_raw[TEMPSENSOR_HOTEND_1] > current_raw[TEMPSENSOR_HOTEND_1];};
FORCE_INLINE float isHeatingHotend(uint8_t extruder){ FORCE_INLINE bool isHeatingHotend(uint8_t extruder){
if(extruder == 0) return heatingtarget_raw[TEMPSENSOR_HOTEND_0] > current_raw[TEMPSENSOR_HOTEND_0]; if(extruder == 0) return heatingtarget_raw[TEMPSENSOR_HOTEND_0] > current_raw[TEMPSENSOR_HOTEND_0];
if(extruder == 1) return target_raw[TEMPSENSOR_HOTEND_1] > current_raw[TEMPSENSOR_HOTEND_1]; if(extruder == 1) return target_raw[TEMPSENSOR_HOTEND_1] > current_raw[TEMPSENSOR_HOTEND_1];
return false;
}; };
FORCE_INLINE bool isHeatingBed() {return target_raw[TEMPSENSOR_BED] > current_raw[TEMPSENSOR_BED];}; FORCE_INLINE bool isHeatingBed() {return target_raw[TEMPSENSOR_BED] > current_raw[TEMPSENSOR_BED];};
FORCE_INLINE bool isCoolingHotend0() {return target_raw[TEMPSENSOR_HOTEND_0] < current_raw[TEMPSENSOR_HOTEND_0];}; FORCE_INLINE bool isCoolingHotend0() {return target_raw[TEMPSENSOR_HOTEND_0] < current_raw[TEMPSENSOR_HOTEND_0];};
FORCE_INLINE bool isCoolingHotend1() {return target_raw[TEMPSENSOR_HOTEND_1] < current_raw[TEMPSENSOR_HOTEND_1];}; FORCE_INLINE bool isCoolingHotend1() {return target_raw[TEMPSENSOR_HOTEND_1] < current_raw[TEMPSENSOR_HOTEND_1];};
FORCE_INLINE float isCoolingHotend(uint8_t extruder){ FORCE_INLINE bool isCoolingHotend(uint8_t extruder){
if(extruder == 0) return target_raw[TEMPSENSOR_HOTEND_0] < current_raw[TEMPSENSOR_HOTEND_0]; if(extruder == 0) return target_raw[TEMPSENSOR_HOTEND_0] < current_raw[TEMPSENSOR_HOTEND_0];
if(extruder == 1) return target_raw[TEMPSENSOR_HOTEND_1] < current_raw[TEMPSENSOR_HOTEND_1]; if(extruder == 1) return target_raw[TEMPSENSOR_HOTEND_1] < current_raw[TEMPSENSOR_HOTEND_1];
return false;
}; };
FORCE_INLINE bool isCoolingBed() {return target_raw[TEMPSENSOR_BED] < current_raw[TEMPSENSOR_BED];}; FORCE_INLINE bool isCoolingBed() {return target_raw[TEMPSENSOR_BED] < current_raw[TEMPSENSOR_BED];};
FORCE_INLINE void autotempShutdown(){
#ifdef AUTOTEMP
if(autotemp_enabled)
{
autotemp_enabled=false;
if(degTargetHotend0()>autotemp_min)
setTargetHotend0(0);
}
#endif
}
void disable_heater(); void disable_heater();
void setWatch(); void setWatch();
void updatePID(); void updatePID();

View file

@ -1,7 +1,7 @@
#ifndef __ULTRALCDH #ifndef __ULTRALCDH
#define __ULTRALCDH #define __ULTRALCDH
#include "Configuration.h" #include "Configuration.h"
#include "Marlin.h"
#ifdef ULTRA_LCD #ifdef ULTRA_LCD
void lcd_status(); void lcd_status();
@ -104,7 +104,6 @@
curencoderpos=maxlines*lcdslow; curencoderpos=maxlines*lcdslow;
} }
lastencoderpos=encoderpos=curencoderpos; lastencoderpos=encoderpos=curencoderpos;
int lastactiveline=activeline;
activeline=curencoderpos/lcdslow; activeline=curencoderpos/lcdslow;
if(activeline<0) activeline=0; if(activeline<0) activeline=0;
if(activeline>LCD_HEIGHT-1) activeline=LCD_HEIGHT-1; if(activeline>LCD_HEIGHT-1) activeline=LCD_HEIGHT-1;
@ -137,7 +136,7 @@
#define LCD_MESSAGE(x) lcd_status(x); #define LCD_MESSAGE(x) lcd_status(x);
#define LCD_MESSAGEPGM(x) lcd_statuspgm(PSTR(x)); #define LCD_MESSAGEPGM(x) lcd_statuspgm(MYPGM(x));
#define LCD_STATUS lcd_status() #define LCD_STATUS lcd_status()
#else //no lcd #else //no lcd
#define LCD_STATUS #define LCD_STATUS

View file

@ -53,7 +53,7 @@ void lcdProgMemprint(const char *str)
ch=pgm_read_byte(++str); ch=pgm_read_byte(++str);
} }
} }
#define lcdprintPGM(x) lcdProgMemprint(PSTR(x)) #define lcdprintPGM(x) lcdProgMemprint(MYPGM(x))
//=========================================================================== //===========================================================================
@ -159,8 +159,8 @@ 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();
@ -503,31 +503,32 @@ void MainMenu::showTune()
lcd.setCursor(13,line);lcd.print(ftostr3(feedmultiply)); lcd.setCursor(13,line);lcd.print(ftostr3(feedmultiply));
} }
if((activeline==line) ) if((activeline!=line) )
break;
if(CLICKED) //nalogWrite(FAN_PIN, fanpwm);
{ {
if(CLICKED) //nalogWrite(FAN_PIN, fanpwm); linechanging=!linechanging;
{
linechanging=!linechanging;
if(linechanging)
{
encoderpos=feedmultiply;
}
else
{
encoderpos=activeline*lcdslow;
beepshort();
}
BLOCK;
}
if(linechanging) if(linechanging)
{ {
if(encoderpos<1) encoderpos=1; encoderpos=feedmultiply;
if(encoderpos>400) encoderpos=400;
feedmultiply = encoderpos;
feedmultiplychanged=true;
lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));
} }
else
{
encoderpos=activeline*lcdslow;
beepshort();
}
BLOCK;
} }
if(linechanging)
{
if(encoderpos<1) encoderpos=1;
if(encoderpos>400) encoderpos=400;
feedmultiply = encoderpos;
feedmultiplychanged=true;
lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));
}
}break; }break;
case ItemT_nozzle: case ItemT_nozzle:
{ {
@ -537,29 +538,29 @@ void MainMenu::showTune()
lcd.setCursor(13,line);lcd.print(ftostr3(intround(degTargetHotend0()))); lcd.setCursor(13,line);lcd.print(ftostr3(intround(degTargetHotend0())));
} }
if((activeline==line) ) if((activeline!=line) )
break;
if(CLICKED)
{ {
if(CLICKED) linechanging=!linechanging;
{
linechanging=!linechanging;
if(linechanging)
{
encoderpos=intround(degTargetHotend0());
}
else
{
setTargetHotend0(encoderpos);
encoderpos=activeline*lcdslow;
beepshort();
}
BLOCK;
}
if(linechanging) if(linechanging)
{ {
if(encoderpos<0) encoderpos=0; encoderpos=intround(degTargetHotend0());
if(encoderpos>260) encoderpos=260;
lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));
} }
else
{
setTargetHotend0(encoderpos);
encoderpos=activeline*lcdslow;
beepshort();
}
BLOCK;
}
if(linechanging)
{
if(encoderpos<0) encoderpos=0;
if(encoderpos>260) encoderpos=260;
lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));
} }
}break; }break;
@ -571,31 +572,32 @@ void MainMenu::showTune()
lcd.setCursor(13,line);lcd.print(ftostr3(fanpwm)); lcd.setCursor(13,line);lcd.print(ftostr3(fanpwm));
} }
if((activeline==line) ) if((activeline!=line) )
break;
if(CLICKED) //nalogWrite(FAN_PIN, fanpwm);
{ {
if(CLICKED) //nalogWrite(FAN_PIN, fanpwm); linechanging=!linechanging;
{
linechanging=!linechanging;
if(linechanging)
{
encoderpos=fanpwm;
}
else
{
encoderpos=activeline*lcdslow;
beepshort();
}
BLOCK;
}
if(linechanging) if(linechanging)
{ {
if(encoderpos<0) encoderpos=0; encoderpos=fanpwm;
if(encoderpos>255) encoderpos=255;
fanpwm=encoderpos;
analogWrite(FAN_PIN, fanpwm);
lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));
} }
else
{
encoderpos=activeline*lcdslow;
beepshort();
}
BLOCK;
} }
if(linechanging)
{
if(encoderpos<0) encoderpos=0;
if(encoderpos>255) encoderpos=255;
fanpwm=encoderpos;
analogWrite(FAN_PIN, fanpwm);
lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));
}
}break; }break;
case ItemT_flow://axis_steps_per_unit[i] = code_value(); case ItemT_flow://axis_steps_per_unit[i] = code_value();
{ {
@ -605,34 +607,35 @@ void MainMenu::showTune()
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) )
break;
if(CLICKED)
{ {
if(CLICKED) linechanging=!linechanging;
{
linechanging=!linechanging;
if(linechanging)
{
encoderpos=(int)axis_steps_per_unit[3];
}
else
{
float factor=float(encoderpos)/float(axis_steps_per_unit[3]);
position[E_AXIS]=lround(position[E_AXIS]*factor);
//current_position[3]*=factor;
axis_steps_per_unit[E_AXIS]= encoderpos;
encoderpos=activeline*lcdslow;
}
BLOCK;
beepshort();
}
if(linechanging) if(linechanging)
{ {
if(encoderpos<5) encoderpos=5; encoderpos=(int)axis_steps_per_unit[3];
if(encoderpos>9999) encoderpos=9999;
lcd.setCursor(13,line);lcd.print(itostr4(encoderpos));
} }
else
{
float factor=float(encoderpos)/float(axis_steps_per_unit[3]);
position[E_AXIS]=lround(position[E_AXIS]*factor);
//current_position[3]*=factor;
axis_steps_per_unit[E_AXIS]= encoderpos;
encoderpos=activeline*lcdslow;
}
BLOCK;
beepshort();
} }
if(linechanging)
{
if(encoderpos<5) encoderpos=5;
if(encoderpos>9999) encoderpos=9999;
lcd.setCursor(13,line);lcd.print(itostr4(encoderpos));
}
}break; }break;
default: default:
break; break;
@ -688,30 +691,31 @@ void MainMenu::showControlTemp()
lcd.setCursor(13,line);lcd.print(ftostr3(intround(degTargetHotend0()))); lcd.setCursor(13,line);lcd.print(ftostr3(intround(degTargetHotend0())));
} }
if((activeline==line) ) if((activeline!=line) )
break;
if(CLICKED)
{ {
if(CLICKED) linechanging=!linechanging;
{
linechanging=!linechanging;
if(linechanging)
{
encoderpos=intround(degTargetHotend0());
}
else
{
setTargetHotend0(encoderpos);
encoderpos=activeline*lcdslow;
beepshort();
}
BLOCK;
}
if(linechanging) if(linechanging)
{ {
if(encoderpos<0) encoderpos=0; encoderpos=intround(degTargetHotend0());
if(encoderpos>260) encoderpos=260;
lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));
} }
else
{
setTargetHotend0(encoderpos);
encoderpos=activeline*lcdslow;
beepshort();
}
BLOCK;
} }
if(linechanging)
{
if(encoderpos<0) encoderpos=0;
if(encoderpos>260) encoderpos=260;
lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));
}
}break; }break;
#ifdef AUTOTEMP #ifdef AUTOTEMP
case ItemCT_autotempmin: case ItemCT_autotempmin:
@ -719,33 +723,34 @@ void MainMenu::showControlTemp()
if(force_lcd_update) if(force_lcd_update)
{ {
lcd.setCursor(0,line);lcdprintPGM(" \002 Min:"); lcd.setCursor(0,line);lcdprintPGM(" \002 Min:");
lcd.setCursor(13,line);lcd.print(ftostr3(autotemp_max)); lcd.setCursor(13,line);lcd.print(ftostr3(autotemp_min));
} }
if((activeline==line) ) if((activeline!=line) )
break;
if(CLICKED)
{ {
if(CLICKED) linechanging=!linechanging;
{
linechanging=!linechanging;
if(linechanging)
{
encoderpos=intround(autotemp_max);
}
else
{
autotemp_max=encoderpos;
encoderpos=activeline*lcdslow;
beepshort();
}
BLOCK;
}
if(linechanging) if(linechanging)
{ {
if(encoderpos<0) encoderpos=0; encoderpos=intround(autotemp_min);
if(encoderpos>260) encoderpos=260;
lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));
} }
else
{
autotemp_min=encoderpos;
encoderpos=activeline*lcdslow;
beepshort();
}
BLOCK;
} }
if(linechanging)
{
if(encoderpos<0) encoderpos=0;
if(encoderpos>260) encoderpos=260;
lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));
}
}break; }break;
case ItemCT_autotempmax: case ItemCT_autotempmax:
{ {
@ -755,30 +760,31 @@ void MainMenu::showControlTemp()
lcd.setCursor(13,line);lcd.print(ftostr3(autotemp_max)); lcd.setCursor(13,line);lcd.print(ftostr3(autotemp_max));
} }
if((activeline==line) ) if((activeline!=line) )
break;
if(CLICKED)
{ {
if(CLICKED) linechanging=!linechanging;
{
linechanging=!linechanging;
if(linechanging)
{
encoderpos=intround(autotemp_max);
}
else
{
autotemp_max=encoderpos;
encoderpos=activeline*lcdslow;
beepshort();
}
BLOCK;
}
if(linechanging) if(linechanging)
{ {
if(encoderpos<0) encoderpos=0; encoderpos=intround(autotemp_max);
if(encoderpos>260) encoderpos=260;
lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));
} }
else
{
autotemp_max=encoderpos;
encoderpos=activeline*lcdslow;
beepshort();
}
BLOCK;
} }
if(linechanging)
{
if(encoderpos<0) encoderpos=0;
if(encoderpos>260) encoderpos=260;
lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));
}
}break; }break;
case ItemCT_autotempfact: case ItemCT_autotempfact:
{ {
@ -788,30 +794,31 @@ void MainMenu::showControlTemp()
lcd.setCursor(13,line);lcd.print(ftostr32(autotemp_factor)); lcd.setCursor(13,line);lcd.print(ftostr32(autotemp_factor));
} }
if((activeline==line) ) if((activeline!=line) )
break;
if(CLICKED)
{ {
if(CLICKED) linechanging=!linechanging;
{
linechanging=!linechanging;
if(linechanging)
{
encoderpos=intround(autotemp_factor*100);
}
else
{
autotemp_max=encoderpos;
encoderpos=activeline*lcdslow;
beepshort();
}
BLOCK;
}
if(linechanging) if(linechanging)
{ {
if(encoderpos<0) encoderpos=0; encoderpos=intround(autotemp_factor*100);
if(encoderpos>99) encoderpos=99;
lcd.setCursor(13,line);lcd.print(ftostr32(encoderpos/100.));
} }
else
{
autotemp_max=encoderpos;
encoderpos=activeline*lcdslow;
beepshort();
}
BLOCK;
} }
if(linechanging)
{
if(encoderpos<0) encoderpos=0;
if(encoderpos>99) encoderpos=99;
lcd.setCursor(13,line);lcd.print(ftostr32(encoderpos/100.));
}
}break; }break;
case ItemCT_autotempactive: case ItemCT_autotempactive:
{ {
@ -819,20 +826,26 @@ void MainMenu::showControlTemp()
{ {
lcd.setCursor(0,line);lcdprintPGM(" Autotemp:"); lcd.setCursor(0,line);lcdprintPGM(" Autotemp:");
lcd.setCursor(13,line); lcd.setCursor(13,line);
if(autotemp_enabled) if(autotemp_enabled)
lcdprintPGM("On"); lcdprintPGM("On");
else else
lcdprintPGM("Off"); lcdprintPGM("Off");
} }
if((activeline==line) ) if((activeline!=line) )
break;
if(CLICKED)
{ {
if(CLICKED) autotemp_enabled=!autotemp_enabled;
{ lcd.setCursor(13,line);
autotemp_enabled=!autotemp_enabled; if(autotemp_enabled)
BLOCK; lcdprintPGM("On ");
} else
lcdprintPGM("Off");
BLOCK;
} }
}break; }break;
#endif //autotemp #endif //autotemp
case ItemCT_fan: case ItemCT_fan:
@ -843,31 +856,32 @@ void MainMenu::showControlTemp()
lcd.setCursor(13,line);lcd.print(ftostr3(fanpwm)); lcd.setCursor(13,line);lcd.print(ftostr3(fanpwm));
} }
if((activeline==line) ) if((activeline!=line) )
break;
if(CLICKED) //nalogWrite(FAN_PIN, fanpwm);
{ {
if(CLICKED) //nalogWrite(FAN_PIN, fanpwm); linechanging=!linechanging;
{
linechanging=!linechanging;
if(linechanging)
{
encoderpos=fanpwm;
}
else
{
encoderpos=activeline*lcdslow;
beepshort();
}
BLOCK;
}
if(linechanging) if(linechanging)
{ {
if(encoderpos<0) encoderpos=0; encoderpos=fanpwm;
if(encoderpos>255) encoderpos=255;
fanpwm=encoderpos;
analogWrite(FAN_PIN, fanpwm);
lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));
} }
else
{
encoderpos=activeline*lcdslow;
beepshort();
}
BLOCK;
} }
if(linechanging)
{
if(encoderpos<0) encoderpos=0;
if(encoderpos>255) encoderpos=255;
fanpwm=encoderpos;
analogWrite(FAN_PIN, fanpwm);
lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));
}
}break; }break;
case ItemCT_PID_P: case ItemCT_PID_P:
{ {
@ -877,31 +891,32 @@ void MainMenu::showControlTemp()
lcd.setCursor(13,line);lcd.print(itostr4(Kp)); lcd.setCursor(13,line);lcd.print(itostr4(Kp));
} }
if((activeline==line) ) if((activeline!=line) )
break;
if(CLICKED)
{ {
if(CLICKED) linechanging=!linechanging;
{
linechanging=!linechanging;
if(linechanging)
{
encoderpos=(int)Kp;
}
else
{
Kp= encoderpos;
encoderpos=activeline*lcdslow;
}
BLOCK;
beepshort();
}
if(linechanging) if(linechanging)
{ {
if(encoderpos<1) encoderpos=1; encoderpos=(int)Kp;
if(encoderpos>9990) encoderpos=9990;
lcd.setCursor(13,line);lcd.print(itostr4(encoderpos));
} }
else
{
Kp= encoderpos;
encoderpos=activeline*lcdslow;
}
BLOCK;
beepshort();
} }
if(linechanging)
{
if(encoderpos<1) encoderpos=1;
if(encoderpos>9990) encoderpos=9990;
lcd.setCursor(13,line);lcd.print(itostr4(encoderpos));
}
}break; }break;
case ItemCT_PID_I: case ItemCT_PID_I:
{ {
@ -911,31 +926,32 @@ void MainMenu::showControlTemp()
lcd.setCursor(13,line);lcd.print(ftostr51(Ki/PID_dT)); lcd.setCursor(13,line);lcd.print(ftostr51(Ki/PID_dT));
} }
if((activeline==line) ) if((activeline!=line) )
break;
if(CLICKED)
{ {
if(CLICKED) linechanging=!linechanging;
{
linechanging=!linechanging;
if(linechanging)
{
encoderpos=(int)(Ki*10/PID_dT);
}
else
{
Ki= encoderpos/10.*PID_dT;
encoderpos=activeline*lcdslow;
}
BLOCK;
beepshort();
}
if(linechanging) if(linechanging)
{ {
if(encoderpos<0) encoderpos=0; encoderpos=(int)(Ki*10/PID_dT);
if(encoderpos>9990) encoderpos=9990;
lcd.setCursor(13,line);lcd.print(ftostr51(encoderpos/10.));
} }
else
{
Ki= encoderpos/10.*PID_dT;
encoderpos=activeline*lcdslow;
}
BLOCK;
beepshort();
} }
if(linechanging)
{
if(encoderpos<0) encoderpos=0;
if(encoderpos>9990) encoderpos=9990;
lcd.setCursor(13,line);lcd.print(ftostr51(encoderpos/10.));
}
}break; }break;
case ItemCT_PID_D: case ItemCT_PID_D:
{ {
@ -945,31 +961,33 @@ void MainMenu::showControlTemp()
lcd.setCursor(13,line);lcd.print(itostr4(Kd*PID_dT)); lcd.setCursor(13,line);lcd.print(itostr4(Kd*PID_dT));
} }
if((activeline==line) ) if((activeline!=line) )
break;
if(CLICKED)
{ {
if(CLICKED) linechanging=!linechanging;
{
linechanging=!linechanging;
if(linechanging)
{
encoderpos=(int)(Kd/5./PID_dT);
}
else
{
Kd= encoderpos;
encoderpos=activeline*lcdslow;
}
BLOCK;
beepshort();
}
if(linechanging) if(linechanging)
{ {
if(encoderpos<0) encoderpos=0; encoderpos=(int)(Kd/5./PID_dT);
if(encoderpos>9990) encoderpos=9990;
lcd.setCursor(13,line);lcd.print(itostr4(encoderpos));
} }
else
{
Kd= encoderpos;
encoderpos=activeline*lcdslow;
}
BLOCK;
beepshort();
} }
if(linechanging)
{
if(encoderpos<0) encoderpos=0;
if(encoderpos>9990) encoderpos=9990;
lcd.setCursor(13,line);lcd.print(itostr4(encoderpos));
}
}break; }break;
case ItemCT_PID_C: case ItemCT_PID_C:
#ifdef PID_ADD_EXTRUSION_RATE #ifdef PID_ADD_EXTRUSION_RATE
@ -980,31 +998,32 @@ void MainMenu::showControlTemp()
lcd.setCursor(13,line);lcd.print(itostr3(Kc)); lcd.setCursor(13,line);lcd.print(itostr3(Kc));
} }
if((activeline==line) ) if((activeline!=line) )
break;
if(CLICKED)
{ {
if(CLICKED) linechanging=!linechanging;
{
linechanging=!linechanging;
if(linechanging)
{
encoderpos=(int)Kc;
}
else
{
Kc= encoderpos;
encoderpos=activeline*lcdslow;
}
BLOCK;
beepshort();
}
if(linechanging) if(linechanging)
{ {
if(encoderpos<0) encoderpos=0; encoderpos=(int)Kc;
if(encoderpos>990) encoderpos=990;
lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));
} }
else
{
Kc= encoderpos;
encoderpos=activeline*lcdslow;
}
BLOCK;
beepshort();
} }
if(linechanging)
{
if(encoderpos<0) encoderpos=0;
if(encoderpos>990) encoderpos=990;
lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));
}
} }
#endif #endif
break; break;
@ -1051,30 +1070,31 @@ void MainMenu::showControlMotion()
lcd.setCursor(13,line);lcd.print(itostr3(acceleration/100));lcdprintPGM("00"); lcd.setCursor(13,line);lcd.print(itostr3(acceleration/100));lcdprintPGM("00");
} }
if((activeline==line) ) if((activeline!=line) )
break;
if(CLICKED)
{ {
if(CLICKED) linechanging=!linechanging;
{
linechanging=!linechanging;
if(linechanging)
{
encoderpos=(int)acceleration/100;
}
else
{
acceleration= encoderpos*100;
encoderpos=activeline*lcdslow;
}
BLOCK;
beepshort();
}
if(linechanging) if(linechanging)
{ {
if(encoderpos<5) encoderpos=5; encoderpos=(int)acceleration/100;
if(encoderpos>990) encoderpos=990;
lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));lcdprintPGM("00");
} }
else
{
acceleration= encoderpos*100;
encoderpos=activeline*lcdslow;
}
BLOCK;
beepshort();
} }
if(linechanging)
{
if(encoderpos<5) encoderpos=5;
if(encoderpos>990) encoderpos=990;
lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));lcdprintPGM("00");
}
}break; }break;
case ItemCM_xyjerk: //max_xy_jerk case ItemCM_xyjerk: //max_xy_jerk
{ {
@ -1084,31 +1104,32 @@ void MainMenu::showControlMotion()
lcd.setCursor(13,line);lcd.print(itostr3(max_xy_jerk)); lcd.setCursor(13,line);lcd.print(itostr3(max_xy_jerk));
} }
if((activeline==line) ) if((activeline!=line) )
break;
if(CLICKED)
{ {
if(CLICKED) linechanging=!linechanging;
{
linechanging=!linechanging;
if(linechanging)
{
encoderpos=(int)max_xy_jerk;
}
else
{
max_xy_jerk= encoderpos;
encoderpos=activeline*lcdslow;
}
BLOCK;
beepshort();
}
if(linechanging) if(linechanging)
{ {
if(encoderpos<1) encoderpos=1; encoderpos=(int)max_xy_jerk;
if(encoderpos>990) encoderpos=990;
lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));
} }
else
{
max_xy_jerk= encoderpos;
encoderpos=activeline*lcdslow;
}
BLOCK;
beepshort();
} }
if(linechanging)
{
if(encoderpos<1) encoderpos=1;
if(encoderpos>990) encoderpos=990;
lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));
}
}break; }break;
case ItemCM_vmaxx: case ItemCM_vmaxx:
@ -1126,31 +1147,32 @@ void MainMenu::showControlMotion()
lcd.setCursor(13,line);lcd.print(itostr3(max_feedrate[i-ItemCM_vmaxx])); lcd.setCursor(13,line);lcd.print(itostr3(max_feedrate[i-ItemCM_vmaxx]));
} }
if((activeline==line) ) if((activeline!=line) )
break;
if(CLICKED)
{ {
if(CLICKED) linechanging=!linechanging;
{
linechanging=!linechanging;
if(linechanging)
{
encoderpos=(int)max_feedrate[i-ItemCM_vmaxx];
}
else
{
max_feedrate[i-ItemCM_vmaxx]= encoderpos;
encoderpos=activeline*lcdslow;
}
BLOCK;
beepshort();
}
if(linechanging) if(linechanging)
{ {
if(encoderpos<1) encoderpos=1; encoderpos=(int)max_feedrate[i-ItemCM_vmaxx];
if(encoderpos>990) encoderpos=990;
lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));
} }
else
{
max_feedrate[i-ItemCM_vmaxx]= encoderpos;
encoderpos=activeline*lcdslow;
}
BLOCK;
beepshort();
} }
if(linechanging)
{
if(encoderpos<1) encoderpos=1;
if(encoderpos>990) encoderpos=990;
lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));
}
}break; }break;
case ItemCM_vmin: case ItemCM_vmin:
@ -1161,31 +1183,32 @@ void MainMenu::showControlMotion()
lcd.setCursor(13,line);lcd.print(itostr3(minimumfeedrate)); lcd.setCursor(13,line);lcd.print(itostr3(minimumfeedrate));
} }
if((activeline==line) ) if((activeline!=line) )
break;
if(CLICKED)
{ {
if(CLICKED) linechanging=!linechanging;
{
linechanging=!linechanging;
if(linechanging)
{
encoderpos=(int)(minimumfeedrate);
}
else
{
minimumfeedrate= encoderpos;
encoderpos=activeline*lcdslow;
}
BLOCK;
beepshort();
}
if(linechanging) if(linechanging)
{ {
if(encoderpos<0) encoderpos=0; encoderpos=(int)(minimumfeedrate);
if(encoderpos>990) encoderpos=990;
lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));
} }
else
{
minimumfeedrate= encoderpos;
encoderpos=activeline*lcdslow;
}
BLOCK;
beepshort();
} }
if(linechanging)
{
if(encoderpos<0) encoderpos=0;
if(encoderpos>990) encoderpos=990;
lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));
}
}break; }break;
case ItemCM_vtravmin: case ItemCM_vtravmin:
{ {
@ -1195,31 +1218,32 @@ void MainMenu::showControlMotion()
lcd.setCursor(13,line);lcd.print(itostr3(mintravelfeedrate)); lcd.setCursor(13,line);lcd.print(itostr3(mintravelfeedrate));
} }
if((activeline==line) ) if((activeline!=line) )
break;
if(CLICKED)
{ {
if(CLICKED) linechanging=!linechanging;
{
linechanging=!linechanging;
if(linechanging)
{
encoderpos=(int)mintravelfeedrate;
}
else
{
mintravelfeedrate= encoderpos;
encoderpos=activeline*lcdslow;
}
BLOCK;
beepshort();
}
if(linechanging) if(linechanging)
{ {
if(encoderpos<0) encoderpos=0; encoderpos=(int)mintravelfeedrate;
if(encoderpos>990) encoderpos=990;
lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));
} }
else
{
mintravelfeedrate= encoderpos;
encoderpos=activeline*lcdslow;
}
BLOCK;
beepshort();
} }
if(linechanging)
{
if(encoderpos<0) encoderpos=0;
if(encoderpos>990) encoderpos=990;
lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));
}
}break; }break;
case ItemCM_amaxx: case ItemCM_amaxx:
@ -1237,30 +1261,31 @@ void MainMenu::showControlMotion()
lcd.setCursor(13,line);lcd.print(itostr3(max_acceleration_units_per_sq_second[i-ItemCM_amaxx]/100));lcdprintPGM("00"); lcd.setCursor(13,line);lcd.print(itostr3(max_acceleration_units_per_sq_second[i-ItemCM_amaxx]/100));lcdprintPGM("00");
} }
if((activeline==line) ) if((activeline!=line) )
break;
if(CLICKED)
{ {
if(CLICKED) linechanging=!linechanging;
{
linechanging=!linechanging;
if(linechanging)
{
encoderpos=(int)max_acceleration_units_per_sq_second[i-ItemCM_amaxx]/100;
}
else
{
max_acceleration_units_per_sq_second[i-ItemCM_amaxx]= encoderpos*100;
encoderpos=activeline*lcdslow;
}
BLOCK;
beepshort();
}
if(linechanging) if(linechanging)
{ {
if(encoderpos<1) encoderpos=1; encoderpos=(int)max_acceleration_units_per_sq_second[i-ItemCM_amaxx]/100;
if(encoderpos>990) encoderpos=990;
lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));lcdprintPGM("00");
} }
else
{
max_acceleration_units_per_sq_second[i-ItemCM_amaxx]= encoderpos*100;
encoderpos=activeline*lcdslow;
}
BLOCK;
beepshort();
} }
if(linechanging)
{
if(encoderpos<1) encoderpos=1;
if(encoderpos>990) encoderpos=990;
lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));lcdprintPGM("00");
}
}break; }break;
case ItemCM_aret://float retract_acceleration = 7000; case ItemCM_aret://float retract_acceleration = 7000;
{ {
@ -1270,31 +1295,32 @@ void MainMenu::showControlMotion()
lcd.setCursor(13,line);lcd.print(ftostr3(retract_acceleration/100));lcdprintPGM("00"); lcd.setCursor(13,line);lcd.print(ftostr3(retract_acceleration/100));lcdprintPGM("00");
} }
if((activeline==line) ) if((activeline!=line) )
break;
if(CLICKED)
{ {
if(CLICKED) linechanging=!linechanging;
{
linechanging=!linechanging;
if(linechanging)
{
encoderpos=(int)retract_acceleration/100;
}
else
{
retract_acceleration= encoderpos*100;
encoderpos=activeline*lcdslow;
}
BLOCK;
beepshort();
}
if(linechanging) if(linechanging)
{ {
if(encoderpos<10) encoderpos=10; encoderpos=(int)retract_acceleration/100;
if(encoderpos>990) encoderpos=990;
lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));lcdprintPGM("00");
} }
else
{
retract_acceleration= encoderpos*100;
encoderpos=activeline*lcdslow;
}
BLOCK;
beepshort();
} }
if(linechanging)
{
if(encoderpos<10) encoderpos=10;
if(encoderpos>990) encoderpos=990;
lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));lcdprintPGM("00");
}
}break; }break;
case ItemCM_esteps://axis_steps_per_unit[i] = code_value(); case ItemCM_esteps://axis_steps_per_unit[i] = code_value();
{ {
@ -1304,34 +1330,35 @@ void MainMenu::showControlMotion()
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) )
break;
if(CLICKED)
{ {
if(CLICKED) linechanging=!linechanging;
{
linechanging=!linechanging;
if(linechanging)
{
encoderpos=(int)axis_steps_per_unit[3];
}
else
{
float factor=float(encoderpos)/float(axis_steps_per_unit[3]);
position[E_AXIS]=lround(position[E_AXIS]*factor);
//current_position[3]*=factor;
axis_steps_per_unit[E_AXIS]= encoderpos;
encoderpos=activeline*lcdslow;
}
BLOCK;
beepshort();
}
if(linechanging) if(linechanging)
{ {
if(encoderpos<5) encoderpos=5; encoderpos=(int)axis_steps_per_unit[3];
if(encoderpos>9999) encoderpos=9999;
lcd.setCursor(13,line);lcd.print(itostr4(encoderpos));
} }
else
{
float factor=float(encoderpos)/float(axis_steps_per_unit[3]);
position[E_AXIS]=lround(position[E_AXIS]*factor);
//current_position[3]*=factor;
axis_steps_per_unit[E_AXIS]= encoderpos;
encoderpos=activeline*lcdslow;
}
BLOCK;
beepshort();
} }
if(linechanging)
{
if(encoderpos<5) encoderpos=5;
if(encoderpos>9999) encoderpos=9999;
lcd.setCursor(13,line);lcd.print(itostr4(encoderpos));
}
}break; }break;
default: default:
break; break;