solved some compiler warnings that are now visible in arduino 1.0.
Found a couple of unused variables, that I commented. Tried to solve the program memory warning message, and failed.
This commit is contained in:
parent
dfd240b260
commit
7714b98da7
|
@ -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);
|
||||||
|
|
|
@ -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;
|
||||||
|
|
|
@ -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>
|
||||||
|
|
|
@ -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]);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
|
@ -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);
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
||||||
|
|
|
@ -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;
|
||||||
|
|
|
@ -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.
|
||||||
|
@ -255,7 +257,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 };
|
||||||
|
@ -294,7 +296,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) {
|
||||||
|
@ -384,7 +386,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;
|
||||||
|
@ -423,7 +425,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++;
|
||||||
|
@ -519,8 +521,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) {
|
||||||
|
@ -538,6 +539,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);
|
||||||
|
|
|
@ -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"
|
||||||
|
@ -444,7 +445,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;
|
||||||
|
@ -463,7 +464,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
|
||||||
|
@ -678,7 +679,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;
|
||||||
|
|
|
@ -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.
|
||||||
|
|
|
@ -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()
|
||||||
|
|
|
@ -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,17 +94,19 @@ 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];};
|
||||||
|
|
||||||
|
|
|
@ -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
|
||||||
|
|
|
@ -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();
|
||||||
|
|
||||||
|
|
Loading…
Reference in a new issue