Commit d0cc94cf authored by MagoKimbra's avatar MagoKimbra

Merge remote-tracking branch 'origin/master' into Development

Conflicts:
	MarlinKimbra/temperature.cpp
	MarlinKimbra/ultralcd_implementation_hitachi_HD44780.h
parents b0afb3e3 749fc944
......@@ -43,6 +43,7 @@
* Laserbeam support
* Firmware test
* Support for a filament diameter sensor, which adjusts extrusion volume
* Support for a hall effect sensor for calucalte Wh. Example sensor ACS712 20A range Current Sensor Module.
The default baudrate is 250000. This baudrate has less jitter and hence errors than the usual 115200 baud, but is less supported by drivers and host-environments.
......
......@@ -20,7 +20,7 @@
// 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
// build by the user have been successfully uploaded into firmware.
#define STRING_VERSION " 4.0.3"
#define STRING_VERSION " 4.0.4"
#define STRING_URL "reprap.org"
#define STRING_VERSION_CONFIG_H __DATE__ " " __TIME__ // build date and time
#define STRING_CONFIG_H_AUTHOR "(none, default config)" // Who made the changes.
......@@ -652,6 +652,29 @@ your extruder heater takes 2 minutes to hit the target on heating.
//#define FILAMENT_LCD_DISPLAY
/**********************************************************************\
* Support for a current sensor (Hall effect sensor like ACS712) for measure the power consumption
* Since it's more simple to deal with, we measure the DC current and we assume that POWER_VOLTAGE that comes from your power supply it's almost stable.
* You have to change the SENSITIVITY with the one that you can find in the datasheet. (in case of ACS712: set to .100 for 20A version or set .066 for 30A version)
* With this module we measure the Printer power consumption ignoring the Power Supply power consumption, so we consider the EFFICIENCY of our supply to be 100% so without
* any power dispersion. If you want to approximately add the supply consumption you can decrease the EFFICIENCY to a value less than 100. Eg: 85 is a good value.
* You can find a better value measuring the AC current with a good multimeter and moltiple it with the mains voltage.
* MULTIMETER_WATT := MULTIMETER_CURRENT * MAINS_VOLTAGE
* Now you have a Wattage value that you can compare with the one measured from ACS712.
* NEW_EFFICENCY := (SENSOR_WATT*EFFICIENCY)/MULTIMETER_WATT
* For now this feature is to be consider BETA as i'll have to do some accurate test to see the affidability
**********************************************************************/
// Uncomment below to enable
//#define POWER_CONSUMPTION
#define POWER_VOLTAGE 12.00 //(V) The power supply OUT voltage
#define POWER_ZERO 2.5 //(V) The /\V coming out from the sensor when no current flow.
#define POWER_SENSITIVITY 0.066 //(V/A) How much increase V for 1A of increase
#define POWER_EFFICIENCY 100.0 //(%) The power efficency of the power supply
//When using an LCD, uncomment the line below to display the Power consumption sensor data on the last line instead of status. Status will appear for 5 sec.
//#define POWER_CONSUMPTION_LCD_DISPLAY
//=================================== Misc =================================
// Temperature status LEDs that display the hotend and bet temperature.
......
......@@ -325,6 +325,9 @@
#ifdef FILAMENT_LCD_DISPLAY
#error LCD_PROGRESS_BAR and FILAMENT_LCD_DISPLAY are not fully compatible. Comment out this line to use both.
#endif
#ifdef POWER_CONSUMPTION_LCD_DISPLAY
#error LCD_PROGRESS_BAR and POWER_CONSUMPTION_LCD_DISPLAY are not fully compatible. Comment out this line to use both.
#endif
#endif
......@@ -439,7 +442,7 @@ const unsigned int dropsegments=5; //everything with less than this number of st
// until then, intended retractions can be detected by moves that only extrude and the direction.
// the moves are than replaced by the firmware controlled ones.
// #define FWRETRACT //ONLY PARTIALLY TESTED
//#define FWRETRACT //ONLY PARTIALLY TESTED
#ifdef FWRETRACT
#define MIN_RETRACT 0.1 //minimum extruded mm to accept a automatic gcode retraction attempt
#define RETRACT_LENGTH 3 //default retract length (positive mm)
......@@ -448,7 +451,7 @@ const unsigned int dropsegments=5; //everything with less than this number of st
#define RETRACT_ZLIFT 0 //default retract Z-lift
#define RETRACT_RECOVER_LENGTH 0 //default additional recover length (mm, added to retract length when recovering)
#define RETRACT_RECOVER_LENGTH_SWAP 0 //default additional swap recover length (mm, added to retract length when recovering from extruder change)
#define RETRACT_RECOVER_FEEDRATE 8 //default feedrate for recovering from retraction (mm/s)
#define RETRACT_RECOVER_FEEDRATE 80 //default feedrate for recovering from retraction (mm/s)
#endif
//adds support for experimental filament exchange support M600; requires display
......
......@@ -298,14 +298,19 @@ extern int EtoPPressure;
extern unsigned char fanSpeedSoftPwm;
#endif
#ifdef FILAMENT_SENSOR
extern float filament_width_nominal; //holds the theoretical filament diameter ie., 3.00 or 1.75
extern bool filament_sensor; //indicates that filament sensor readings should control extrusion
extern float filament_width_meas; //holds the filament diameter as accurately measured
extern signed char measurement_delay[]; //ring buffer to delay measurement
#if (defined(FILAMENT_SENSOR) && defined(FILWIDTH_PIN) && FILWIDTH_PIN >= 0)
extern float filament_width_nominal; //holds the theoretical filament diameter ie., 3.00 or 1.75
extern bool filament_sensor; //indicates that filament sensor readings should control extrusion
extern float filament_width_meas; //holds the filament diameter as accurately measured
extern signed char measurement_delay[]; //ring buffer to delay measurement
extern int delay_index1, delay_index2; //index into ring buffer
extern float delay_dist; //delay distance counter
extern int meas_delay_cm; //delay distance
extern float delay_dist; //delay distance counter
extern int meas_delay_cm; //delay distance
#endif
#if (defined(POWER_CONSUMPTION) && defined(POWER_CONSUMPTION_PIN) && POWER_CONSUMPTION_PIN >= 0)
extern unsigned int power_consumption_meas; //holds the power consumption as accurately measured
extern unsigned long power_consumption_hour; //holds the power consumption per hour as accurately measured
#endif
#ifdef FWRETRACT
......@@ -348,4 +353,4 @@ void FirmwareTest();
extern void calculate_volumetric_multipliers();
#endif //__MARLIN_H
\ No newline at end of file
#endif //__MARLIN_H
......@@ -331,6 +331,10 @@ uint8_t debugLevel = 0;
int EtoPPressure = 0;
#endif //BARICUDA
#ifdef FILAMENTCHANGEENABLE
bool filament_changing = false;
#endif
#ifdef FWRETRACT
bool autoretract_enabled = false;
bool retracted[EXTRUDERS] = { false
......@@ -377,16 +381,21 @@ uint8_t debugLevel = 0;
static float delta[3] = { 0, 0, 0 };
#endif //SCARA
#ifdef FILAMENT_SENSOR
#if (defined(FILAMENT_SENSOR) && defined(FILWIDTH_PIN) && FILWIDTH_PIN >= 0)
//Variables for Filament Sensor input
float filament_width_nominal=DEFAULT_NOMINAL_FILAMENT_DIA; //Set nominal filament width, can be changed with M404
bool filament_sensor=false; //M405 turns on filament_sensor control, M406 turns it off
float filament_width_meas=DEFAULT_MEASURED_FILAMENT_DIA; //Stores the measured filament diameter
signed char measurement_delay[MAX_MEASUREMENT_DELAY+1]; //ring buffer to delay measurement store extruder factor after subtracting 100
int delay_index1=0; //index into ring buffer
int delay_index2=-1; //index into ring buffer - set to -1 on startup to indicate ring buffer needs to be initialized
float delay_dist=0; //delay distance counter
int meas_delay_cm = MEASUREMENT_DELAY_CM; //distance delay setting
bool filament_sensor=false; //M405 turns on filament_sensor control, M406 turns it off
float filament_width_meas=DEFAULT_MEASURED_FILAMENT_DIA; //Stores the measured filament diameter
signed char measurement_delay[MAX_MEASUREMENT_DELAY+1]; //ring buffer to delay measurement store extruder factor after subtracting 100
int delay_index1=0; //index into ring buffer
int delay_index2=-1; //index into ring buffer - set to -1 on startup to indicate ring buffer needs to be initialized
float delay_dist=0; //delay distance counter
int meas_delay_cm = MEASUREMENT_DELAY_CM; //distance delay setting
#endif
#if (defined(POWER_CONSUMPTION) && defined(POWER_CONSUMPTION_PIN) && POWER_CONSUMPTION_PIN >= 0)
unsigned int power_consumption_meas = 0;
unsigned long power_consumption_hour = 0.0;
#endif
#ifdef LASERBEAM
......@@ -3823,6 +3832,7 @@ inline void gcode_M204() {
#ifdef FILAMENTCHANGEENABLE
//M600: Pause for filament change X[pos] Y[pos] Z[relative lift] E[initial retract] L[later retract distance for removal]
inline void gcode_M600() {
filament_changing = true;
float target[NUM_AXIS];
for (int i=0; i < NUM_AXIS; i++) target[i] = lastpos[i] = current_position[i];
......@@ -3973,6 +3983,7 @@ inline void gcode_M204() {
for(int8_t i=0; i < NUM_AXIS; i++) current_position[i]=lastpos[i];
plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
#endif
filament_changing = false;
}
#endif //FILAMENTCHANGEENABLE
......@@ -5545,17 +5556,15 @@ void process_commands()
break;
#endif // NABLE_AUTO_BED_LEVELING
#ifdef FILAMENT_SENSOR
#if (defined(FILAMENT_SENSOR) && defined(FILWIDTH_PIN) && FILWIDTH_PIN >= 0)
case 404: //M404 Enter the nominal filament width (3mm, 1.75mm ) N<3.0> or display nominal filament width
{
#if (FILWIDTH_PIN > -1)
if(code_seen('D')) filament_width_nominal=code_value();
else
{
SERIAL_PROTOCOLPGM("Filament dia (nominal mm):");
SERIAL_PROTOCOLLN(filament_width_nominal);
}
#endif
if(code_seen('D')) filament_width_nominal=code_value();
else
{
SERIAL_PROTOCOLPGM("Filament dia (nominal mm):");
SERIAL_PROTOCOLLN(filament_width_nominal);
}
}
break;
case 405: //M405 Turn on filament sensor for control
......@@ -6484,22 +6493,20 @@ void manage_inactivity(bool ignore_stepper_queue/*=false*/) //default argument s
controllerFan(); //Check if fan should be turned on to cool stepper drivers down
#endif
#ifdef EXTRUDER_RUNOUT_PREVENT
if( (millis() - previous_millis_cmd) > EXTRUDER_RUNOUT_SECONDS*1000 )
if(degHotend(active_extruder)>EXTRUDER_RUNOUT_MINTEMP)
if(!debugDryrun() && !axis_is_moving && !filament_changing && (millis() - axis_last_activity) > EXTRUDER_RUNOUT_SECONDS*1000 && degHotend(active_extruder)>EXTRUDER_RUNOUT_MINTEMP)
{
bool oldstatus=READ(E0_ENABLE_PIN);
enable_e0();
float oldepos=current_position[E_AXIS];
float oldedes=destination[E_AXIS];
plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS],
bool oldstatus=READ(E0_ENABLE_PIN);
enable_e0();
float oldepos=current_position[E_AXIS];
float oldedes=destination[E_AXIS];
plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS],
destination[E_AXIS]+EXTRUDER_RUNOUT_EXTRUDE*EXTRUDER_RUNOUT_ESTEPS/axis_steps_per_unit[active_extruder+3],
EXTRUDER_RUNOUT_SPEED/60.*EXTRUDER_RUNOUT_ESTEPS/axis_steps_per_unit[active_extruder+3], active_extruder, active_driver);
current_position[E_AXIS]=oldepos;
destination[E_AXIS]=oldedes;
plan_set_e_position(oldepos);
previous_millis_cmd=millis();
st_synchronize();
WRITE(E0_ENABLE_PIN,oldstatus);
current_position[E_AXIS]=oldepos;
destination[E_AXIS]=oldedes;
plan_set_e_position(oldepos);
st_synchronize();
WRITE(E0_ENABLE_PIN,oldstatus);
}
#endif
#if defined(DUAL_X_CARRIAGE)
......
......@@ -267,19 +267,35 @@ static void lcd_implementation_status_screen() {
// Status line
u8g.setFont(FONT_STATUSMENU);
u8g.setPrintPos(0,63);
#ifndef FILAMENT_LCD_DISPLAY
u8g.print(lcd_status_message);
#else
#if (defined(FILAMENT_SENSOR) && defined(FILWIDTH_PIN) && FILWIDTH_PIN >= 0) && defined(FILAMENT_LCD_DISPLAY) || (defined(POWER_CONSUMPTION) && defined(POWER_CONSUMPTION_PIN) && POWER_CONSUMPTION_PIN >= 0) && defined(POWER_CONSUMPTION_LCD_DISPLAY)
if (millis() < message_millis + 5000) { //Display both Status message line and Filament display on the last line
u8g.print(lcd_status_message);
}
else {
lcd_printPGM(PSTR("dia:"));
u8g.print(ftostr12ns(filament_width_meas));
lcd_printPGM(PSTR(" factor:"));
u8g.print(itostr3(volumetric_multiplier[active_extruder] * 100));
u8g.print('%');
}
#if (defined(POWER_CONSUMPTION) && defined(POWER_CONSUMPTION_PIN) && POWER_CONSUMPTION_PIN >= 0) && defined(POWER_CONSUMPTION_LCD_DISPLAY)
#if (defined(FILAMENT_SENSOR) && defined(FILWIDTH_PIN) && FILWIDTH_PIN >= 0) && defined(FILAMENT_LCD_DISPLAY)
else if (millis() < message_millis + 10000)
#else
else
#endif
{
lcd_printPGM(PSTR("P:"));
u8g.print(itostr3(power_consumption_meas));
lcd_printPGM(PSTR("W C:"));
u8g.print(ltostr7(power_consumption_hour));
lcd_printPGM(PSTR("Wh"));
}
#endif
#if (defined(FILAMENT_SENSOR) && defined(FILWIDTH_PIN) && FILWIDTH_PIN >= 0) && defined(FILAMENT_LCD_DISPLAY)
else {
lcd_printPGM(PSTR("D:"));
u8g.print(ftostr12ns(filament_width_meas));
lcd_printPGM(PSTR("mm F:"));
u8g.print(itostr3(volumetric_multiplier[active_extruder] * 100));
u8g.print('%');
}
#endif
#else
u8g.print(lcd_status_message);
#endif
}
......
......@@ -4488,6 +4488,10 @@ DaveX plan for Teensylu/printrboard-type pinouts (ref teensylu & sprinter) for a
#ifdef FILAMENT_END_SWITCH
#define PAUSE_PIN 19
#endif
#ifdef POWER_CONSUMPTION
#define POWER_CONSUMPTION_PIN 4 // ANALOG NUMBERING
#endif
/****************************************************************************************/
......
......@@ -78,12 +78,12 @@ float mintravelfeedrate;
unsigned long axis_steps_per_sqr_second[3 + EXTRUDERS];
#ifdef ENABLE_AUTO_BED_LEVELING
// this holds the required transform to compensate for bed level
matrix_3x3 plan_bed_level_matrix = {
1.0, 0.0, 0.0,
0.0, 1.0, 0.0,
0.0, 0.0, 1.0
};
// this holds the required transform to compensate for bed level
matrix_3x3 plan_bed_level_matrix = {
1.0, 0.0, 0.0,
0.0, 1.0, 0.0,
0.0, 0.0, 1.0
};
#endif // #ifdef ENABLE_AUTO_BED_LEVELING
// The current position of the tool in absolute steps
......@@ -92,26 +92,26 @@ static float previous_speed[NUM_AXIS]; // Speed of previous path line segment
static float previous_nominal_speed; // Nominal speed of previous path line segment
#ifdef AUTOTEMP
float autotemp_max=250;
float autotemp_min=210;
float autotemp_factor=0.1;
bool autotemp_enabled=false;
float autotemp_max = 250;
float autotemp_min = 210;
float autotemp_factor = 0.1;
bool autotemp_enabled = false;
#endif
unsigned char g_uc_extruder_last_move[4] = {0,0,0,0};
//===========================================================================
//=================semi-private variables, used in inline functions =====
//=================semi-private variables, used in inline functions =========
//===========================================================================
block_t block_buffer[BLOCK_BUFFER_SIZE]; // A ring buffer for motion instfructions
volatile unsigned char block_buffer_head; // Index of the next block to be pushed
volatile unsigned char block_buffer_tail; // Index of the block to process now
block_t block_buffer[BLOCK_BUFFER_SIZE]; // A ring buffer for motion instructions
volatile unsigned char block_buffer_head; // Index of the next block to be pushed
volatile unsigned char block_buffer_tail; // Index of the block to process now
//===========================================================================
//=============================private variables ============================
//===========================================================================
#ifdef PREVENT_DANGEROUS_EXTRUDE
float extrude_min_temp=EXTRUDE_MINTEMP;
float extrude_min_temp = EXTRUDE_MINTEMP;
#endif
#ifdef XY_FREQUENCY_LIMIT
#define MAX_FREQ_TIME (1000000.0/XY_FREQUENCY_LIMIT)
......@@ -121,7 +121,7 @@ static long x_segment_time[3]={MAX_FREQ_TIME + 1,0,0}; // Segment times (in
static long y_segment_time[3]={MAX_FREQ_TIME + 1,0,0};
#endif
#ifdef FILAMENT_SENSOR
#if (defined(FILAMENT_SENSOR) && defined(FILWIDTH_PIN) && FILWIDTH_PIN >= 0)
static char meas_sample; //temporary variable to hold filament measurement sample
#endif
......@@ -151,15 +151,9 @@ static int8_t prev_block_index(int8_t block_index) {
// Calculates the distance (not time) it takes to accelerate from initial_rate to target_rate using the
// given acceleration:
FORCE_INLINE float estimate_acceleration_distance(float initial_rate, float target_rate, float acceleration)
{
if (acceleration!=0) {
return((target_rate*target_rate-initial_rate*initial_rate)/
(2.0*acceleration));
}
else {
return 0.0; // acceleration was 0, set acceleration distance to 0
}
FORCE_INLINE float estimate_acceleration_distance(float initial_rate, float target_rate, float acceleration) {
if (acceleration == 0) return 0; // acceleration was 0, set acceleration distance to 0
return (target_rate * target_rate - initial_rate * initial_rate) / (acceleration * 2);
}
// This function gives you the point at which you must start braking (at the rate of -acceleration) if
......@@ -167,54 +161,42 @@ FORCE_INLINE float estimate_acceleration_distance(float initial_rate, float targ
// a total travel of distance. This can be used to compute the intersection point between acceleration and
// deceleration in the cases where the trapezoid has no plateau (i.e. never reaches maximum speed)
FORCE_INLINE float intersection_distance(float initial_rate, float final_rate, float acceleration, float distance)
{
if (acceleration!=0) {
return((2.0*acceleration*distance-initial_rate*initial_rate+final_rate*final_rate)/
(4.0*acceleration) );
}
else {
return 0.0; // acceleration was 0, set intersection distance to 0
}
FORCE_INLINE float intersection_distance(float initial_rate, float final_rate, float acceleration, float distance) {
if (acceleration == 0) return 0; // acceleration was 0, set intersection distance to 0
return (acceleration * 2 * distance - initial_rate * initial_rate + final_rate * final_rate) / (acceleration * 4);
}
// Calculates trapezoid parameters so that the entry- and exit-speed is compensated by the provided factors.
void calculate_trapezoid_for_block(block_t *block, float entry_factor, float exit_factor) {
unsigned long initial_rate = ceil(block->nominal_rate*entry_factor); // (step/min)
unsigned long final_rate = ceil(block->nominal_rate*exit_factor); // (step/min)
unsigned long initial_rate = ceil(block->nominal_rate * entry_factor); // (step/min)
unsigned long final_rate = ceil(block->nominal_rate * exit_factor); // (step/min)
// Limit minimal step rate (Otherwise the timer will overflow.)
if(initial_rate <120) {
initial_rate=120;
}
if(final_rate < 120) {
final_rate=120;
}
if (initial_rate < 120) initial_rate = 120;
if (final_rate < 120) final_rate = 120;
long acceleration = block->acceleration_st;
int32_t accelerate_steps =
ceil(estimate_acceleration_distance(initial_rate, block->nominal_rate, acceleration));
int32_t decelerate_steps =
floor(estimate_acceleration_distance(block->nominal_rate, final_rate, -acceleration));
int32_t accelerate_steps = ceil(estimate_acceleration_distance(initial_rate, block->nominal_rate, acceleration));
int32_t decelerate_steps = floor(estimate_acceleration_distance(block->nominal_rate, final_rate, -acceleration));
// Calculate the size of Plateau of Nominal Rate.
int32_t plateau_steps = block->step_event_count-accelerate_steps-decelerate_steps;
int32_t plateau_steps = block->step_event_count - accelerate_steps - decelerate_steps;
// Is the Plateau of Nominal Rate smaller than nothing? That means no cruising, and we will
// have to use intersection_distance() to calculate when to abort acceleration and start braking
// in order to reach the final_rate exactly at the end of this block.
if (plateau_steps < 0) {
accelerate_steps = ceil(intersection_distance(initial_rate, final_rate, acceleration, block->step_event_count));
accelerate_steps = max(accelerate_steps,0); // Check limits due to numerical round-off
accelerate_steps = min((uint32_t)accelerate_steps,block->step_event_count);//(We can cast here to unsigned, because the above line ensures that we are above zero)
accelerate_steps = max(accelerate_steps, 0); // Check limits due to numerical round-off
accelerate_steps = min((uint32_t)accelerate_steps, block->step_event_count);//(We can cast here to unsigned, because the above line ensures that we are above zero)
plateau_steps = 0;
}
#ifdef ADVANCE
volatile long initial_advance = block->advance*entry_factor*entry_factor;
volatile long final_advance = block->advance*exit_factor*exit_factor;
#endif // ADVANCE
#ifdef ADVANCE
volatile long initial_advance = block->advance * entry_factor * entry_factor;
volatile long final_advance = block->advance * exit_factor * exit_factor;
#endif // ADVANCE
// block->accelerate_until = accelerate_steps;
// block->decelerate_after = accelerate_steps+plateau_steps;
......@@ -861,7 +843,7 @@ Having the real displacement of the head, we can calculate the total movement le
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
#ifdef FILAMENT_SENSOR
#if (defined(FILAMENT_SENSOR) && defined(FILWIDTH_PIN) && FILWIDTH_PIN >= 0)
//FMM update ring buffer used for delay with filament measurements
......
......@@ -59,6 +59,7 @@
#define HAS_TEMP_3 (defined(TEMP_3_PIN) && TEMP_3_PIN >= 0)
#define HAS_TEMP_BED (defined(TEMP_BED_PIN) && TEMP_BED_PIN >= 0)
#define HAS_FILAMENT_SENSOR (defined(FILAMENT_SENSOR) && defined(FILWIDTH_PIN) && FILWIDTH_PIN >= 0)
#define HAS_POWER_CONSUMPTION_SENSOR (defined(POWER_CONSUMPTION) && defined(POWER_CONSUMPTION_PIN) && POWER_CONSUMPTION_PIN >= 0)
#define HAS_HEATER_0 (defined(HEATER_0_PIN) && HEATER_0_PIN >= 0)
#define HAS_HEATER_1 (defined(HEATER_1_PIN) && HEATER_1_PIN >= 0)
#define HAS_HEATER_2 (defined(HEATER_2_PIN) && HEATER_2_PIN >= 0)
......@@ -79,7 +80,7 @@
#ifdef PID_dT
#undef PID_dT
#endif
#define PID_dT ((OVERSAMPLENR * 12.0)/(F_CPU / 64.0 / 256.0))
#define PID_dT ((OVERSAMPLENR * 14.0)/(F_CPU / 64.0 / 256.0))
int target_temperature[HOTENDS] = { 0 };
int current_temperature_raw[HOTENDS] = { 0 };
......@@ -112,9 +113,14 @@ unsigned char soft_pwm_bed;
volatile int babystepsTodo[3] = { 0 };
#endif
#ifdef FILAMENT_SENSOR
#if HAS_FILAMENT_SENSOR
int current_raw_filwidth = 0; //Holds measured filament diameter - one extruder only
#endif
#if HAS_POWER_CONSUMPTION_SENSOR
int current_raw_powconsumption = 0; //Holds measured power consumption
#endif
//===========================================================================
//=============================private variables============================
//===========================================================================
......@@ -189,7 +195,7 @@ static void updateTemperaturesFromRawValues();
#define SOFT_PWM_SCALE 0
#endif
#ifdef FILAMENT_SENSOR
#if HAS_FILAMENT_SENSOR
static int meas_shift_index; //used to point to a delayed sample in buffer for filament width sensor
#endif
......@@ -734,7 +740,7 @@ void manage_heater() {
#endif //TEMP_SENSOR_BED != 0
// Control the extruder rate based on the width sensor
#ifdef FILAMENT_SENSOR
#if HAS_FILAMENT_SENSOR
if (filament_sensor) {
meas_shift_index = delay_index1 - meas_delay_cm;
if (meas_shift_index < 0) meas_shift_index += MAX_MEASUREMENT_DELAY + 1; //loop around buffer if needed
......@@ -746,7 +752,7 @@ void manage_heater() {
if (vm < 0.01) vm = 0.01;
volumetric_multiplier[FILAMENT_SENSOR_EXTRUDER_NUM] = vm;
}
#endif //FILAMENT_SENSOR
#endif //HAS_FILAMENT_SENSOR
}
#define PGM_RD_W(x) (short)pgm_read_word(&x)
......@@ -846,6 +852,19 @@ static void updateTemperaturesFromRawValues() {
#if HAS_FILAMENT_SENSOR
filament_width_meas = analog2widthFil();
#endif
#if HAS_POWER_CONSUMPTION_SENSOR
static float watt_overflow = 0.0;
static unsigned long last_power_update = millis();
unsigned long temp_last_power_update = millis();
float power_temp = analog2power();
power_consumption_meas = (unsigned int)power_temp;
watt_overflow += (power_temp*(temp_last_power_update-last_power_update))/3600000.0;
if(watt_overflow >= 1.0) {
power_consumption_hour++;
watt_overflow--;
}
last_power_update = temp_last_power_update;
#endif
//Reset the watchdog after we know we have a temperature measurement.
watchdog_reset();
......@@ -855,8 +874,7 @@ static void updateTemperaturesFromRawValues() {
}
#ifdef FILAMENT_SENSOR
#if HAS_FILAMENT_SENSOR
// Convert raw Filament Width to millimeters
float analog2widthFil() {
return current_raw_filwidth / (1024 * OVERSAMPLENR) * 5.0;
......@@ -873,6 +891,15 @@ static void updateTemperaturesFromRawValues() {
#endif
<<<<<<< HEAD
=======
#if HAS_POWER_CONSUMPTION_SENSOR
// Convert raw Power Consumption to watt
float analog2power() {
return (((((5.0 * current_raw_powconsumption) / (1024.0 * OVERSAMPLENR)) - POWER_ZERO) * (POWER_VOLTAGE * 100.0)) / (POWER_SENSITIVITY * POWER_EFFICIENCY));
}
#endif
>>>>>>> origin/master
void tp_init()
{
......@@ -967,6 +994,9 @@ void tp_init()
#if HAS_FILAMENT_SENSOR
ANALOG_SELECT(FILWIDTH_PIN);
#endif
#if HAS_POWER_CONSUMPTION_SENSOR
ANALOG_SELECT(POWER_CONSUMPTION_PIN);
#endif
// Use timer0 for temperature measurement
// Interleave temperature interrupt with millies interrupt
......@@ -1231,6 +1261,8 @@ enum TempState {
MeasureTemp_3,
Prepare_FILWIDTH,
Measure_FILWIDTH,
Prepare_POWCONSUMPTION,
Measure_POWCONSUMPTION,
StartupDelay // Startup, delay initial temp reading a tiny bit so the hardware can settle
};
......@@ -1274,6 +1306,10 @@ ISR(TIMER0_COMPB_vect) {
static unsigned long raw_filwidth_value = 0;
#endif
#if HAS_POWER_CONSUMPTION_SENSOR
static unsigned long raw_powconsumption_value = 0;
#endif
#ifndef SLOW_PWM_HEATERS
/**
* standard PWM modulation
......@@ -1526,6 +1562,21 @@ ISR(TIMER0_COMPB_vect) {
raw_filwidth_value += ((unsigned long)ADC<<7); //add new ADC reading
}
#endif
temp_state = Prepare_POWCONSUMPTION;
break;
case Prepare_POWCONSUMPTION:
#if HAS_POWER_CONSUMPTION_SENSOR
START_ADC(POWER_CONSUMPTION_PIN);
#endif
lcd_buttons_update();
temp_state = Measure_POWCONSUMPTION;
break;
case Measure_POWCONSUMPTION:
#if HAS_POWER_CONSUMPTION_SENSOR
// raw_powconsumption_value += ADC; //remove to use an IIR filter approach
raw_powconsumption_value -= (raw_powconsumption_value>>7); //multiply raw_powconsumption_value by 127/128
raw_powconsumption_value += ((unsigned long)((ADC < (POWER_ZERO*1024)/5.0) ? (1024 - ADC) : (ADC))<<7); //add new ADC reading
#endif
temp_state = PrepareTemp_0;
temp_count++;
break;
......@@ -1564,6 +1615,10 @@ ISR(TIMER0_COMPB_vect) {
#if HAS_FILAMENT_SENSOR
current_raw_filwidth = raw_filwidth_value >> 10; // Divide to get to 0-16384 range since we used 1/128 IIR filter approach
#endif
// Power Sensor - can be read any time since IIR filtering is used
#if HAS_POWER_CONSUMPTION_SENSOR
current_raw_powconsumption = raw_powconsumption_value >> 10; // Divide to get to 0-16384 range since we used 1/128 IIR filter approach
#endif
temp_meas_ready = true;
temp_count = 0;
......
......@@ -30,12 +30,17 @@
void tp_init(); //initialize the heating
void manage_heater(); //it is critical that this is called periodically.
#ifdef FILAMENT_SENSOR
// For converting raw Filament Width to milimeters
float analog2widthFil();
// For converting raw Filament Width to an extrusion ratio
int widthFil_to_size_ratio();
#if (defined(FILAMENT_SENSOR) && defined(FILWIDTH_PIN) && FILWIDTH_PIN >= 0)
// For converting raw Filament Width to milimeters
float analog2widthFil();
// For converting raw Filament Width to an extrusion ratio
int widthFil_to_size_ratio();
#endif
#if (defined(POWER_CONSUMPTION) && defined(POWER_CONSUMPTION_PIN) && POWER_CONSUMPTION_PIN >= 0)
// For converting raw Power Consumption to watt
float analog2power();
#endif
// low level conversion routines
......
......@@ -33,7 +33,8 @@ int gumPreheatFanSpeed;
const long baudrates[] = {9600,14400,19200,28800,38400,56000,115200,250000};
int baudrate_position = -1;
#ifdef FILAMENT_LCD_DISPLAY
#if (defined(FILAMENT_SENSOR) && defined(FILWIDTH_PIN) && FILWIDTH_PIN >= 0) && defined(FILAMENT_LCD_DISPLAY) || (defined(POWER_CONSUMPTION) && defined(POWER_CONSUMPTION_PIN) && POWER_CONSUMPTION_PIN >= 0) && defined(POWER_CONSUMPTION_LCD_DISPLAY)
unsigned long message_millis = 0;
#endif
......@@ -310,6 +311,12 @@ static void lcd_status_screen()
lcd_status_update_delay = 10; /* redraw the main screen every second. This is easier then trying keep track of all things that change on the screen */
}
#if (defined(FILAMENT_SENSOR) && defined(FILWIDTH_PIN) && FILWIDTH_PIN >= 0) && defined(FILAMENT_LCD_DISPLAY) || (defined(POWER_CONSUMPTION) && defined(POWER_CONSUMPTION_PIN) && POWER_CONSUMPTION_PIN >= 0) && defined(POWER_CONSUMPTION_LCD_DISPLAY)
if (millis() > message_millis + 15000) message_millis = millis();
#else
if (millis() > message_millis + 10000) message_millis = millis();
#endif
#ifdef ULTIPANEL
bool current_click = LCD_CLICKED;
......@@ -338,9 +345,6 @@ static void lcd_status_screen()
currentMenu == lcd_status_screen
#endif
);
#ifdef FILAMENT_LCD_DISPLAY
message_millis = millis(); // get status message to show up for a while
#endif
}
#ifdef ULTIPANEL_FEEDMULTIPLY
......@@ -685,9 +689,9 @@ void config_lcd_level_bed()
void lcd_level_bed()
{
if(ChangeScreen){
lcd.clear();
switch(pageShowInfo){
if(ChangeScreen) {
lcd.clear();
switch(pageShowInfo) {
case 0:
{
......@@ -1571,10 +1575,6 @@ void lcd_finishstatus() {
progressBarTick = millis();
#endif
lcdDrawUpdate = 2;
#ifdef FILAMENT_LCD_DISPLAY
message_millis = millis(); //get status message to show up for a while
#endif
}
void lcd_setstatus(const char* message) {
......
......@@ -56,7 +56,7 @@
extern bool cancel_heatup;
#ifdef FILAMENT_LCD_DISPLAY
#if (defined(FILAMENT_SENSOR) && defined(FILWIDTH_PIN) && FILWIDTH_PIN >= 0) && defined(FILAMENT_LCD_DISPLAY) || (defined(POWER_CONSUMPTION) && defined(POWER_CONSUMPTION_PIN) && POWER_CONSUMPTION_PIN >= 0) && defined(POWER_CONSUMPTION_LCD_DISPLAY)
extern unsigned long message_millis;
#endif
......
......@@ -468,10 +468,17 @@ static void lcd_implementation_status_screen() {
lcd.print('/');
lcd.print(itostr3left(tTarget));
<<<<<<< HEAD
#if HOTENDS > 1 || TEMP_SENSOR_BED != 0
//If we have an 2nd extruder or heated bed, show that in the top right corner
lcd.setCursor(8, 0);
#if HOTENDS > 1
=======
#if (EXTRUDERS > 1 && !defined(SINGLENOZZLE)) || TEMP_SENSOR_BED != 0
//If we have an 2nd extruder or heated bed, show that in the top right corner
lcd.setCursor(8, 0);
#if EXTRUDERS > 1 && !defined(SINGLENOZZLE)
>>>>>>> origin/master
tHotend = int(degHotend(1) + 0.5);
tTarget = int(degTargetHotend(1) + 0.5);
lcd.print(LCD_STR_THERMOMETER[0]);
......@@ -483,7 +490,11 @@ static void lcd_implementation_status_screen() {
lcd.print(itostr3(tHotend));
lcd.print('/');
lcd.print(itostr3left(tTarget));
<<<<<<< HEAD
#endif //HOTENDS > 1 || TEMP_SENSOR_BED != 0
=======
#endif //(EXTRUDERS > 1 && !defined(SINGLENOZZLE)) || TEMP_SENSOR_BED != 0
>>>>>>> origin/master
#else//LCD_WIDTH > 19
lcd.setCursor(0, 0);
......@@ -494,10 +505,17 @@ static void lcd_implementation_status_screen() {
lcd_printPGM(PSTR(LCD_STR_DEGREE " "));
if (tTarget < 10) lcd.print(' ');
<<<<<<< HEAD
#if HOTENDS > 1 || TEMP_SENSOR_BED != 0
//If we have an 2nd extruder or heated bed, show that in the top right corner
lcd.setCursor(10, 0);
#if HOTENDS > 1
=======
#if (EXTRUDERS > 1 && !defined(SINGLENOZZLE)) || TEMP_SENSOR_BED != 0
//If we have an 2nd extruder or heated bed, show that in the top right corner
lcd.setCursor(10, 0);
#if EXTRUDERS > 1 && !defined(SINGLENOZZLE)
>>>>>>> origin/master
tHotend = int(degHotend(1) + 0.5);
tTarget = int(degTargetHotend(1) + 0.5);
lcd.print(LCD_STR_THERMOMETER[0]);
......@@ -511,6 +529,7 @@ static void lcd_implementation_status_screen() {
lcd.print(itostr3left(tTarget));
lcd_printPGM(PSTR(LCD_STR_DEGREE " "));
if (tTarget < 10) lcd.print(' ');
<<<<<<< HEAD
#endif//HOTENDS > 1 || TEMP_SENSOR_BED != 0
#endif//LCD_WIDTH > 19
......@@ -560,6 +579,58 @@ static void lcd_implementation_status_screen() {
#endif //LCD_HEIGHT > 2
#if LCD_HEIGHT > 3
=======
#endif//(EXTRUDERS > 1 && !defined(SINGLENOZZLE)) || TEMP_SENSOR_BED != 0
#endif//LCD_WIDTH > 19
#if LCD_HEIGHT > 2
//Lines 2 for 4 line LCD
# if LCD_WIDTH < 20
# ifdef SDSUPPORT
lcd.setCursor(0, 2);
lcd_printPGM(PSTR("SD"));
if (IS_SD_PRINTING)
lcd.print(itostr3(card.percentDone()));
else
lcd_printPGM(PSTR("---"));
lcd.print('%');
# endif//SDSUPPORT
# else//LCD_WIDTH > 19
# if EXTRUDERS > 1 && TEMP_SENSOR_BED != 0 && !defined(SINGLENOZZLE)
//If we both have a 2nd extruder and a heated bed, show the heated bed temp on the 2nd line on the left, as the first line is filled with extruder temps
tHotend=int(degBed() + 0.5);
tTarget=int(degTargetBed() + 0.5);
lcd.setCursor(0, 1);
lcd.print(LCD_STR_BEDTEMP[0]);
lcd.print(itostr3(tHotend));
lcd.print('/');
lcd.print(itostr3left(tTarget));
lcd_printPGM(PSTR(LCD_STR_DEGREE " "));
if (tTarget < 10)
lcd.print(' ');
# else
lcd.setCursor(0,1);
# ifdef DELTA
lcd.print('X');
lcd.print(ftostr30(current_position[X_AXIS]));
lcd_printPGM(PSTR(" Y"));
lcd.print(ftostr30(current_position[Y_AXIS]));
# else
lcd.print('X');
lcd.print(ftostr3(current_position[X_AXIS]));
lcd_printPGM(PSTR(" Y"));
lcd.print(ftostr3(current_position[Y_AXIS]));
# endif // DELTA
# endif//EXTRUDERS > 1 || TEMP_SENSOR_BED != 0
# endif//LCD_WIDTH > 19
lcd.setCursor(LCD_WIDTH - 8, 1);
lcd.print('Z');
lcd.print(ftostr32sp(current_position[Z_AXIS] + 0.00001));
#endif//LCD_HEIGHT > 2
#if LCD_HEIGHT > 3
>>>>>>> origin/master
lcd.setCursor(0, 2);
lcd.print(LCD_STR_FEEDRATE[0]);
lcd.print(itostr3(feedmultiply));
......@@ -617,6 +688,7 @@ static void lcd_implementation_status_screen() {
#endif //LCD_PROGRESS_BAR
//Display both Status message line and Filament display on the last line
<<<<<<< HEAD
#ifdef FILAMENT_LCD_DISPLAY
if (message_millis + 5000 <= millis()) { //display any status for the first 5 sec after screen is initiated
lcd_printPGM(PSTR("Dia "));
......@@ -625,10 +697,38 @@ static void lcd_implementation_status_screen() {
lcd.print(itostr3(100.0*volumetric_multiplier[FILAMENT_SENSOR_EXTRUDER_NUM]));
lcd.print('%');
return;
=======
#if (defined(FILAMENT_SENSOR) && defined(FILWIDTH_PIN) && FILWIDTH_PIN >= 0) && defined(FILAMENT_LCD_DISPLAY) || (defined(POWER_CONSUMPTION) && defined(POWER_CONSUMPTION_PIN) && POWER_CONSUMPTION_PIN >= 0) && defined(POWER_CONSUMPTION_LCD_DISPLAY)
if (millis() < message_millis + 5000) { //Display both Status message line and Filament display on the last line
lcd.print(lcd_status_message);
>>>>>>> origin/master
}
#endif //FILAMENT_LCD_DISPLAY
lcd.print(lcd_status_message);
#if (defined(POWER_CONSUMPTION) && defined(POWER_CONSUMPTION_PIN) && POWER_CONSUMPTION_PIN >= 0) && defined(POWER_CONSUMPTION_LCD_DISPLAY)
#if (defined(FILAMENT_SENSOR) && defined(FILWIDTH_PIN) && FILWIDTH_PIN >= 0) && defined(FILAMENT_LCD_DISPLAY)
else if (millis() < message_millis + 10000)
#else
else
#endif
{
lcd_printPGM(PSTR("P:"));
lcd.print(itostr3(power_consumption_meas));
lcd_printPGM(PSTR("W C:"));
lcd.print(ltostr7(power_consumption_hour));
lcd_printPGM(PSTR("Wh"));
}
#endif
#if (defined(FILAMENT_SENSOR) && defined(FILWIDTH_PIN) && FILWIDTH_PIN >= 0) && defined(FILAMENT_LCD_DISPLAY)
else {
lcd_printPGM(PSTR("D:"));
lcd.print(ftostr12ns(filament_width_meas));
lcd_printPGM(PSTR("mm F:"));
lcd.print(itostr3(100.0 * volumetric_multiplier[FILAMENT_SENSOR_EXTRUDER_NUM]));
lcd.print('%');
return;
}
#else
lcd.print(lcd_status_message);
#endif
}
static void lcd_implementation_drawmenu_generic(bool sel, uint8_t row, const char* pstr, char pre_char, char post_char) {
......
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