Merge branch 'Marlin_v1' of https://github.com/ErikZalm/Marlin into Marlin_v1

This commit is contained in:
Daid 2012-05-19 17:38:46 +02:00
commit 7244aa7eb7
9 changed files with 96 additions and 74 deletions

View File

@ -26,6 +26,7 @@
// Gen6 = 5 // Gen6 = 5
// Gen6 deluxe = 51 // Gen6 deluxe = 51
// Sanguinololu 1.2 and above = 62 // Sanguinololu 1.2 and above = 62
// Melzi = 63
// Ultimaker = 7 // Ultimaker = 7
// Teensylu = 8 // Teensylu = 8
// Gen3+ =9 // Gen3+ =9

View File

@ -300,6 +300,8 @@ void setup()
st_init(); // Initialize stepper; st_init(); // Initialize stepper;
wd_init(); wd_init();
setup_photpin(); setup_photpin();
LCD_INIT;
} }
@ -687,7 +689,6 @@ void process_commands()
st_synchronize(); st_synchronize();
for(int8_t i=0; i < NUM_AXIS; i++) { for(int8_t i=0; i < NUM_AXIS; i++) {
if(code_seen(axis_codes[i])) { if(code_seen(axis_codes[i])) {
current_position[i] = code_value()+add_homeing[i];
if(i == E_AXIS) { if(i == E_AXIS) {
current_position[i] = code_value(); current_position[i] = code_value();
plan_set_e_position(current_position[E_AXIS]); plan_set_e_position(current_position[E_AXIS]);
@ -1246,7 +1247,7 @@ void process_commands()
} }
break; break;
case 302: // finish all moves case 302: // allow cold extrudes
{ {
allow_cold_extrudes(true); allow_cold_extrudes(true);
} }

View File

@ -554,7 +554,10 @@
* Sanguinololu pin assignment * Sanguinololu pin assignment
* *
****************************************************************************************/ ****************************************************************************************/
#if MOTHERBOARD == 62 #if MOTHERBOARD == 63
#define MELZI
#endif
#if MOTHERBOARD == 62 || MOTHERBOARD == 63
#undef MOTHERBOARD #undef MOTHERBOARD
#define MOTHERBOARD 6 #define MOTHERBOARD 6
#define SANGUINOLOLU_V_1_2 #define SANGUINOLOLU_V_1_2
@ -589,6 +592,11 @@
#define FAN_PIN -1 #define FAN_PIN -1
#ifdef MELZI
#define LED_PIN 28
#define FAN_PIN 4
#endif
#define PS_ON_PIN -1 #define PS_ON_PIN -1
#define KILL_PIN -1 #define KILL_PIN -1
@ -621,6 +629,10 @@
#define SDPOWER -1 #define SDPOWER -1
#define SDSS 31 #define SDSS 31
#ifdef MELZI
#define SDSS 24
#endif
#endif #endif

View File

@ -556,8 +556,8 @@ void plan_buffer_line(const float &x, const float &y, const float &z, const floa
delta_mm[Y_AXIS] = (target[Y_AXIS]-position[Y_AXIS])/axis_steps_per_unit[Y_AXIS]; delta_mm[Y_AXIS] = (target[Y_AXIS]-position[Y_AXIS])/axis_steps_per_unit[Y_AXIS];
delta_mm[Z_AXIS] = (target[Z_AXIS]-position[Z_AXIS])/axis_steps_per_unit[Z_AXIS]; delta_mm[Z_AXIS] = (target[Z_AXIS]-position[Z_AXIS])/axis_steps_per_unit[Z_AXIS];
delta_mm[E_AXIS] = ((target[E_AXIS]-position[E_AXIS])/axis_steps_per_unit[E_AXIS])*extrudemultiply/100.0; delta_mm[E_AXIS] = ((target[E_AXIS]-position[E_AXIS])/axis_steps_per_unit[E_AXIS])*extrudemultiply/100.0;
if ( block->steps_x == 0 && block->steps_y == 0 && block->steps_z == 0 ) { if ( block->steps_x <=dropsegments && block->steps_y <=dropsegments && block->steps_z <=dropsegments ) {
block->millimeters = abs(delta_mm[E_AXIS]); block->millimeters = fabs(delta_mm[E_AXIS]);
} else { } else {
block->millimeters = sqrt(square(delta_mm[X_AXIS]) + square(delta_mm[Y_AXIS]) + square(delta_mm[Z_AXIS])); block->millimeters = sqrt(square(delta_mm[X_AXIS]) + square(delta_mm[Y_AXIS]) + square(delta_mm[Z_AXIS]));
} }
@ -593,8 +593,8 @@ void plan_buffer_line(const float &x, const float &y, const float &z, const floa
float speed_factor = 1.0; //factor <=1 do decrease speed float speed_factor = 1.0; //factor <=1 do decrease speed
for(int i=0; i < 4; i++) { for(int i=0; i < 4; i++) {
current_speed[i] = delta_mm[i] * inverse_second; current_speed[i] = delta_mm[i] * inverse_second;
if(abs(current_speed[i]) > max_feedrate[i]) if(fabs(current_speed[i]) > max_feedrate[i])
speed_factor = min(speed_factor, max_feedrate[i] / abs(current_speed[i])); speed_factor = min(speed_factor, max_feedrate[i] / fabs(current_speed[i]));
} }
// Max segement time in us. // Max segement time in us.
@ -698,25 +698,25 @@ void plan_buffer_line(const float &x, const float &y, const float &z, const floa
#endif #endif
// Start with a safe speed // Start with a safe speed
float vmax_junction = max_xy_jerk/2; float vmax_junction = max_xy_jerk/2;
if(abs(current_speed[Z_AXIS]) > max_z_jerk/2) if(fabs(current_speed[Z_AXIS]) > max_z_jerk/2)
vmax_junction = max_z_jerk/2; vmax_junction = max_z_jerk/2;
vmax_junction = min(vmax_junction, block->nominal_speed); vmax_junction = min(vmax_junction, block->nominal_speed);
if(abs(current_speed[E_AXIS]) > max_e_jerk/2) if(fabs(current_speed[E_AXIS]) > max_e_jerk/2)
vmax_junction = min(vmax_junction, max_e_jerk/2); vmax_junction = min(vmax_junction, max_e_jerk/2);
if ((moves_queued > 1) && (previous_nominal_speed > 0.0001)) { if ((moves_queued > 1) && (previous_nominal_speed > 0.0001)) {
float jerk = sqrt(pow((current_speed[X_AXIS]-previous_speed[X_AXIS]), 2)+pow((current_speed[Y_AXIS]-previous_speed[Y_AXIS]), 2)); float jerk = sqrt(pow((current_speed[X_AXIS]-previous_speed[X_AXIS]), 2)+pow((current_speed[Y_AXIS]-previous_speed[Y_AXIS]), 2));
if((abs(previous_speed[X_AXIS]) > 0.0001) || (abs(previous_speed[Y_AXIS]) > 0.0001)) { if((fabs(previous_speed[X_AXIS]) > 0.0001) || (fabs(previous_speed[Y_AXIS]) > 0.0001)) {
vmax_junction = block->nominal_speed; vmax_junction = block->nominal_speed;
} }
if (jerk > max_xy_jerk) { if (jerk > max_xy_jerk) {
vmax_junction *= (max_xy_jerk/jerk); vmax_junction *= (max_xy_jerk/jerk);
} }
if(abs(current_speed[Z_AXIS] - previous_speed[Z_AXIS]) > max_z_jerk) { if(fabs(current_speed[Z_AXIS] - previous_speed[Z_AXIS]) > max_z_jerk) {
vmax_junction *= (max_z_jerk/abs(current_speed[Z_AXIS] - previous_speed[Z_AXIS])); vmax_junction *= (max_z_jerk/fabs(current_speed[Z_AXIS] - previous_speed[Z_AXIS]));
} }
if(abs(current_speed[E_AXIS] - previous_speed[E_AXIS]) > max_e_jerk) { if(fabs(current_speed[E_AXIS] - previous_speed[E_AXIS]) > max_e_jerk) {
vmax_junction *= (max_e_jerk/abs(current_speed[E_AXIS] - previous_speed[E_AXIS])); vmax_junction *= (max_e_jerk/fabs(current_speed[E_AXIS] - previous_speed[E_AXIS]));
} }
} }
block->max_entry_speed = vmax_junction; block->max_entry_speed = vmax_junction;

View File

@ -45,10 +45,10 @@ typedef struct {
#endif #endif
// Fields used by the motion planner to manage acceleration // Fields used by the motion planner to manage acceleration
// float speed_x, speed_y, speed_z, speed_e; // Nominal mm/minute for each axis // float speed_x, speed_y, speed_z, speed_e; // Nominal mm/sec for each axis
float nominal_speed; // The nominal speed for this block in mm/min float nominal_speed; // The nominal speed for this block in mm/sec
float entry_speed; // Entry speed at previous-current junction in mm/min float entry_speed; // Entry speed at previous-current junction in mm/sec
float max_entry_speed; // Maximum allowable junction entry speed in mm/min float max_entry_speed; // Maximum allowable junction entry speed in mm/sec
float millimeters; // The total travel of this block in mm float millimeters; // The total travel of this block in mm
float acceleration; // acceleration mm/sec^2 float acceleration; // acceleration mm/sec^2
unsigned char recalculate_flag; // Planner flag to recalculate trapezoids on entry junction unsigned char recalculate_flag; // Planner flag to recalculate trapezoids on entry junction

View File

@ -134,8 +134,8 @@ void PID_autotune(float temp)
long t_high; long t_high;
long t_low; long t_low;
long bias=127; long bias=PID_MAX/2;
long d = 127; long d = PID_MAX/2;
float Ku, Tu; float Ku, Tu;
float Kp, Ki, Kd; float Kp, Ki, Kd;
float max, min; float max, min;
@ -144,7 +144,7 @@ void PID_autotune(float temp)
disable_heater(); // switch off all heaters. disable_heater(); // switch off all heaters.
soft_pwm[0] = 255>>1; soft_pwm[0] = PID_MAX/2;
for(;;) { for(;;) {
@ -172,8 +172,8 @@ void PID_autotune(float temp)
t_low=t2 - t1; t_low=t2 - t1;
if(cycles > 0) { if(cycles > 0) {
bias += (d*(t_high - t_low))/(t_low + t_high); bias += (d*(t_high - t_low))/(t_low + t_high);
bias = constrain(bias, 20 ,235); bias = constrain(bias, 20 ,PID_MAX-20);
if(bias > 127) d = 254 - bias; if(bias > PID_MAX/2) d = PID_MAX - 1 - bias;
else d = bias; else d = bias;
SERIAL_PROTOCOLPGM(" bias: "); SERIAL_PROTOCOL(bias); SERIAL_PROTOCOLPGM(" bias: "); SERIAL_PROTOCOL(bias);

View File

@ -7,6 +7,7 @@
void lcd_init(); void lcd_init();
void lcd_status(const char* message); void lcd_status(const char* message);
void beep(); void beep();
void buttons_init();
void buttons_check(); void buttons_check();
#define LCD_UPDATE_INTERVAL 100 #define LCD_UPDATE_INTERVAL 100
@ -69,7 +70,7 @@
void showAxisMove(); void showAxisMove();
void showSD(); void showSD();
bool force_lcd_update; bool force_lcd_update;
int lastencoderpos; long lastencoderpos;
int8_t lineoffset; int8_t lineoffset;
int8_t lastlineoffset; int8_t lastlineoffset;
@ -78,11 +79,11 @@
bool tune; bool tune;
private: private:
FORCE_INLINE void updateActiveLines(const uint8_t &maxlines,volatile int &encoderpos) FORCE_INLINE void updateActiveLines(const uint8_t &maxlines,volatile long &encoderpos)
{ {
if(linechanging) return; // an item is changint its value, do not switch lines hence if(linechanging) return; // an item is changint its value, do not switch lines hence
lastlineoffset=lineoffset; lastlineoffset=lineoffset;
int curencoderpos=encoderpos; long curencoderpos=encoderpos;
force_lcd_update=false; force_lcd_update=false;
if( (abs(curencoderpos-lastencoderpos)<lcdslow) ) if( (abs(curencoderpos-lastencoderpos)<lcdslow) )
{ {
@ -134,11 +135,12 @@
char *ftostr3(const float &x); char *ftostr3(const float &x);
#define LCD_INIT lcd_init();
#define LCD_MESSAGE(x) lcd_status(x); #define LCD_MESSAGE(x) lcd_status(x);
#define LCD_MESSAGEPGM(x) lcd_statuspgm(MYPGM(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_INIT
#define LCD_STATUS #define LCD_STATUS
#define LCD_MESSAGE(x) #define LCD_MESSAGE(x)
#define LCD_MESSAGEPGM(x) #define LCD_MESSAGEPGM(x)

View File

@ -3,6 +3,9 @@
#include "ultralcd.h" #include "ultralcd.h"
#ifdef ULTRA_LCD #ifdef ULTRA_LCD
#include "Marlin.h" #include "Marlin.h"
#include "language.h"
#include "temperature.h"
#include "EEPROMwrite.h"
#include <LiquidCrystal.h> #include <LiquidCrystal.h>
//=========================================================================== //===========================================================================
//=============================imported variables============================ //=============================imported variables============================
@ -15,6 +18,7 @@ extern volatile int extrudemultiply;
extern long position[4]; extern long position[4];
#ifdef SDSUPPORT #ifdef SDSUPPORT
#include "cardreader.h"
extern CardReader card; extern CardReader card;
#endif #endif
@ -22,7 +26,7 @@ extern CardReader card;
//=============================public variables============================ //=============================public variables============================
//=========================================================================== //===========================================================================
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; long encoderpos=0;
short lastenc=0; short lastenc=0;
@ -97,6 +101,9 @@ FORCE_INLINE void clear()
void lcd_init() void lcd_init()
{ {
//beep(); //beep();
#ifdef ULTIPANEL
buttons_init();
#endif
byte Degree[8] = byte Degree[8] =
{ {
@ -304,10 +311,6 @@ MainMenu::MainMenu()
displayStartingRow=0; displayStartingRow=0;
activeline=0; activeline=0;
force_lcd_update=true; force_lcd_update=true;
#ifdef ULTIPANEL
buttons_init();
#endif
lcd_init();
linechanging=false; linechanging=false;
tune=false; tune=false;
} }
@ -884,7 +887,7 @@ void MainMenu::showTune()
if(force_lcd_update) if(force_lcd_update)
{ {
lcd.setCursor(0,line);lcdprintPGM(MSG_FLOW); lcd.setCursor(0,line);lcdprintPGM(MSG_FLOW);
lcd.setCursor(13,line);lcd.print(itostr4(axis_steps_per_unit[3])); lcd.setCursor(13,line);lcd.print(ftostr52(axis_steps_per_unit[E_AXIS]));
} }
if((activeline!=line) ) if((activeline!=line) )
@ -895,14 +898,14 @@ void MainMenu::showTune()
linechanging=!linechanging; linechanging=!linechanging;
if(linechanging) if(linechanging)
{ {
encoderpos=(int)axis_steps_per_unit[3]; encoderpos=(long)(axis_steps_per_unit[E_AXIS]*100.0);
} }
else else
{ {
float factor=float(encoderpos)/float(axis_steps_per_unit[3]); float factor=float(encoderpos)/100.0/float(axis_steps_per_unit[E_AXIS]);
position[E_AXIS]=lround(position[E_AXIS]*factor); position[E_AXIS]=lround(position[E_AXIS]*factor);
//current_position[3]*=factor; //current_position[E_AXIS]*=factor;
axis_steps_per_unit[E_AXIS]= encoderpos; axis_steps_per_unit[E_AXIS]= encoderpos/100.0;
encoderpos=activeline*lcdslow; encoderpos=activeline*lcdslow;
} }
@ -912,8 +915,8 @@ void MainMenu::showTune()
if(linechanging) if(linechanging)
{ {
if(encoderpos<5) encoderpos=5; if(encoderpos<5) encoderpos=5;
if(encoderpos>9999) encoderpos=9999; if(encoderpos>999999) encoderpos=999999;
lcd.setCursor(13,line);lcd.print(itostr4(encoderpos)); lcd.setCursor(13,line);lcd.print(ftostr52(encoderpos/100.0));
} }
}break; }break;
@ -1296,7 +1299,7 @@ void MainMenu::showControlTemp()
linechanging=!linechanging; linechanging=!linechanging;
if(linechanging) if(linechanging)
{ {
encoderpos=(int)Kp; encoderpos=(long)Kp;
} }
else else
{ {
@ -1331,7 +1334,7 @@ void MainMenu::showControlTemp()
linechanging=!linechanging; linechanging=!linechanging;
if(linechanging) if(linechanging)
{ {
encoderpos=(int)(Ki*10/PID_dT); encoderpos=(long)(Ki*10/PID_dT);
} }
else else
{ {
@ -1367,7 +1370,7 @@ void MainMenu::showControlTemp()
linechanging=!linechanging; linechanging=!linechanging;
if(linechanging) if(linechanging)
{ {
encoderpos=(int)(Kd/5./PID_dT); encoderpos=(long)(Kd/5./PID_dT);
} }
else else
{ {
@ -1403,7 +1406,7 @@ void MainMenu::showControlTemp()
linechanging=!linechanging; linechanging=!linechanging;
if(linechanging) if(linechanging)
{ {
encoderpos=(int)Kc; encoderpos=(long)Kc;
} }
else else
{ {
@ -1476,7 +1479,7 @@ void MainMenu::showControlMotion()
linechanging=!linechanging; linechanging=!linechanging;
if(linechanging) if(linechanging)
{ {
encoderpos=(int)acceleration/100; encoderpos=(long)acceleration/100;
} }
else else
{ {
@ -1510,7 +1513,7 @@ void MainMenu::showControlMotion()
linechanging=!linechanging; linechanging=!linechanging;
if(linechanging) if(linechanging)
{ {
encoderpos=(int)max_xy_jerk; encoderpos=(long)max_xy_jerk;
} }
else else
{ {
@ -1553,7 +1556,7 @@ void MainMenu::showControlMotion()
linechanging=!linechanging; linechanging=!linechanging;
if(linechanging) if(linechanging)
{ {
encoderpos=(int)max_feedrate[i-ItemCM_vmaxx]; encoderpos=(long)max_feedrate[i-ItemCM_vmaxx];
} }
else else
{ {
@ -1589,7 +1592,7 @@ void MainMenu::showControlMotion()
linechanging=!linechanging; linechanging=!linechanging;
if(linechanging) if(linechanging)
{ {
encoderpos=(int)(minimumfeedrate); encoderpos=(long)(minimumfeedrate);
} }
else else
{ {
@ -1624,7 +1627,7 @@ void MainMenu::showControlMotion()
linechanging=!linechanging; linechanging=!linechanging;
if(linechanging) if(linechanging)
{ {
encoderpos=(int)mintravelfeedrate; encoderpos=(long)mintravelfeedrate;
} }
else else
{ {
@ -1667,7 +1670,7 @@ void MainMenu::showControlMotion()
linechanging=!linechanging; linechanging=!linechanging;
if(linechanging) if(linechanging)
{ {
encoderpos=(int)max_acceleration_units_per_sq_second[i-ItemCM_amaxx]/100; encoderpos=(long)max_acceleration_units_per_sq_second[i-ItemCM_amaxx]/100;
} }
else else
{ {
@ -1701,7 +1704,7 @@ void MainMenu::showControlMotion()
linechanging=!linechanging; linechanging=!linechanging;
if(linechanging) if(linechanging)
{ {
encoderpos=(int)retract_acceleration/100; encoderpos=(long)retract_acceleration/100;
} }
else else
{ {
@ -1725,7 +1728,7 @@ void MainMenu::showControlMotion()
if(force_lcd_update) if(force_lcd_update)
{ {
lcd.setCursor(0,line);lcdprintPGM(MSG_XSTEPS); lcd.setCursor(0,line);lcdprintPGM(MSG_XSTEPS);
lcd.setCursor(11,line);lcd.print(ftostr52(axis_steps_per_unit[0])); lcd.setCursor(11,line);lcd.print(ftostr52(axis_steps_per_unit[X_AXIS]));
} }
if((activeline!=line) ) if((activeline!=line) )
@ -1736,13 +1739,13 @@ void MainMenu::showControlMotion()
linechanging=!linechanging; linechanging=!linechanging;
if(linechanging) if(linechanging)
{ {
encoderpos=(int)(axis_steps_per_unit[0]*100.0); encoderpos=(long)(axis_steps_per_unit[X_AXIS]*100.0);
} }
else else
{ {
float factor=float(encoderpos)/100.0/float(axis_steps_per_unit[0]); float factor=float(encoderpos)/100.0/float(axis_steps_per_unit[X_AXIS]);
position[X_AXIS]=lround(position[X_AXIS]*factor); position[X_AXIS]=lround(position[X_AXIS]*factor);
//current_position[3]*=factor; //current_position[X_AXIS]*=factor;
axis_steps_per_unit[X_AXIS]= encoderpos/100.0; axis_steps_per_unit[X_AXIS]= encoderpos/100.0;
encoderpos=activeline*lcdslow; encoderpos=activeline*lcdslow;
} }
@ -1752,7 +1755,7 @@ void MainMenu::showControlMotion()
if(linechanging) if(linechanging)
{ {
if(encoderpos<5) encoderpos=5; if(encoderpos<5) encoderpos=5;
if(encoderpos>32000) encoderpos=32000;//TODO: This is a problem, encoderpos is 16bit, but steps_per_unit for e can be wel over 800 if(encoderpos>999999) encoderpos=999999;
lcd.setCursor(11,line);lcd.print(ftostr52(encoderpos/100.0)); lcd.setCursor(11,line);lcd.print(ftostr52(encoderpos/100.0));
} }
@ -1762,7 +1765,7 @@ void MainMenu::showControlMotion()
if(force_lcd_update) if(force_lcd_update)
{ {
lcd.setCursor(0,line);lcdprintPGM(MSG_YSTEPS); lcd.setCursor(0,line);lcdprintPGM(MSG_YSTEPS);
lcd.setCursor(11,line);lcd.print(ftostr52(axis_steps_per_unit[1])); lcd.setCursor(11,line);lcd.print(ftostr52(axis_steps_per_unit[Y_AXIS]));
} }
if((activeline!=line) ) if((activeline!=line) )
@ -1773,13 +1776,13 @@ void MainMenu::showControlMotion()
linechanging=!linechanging; linechanging=!linechanging;
if(linechanging) if(linechanging)
{ {
encoderpos=(int)(axis_steps_per_unit[1]*100.0); encoderpos=(long)(axis_steps_per_unit[Y_AXIS]*100.0);
} }
else else
{ {
float factor=float(encoderpos)/100.0/float(axis_steps_per_unit[1]); float factor=float(encoderpos)/100.0/float(axis_steps_per_unit[Y_AXIS]);
position[Y_AXIS]=lround(position[Y_AXIS]*factor); position[Y_AXIS]=lround(position[Y_AXIS]*factor);
//current_position[3]*=factor; //current_position[Y_AXIS]*=factor;
axis_steps_per_unit[Y_AXIS]= encoderpos/100.0; axis_steps_per_unit[Y_AXIS]= encoderpos/100.0;
encoderpos=activeline*lcdslow; encoderpos=activeline*lcdslow;
@ -1790,7 +1793,7 @@ void MainMenu::showControlMotion()
if(linechanging) if(linechanging)
{ {
if(encoderpos<5) encoderpos=5; if(encoderpos<5) encoderpos=5;
if(encoderpos>9999) encoderpos=9999; if(encoderpos>999999) encoderpos=999999;
lcd.setCursor(11,line);lcd.print(ftostr52(encoderpos/100.0)); lcd.setCursor(11,line);lcd.print(ftostr52(encoderpos/100.0));
} }
@ -1800,7 +1803,7 @@ void MainMenu::showControlMotion()
if(force_lcd_update) if(force_lcd_update)
{ {
lcd.setCursor(0,line);lcdprintPGM(MSG_ZSTEPS); lcd.setCursor(0,line);lcdprintPGM(MSG_ZSTEPS);
lcd.setCursor(11,line);lcd.print(ftostr52(axis_steps_per_unit[2])); lcd.setCursor(11,line);lcd.print(ftostr52(axis_steps_per_unit[Z_AXIS]));
} }
if((activeline!=line) ) if((activeline!=line) )
@ -1811,13 +1814,13 @@ void MainMenu::showControlMotion()
linechanging=!linechanging; linechanging=!linechanging;
if(linechanging) if(linechanging)
{ {
encoderpos=(int)(axis_steps_per_unit[2]*100.0); encoderpos=(long)(axis_steps_per_unit[Z_AXIS]*100.0);
} }
else else
{ {
float factor=float(encoderpos)/100.0/float(axis_steps_per_unit[2]); float factor=float(encoderpos)/100.0/float(axis_steps_per_unit[Z_AXIS]);
position[Z_AXIS]=lround(position[Z_AXIS]*factor); position[Z_AXIS]=lround(position[Z_AXIS]*factor);
//current_position[3]*=factor; //current_position[Z_AXIS]*=factor;
axis_steps_per_unit[Z_AXIS]= encoderpos/100.0; axis_steps_per_unit[Z_AXIS]= encoderpos/100.0;
encoderpos=activeline*lcdslow; encoderpos=activeline*lcdslow;
@ -1828,7 +1831,7 @@ void MainMenu::showControlMotion()
if(linechanging) if(linechanging)
{ {
if(encoderpos<5) encoderpos=5; if(encoderpos<5) encoderpos=5;
if(encoderpos>9999) encoderpos=9999; if(encoderpos>999999) encoderpos=999999;
lcd.setCursor(11,line);lcd.print(ftostr52(encoderpos/100.0)); lcd.setCursor(11,line);lcd.print(ftostr52(encoderpos/100.0));
} }
@ -1839,7 +1842,7 @@ void MainMenu::showControlMotion()
if(force_lcd_update) if(force_lcd_update)
{ {
lcd.setCursor(0,line);lcdprintPGM(MSG_ESTEPS); lcd.setCursor(0,line);lcdprintPGM(MSG_ESTEPS);
lcd.setCursor(11,line);lcd.print(ftostr52(axis_steps_per_unit[3])); lcd.setCursor(11,line);lcd.print(ftostr52(axis_steps_per_unit[E_AXIS]));
} }
if((activeline!=line) ) if((activeline!=line) )
@ -1850,13 +1853,13 @@ void MainMenu::showControlMotion()
linechanging=!linechanging; linechanging=!linechanging;
if(linechanging) if(linechanging)
{ {
encoderpos=(int)(axis_steps_per_unit[3]*100.0); encoderpos=(long)(axis_steps_per_unit[E_AXIS]*100.0);
} }
else else
{ {
float factor=float(encoderpos)/100.0/float(axis_steps_per_unit[3]); float factor=float(encoderpos)/100.0/float(axis_steps_per_unit[E_AXIS]);
position[E_AXIS]=lround(position[E_AXIS]*factor); position[E_AXIS]=lround(position[E_AXIS]*factor);
//current_position[3]*=factor; //current_position[E_AXIS]*=factor;
axis_steps_per_unit[E_AXIS]= encoderpos/100.0; axis_steps_per_unit[E_AXIS]= encoderpos/100.0;
encoderpos=activeline*lcdslow; encoderpos=activeline*lcdslow;
@ -1867,7 +1870,7 @@ void MainMenu::showControlMotion()
if(linechanging) if(linechanging)
{ {
if(encoderpos<5) encoderpos=5; if(encoderpos<5) encoderpos=5;
if(encoderpos>9999) encoderpos=9999; if(encoderpos>999999) encoderpos=999999;
lcd.setCursor(11,line);lcd.print(ftostr52(encoderpos/100.0)); lcd.setCursor(11,line);lcd.print(ftostr52(encoderpos/100.0));
} }
@ -2108,9 +2111,10 @@ void MainMenu::showMainMenu()
} }
} }
clearIfNecessary(); clearIfNecessary();
for(int8_t line=0;line<LCD_HEIGHT;line++) uint8_t line=0;
for(int8_t i=lineoffset;i<lineoffset+LCD_HEIGHT;i++)
{ {
switch(line) switch(i)
{ {
case ItemM_watch: case ItemM_watch:
MENUITEM( lcdprintPGM(MSG_WATCH) , BLOCK;status=Main_Status;beepshort(); ) ; MENUITEM( lcdprintPGM(MSG_WATCH) , BLOCK;status=Main_Status;beepshort(); ) ;
@ -2164,6 +2168,7 @@ void MainMenu::showMainMenu()
SERIAL_ERRORLNPGM(MSG_SERIAL_ERROR_MENU_STRUCTURE); SERIAL_ERRORLNPGM(MSG_SERIAL_ERROR_MENU_STRUCTURE);
break; break;
} }
line++;
} }
updateActiveLines(3,encoderpos); updateActiveLines(3,encoderpos);
} }
@ -2381,4 +2386,4 @@ char *ftostr52(const float &x)
#endif //ULTRA_LCD #endif //ULTRA_LCD

View File

@ -161,7 +161,8 @@ Advance:
EEPROM: EEPROM:
* M500 - stores paramters in EEPROM * M500 - stores paramters in EEPROM. This parameters are stored: axis_steps_per_unit, max_feedrate, max_acceleration ,acceleration,retract_acceleration,
minimumfeedrate,mintravelfeedrate,minsegmenttime, jerk velocities, PID
* M501 - reads parameters from EEPROM (if you need reset them after you changed them temporarily). * M501 - reads parameters from EEPROM (if you need reset them after you changed them temporarily).
* M502 - reverts to the default "factory settings". You still need to store them in EEPROM afterwards if you want to. * M502 - reverts to the default "factory settings". You still need to store them in EEPROM afterwards if you want to.
* M503 - print the current settings (from memory not from eeprom) * M503 - print the current settings (from memory not from eeprom)