From 235051253a504fa6f4866bda604f2612df7aad0e Mon Sep 17 00:00:00 2001 From: Bernhard Date: Fri, 25 Nov 2011 22:14:29 +0100 Subject: [PATCH] overworked lcd+eeprom to have only mm/sec and PID including pid_dt --- Marlin/EEPROMwrite.h | 22 +++++++++++----------- Marlin/ultralcd.pde | 24 ++++++++++++------------ 2 files changed, 23 insertions(+), 23 deletions(-) diff --git a/Marlin/EEPROMwrite.h b/Marlin/EEPROMwrite.h index be3210fc95..3d559c0269 100644 --- a/Marlin/EEPROMwrite.h +++ b/Marlin/EEPROMwrite.h @@ -136,10 +136,10 @@ inline void RetrieveSettings(bool def=false) SERIAL_ECHO_START; SERIAL_ECHOLNPGM("Maximum feedrates (mm/s):"); SERIAL_ECHO_START; - SERIAL_ECHOPAIR(" M203 X",max_feedrate[0]/60); - SERIAL_ECHOPAIR(" Y",max_feedrate[1]/60 ); - SERIAL_ECHOPAIR(" Z", max_feedrate[2]/60 ); - SERIAL_ECHOPAIR(" E", max_feedrate[3]/60); + SERIAL_ECHOPAIR(" M203 X",max_feedrate[0]); + SERIAL_ECHOPAIR(" Y",max_feedrate[1] ); + SERIAL_ECHOPAIR(" Z", max_feedrate[2] ); + SERIAL_ECHOPAIR(" E", max_feedrate[3]); SERIAL_ECHOLN(""); SERIAL_ECHO_START; SERIAL_ECHOLNPGM("Maximum Acceleration (mm/s2):"); @@ -158,19 +158,19 @@ inline void RetrieveSettings(bool def=false) SERIAL_ECHO_START; SERIAL_ECHOLNPGM("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)"); SERIAL_ECHO_START; - SERIAL_ECHOPAIR(" M205 S",minimumfeedrate/60 ); - SERIAL_ECHOPAIR(" T" ,mintravelfeedrate/60 ); + SERIAL_ECHOPAIR(" M205 S",minimumfeedrate ); + SERIAL_ECHOPAIR(" T" ,mintravelfeedrate ); SERIAL_ECHOPAIR(" B" ,minsegmenttime ); - SERIAL_ECHOPAIR(" X" ,max_xy_jerk/60 ); - SERIAL_ECHOPAIR(" Z" ,max_z_jerk/60); + SERIAL_ECHOPAIR(" X" ,max_xy_jerk ); + SERIAL_ECHOPAIR(" Z" ,max_z_jerk); SERIAL_ECHOLN(""); #ifdef PIDTEMP SERIAL_ECHO_START; SERIAL_ECHOLNPGM("PID settings:"); SERIAL_ECHO_START; - SERIAL_ECHOPAIR(" M301 P",Kp ); - SERIAL_ECHOPAIR(" I" ,Ki ); - SERIAL_ECHOPAIR(" D" ,Kd); + SERIAL_ECHOPAIR(" M301 P",Kp); + SERIAL_ECHOPAIR(" I" ,Ki/PID_dT); + SERIAL_ECHOPAIR(" D" ,Kd*PID_dT); SERIAL_ECHOLN(""); #endif #endif diff --git a/Marlin/ultralcd.pde b/Marlin/ultralcd.pde index e2a75df10a..e6a16a408e 100644 --- a/Marlin/ultralcd.pde +++ b/Marlin/ultralcd.pde @@ -758,11 +758,11 @@ void MainMenu::showControlTemp() linechanging=!linechanging; if(linechanging) { - encoderpos=(int)Kp/5; + encoderpos=(int)Kp; } else { - Kp= encoderpos*5; + Kp= encoderpos; encoderpos=activeline*lcdslow; } @@ -772,8 +772,8 @@ void MainMenu::showControlTemp() if(linechanging) { if(encoderpos<1) encoderpos=1; - if(encoderpos>9990/5) encoderpos=9990/5; - lcd.setCursor(13,line);lcd.print(itostr4(encoderpos*5)); + if(encoderpos>9990) encoderpos=9990; + lcd.setCursor(13,line);lcd.print(itostr4(encoderpos)); } } }break; @@ -782,7 +782,7 @@ void MainMenu::showControlTemp() if(force_lcd_update) { lcd.setCursor(0,line);lcdprintPGM(" PID-I: "); - lcd.setCursor(13,line);lcd.print(ftostr51(Ki)); + lcd.setCursor(13,line);lcd.print(ftostr51(Ki/PID_dT)); } if((activeline==line) ) @@ -792,11 +792,11 @@ void MainMenu::showControlTemp() linechanging=!linechanging; if(linechanging) { - encoderpos=(int)(Ki*10); + encoderpos=(int)(Ki*10/PID_dT); } else { - Ki= encoderpos/10.; + Ki= encoderpos/10.*PID_dT; encoderpos=activeline*lcdslow; } @@ -816,7 +816,7 @@ void MainMenu::showControlTemp() if(force_lcd_update) { lcd.setCursor(0,line);lcdprintPGM(" PID-D: "); - lcd.setCursor(13,line);lcd.print(itostr4(Kd)); + lcd.setCursor(13,line);lcd.print(itostr4(Kd*PID_dT)); } if((activeline==line) ) @@ -826,11 +826,11 @@ void MainMenu::showControlTemp() linechanging=!linechanging; if(linechanging) { - encoderpos=(int)Kd/5; + encoderpos=(int)(Kd/5./PID_dT); } else { - Kd= encoderpos*5; + Kd= encoderpos; encoderpos=activeline*lcdslow; } @@ -840,8 +840,8 @@ void MainMenu::showControlTemp() if(linechanging) { if(encoderpos<0) encoderpos=0; - if(encoderpos>9990/5) encoderpos=9990/5; - lcd.setCursor(13,line);lcd.print(itostr4(encoderpos*5)); + if(encoderpos>9990) encoderpos=9990; + lcd.setCursor(13,line);lcd.print(itostr4(encoderpos)); } } }break;