Commit ebb1c7b4 authored by MagoKimbra's avatar MagoKimbra

Upgrade v4.1.0

parent 544b2baa
...@@ -20,7 +20,7 @@ ...@@ -20,7 +20,7 @@
// User-specified version info of this build to display in [Pronterface, etc] terminal window during // User-specified version info of this build to display in [Pronterface, etc] terminal window during
// startup. Implementation of an idea by Prof Braino to inform user that any changes made to this // startup. Implementation of an idea by Prof Braino to inform user that any changes made to this
// build by the user have been successfully uploaded into firmware. // build by the user have been successfully uploaded into firmware.
#define STRING_VERSION " 4.0.9" #define STRING_VERSION "4.1.0"
#define STRING_URL "reprap.org" #define STRING_URL "reprap.org"
#define STRING_VERSION_CONFIG_H __DATE__ " " __TIME__ // build date and time #define STRING_VERSION_CONFIG_H __DATE__ " " __TIME__ // build date and time
#define STRING_CONFIG_H_AUTHOR "(none, default config)" // Who made the changes. #define STRING_CONFIG_H_AUTHOR "(none, default config)" // Who made the changes.
...@@ -228,9 +228,9 @@ ...@@ -228,9 +228,9 @@
#define K1 0.95 // Smoothing factor within the PID #define K1 0.95 // Smoothing factor within the PID
// HotEnd{HE0,HE1,HE2,HE3} // HotEnd{HE0,HE1,HE2,HE3}
#define DEFAULT_Kp {41,41,41,41} // Kp for E0, E1, E2, E3 #define DEFAULT_Kp {40, 40, 40, 40} // Kp for E0, E1, E2, E3
#define DEFAULT_Ki {07,07,07,07} // Ki for E0, E1, E2, E3 #define DEFAULT_Ki {07, 07, 07, 07} // Ki for E0, E1, E2, E3
#define DEFAULT_Kd {59,59,59,59} // Kd for E0, E1, E2, E3 #define DEFAULT_Kd {60, 60, 60, 60} // Kd for E0, E1, E2, E3
#endif // PIDTEMP #endif // PIDTEMP
......
...@@ -198,9 +198,9 @@ ...@@ -198,9 +198,9 @@
//Manual homing switch locations: //Manual homing switch locations:
// For SCARA: Offset between HomingPosition and Bed X=0 / Y=0 // For SCARA: Offset between HomingPosition and Bed X=0 / Y=0
#ifdef MANUAL_HOME_POSITIONS #ifdef MANUAL_HOME_POSITIONS
#define MANUAL_X_HOME_POS -22 #define MANUAL_X_HOME_POS -22
#define MANUAL_Y_HOME_POS -52 #define MANUAL_Y_HOME_POS -52
#define MANUAL_Z_HOME_POS 0.1 // Distance between nozzle and print surface after homing. #define MANUAL_Z_HOME_POS 0.1 // Distance between nozzle and print surface after homing.
#endif #endif
// MOVEMENT SETTINGS // MOVEMENT SETTINGS
......
...@@ -35,6 +35,10 @@ ...@@ -35,6 +35,10 @@
#define TEST(n,b) (((n)&BIT(b))!=0) #define TEST(n,b) (((n)&BIT(b))!=0)
#define RADIANS(d) ((d)*M_PI/180.0) #define RADIANS(d) ((d)*M_PI/180.0)
#define DEGREES(r) ((d)*180.0/M_PI) #define DEGREES(r) ((d)*180.0/M_PI)
#define NOLESS(v,n) do{ if (v < n) v = n; }while(0)
#define NOMORE(v,n) do{ if (v > n) v = n; }while(0)
typedef unsigned long millis_t;
// Arduino < 1.0.0 does not define this, so we need to do it ourselves // Arduino < 1.0.0 does not define this, so we need to do it ourselves
#ifndef analogInputToDigitalPin #ifndef analogInputToDigitalPin
...@@ -244,14 +248,14 @@ extern bool Running; ...@@ -244,14 +248,14 @@ extern bool Running;
inline bool IsRunning() { return Running; } inline bool IsRunning() { return Running; }
inline bool IsStopped() { return !Running; } inline bool IsStopped() { return !Running; }
bool enquecommand(const char *cmd); //put a single ASCII command at the end of the current buffer or return false when it is full bool enqueuecommand(const char *cmd); //put a single ASCII command at the end of the current buffer or return false when it is full
void enquecommands_P(const char *cmd); //put one or many ASCII commands at the end of the current buffer, read from flash void enqueuecommands_P(const char *cmd); //put one or many ASCII commands at the end of the current buffer, read from flash
void prepare_arc_move(char isclockwise); void prepare_arc_move(char isclockwise);
void clamp_to_software_endstops(float target[3]); void clamp_to_software_endstops(float target[3]);
extern unsigned long previous_millis_cmd; extern millis_t previous_cmd_ms;
inline void refresh_cmd_timeout() { previous_millis_cmd = millis(); } inline void refresh_cmd_timeout() { previous_cmd_ms = millis(); }
#ifdef FAST_PWM_FAN #ifdef FAST_PWM_FAN
void setPwmFrequency(uint8_t pin, int val); void setPwmFrequency(uint8_t pin, int val);
...@@ -264,7 +268,7 @@ inline void refresh_cmd_timeout() { previous_millis_cmd = millis(); } ...@@ -264,7 +268,7 @@ inline void refresh_cmd_timeout() { previous_millis_cmd = millis(); }
extern float homing_feedrate[]; extern float homing_feedrate[];
extern bool axis_relative_modes[]; extern bool axis_relative_modes[];
extern int feedmultiply; extern int feedrate_multiplier;
extern bool volumetric_enabled; extern bool volumetric_enabled;
extern int extruder_multiply[EXTRUDERS]; // sets extrude multiply factor (in percent) for each extruder individually extern int extruder_multiply[EXTRUDERS]; // sets extrude multiply factor (in percent) for each extruder individually
extern float filament_size[EXTRUDERS]; // cross-sectional area of filament (in millimeters), typically around 1.75 or 2.85, 0 disables the volumetric calculations for the extruder. extern float filament_size[EXTRUDERS]; // cross-sectional area of filament (in millimeters), typically around 1.75 or 2.85, 0 disables the volumetric calculations for the extruder.
...@@ -358,8 +362,8 @@ extern int fanSpeed; ...@@ -358,8 +362,8 @@ extern int fanSpeed;
extern int laser_ttl_modulation; extern int laser_ttl_modulation;
#endif #endif
extern unsigned long starttime; extern millis_t print_job_start_ms;
extern unsigned long stoptime; extern millis_t print_job_stop_ms;
// Handling multiple extruders pins // Handling multiple extruders pins
extern uint8_t active_extruder; extern uint8_t active_extruder;
......
This source diff could not be displayed because it is too large. You can view the blob instead.
...@@ -25,7 +25,7 @@ CardReader::CardReader() { ...@@ -25,7 +25,7 @@ CardReader::CardReader() {
OUT_WRITE(SDPOWER, HIGH); OUT_WRITE(SDPOWER, HIGH);
#endif //SDPOWER #endif //SDPOWER
autostart_atmillis = millis() + 5000; next_autostart_ms = millis() + 5000;
} }
char *createFilename(char *buffer, const dir_t &p) { //buffer > 12characters char *createFilename(char *buffer, const dir_t &p) { //buffer > 12characters
...@@ -397,7 +397,7 @@ void CardReader::write_command(char *buf) { ...@@ -397,7 +397,7 @@ void CardReader::write_command(char *buf) {
} }
void CardReader::checkautostart(bool force) { void CardReader::checkautostart(bool force) {
if (!force && (!autostart_stilltocheck || autostart_atmillis < millis())) if (!force && (!autostart_stilltocheck || next_autostart_ms < millis()))
return; return;
autostart_stilltocheck = false; autostart_stilltocheck = false;
...@@ -421,8 +421,8 @@ void CardReader::checkautostart(bool force) { ...@@ -421,8 +421,8 @@ void CardReader::checkautostart(bool force) {
if (p.name[9] != '~' && strncmp((char*)p.name, autoname, 5) == 0) { if (p.name[9] != '~' && strncmp((char*)p.name, autoname, 5) == 0) {
char cmd[30]; char cmd[30];
sprintf_P(cmd, PSTR("M23 %s"), autoname); sprintf_P(cmd, PSTR("M23 %s"), autoname);
enquecommand(cmd); enqueuecommand(cmd);
enquecommands_P(PSTR("M24")); enqueuecommands_P(PSTR("M24"));
found = true; found = true;
} }
} }
...@@ -508,7 +508,7 @@ void CardReader::printingHasFinished() { ...@@ -508,7 +508,7 @@ void CardReader::printingHasFinished() {
sdprinting = false; sdprinting = false;
if (SD_FINISHED_STEPPERRELEASE) { if (SD_FINISHED_STEPPERRELEASE) {
//finishAndDisableSteppers(); //finishAndDisableSteppers();
enquecommands_P(PSTR(SD_FINISHED_RELEASECOMMAND)); enqueuecommands_P(PSTR(SD_FINISHED_RELEASECOMMAND));
} }
autotempShutdown(); autotempShutdown();
} }
......
...@@ -62,7 +62,7 @@ private: ...@@ -62,7 +62,7 @@ private:
uint32_t filespos[SD_PROCEDURE_DEPTH]; uint32_t filespos[SD_PROCEDURE_DEPTH];
char filenames[SD_PROCEDURE_DEPTH][MAXPATHNAMELENGTH]; char filenames[SD_PROCEDURE_DEPTH][MAXPATHNAMELENGTH];
uint32_t filesize; uint32_t filesize;
unsigned long autostart_atmillis; millis_t next_autostart_ms;
uint32_t sdpos; uint32_t sdpos;
bool autostart_stilltocheck; //the sd start is delayed, because otherwise the serial cannot answer fast enought to make contact with the hostsoftware. bool autostart_stilltocheck; //the sd start is delayed, because otherwise the serial cannot answer fast enought to make contact with the hostsoftware.
......
...@@ -269,10 +269,10 @@ static void lcd_implementation_status_screen() { ...@@ -269,10 +269,10 @@ static void lcd_implementation_status_screen() {
} }
u8g.setPrintPos(80,48); u8g.setPrintPos(80,48);
if (starttime != 0) { if (print_job_start_ms != 0) {
#if HAS_LCD_POWER_SENSOR #if HAS_LCD_POWER_SENSOR
if (millis() < print_millis + 1000) { if (millis() < print_millis + 1000) {
uint16_t time = (millis() - starttime) / 60000; uint16_t time = (millis() - print_job_start_ms) / 60000;
lcd_print(itostr2(time/60)); lcd_print(itostr2(time/60));
lcd_print(':'); lcd_print(':');
lcd_print(itostr2(time%60)); lcd_print(itostr2(time%60));
...@@ -282,7 +282,7 @@ static void lcd_implementation_status_screen() { ...@@ -282,7 +282,7 @@ static void lcd_implementation_status_screen() {
lcd_print('Wh'); lcd_print('Wh');
} }
#else #else
uint16_t time = (millis() - starttime) / 60000; uint16_t time = (millis() - print_job_start_ms) / 60000;
lcd_print(itostr2(time/60)); lcd_print(itostr2(time/60));
lcd_print(':'); lcd_print(':');
lcd_print(itostr2(time%60)); lcd_print(itostr2(time%60));
...@@ -350,7 +350,7 @@ static void lcd_implementation_status_screen() { ...@@ -350,7 +350,7 @@ static void lcd_implementation_status_screen() {
lcd_print(LCD_STR_FEEDRATE[0]); lcd_print(LCD_STR_FEEDRATE[0]);
lcd_setFont(FONT_STATUSMENU); lcd_setFont(FONT_STATUSMENU);
u8g.setPrintPos(12,49); u8g.setPrintPos(12,49);
lcd_print(itostr3(feedmultiply)); lcd_print(itostr3(feedrate_multiplier));
lcd_print('%'); lcd_print('%');
// Status line // Status line
...@@ -362,12 +362,12 @@ static void lcd_implementation_status_screen() { ...@@ -362,12 +362,12 @@ static void lcd_implementation_status_screen() {
#endif #endif
#if HAS_LCD_FILAMENT_SENSOR || HAS_LCD_POWER_SENSOR #if HAS_LCD_FILAMENT_SENSOR || HAS_LCD_POWER_SENSOR
if (millis() < message_millis + 5000) { //Display both Status message line and Filament display on the last line if (millis() < previous_lcd_status_ms + 5000) { //Display both Status message line and Filament display on the last line
lcd_print(lcd_status_message); lcd_print(lcd_status_message);
} }
#if HAS_LCD_POWER_SENSOR #if HAS_LCD_POWER_SENSOR
#if HAS_LCD_FILAMENT_SENSOR #if HAS_LCD_FILAMENT_SENSOR
else if (millis() < message_millis + 10000) else if (millis() < previous_lcd_status_ms + 10000)
#else #else
else else
#endif #endif
......
...@@ -59,6 +59,10 @@ ...@@ -59,6 +59,10 @@
#define MACHINE_NAME CUSTOM_MENDEL_NAME #define MACHINE_NAME CUSTOM_MENDEL_NAME
#endif #endif
#ifndef BUILD_VERSION
#define BUILD_VERSION "V4;"
#endif
#ifndef MACHINE_UUID #ifndef MACHINE_UUID
#define MACHINE_UUID "00000000-0000-0000-0000-000000000000" #define MACHINE_UUID "00000000-0000-0000-0000-000000000000"
#endif #endif
...@@ -77,7 +81,7 @@ ...@@ -77,7 +81,7 @@
// Serial Console Messages (do not translate those!) // Serial Console Messages (do not translate those!)
#define MSG_Enqueing "enqueing \"" #define MSG_Enqueueing "enqueueing \""
#define MSG_POWERUP "PowerUp" #define MSG_POWERUP "PowerUp"
#define MSG_EXTERNAL_RESET " External Reset" #define MSG_EXTERNAL_RESET " External Reset"
#define MSG_BROWNOUT_RESET " Brown out Reset" #define MSG_BROWNOUT_RESET " Brown out Reset"
...@@ -86,8 +90,9 @@ ...@@ -86,8 +90,9 @@
#define MSG_AUTHOR " | Author: " #define MSG_AUTHOR " | Author: "
#define MSG_CONFIGURATION_VER " Last Updated: " #define MSG_CONFIGURATION_VER " Last Updated: "
#define MSG_FREE_MEMORY " Free Memory: " #define MSG_FREE_MEMORY " Free Memory: "
#define MSG_PLANNER_BUFFER_BYTES " PlannerBufferBytes: " #define MSG_PLANNER_BUFFER_BYTES " PlannerBufferBytes: "
#define MSG_OK "ok" #define MSG_OK "ok"
#define MSG_WAIT "wait"
#define MSG_FILE_SAVED "Done saving file." #define MSG_FILE_SAVED "Done saving file."
#define MSG_ERR_LINE_NO "Line Number is not Last Line Number+1, Last Line: " #define MSG_ERR_LINE_NO "Line Number is not Last Line Number+1, Last Line: "
#define MSG_ERR_CHECKSUM_MISMATCH "checksum mismatch, Last Line: " #define MSG_ERR_CHECKSUM_MISMATCH "checksum mismatch, Last Line: "
...@@ -107,7 +112,7 @@ ...@@ -107,7 +112,7 @@
#define MSG_HEATING_COMPLETE "Heating done." #define MSG_HEATING_COMPLETE "Heating done."
#define MSG_BED_HEATING "Bed Heating." #define MSG_BED_HEATING "Bed Heating."
#define MSG_BED_DONE "Bed done." #define MSG_BED_DONE "Bed done."
#define MSG_M115_REPORT "FIRMWARE_NAME:MarlinKimbra V4; FIRMWARE_URL:" FIRMWARE_URL " PROTOCOL_VERSION:" PROTOCOL_VERSION " MACHINE_TYPE:" MACHINE_NAME " EXTRUDER_COUNT:" STRINGIFY(EXTRUDERS) " UUID:" MACHINE_UUID "\n" #define MSG_M115_REPORT "FIRMWARE_NAME:MarlinKimbra " BUILD_VERSION " FIRMWARE_URL:" FIRMWARE_URL " PROTOCOL_VERSION:" PROTOCOL_VERSION " MACHINE_TYPE:" MACHINE_NAME " EXTRUDER_COUNT:" STRINGIFY(EXTRUDERS) " UUID:" MACHINE_UUID "\n"
#define MSG_COUNT_X " Count X: " #define MSG_COUNT_X " Count X: "
#define MSG_ERR_KILLED "Printer halted. kill() called!" #define MSG_ERR_KILLED "Printer halted. kill() called!"
#define MSG_ERR_STOPPED "Printer stopped due to errors. Fix the error and use M999 to restart. (Temperature is reset. Set it after restarting)" #define MSG_ERR_STOPPED "Printer stopped due to errors. Fix the error and use M999 to restart. (Temperature is reset. Set it after restarting)"
......
...@@ -62,7 +62,7 @@ ...@@ -62,7 +62,7 @@
//============================= public variables ============================ //============================= public variables ============================
//=========================================================================== //===========================================================================
unsigned long minsegmenttime; millis_t minsegmenttime;
float max_feedrate[3 + EXTRUDERS]; // Max speeds in mm per minute float max_feedrate[3 + EXTRUDERS]; // Max speeds in mm per minute
float max_retraction_feedrate[EXTRUDERS]; // set the max speeds for retraction float max_retraction_feedrate[EXTRUDERS]; // set the max speeds for retraction
float axis_steps_per_unit[3 + EXTRUDERS]; float axis_steps_per_unit[3 + EXTRUDERS];
...@@ -156,8 +156,8 @@ void calculate_trapezoid_for_block(block_t *block, float entry_factor, float exi ...@@ -156,8 +156,8 @@ void calculate_trapezoid_for_block(block_t *block, float entry_factor, float exi
unsigned long final_rate = ceil(block->nominal_rate * exit_factor); // (step/min) unsigned long final_rate = ceil(block->nominal_rate * exit_factor); // (step/min)
// Limit minimal step rate (Otherwise the timer will overflow.) // Limit minimal step rate (Otherwise the timer will overflow.)
if (initial_rate < 120) initial_rate = 120; NOLESS(initial_rate, 120);
if (final_rate < 120) final_rate = 120; NOLESS(final_rate, 120);
long acceleration = block->acceleration_st; long acceleration = block->acceleration_st;
int32_t accelerate_steps = ceil(estimate_acceleration_distance(initial_rate, block->nominal_rate, acceleration)); int32_t accelerate_steps = ceil(estimate_acceleration_distance(initial_rate, block->nominal_rate, acceleration));
...@@ -378,16 +378,18 @@ void plan_init() { ...@@ -378,16 +378,18 @@ void plan_init() {
} }
float t = autotemp_min + high * autotemp_factor; float t = autotemp_min + high * autotemp_factor;
if (t < autotemp_min) t = autotemp_min; t = constrain(t, autotemp_min, autotemp_max);
if (t > autotemp_max) t = autotemp_max; if (oldt > t) {
if (oldt > t) t = AUTOTEMP_OLDWEIGHT * oldt + (1 - AUTOTEMP_OLDWEIGHT) * t; t *= (1 - AUTOTEMP_OLDWEIGHT);
t += AUTOTEMP_OLDWEIGHT * oldt;
}
oldt = t; oldt = t;
setTargetHotend0(t); setTargetHotend0(t);
} }
#endif #endif
void check_axes_activity() { void check_axes_activity() {
unsigned char axis_active[NUM_AXIS], unsigned char axis_active[NUM_AXIS] = { 0 },
tail_fan_speed = fanSpeed; tail_fan_speed = fanSpeed;
#ifdef BARICUDA #ifdef BARICUDA
unsigned char tail_valve_pressure = ValvePressure, unsigned char tail_valve_pressure = ValvePressure,
...@@ -428,7 +430,7 @@ void check_axes_activity() { ...@@ -428,7 +430,7 @@ void check_axes_activity() {
#if HAS_FAN #if HAS_FAN
#ifdef FAN_KICKSTART_TIME #ifdef FAN_KICKSTART_TIME
static unsigned long fan_kick_end; static millis_t fan_kick_end;
if (tail_fan_speed) { if (tail_fan_speed) {
if (fan_kick_end == 0) { if (fan_kick_end == 0) {
// Just starting up fan - run at full power. // Just starting up fan - run at full power.
...@@ -500,7 +502,7 @@ float junction_deviation = 0.1; ...@@ -500,7 +502,7 @@ float junction_deviation = 0.1;
target[X_AXIS] = lround(x * axis_steps_per_unit[X_AXIS]); target[X_AXIS] = lround(x * axis_steps_per_unit[X_AXIS]);
target[Y_AXIS] = lround(y * axis_steps_per_unit[Y_AXIS]); target[Y_AXIS] = lround(y * axis_steps_per_unit[Y_AXIS]);
target[Z_AXIS] = lround(z * axis_steps_per_unit[Z_AXIS]); target[Z_AXIS] = lround(z * axis_steps_per_unit[Z_AXIS]);
target[E_AXIS] = lround(e * axis_steps_per_unit[E_AXIS + extruder]); target[E_AXIS] = lround(e * axis_steps_per_unit[E_AXIS + active_extruder]);
float dx = target[X_AXIS] - position[X_AXIS], float dx = target[X_AXIS] - position[X_AXIS],
dy = target[Y_AXIS] - position[Y_AXIS], dy = target[Y_AXIS] - position[Y_AXIS],
...@@ -693,7 +695,11 @@ float junction_deviation = 0.1; ...@@ -693,7 +695,11 @@ float junction_deviation = 0.1;
#endif //!MKR4 && !NPR2 #endif //!MKR4 && !NPR2
if (feed_rate < minimumfeedrate) feed_rate = minimumfeedrate; if (feed_rate < minimumfeedrate) feed_rate = minimumfeedrate;
} }
else if (feed_rate < mintravelfeedrate) feed_rate = mintravelfeedrate;
if (block->steps[E_AXIS])
NOLESS(feed_rate, minimumfeedrate);
else
NOLESS(feed_rate, mintravelfeedrate);
/** /**
* This part of the code calculates the total length of the movement. * This part of the code calculates the total length of the movement.
......
...@@ -114,7 +114,7 @@ FORCE_INLINE uint8_t movesplanned() { return BLOCK_MOD(block_buffer_head - block ...@@ -114,7 +114,7 @@ FORCE_INLINE uint8_t movesplanned() { return BLOCK_MOD(block_buffer_head - block
void plan_set_e_position(const float &e); void plan_set_e_position(const float &e);
extern unsigned long minsegmenttime; extern millis_t minsegmenttime;
extern float max_feedrate[3 + EXTRUDERS]; // set the max speeds extern float max_feedrate[3 + EXTRUDERS]; // set the max speeds
extern float max_retraction_feedrate[EXTRUDERS]; // set the max speeds for retraction extern float max_retraction_feedrate[EXTRUDERS]; // set the max speeds for retraction
extern float axis_steps_per_unit[3 + EXTRUDERS]; extern float axis_steps_per_unit[3 + EXTRUDERS];
......
...@@ -54,7 +54,7 @@ static unsigned int cleaning_buffer_counter; ...@@ -54,7 +54,7 @@ static unsigned int cleaning_buffer_counter;
locked_z2_motor = false; locked_z2_motor = false;
#endif #endif
// Counter variables for the bresenham line tracer // Counter variables for the Bresenham line tracer
static long counter_x, counter_y, counter_z, counter_e; static long counter_x, counter_y, counter_z, counter_e;
volatile static unsigned long step_events_completed; // The number of step events executed in the current block volatile static unsigned long step_events_completed; // The number of step events executed in the current block
...@@ -66,7 +66,7 @@ volatile static unsigned long step_events_completed; // The number of step event ...@@ -66,7 +66,7 @@ volatile static unsigned long step_events_completed; // The number of step event
static long acceleration_time, deceleration_time; static long acceleration_time, deceleration_time;
//static unsigned long accelerate_until, decelerate_after, acceleration_rate, initial_rate, final_rate, nominal_rate; //static unsigned long accelerate_until, decelerate_after, acceleration_rate, initial_rate, final_rate, nominal_rate;
static unsigned short acc_step_rate; // needed for deccelaration start point static unsigned short acc_step_rate; // needed for deceleration start point
static char step_loops; static char step_loops;
static unsigned short OCR1A_nominal; static unsigned short OCR1A_nominal;
static unsigned short step_loops_nominal; static unsigned short step_loops_nominal;
...@@ -210,8 +210,14 @@ volatile signed char count_direction[NUM_AXIS] = { 1, 1, 1, 1 }; ...@@ -210,8 +210,14 @@ volatile signed char count_direction[NUM_AXIS] = { 1, 1, 1, 1 };
// intRes = longIn1 * longIn2 >> 24 // intRes = longIn1 * longIn2 >> 24
// uses: // uses:
// r26 to store 0 // r26 to store 0
// r27 to store the byte 1 of the 48bit result // r27 to store bits 16-23 of the 48bit result. The top bit is used to round the two byte result.
#define MultiU24X24toH16(intRes, longIn1, longIn2) \ // note that the lower two bytes and the upper byte of the 48bit result are not calculated.
// this can cause the result to be out by one as the lower bytes may cause carries into the upper ones.
// B0 A0 are bits 24-39 and are the returned value
// C1 B1 A1 is longIn1
// D2 C2 B2 A2 is longIn2
//
#define MultiU24X32toH16(intRes, longIn1, longIn2) \
asm volatile ( \ asm volatile ( \
"clr r26 \n\t" \ "clr r26 \n\t" \
"mul %A1, %B2 \n\t" \ "mul %A1, %B2 \n\t" \
...@@ -242,6 +248,11 @@ volatile signed char count_direction[NUM_AXIS] = { 1, 1, 1, 1 }; ...@@ -242,6 +248,11 @@ volatile signed char count_direction[NUM_AXIS] = { 1, 1, 1, 1 };
"lsr r27 \n\t" \ "lsr r27 \n\t" \
"adc %A0, r26 \n\t" \ "adc %A0, r26 \n\t" \
"adc %B0, r26 \n\t" \ "adc %B0, r26 \n\t" \
"mul %D2, %A1 \n\t" \
"add %A0, r0 \n\t" \
"adc %B0, r1 \n\t" \
"mul %D2, %B1 \n\t" \
"add %B0, r0 \n\t" \
"clr r1 \n\t" \ "clr r1 \n\t" \
: \ : \
"=&r" (intRes) \ "=&r" (intRes) \
...@@ -372,7 +383,7 @@ void enable_endstops(bool check) { check_endstops = check; } ...@@ -372,7 +383,7 @@ void enable_endstops(bool check) { check_endstops = check; }
// The trapezoid is the shape the speed curve over time. It starts at block->initial_rate, accelerates // The trapezoid is the shape the speed curve over time. It starts at block->initial_rate, accelerates
// first block->accelerate_until step_events_completed, then keeps going at constant speed until // first block->accelerate_until step_events_completed, then keeps going at constant speed until
// step_events_completed reaches block->decelerate_after after which it decelerates until the trapezoid generator is reset. // step_events_completed reaches block->decelerate_after after which it decelerates until the trapezoid generator is reset.
// The slope of acceleration is calculated with the lib ramp algorithm. // The slope of acceleration is calculated using v = u + at where t is the accumulated timer values of the steps so far.
void st_wake_up() { void st_wake_up() {
// TCNT1 = 0; // TCNT1 = 0;
...@@ -453,7 +464,7 @@ ISR(TIMER1_COMPA_vect) { ...@@ -453,7 +464,7 @@ ISR(TIMER1_COMPA_vect) {
current_block = NULL; current_block = NULL;
plan_discard_current_block(); plan_discard_current_block();
#ifdef SD_FINISHED_RELEASECOMMAND #ifdef SD_FINISHED_RELEASECOMMAND
if ((cleaning_buffer_counter == 1) && (SD_FINISHED_STEPPERRELEASE)) enquecommands_P(PSTR(SD_FINISHED_RELEASECOMMAND)); if ((cleaning_buffer_counter == 1) && (SD_FINISHED_STEPPERRELEASE)) enqueuecommands_P(PSTR(SD_FINISHED_RELEASECOMMAND));
#endif #endif
cleaning_buffer_counter--; cleaning_buffer_counter--;
OCR1A = 200; OCR1A = 200;
...@@ -528,7 +539,7 @@ ISR(TIMER1_COMPA_vect) { ...@@ -528,7 +539,7 @@ ISR(TIMER1_COMPA_vect) {
if ((current_block->steps[A_AXIS] != current_block->steps[B_AXIS]) || (TEST(out_bits, A_AXIS) == TEST(out_bits, B_AXIS))) { if ((current_block->steps[A_AXIS] != current_block->steps[B_AXIS]) || (TEST(out_bits, A_AXIS) == TEST(out_bits, B_AXIS))) {
if (TEST(out_bits, X_HEAD)) if (TEST(out_bits, X_HEAD))
#else #else
if (TEST(out_bits, X_AXIS)) // stepping along -X axis (regular cartesians bot) if (TEST(out_bits, X_AXIS)) // stepping along -X axis (regular Cartesian bot)
#endif #endif
{ // -direction { // -direction
#ifdef DUAL_X_CARRIAGE #ifdef DUAL_X_CARRIAGE
...@@ -772,9 +783,9 @@ ISR(TIMER1_COMPA_vect) { ...@@ -772,9 +783,9 @@ ISR(TIMER1_COMPA_vect) {
// Calculate new timer value // Calculate new timer value
unsigned short timer; unsigned short timer;
unsigned short step_rate; unsigned short step_rate;
if (step_events_completed <= (unsigned long int)current_block->accelerate_until) { if (step_events_completed <= (unsigned long)current_block->accelerate_until) {
MultiU24X24toH16(acc_step_rate, acceleration_time, current_block->acceleration_rate); MultiU24X32toH16(acc_step_rate, acceleration_time, current_block->acceleration_rate);
acc_step_rate += current_block->initial_rate; acc_step_rate += current_block->initial_rate;
// upper limit // upper limit
...@@ -796,8 +807,8 @@ ISR(TIMER1_COMPA_vect) { ...@@ -796,8 +807,8 @@ ISR(TIMER1_COMPA_vect) {
#endif #endif
} }
else if (step_events_completed > (unsigned long int)current_block->decelerate_after) { else if (step_events_completed > (unsigned long)current_block->decelerate_after) {
MultiU24X24toH16(step_rate, deceleration_time, current_block->acceleration_rate); MultiU24X32toH16(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
step_rate = current_block->final_rate; step_rate = current_block->final_rate;
...@@ -1236,7 +1247,7 @@ void quickStop() { ...@@ -1236,7 +1247,7 @@ void quickStop() {
uint8_t old_pin = AXIS ##_DIR_READ; \ uint8_t old_pin = AXIS ##_DIR_READ; \
AXIS ##_APPLY_DIR(INVERT_## AXIS ##_DIR^direction^INVERT, true); \ AXIS ##_APPLY_DIR(INVERT_## AXIS ##_DIR^direction^INVERT, true); \
AXIS ##_APPLY_STEP(!INVERT_## AXIS ##_STEP_PIN, true); \ AXIS ##_APPLY_STEP(!INVERT_## AXIS ##_STEP_PIN, true); \
_delay_us(1U); \ delayMicroseconds(2); \
AXIS ##_APPLY_STEP(INVERT_## AXIS ##_STEP_PIN, true); \ AXIS ##_APPLY_STEP(INVERT_## AXIS ##_STEP_PIN, true); \
AXIS ##_APPLY_DIR(old_pin, true); \ AXIS ##_APPLY_DIR(old_pin, true); \
} }
...@@ -1275,7 +1286,7 @@ void quickStop() { ...@@ -1275,7 +1286,7 @@ void quickStop() {
X_STEP_WRITE(!INVERT_X_STEP_PIN); X_STEP_WRITE(!INVERT_X_STEP_PIN);
Y_STEP_WRITE(!INVERT_Y_STEP_PIN); Y_STEP_WRITE(!INVERT_Y_STEP_PIN);
Z_STEP_WRITE(!INVERT_Z_STEP_PIN); Z_STEP_WRITE(!INVERT_Z_STEP_PIN);
_delay_us(1U); delayMicroseconds(2);
X_STEP_WRITE(INVERT_X_STEP_PIN); X_STEP_WRITE(INVERT_X_STEP_PIN);
Y_STEP_WRITE(INVERT_Y_STEP_PIN); Y_STEP_WRITE(INVERT_Y_STEP_PIN);
Z_STEP_WRITE(INVERT_Z_STEP_PIN); Z_STEP_WRITE(INVERT_Z_STEP_PIN);
......
...@@ -109,7 +109,7 @@ void microstep_readings(); ...@@ -109,7 +109,7 @@ void microstep_readings();
#ifdef BABYSTEPPING #ifdef BABYSTEPPING
void babystep(const uint8_t axis,const bool direction); // perform a short step with a single stepper motor, outside of any convention void babystep(const uint8_t axis,const bool direction); // perform a short step with a single stepper motor, outside of any convention
#endif //BABYSTEPPING #endif
#ifdef NPR2 //Multiextruder #ifdef NPR2 //Multiextruder
void colorstep(long csteps,const bool direction); void colorstep(long csteps,const bool direction);
......
This diff is collapsed.
...@@ -133,7 +133,7 @@ HOTEND_ROUTINES(0); ...@@ -133,7 +133,7 @@ HOTEND_ROUTINES(0);
#endif #endif
int getHeaterPower(int heater); int getHeaterPower(int heater);
void disable_heater(); void disable_all_heaters();
void setWatch(); void setWatch();
void updatePID(); void updatePID();
......
This diff is collapsed.
...@@ -57,10 +57,11 @@ ...@@ -57,10 +57,11 @@
extern bool cancel_heatup; extern bool cancel_heatup;
#if (HAS_FILAMENT_SENSOR && defined(FILAMENT_LCD_DISPLAY)) || (HAS_POWER_CONSUMPTION_SENSOR && defined(POWER_CONSUMPTION_LCD_DISPLAY)) #if (HAS_FILAMENT_SENSOR && defined(FILAMENT_LCD_DISPLAY)) || (HAS_POWER_CONSUMPTION_SENSOR && defined(POWER_CONSUMPTION_LCD_DISPLAY))
extern unsigned long message_millis; extern millis_t previous_lcd_status_ms;
#endif #endif
void lcd_buzz(long duration,uint16_t freq); void lcd_buzz(long duration,uint16_t freq);
void lcd_quick_feedback(); // Audible feedback for a button click - could also be visual
bool lcd_clicked(); bool lcd_clicked();
void lcd_ignore_click(bool b=true); void lcd_ignore_click(bool b=true);
......
...@@ -582,7 +582,7 @@ static void lcd_implementation_status_screen() { ...@@ -582,7 +582,7 @@ static void lcd_implementation_status_screen() {
lcd.setCursor(0, 2); lcd.setCursor(0, 2);
lcd.print(LCD_STR_FEEDRATE[0]); lcd.print(LCD_STR_FEEDRATE[0]);
lcd.print(itostr3(feedmultiply)); lcd.print(itostr3(feedrate_multiplier));
lcd.print('%'); lcd.print('%');
#if LCD_WIDTH > 19 && defined(SDSUPPORT) #if LCD_WIDTH > 19 && defined(SDSUPPORT)
...@@ -598,11 +598,11 @@ static void lcd_implementation_status_screen() { ...@@ -598,11 +598,11 @@ static void lcd_implementation_status_screen() {
#endif // LCD_WIDTH > 19 && SDSUPPORT #endif // LCD_WIDTH > 19 && SDSUPPORT
lcd.setCursor(LCD_WIDTH - 6, 2); lcd.setCursor(LCD_WIDTH - 6, 2);
if(starttime != 0) { if(print_job_start_ms != 0) {
#if HAS_LCD_POWER_SENSOR #if HAS_LCD_POWER_SENSOR
if (millis() < print_millis + 1000) { if (millis() < print_millis + 1000) {
lcd.print(LCD_STR_CLOCK[0]); lcd.print(LCD_STR_CLOCK[0]);
uint16_t time = millis()/60000 - starttime/60000; uint16_t time = millis()/60000 - print_job_start_ms/60000;
lcd.print(itostr2(time/60)); lcd.print(itostr2(time/60));
lcd.print(':'); lcd.print(':');
lcd.print(itostr2(time%60)); lcd.print(itostr2(time%60));
...@@ -613,7 +613,7 @@ static void lcd_implementation_status_screen() { ...@@ -613,7 +613,7 @@ static void lcd_implementation_status_screen() {
} }
#else #else
lcd.print(LCD_STR_CLOCK[0]); lcd.print(LCD_STR_CLOCK[0]);
uint16_t time = millis()/60000 - starttime/60000; uint16_t time = millis()/60000 - print_job_start_ms/60000;
lcd.print(itostr2(time/60)); lcd.print(itostr2(time/60));
lcd.print(':'); lcd.print(':');
lcd.print(itostr2(time%60)); lcd.print(itostr2(time%60));
...@@ -656,7 +656,7 @@ static void lcd_implementation_status_screen() { ...@@ -656,7 +656,7 @@ static void lcd_implementation_status_screen() {
//Display both Status message line and Filament display on the last line //Display both Status message line and Filament display on the last line
#if HAS_LCD_FILAMENT_SENSOR || HAS_LCD_POWER_SENSOR #if HAS_LCD_FILAMENT_SENSOR || HAS_LCD_POWER_SENSOR
if (millis() < message_millis + 5000) { //Display both Status message line and Filament display on the last line if (millis() >= previous_lcd_status_ms + 5000) {
lcd_print(lcd_status_message); lcd_print(lcd_status_message);
} }
#if HAS_LCD_POWER_SENSOR #if HAS_LCD_POWER_SENSOR
...@@ -788,46 +788,45 @@ static void lcd_implementation_drawmenu_sddirectory(bool sel, uint8_t row, const ...@@ -788,46 +788,45 @@ static void lcd_implementation_drawmenu_sddirectory(bool sel, uint8_t row, const
#define lcd_implementation_drawmenu_function(sel, row, pstr, data) lcd_implementation_drawmenu_generic(sel, row, pstr, '>', ' ') #define lcd_implementation_drawmenu_function(sel, row, pstr, data) lcd_implementation_drawmenu_generic(sel, row, pstr, '>', ' ')
#ifdef LCD_HAS_STATUS_INDICATORS #ifdef LCD_HAS_STATUS_INDICATORS
static void lcd_implementation_update_indicators()
{ static void lcd_implementation_update_indicators() {
#if defined(LCD_I2C_PANELOLU2) || defined(LCD_I2C_VIKI) #if defined(LCD_I2C_PANELOLU2) || defined(LCD_I2C_VIKI)
//set the LEDS - referred to as backlights by the LiquidTWI2 library //set the LEDS - referred to as backlights by the LiquidTWI2 library
static uint8_t ledsprev = 0; static uint8_t ledsprev = 0;
uint8_t leds = 0; uint8_t leds = 0;
if (target_temperature_bed > 0) leds |= LED_A; if (target_temperature_bed > 0) leds |= LED_A;
if (target_temperature[0] > 0) leds |= LED_B; if (target_temperature[0] > 0) leds |= LED_B;
if (fanSpeed) leds |= LED_C; if (fanSpeed) leds |= LED_C;
#if HOTENDS > 1 #if HOTENDS > 1
if (target_temperature[1] > 0) leds |= LED_C; if (target_temperature[1] > 0) leds |= LED_C;
#endif
if (leds != ledsprev) {
lcd.setBacklight(leds);
ledsprev = leds;
}
#endif #endif
if (leds != ledsprev) { }
lcd.setBacklight(leds);
ledsprev = leds; #endif // LCD_HAS_STATUS_INDICATORS
}
#endif
}
#endif
#ifdef LCD_HAS_SLOW_BUTTONS #ifdef LCD_HAS_SLOW_BUTTONS
extern uint32_t blocking_enc;
extern millis_t next_button_update_ms;
static uint8_t lcd_implementation_read_slow_buttons()
{ static uint8_t lcd_implementation_read_slow_buttons() {
#ifdef LCD_I2C_TYPE_MCP23017 #ifdef LCD_I2C_TYPE_MCP23017
uint8_t slow_buttons; uint8_t slow_buttons;
// Reading these buttons this is likely to be too slow to call inside interrupt context // Reading these buttons this is likely to be too slow to call inside interrupt context
// so they are called during normal lcd_update // so they are called during normal lcd_update
slow_buttons = lcd.readButtons() << B_I2C_BTN_OFFSET; slow_buttons = lcd.readButtons() << B_I2C_BTN_OFFSET;
#if defined(LCD_I2C_VIKI) #ifdef LCD_I2C_VIKI
if(slow_buttons & (B_MI|B_RI)) { //LCD clicked if ((slow_buttons & (B_MI|B_RI)) && millis() < next_button_update_ms) // LCD clicked
if(blocking_enc > millis()) { slow_buttons &= ~(B_MI|B_RI); // Disable LCD clicked buttons if screen is updated
slow_buttons &= ~(B_MI|B_RI); // Disable LCD clicked buttons if screen is updated #endif
} return slow_buttons;
}
#endif #endif
return slow_buttons; }
#endif
} #endif // LCD_HAS_SLOW_BUTTONS
#endif
#endif //__ULTRALCD_IMPLEMENTATION_HITACHI_HD44780_H #endif //__ULTRALCD_IMPLEMENTATION_HITACHI_HD44780_H
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment