refactured temperature.cpp so that there are now abstract functions to access temperatures.

This commit is contained in:
Bernhard Kubicek 2011-11-06 14:03:41 +01:00
parent 0b82465168
commit 2afb7bd4cf
5 changed files with 237 additions and 179 deletions

View file

@ -157,6 +157,7 @@ const int dropsegments=5; //everything with this number of steps will be ignore
//// Experimental watchdog and minimal temp
// 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
/// CURRENTLY NOT IMPLEMENTED AND UNUSEABLE
//#define WATCHPERIOD 5000 //5 seconds
// Actual temperature must be close to target for this long before M109 returns success
@ -245,4 +246,4 @@ const int dropsegments=5; //everything with this number of steps will be ignore
#endif
#endif
#endif

View file

@ -150,10 +150,7 @@ extern float HeaterPower;
const int sensitive_pins[] = SENSITIVE_PINS; // Sensitive pin list for M42
float tt = 0, bt = 0;
#ifdef WATCHPERIOD
int watch_raw = -1000;
unsigned long watchmillis = 0;
#endif //WATCHPERIOD
//Inactivity shutdown variables
unsigned long previous_millis_cmd = 0;
@ -817,28 +814,18 @@ inline void process_commands()
}
break;
case 104: // M104
if (code_seen('S')) target_raw[TEMPSENSOR_HOTEND_0] = temp2analog(code_value());
#ifdef PIDTEMP
pid_setpoint = code_value();
#endif //PIDTEM
#ifdef WATCHPERIOD
if(target_raw[TEMPSENSOR_HOTEND_0] > current_raw[TEMPSENSOR_HOTEND_0]){
watchmillis = max(1,millis());
watch_raw[TEMPSENSOR_HOTEND_0] = current_raw[TEMPSENSOR_HOTEND_0];
}else{
watchmillis = 0;
}
#endif
if (code_seen('S')) setTargetHotend0(code_value());
setWatch();
break;
case 140: // M140 set bed temp
if (code_seen('S')) target_raw[TEMPSENSOR_BED] = temp2analogBed(code_value());
if (code_seen('S')) setTargetBed(code_value());
break;
case 105: // M105
#if (TEMP_0_PIN > -1) || defined (HEATER_USES_AD595)
tt = analog2temp(current_raw[TEMPSENSOR_HOTEND_0]);
tt = degHotend0();
#endif
#if TEMP_1_PIN > -1
bt = analog2tempBed(current_raw[TEMPSENSOR_BED]);
bt = degBed();
#endif
#if (TEMP_0_PIN > -1) || defined (HEATER_USES_AD595)
Serial.print("ok T:");
@ -866,36 +853,27 @@ inline void process_commands()
//break;
case 109: {// M109 - Wait for extruder heater to reach target.
LCD_MESSAGE("Heating...");
if (code_seen('S')) target_raw[TEMPSENSOR_HOTEND_0] = temp2analog(code_value());
#ifdef PIDTEMP
pid_setpoint = code_value();
#endif //PIDTEM
#ifdef WATCHPERIOD
if(target_raw[TEMPSENSOR_HOTEND_0]>current_raw[TEMPSENSOR_HOTEND_0]){
watchmillis = max(1,millis());
watch_raw[TEMPSENSOR_HOTEND_0] = current_raw[TEMPSENSOR_HOTEND_0];
} else {
watchmillis = 0;
}
#endif //WATCHPERIOD
if (code_seen('S')) setTargetHotend0(code_value());
setWatch();
codenum = millis();
/* See if we are heating up or cooling down */
bool target_direction = (current_raw[TEMPSENSOR_HOTEND_0] < target_raw[TEMPSENSOR_HOTEND_0]); // true if heating, false if cooling
bool target_direction = isHeatingHotend0(); // true if heating, false if cooling
#ifdef TEMP_RESIDENCY_TIME
long residencyStart;
residencyStart = -1;
/* continue to loop until we have reached the target temp
_and_ until TEMP_RESIDENCY_TIME hasn't passed since we reached it */
while((target_direction ? (current_raw[TEMPSENSOR_HOTEND_0] < target_raw[TEMPSENSOR_HOTEND_0]) : (current_raw[TEMPSENSOR_HOTEND_0] > target_raw[TEMPSENSOR_HOTEND_0])) ||
while((target_direction ? (isHeatingHotend0()) : (isCoolingHotend0()) ||
(residencyStart > -1 && (millis() - residencyStart) < TEMP_RESIDENCY_TIME*1000) ) {
#else
while ( target_direction ? (current_raw[TEMPSENSOR_HOTEND_0] < target_raw[TEMPSENSOR_HOTEND_0]) : (current_raw[TEMPSENSOR_HOTEND_0] > target_raw[TEMPSENSOR_HOTEND_0]) ) {
while ( target_direction ? (isHeatingHotend0()) : (isCoolingHotend0()) ) {
#endif //TEMP_RESIDENCY_TIME
if( (millis() - codenum) > 1000 ) { //Print Temp Reading every 1 second while heating up/cooling down
Serial.print("T:");
Serial.println( analog2temp(current_raw[TEMPSENSOR_HOTEND_0]) );
Serial.println( degHotend0() );
codenum = millis();
}
manage_heater();
@ -903,9 +881,9 @@ inline void process_commands()
#ifdef TEMP_RESIDENCY_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 */
if ((residencyStart == -1 && target_direction && current_raw[TEMPSENSOR_HOTEND_0] >= target_raw[TEMPSENSOR_HOTEND_0]) ||
(residencyStart == -1 && !target_direction && current_raw[TEMPSENSOR_HOTEND_0] <= target_raw[TEMPSENSOR_HOTEND_0]) ||
(residencyStart > -1 && labs(analog2temp(current_raw[TEMPSENSOR_HOTEND_0]) - analog2temp(target_raw[TEMPSENSOR_HOTEND_0])) > TEMP_HYSTERESIS) ) {
if ((residencyStart == -1 && target_direction && !isHeatingHotend0()) ||
(residencyStart == -1 && !target_direction && !isCoolingHotend0()) ||
(residencyStart > -1 && labs(degHotend0() - degTargetHotend0()) > TEMP_HYSTERESIS) ) {
residencyStart = millis();
}
#endif //TEMP_RESIDENCY_TIME
@ -915,23 +893,23 @@ inline void process_commands()
break;
case 190: // M190 - Wait bed for heater to reach target.
#if TEMP_1_PIN > -1
if (code_seen('S')) target_raw[TEMPSENSOR_BED] = temp2analog(code_value());
codenum = millis();
while(current_raw[TEMPSENSOR_BED] < target_raw[TEMPSENSOR_BED])
{
if( (millis()-codenum) > 1000 ) //Print Temp Reading every 1 second while heating up.
if (code_seen('S')) setTargetBed(code_value());
codenum = millis();
while(isHeatingBed())
{
float tt=analog2temp(current_raw[TEMPSENSOR_HOTEND_0]);
Serial.print("T:");
Serial.println( tt );
Serial.print("ok T:");
Serial.print( tt );
Serial.print(" B:");
Serial.println( analog2temp(current_raw[TEMPSENSOR_BED]) );
codenum = millis();
}
if( (millis()-codenum) > 1000 ) //Print Temp Reading every 1 second while heating up.
{
float tt=degHotend0();
Serial.print("T:");
Serial.println( tt );
Serial.print("ok T:");
Serial.print( tt );
Serial.print(" B:");
Serial.println( degBed() );
codenum = millis();
}
manage_heater();
}
}
#endif
break;
#if FAN_PIN > -1
@ -1331,24 +1309,8 @@ void wd_reset() {
inline void kill()
{
#if TEMP_0_PIN > -1
target_raw[0]=0;
#if HEATER_0_PIN > -1
WRITE(HEATER_0_PIN,LOW);
#endif
#endif
#if TEMP_1_PIN > -1
target_raw[1]=0;
#if HEATER_1_PIN > -1
WRITE(HEATER_1_PIN,LOW);
#endif
#endif
#if TEMP_2_PIN > -1
target_raw[2]=0;
#if HEATER_2_PIN > -1
WRITE(HEATER_2_PIN,LOW);
#endif
#endif
disable_heater();
disable_x();
disable_y();
disable_z();
@ -1369,4 +1331,4 @@ void manage_inactivity(byte debug) {
}
check_axes_activity();
}

View file

@ -37,28 +37,27 @@
#include "streaming.h"
#include "temperature.h"
int target_bed_raw = 0;
int current_bed_raw = 0;
int target_raw[3] = {0, 0, 0};
int current_raw[3] = {0, 0, 0};
unsigned char temp_meas_ready = false;
bool temp_meas_ready = false;
unsigned long previous_millis_heater, previous_millis_bed_heater;
#ifdef PIDTEMP
double temp_iState = 0;
double temp_dState = 0;
double pTerm;
double iTerm;
double dTerm;
float temp_iState = 0;
float temp_dState = 0;
float pTerm;
float iTerm;
float dTerm;
//int output;
double pid_error;
double temp_iState_min;
double temp_iState_max;
double pid_setpoint = 0.0;
double pid_input;
double pid_output;
float pid_error;
float temp_iState_min;
float temp_iState_max;
float pid_setpoint = 0.0;
float pid_input;
float pid_output;
bool pid_reset;
float HeaterPower;
@ -67,6 +66,11 @@ unsigned long previous_millis_heater, previous_millis_bed_heater;
float Kd=DEFAULT_Kd;
float Kc=DEFAULT_Kc;
#endif //PIDTEMP
#ifdef WATCHPERIOD
int watch_raw[3] = {-1000,-1000,-1000};
unsigned long watchmillis = 0;
#endif //WATCHPERIOD
#ifdef HEATER_0_MINTEMP
int minttemp_0 = temp2analog(HEATER_0_MINTEMP);
@ -91,9 +95,9 @@ int bed_maxttemp = temp2analog(BED_MAXTEMP);
void manage_heater()
{
#ifdef USE_WATCHDOG
wd_reset();
#endif
#ifdef USE_WATCHDOG
wd_reset();
#endif
float pid_input;
float pid_output;
@ -330,6 +334,22 @@ void tp_init()
void setWatch()
{
#ifdef WATCHPERIOD
if(isHeatingHotend0())
{
watchmillis = max(1,millis());
watch_raw[TEMPSENSOR_HOTEND_0] = current_raw[TEMPSENSOR_HOTEND_0];
}
else
{
watchmillis = 0;
}
#endif
}
// Timer 0 is shared with millies
ISR(TIMER0_COMPB_vect)
{
@ -500,4 +520,5 @@ ISR(TIMER0_COMPB_vect)
#endif
#endif
}
}
}

View file

@ -22,18 +22,97 @@
#define temperature_h
#include "Marlin.h"
#include "fastio.h"
#ifdef PID_ADD_EXTRUSION_RATE
#include "stepper.h"
#endif
void tp_init();
void manage_heater();
//int temp2analogu(int celsius, const short table[][2], int numtemps);
//float analog2tempu(int raw, const short table[][2], int numtemps);
void tp_init(); //initialise the heating
void manage_heater(); //it is critical that this is called periodically.
enum TempSensor {TEMPSENSOR_HOTEND_0=0,TEMPSENSOR_BED=1, TEMPSENSOR_HOTEND_1=2};
//low leven conversion routines
// do not use this routines and variables outsie of temperature.cpp
int temp2analog(int celsius);
int temp2analogBed(int celsius);
float analog2temp(int raw);
float analog2tempBed(int raw);
extern int target_raw[3];
extern int current_raw[3];
extern float Kp,Ki,Kd,Kc;
#ifdef PIDTEMP
float pid_setpoint = 0.0;
#endif
#ifdef WATCHPERIOD
extern int watch_raw[3] ;
extern unsigned long watchmillis;
#endif
//high level conversion routines, for use outside of temperature.cpp
//inline so that there is no performance decrease.
//deg=degreeCelsius
inline float degHotend0(){ return analog2temp(current_raw[TEMPSENSOR_HOTEND_0]);};
inline float degHotend1(){ return analog2temp(current_raw[TEMPSENSOR_HOTEND_1]);};
inline float degBed() { return analog2tempBed(current_raw[TEMPSENSOR_BED]);};
inline float degTargetHotend0() { return analog2temp(target_raw[TEMPSENSOR_HOTEND_0]);};
inline float degTargetHotend1() { return analog2temp(target_raw[TEMPSENSOR_HOTEND_1]);};
inline float degTargetBed() { return analog2tempBed(target_raw[TEMPSENSOR_BED]);};
inline void setTargetHotend0(float celsius)
{
target_raw[TEMPSENSOR_HOTEND_0]=temp2analog(celsius);
#ifdef PIDTEMP
pid_setpoint = celsius;
#endif //PIDTEMP
};
inline void setTargetHotend1(float celsius) { target_raw[TEMPSENSOR_HOTEND_1]=temp2analog(celsius);};
inline void setTargetBed(float celsius) { target_raw[TEMPSENSOR_BED ]=temp2analogBed(celsius);};
inline bool isHeatingHotend0() {return target_raw[TEMPSENSOR_HOTEND_0] > current_raw[TEMPSENSOR_HOTEND_0];};
inline bool isHeatingHotend1() {return target_raw[TEMPSENSOR_HOTEND_1] > current_raw[TEMPSENSOR_HOTEND_1];};
inline bool isHeatingBed() {return target_raw[TEMPSENSOR_BED] > current_raw[TEMPSENSOR_BED];};
inline bool isCoolingHotend0() {return target_raw[TEMPSENSOR_HOTEND_0] < current_raw[TEMPSENSOR_HOTEND_0];};
inline bool isCoolingHotend1() {return target_raw[TEMPSENSOR_HOTEND_1] < current_raw[TEMPSENSOR_HOTEND_1];};
inline bool isCoolingBed() {return target_raw[TEMPSENSOR_BED] < current_raw[TEMPSENSOR_BED];};
inline void disable_heater()
{
#if TEMP_0_PIN > -1
target_raw[0]=0;
#if HEATER_0_PIN > -1
WRITE(HEATER_0_PIN,LOW);
#endif
#endif
#if TEMP_1_PIN > -1
target_raw[1]=0;
#if HEATER_1_PIN > -1
WRITE(HEATER_1_PIN,LOW);
#endif
#endif
#if TEMP_2_PIN > -1
target_raw[2]=0;
#if HEATER_2_PIN > -1
WRITE(HEATER_2_PIN,LOW);
#endif
#endif
}
void setWatch() {
if(isHeatingHotend0())
{
watchmillis = max(1,millis());
watch_raw[TEMPSENSOR_HOTEND_0] = current_raw[TEMPSENSOR_HOTEND_0];
}
else
{
watchmillis = 0;
}
}
#ifdef HEATER_0_USES_THERMISTOR
#define HEATERSOURCE 1
#endif
@ -41,18 +120,9 @@ float analog2tempBed(int raw);
#define BEDSOURCE 1
#endif
//#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 Kc;
enum {TEMPSENSOR_HOTEND_0=0,TEMPSENSOR_BED=1, TEMPSENSOR_HOTEND_1=2};
extern int target_raw[3];
extern int current_raw[3];
extern double pid_setpoint;
#endif
#endif

View file

@ -12,7 +12,7 @@ LiquidCrystal lcd(LCD_PINS_RS, LCD_PINS_ENABLE, LCD_PINS_D4, LCD_PINS_D5,LCD_PIN
unsigned long previous_millis_lcd=0;
inline int intround(const float &x){return int(0.5+x);}
volatile char buttons=0; //the last checked buttons in a bit array.
int encoderpos=0;
@ -29,13 +29,10 @@ void lcd_status(const char* message)
strncpy(messagetext,message,LCD_WIDTH);
}
void clear()
inline void clear()
{
//lcd.setCursor(0,0);
lcd.clear();
//delay(1);
// lcd.begin(LCD_WIDTH,LCD_HEIGHT);
//lcd_init();
}
long previous_millis_buttons=0;
@ -78,47 +75,48 @@ void lcd_init()
void beep()
{
//return;
#ifdef ULTIPANEL
pinMode(BEEPER,OUTPUT);
for(int i=0;i<20;i++){
WRITE(BEEPER,HIGH);
delay(5);
WRITE(BEEPER,LOW);
delay(5);
}
#endif
#ifdef ULTIPANEL
pinMode(BEEPER,OUTPUT);
for(int i=0;i<20;i++){
WRITE(BEEPER,HIGH);
delay(5);
WRITE(BEEPER,LOW);
delay(5);
}
#endif
}
void beepshort()
{
//return;
#ifdef ULTIPANEL
pinMode(BEEPER,OUTPUT);
for(int i=0;i<10;i++){
WRITE(BEEPER,HIGH);
delay(3);
WRITE(BEEPER,LOW);
delay(3);
}
#endif
#ifdef ULTIPANEL
pinMode(BEEPER,OUTPUT);
for(int i=0;i<10;i++){
WRITE(BEEPER,HIGH);
delay(3);
WRITE(BEEPER,LOW);
delay(3);
}
#endif
}
void lcd_status()
{
#ifdef ULTIPANEL
static uint8_t oldbuttons=0;
static long previous_millis_buttons=0;
static long previous_lcdinit=0;
// buttons_check(); // Done in temperature interrupt
//previous_millis_buttons=millis();
#ifdef ULTIPANEL
static uint8_t oldbuttons=0;
static long previous_millis_buttons=0;
static long previous_lcdinit=0;
// buttons_check(); // Done in temperature interrupt
//previous_millis_buttons=millis();
if((buttons==oldbuttons) && ((millis() - previous_millis_lcd) < LCD_UPDATE_INTERVAL) )
return;
oldbuttons=buttons;
#else
if((buttons==oldbuttons) && ((millis() - previous_millis_lcd) < LCD_UPDATE_INTERVAL) )
return;
oldbuttons=buttons;
#else
if(((millis() - previous_millis_lcd) < LCD_UPDATE_INTERVAL) )
return;
#endif
if(((millis() - previous_millis_lcd) < LCD_UPDATE_INTERVAL) )
return;
#endif
previous_millis_lcd=millis();
menu.update();
@ -161,8 +159,7 @@ void buttons_check()
if((blocking<millis()) &&(READ(BTN_ENC)==0))
newbutton|=EN_C;
buttons=newbutton;
#else
//read it from the shift register
#else //read it from the shift register
uint8_t newbutton=0;
WRITE(SHIFT_LD,LOW);
WRITE(SHIFT_LD,HIGH);
@ -238,8 +235,8 @@ extern volatile bool feedmultiplychanged;
void MainMenu::showStatus()
{
#if LCD_HEIGHT==4
static int oldcurrentraw=-1;
static int oldtargetraw=-1;
static int olddegHotEnd0=-1;
static int oldtargetHotEnd0=-1;
//force_lcd_update=true;
if(force_lcd_update||feedmultiplychanged) //initial display of content
{
@ -247,38 +244,41 @@ void MainMenu::showStatus()
encoderpos=feedmultiply;
clear();
lcd.setCursor(0,0);lcd.print("\002123/567\001 ");
#if defined BED_USES_THERMISTOR || defined BED_USES_AD595
lcd.setCursor(10,0);lcd.print("B123/567\001 ");
#endif
#if defined BED_USES_THERMISTOR || defined BED_USES_AD595
lcd.setCursor(10,0);lcd.print("B123/567\001 ");
#endif
}
if((abs(current_raw[TEMPSENSOR_HOTEND_0]-oldcurrentraw)>3)||force_lcd_update)
int tHotEnd0=intround(degHotend0());
if((abs(tHotEnd0-olddegHotEnd0)>1)||force_lcd_update) //>1 because otherwise the lcd is refreshed to often.
{
lcd.setCursor(1,0);
lcd.print(ftostr3(analog2temp(current_raw[TEMPSENSOR_HOTEND_0])));
oldcurrentraw=current_raw[TEMPSENSOR_HOTEND_0];
lcd.print(ftostr3(tHotEnd0));
olddegHotEnd0=tHotEnd0;
}
if((target_raw[TEMPSENSOR_HOTEND_0]!=oldtargetraw)||force_lcd_update)
int ttHotEnd0=intround(degTargetHotend0());
if((ttHotEnd0!=oldtargetHotEnd0)||force_lcd_update)
{
lcd.setCursor(5,0);
lcd.print(ftostr3(analog2temp(target_raw[TEMPSENSOR_HOTEND_0])));
oldtargetraw=target_raw[TEMPSENSOR_HOTEND_0];
lcd.print(ftostr3(ttHotEnd0));
oldtargetHotEnd0=ttHotEnd0;
}
#if defined BED_USES_THERMISTOR || defined BED_USES_AD595
static int oldcurrentbedraw=-1;
static int oldtargetbedraw=-1;
if((current_bed_raw!=oldcurrentbedraw)||force_lcd_update)
static int oldtBed=-1;
static int oldtargetBed=-1;
int tBed=intround(degBed());
if((tBed!=oldtBed)||force_lcd_update)
{
lcd.setCursor(1,0);
lcd.print(ftostr3(analog2temp(current_bed_raw)));
oldcurrentraw=current_raw[TEMPSENSOR_BED];
lcd.print(ftostr3(tBed));
olddegHotEnd0=tBed;
}
if((target_bed_raw!=oldtargebedtraw)||force_lcd_update)
int targetBed=intround(degTargetBed());
if((targetBed!=oldtargetBed)||force_lcd_update)
{
lcd.setCursor(5,0);
lcd.print(ftostr3(analog2temp(target_bed_raw)));
oldtargetraw=target_bed_raw;
lcd.print(ftostr3(targetBed));
oldtargetBed=targetBed;
}
#endif
//starttime=2;
@ -327,8 +327,8 @@ void MainMenu::showStatus()
messagetext[0]='\0';
}
#else //smaller LCDS----------------------------------
static int oldcurrentraw=-1;
static int oldtargetraw=-1;
static int olddegHotEnd0=-1;
static int oldtargetHotEnd0=-1;
if(force_lcd_update) //initial display of content
{
encoderpos=feedmultiply;
@ -338,18 +338,21 @@ void MainMenu::showStatus()
#endif
}
int tHotEnd0=intround(degHotend0());
int ttHotEnd0=intround(degTargetHotend0());
if((abs(current_raw[TEMPSENSOR_HOTEND]-oldcurrentraw)>3)||force_lcd_update)
if((abs(tHotEnd0-olddegHotEnd0)>1)||force_lcd_update)
{
lcd.setCursor(1,0);
lcd.print(ftostr3(analog2temp(current_raw[TEMPSENSOR_HOTEND])));
oldcurrentraw=current_raw[TEMPSENSOR_HOTEND];
lcd.print(ftostr3(tHotEnd0));
olddegHotEnd0=tHotEnd0;
}
if((target_raw[TEMPSENSOR_HOTEND]!=oldtargetraw)||force_lcd_update)
if((ttHotEnd0!=oldtargetHotEnd0)||force_lcd_update)
{
lcd.setCursor(5,0);
lcd.print(ftostr3(analog2temp(target_raw[TEMPSENSOR_HOTEND])));
oldtargetraw=target_raw[TEMPSENSOR_HOTEND];
lcd.print(ftostr3(ttHotEnd0));
oldtargetHotEnd0=ttHotEnd0;
}
if(messagetext[0]!='\0')
@ -426,7 +429,7 @@ void MainMenu::showPrepare()
if((activeline==line) && CLICKED)
{
BLOCK
target_raw[TEMPSENSOR_HOTEND_0] = temp2analog(170);
setTargetHotend0(170);
beepshort();
}
}break;
@ -531,7 +534,7 @@ void MainMenu::showControl()
if(force_lcd_update)
{
lcd.setCursor(0,line);lcd.print(" \002Nozzle:");
lcd.setCursor(13,line);lcd.print(ftostr3(analog2temp(target_raw[TEMPSENSOR_HOTEND_0])));
lcd.setCursor(13,line);lcd.print(ftostr3(intround(degHotend0())));
}
if((activeline==line) )
@ -541,11 +544,11 @@ void MainMenu::showControl()
linechanging=!linechanging;
if(linechanging)
{
encoderpos=(int)analog2temp(target_raw[TEMPSENSOR_HOTEND_0]);
encoderpos=intround(degHotend0());
}
else
{
target_raw[TEMPSENSOR_HOTEND_0] = temp2analog(encoderpos);
setTargetHotend0(encoderpos);
encoderpos=activeline*lcdslow;
beepshort();
}
@ -1590,4 +1593,5 @@ char *fillto(int8_t n,char *c)
#else
inline void lcd_status() {};
#endif