Merge pull request #570 from hg42/separate-INVERTING-macros-for-MIN-and-MAX-endstops

separate INVERTING for MIN and MAX endstops (6 #defines instead of 3)
This commit is contained in:
ErikZalm 2013-08-02 13:15:30 -07:00
commit 4187b637a5
4 changed files with 189 additions and 183 deletions

View File

@ -141,7 +141,7 @@
#define TEMP_SENSOR_BED 0
// This makes temp sensor 1 a redundant sensor for sensor 0. If the temperatures difference between these sensors is to high the print will be aborted.
//#define TEMP_SENSOR_1_AS_REDUNDANT
//#define TEMP_SENSOR_1_AS_REDUNDANT
#define MAX_REDUNDANT_TEMP_SENSOR_DIFF 10
// Actual temperature must be close to target for this long before M109 returns success
@ -278,9 +278,12 @@
#endif
// The pullups are needed if you directly connect a mechanical endswitch between the signal and ground pins.
const bool X_ENDSTOPS_INVERTING = true; // set to true to invert the logic of the endstops.
const bool Y_ENDSTOPS_INVERTING = true; // set to true to invert the logic of the endstops.
const bool Z_ENDSTOPS_INVERTING = true; // set to true to invert the logic of the endstops.
const bool X_MIN_ENDSTOP_INVERTING = true; // set to true to invert the logic of the endstop.
const bool Y_MIN_ENDSTOP_INVERTING = true; // set to true to invert the logic of the endstop.
const bool Z_MIN_ENDSTOP_INVERTING = true; // set to true to invert the logic of the endstop.
const bool X_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of the endstop.
const bool Y_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of the endstop.
const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of the endstop.
//#define DISABLE_MAX_ENDSTOPS
//#define DISABLE_MIN_ENDSTOPS
@ -379,7 +382,7 @@ const bool Z_ENDSTOPS_INVERTING = true; // set to true to invert the logic of th
//#define EEPROM_CHITCHAT
// Preheat Constants
#define PLA_PREHEAT_HOTEND_TEMP 180
#define PLA_PREHEAT_HOTEND_TEMP 180
#define PLA_PREHEAT_HPB_TEMP 70
#define PLA_PREHEAT_FAN_SPEED 255 // Insert Value between 0 and 255
@ -464,7 +467,7 @@ const bool Z_ENDSTOPS_INVERTING = true; // set to true to invert the logic of th
#define LCD_I2C_TYPE_PCF8575
#define LCD_I2C_ADDRESS 0x27 // I2C Address of the port expander
#define NEWPANEL
#define ULTIPANEL
#define ULTIPANEL
#endif
// PANELOLU2 LCD with status LEDs, separate encoder and click inputs
@ -473,13 +476,13 @@ const bool Z_ENDSTOPS_INVERTING = true; // set to true to invert the logic of th
// This uses the LiquidTWI2 library v1.2.3 or later ( https://github.com/lincomatic/LiquidTWI2 )
// Make sure the LiquidTWI2 directory is placed in the Arduino or Sketchbook libraries subdirectory.
// (v1.2.3 no longer requires you to define PANELOLU in the LiquidTWI2.h library header file)
// Note: The PANELOLU2 encoder click input can either be directly connected to a pin
// (if BTN_ENC defined to != -1) or read through I2C (when BTN_ENC == -1).
// Note: The PANELOLU2 encoder click input can either be directly connected to a pin
// (if BTN_ENC defined to != -1) or read through I2C (when BTN_ENC == -1).
#define LCD_I2C_TYPE_MCP23017
#define LCD_I2C_ADDRESS 0x20 // I2C Address of the port expander
#define LCD_USE_I2C_BUZZER //comment out to disable buzzer on LCD
#define NEWPANEL
#define ULTIPANEL
#define ULTIPANEL
#endif
// Panucatt VIKI LCD with status LEDs, integrated click & L/R/U/P buttons, separate encoder inputs
@ -489,11 +492,11 @@ const bool Z_ENDSTOPS_INVERTING = true; // set to true to invert the logic of th
// Make sure the LiquidTWI2 directory is placed in the Arduino or Sketchbook libraries subdirectory.
// Note: The pause/stop/resume LCD button pin should be connected to the Arduino
// BTN_ENC pin (or set BTN_ENC to -1 if not used)
#define LCD_I2C_TYPE_MCP23017
#define LCD_I2C_TYPE_MCP23017
#define LCD_I2C_ADDRESS 0x20 // I2C Address of the port expander
#define LCD_USE_I2C_BUZZER //comment out to disable buzzer on LCD (requires LiquidTWI2 v1.2.3 or later)
#define NEWPANEL
#define ULTIPANEL
#define ULTIPANEL
#endif
#ifdef ULTIPANEL
@ -565,10 +568,10 @@ const bool Z_ENDSTOPS_INVERTING = true; // set to true to invert the logic of th
//#define NUM_SERVOS 3 // Servo index starts with 0 for M280 command
// Servo Endstops
//
//
// This allows for servo actuated endstops, primary usage is for the Z Axis to eliminate calibration or bed height changes.
// Use M206 command to correct for switch height offset to actual nozzle height. Store that setting with M500.
//
//
//#define SERVO_ENDSTOPS {-1, -1, 0} // Servo index for X, Y, Z. Disable with -1
//#define SERVO_ENDSTOP_ANGLES {0,0, 0,0, 70,0} // X,Y,Z Axis Extend and Retract angles

View File

@ -431,10 +431,10 @@ void setup()
lcd_init();
_delay_ms(1000); // wait 1sec to display the splash screen
#if defined(CONTROLLERFAN_PIN) && CONTROLLERFAN_PIN > -1
SET_OUTPUT(CONTROLLERFAN_PIN); //Set pin used for driver cooling fan
#endif
#endif
}
@ -691,15 +691,15 @@ XYZ_CONSTS_FROM_CONFIG(signed char, home_dir, HOME_DIR);
#endif
#if X_HOME_DIR != -1 || X2_HOME_DIR != 1
#error "Please use canonical x-carriage assignment" // the x-carriages are defined by their homing directions
#endif
#endif
static float x_home_pos(int extruder) {
if (extruder == 0)
return base_home_pos(X_AXIS) + add_homeing[X_AXIS];
else
// In dual carriage mode the extruder offset provides an override of the
// second X-carriage offset when homed - otherwise X2_HOME_POS is used.
// This allow soft recalibration of the second extruder offset position without firmware reflash
// This allow soft recalibration of the second extruder offset position without firmware reflash
// (through the M218 command).
return (extruder_offset[X_AXIS][1] > 0) ? extruder_offset[X_AXIS][1] : X2_HOME_POS;
}
@ -709,7 +709,7 @@ static int x_home_dir(int extruder) {
}
static float inactive_x_carriage_pos = X2_MAX_POS;
#endif
#endif
static void axis_is_at_home(int axis) {
#ifdef DUAL_X_CARRIAGE
@ -719,7 +719,7 @@ static void axis_is_at_home(int axis) {
max_pos[X_AXIS] = max(extruder_offset[X_AXIS][1], X2_MAX_POS);
return;
}
#endif
#endif
current_position[axis] = base_home_pos(axis) + add_homeing[axis];
min_pos[axis] = base_min_pos(axis) + add_homeing[axis];
max_pos[axis] = base_max_pos(axis) + add_homeing[axis];
@ -745,7 +745,7 @@ static void homeaxis(int axis) {
servos[servo_endstops[axis]].write(servo_endstop_angles[axis * 2]);
}
#endif
current_position[axis] = 0;
plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
destination[axis] = 1.5 * max_length(axis) * axis_home_dir;
@ -879,7 +879,7 @@ void process_commands()
current_position[X_AXIS] = 0;
current_position[Y_AXIS] = 0;
current_position[Z_AXIS] = 0;
plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
destination[X_AXIS] = 3 * Z_MAX_LENGTH;
destination[Y_AXIS] = 3 * Z_MAX_LENGTH;
@ -892,7 +892,7 @@ void process_commands()
current_position[X_AXIS] = destination[X_AXIS];
current_position[Y_AXIS] = destination[Y_AXIS];
current_position[Z_AXIS] = destination[Z_AXIS];
// take care of back off and rehome now we are all at the top
HOMEAXIS(X);
HOMEAXIS(Y);
@ -921,7 +921,7 @@ void process_commands()
#else
int x_axis_home_dir = x_home_dir(active_extruder);
#endif
plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
destination[X_AXIS] = 1.5 * max_length(X_AXIS) * x_axis_home_dir;destination[Y_AXIS] = 1.5 * max_length(Y_AXIS) * home_dir(Y_AXIS);
feedrate = homing_feedrate[X_AXIS];
@ -954,7 +954,7 @@ void process_commands()
HOMEAXIS(X);
inactive_x_carriage_pos = current_position[X_AXIS];
active_extruder = tmp_extruder;
#endif
#endif
HOMEAXIS(X);
}
@ -988,7 +988,7 @@ void process_commands()
}
plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
#endif // else DELTA
#ifdef ENDSTOPS_ONLY_FOR_HOMING
enable_endstops(false);
#endif
@ -1223,9 +1223,9 @@ void process_commands()
SERIAL_PROTOCOLPGM(" T");
SERIAL_PROTOCOL(cur_extruder);
SERIAL_PROTOCOLPGM(":");
SERIAL_PROTOCOL_F(degHotend(cur_extruder),1);
SERIAL_PROTOCOL_F(degHotend(cur_extruder),1);
SERIAL_PROTOCOLPGM(" /");
SERIAL_PROTOCOL_F(degTargetHotend(cur_extruder),1);
SERIAL_PROTOCOL_F(degTargetHotend(cur_extruder),1);
}
#else
SERIAL_ERROR_START;
@ -1250,7 +1250,7 @@ void process_commands()
#ifdef AUTOTEMP
autotemp_enabled=false;
#endif
if (code_seen('S')) {
if (code_seen('S')) {
setTargetHotend(code_value(), tmp_extruder);
CooldownNoWait = true;
} else if (code_seen('R')) {
@ -1327,7 +1327,7 @@ void process_commands()
case 190: // M190 - Wait for bed heater to reach target.
#if defined(TEMP_BED_PIN) && TEMP_BED_PIN > -1
LCD_MESSAGEPGM(MSG_BED_HEATING);
if (code_seen('S')) {
if (code_seen('S')) {
setTargetBed(code_value());
CooldownNoWait = true;
} else if (code_seen('R')) {
@ -1335,9 +1335,9 @@ void process_commands()
CooldownNoWait = false;
}
codenum = millis();
target_direction = isHeatingBed(); // true if heating, false if cooling
while ( target_direction ? (isHeatingBed()) : (isCoolingBed()&&(CooldownNoWait==false)) )
{
if(( millis() - codenum) > 1000 ) //Print Temp Reading every 1 second while heating up.
@ -1417,7 +1417,7 @@ void process_commands()
#endif
break;
#endif
case 81: // M81 - Turn off Power Supply
disable_heater();
st_synchronize();
@ -1542,27 +1542,27 @@ void process_commands()
SERIAL_PROTOCOLLN(MSG_M119_REPORT);
#if defined(X_MIN_PIN) && X_MIN_PIN > -1
SERIAL_PROTOCOLPGM(MSG_X_MIN);
SERIAL_PROTOCOLLN(((READ(X_MIN_PIN)^X_ENDSTOPS_INVERTING)?MSG_ENDSTOP_HIT:MSG_ENDSTOP_OPEN));
SERIAL_PROTOCOLLN(((READ(X_MIN_PIN)^X_MIN_ENDSTOP_INVERTING)?MSG_ENDSTOP_HIT:MSG_ENDSTOP_OPEN));
#endif
#if defined(X_MAX_PIN) && X_MAX_PIN > -1
SERIAL_PROTOCOLPGM(MSG_X_MAX);
SERIAL_PROTOCOLLN(((READ(X_MAX_PIN)^X_ENDSTOPS_INVERTING)?MSG_ENDSTOP_HIT:MSG_ENDSTOP_OPEN));
SERIAL_PROTOCOLLN(((READ(X_MAX_PIN)^X_MAX_ENDSTOP_INVERTING)?MSG_ENDSTOP_HIT:MSG_ENDSTOP_OPEN));
#endif
#if defined(Y_MIN_PIN) && Y_MIN_PIN > -1
SERIAL_PROTOCOLPGM(MSG_Y_MIN);
SERIAL_PROTOCOLLN(((READ(Y_MIN_PIN)^Y_ENDSTOPS_INVERTING)?MSG_ENDSTOP_HIT:MSG_ENDSTOP_OPEN));
SERIAL_PROTOCOLLN(((READ(Y_MIN_PIN)^Y_MIN_ENDSTOP_INVERTING)?MSG_ENDSTOP_HIT:MSG_ENDSTOP_OPEN));
#endif
#if defined(Y_MAX_PIN) && Y_MAX_PIN > -1
SERIAL_PROTOCOLPGM(MSG_Y_MAX);
SERIAL_PROTOCOLLN(((READ(Y_MAX_PIN)^Y_ENDSTOPS_INVERTING)?MSG_ENDSTOP_HIT:MSG_ENDSTOP_OPEN));
SERIAL_PROTOCOLLN(((READ(Y_MAX_PIN)^Y_MAX_ENDSTOP_INVERTING)?MSG_ENDSTOP_HIT:MSG_ENDSTOP_OPEN));
#endif
#if defined(Z_MIN_PIN) && Z_MIN_PIN > -1
SERIAL_PROTOCOLPGM(MSG_Z_MIN);
SERIAL_PROTOCOLLN(((READ(Z_MIN_PIN)^Z_ENDSTOPS_INVERTING)?MSG_ENDSTOP_HIT:MSG_ENDSTOP_OPEN));
SERIAL_PROTOCOLLN(((READ(Z_MIN_PIN)^Z_MIN_ENDSTOP_INVERTING)?MSG_ENDSTOP_HIT:MSG_ENDSTOP_OPEN));
#endif
#if defined(Z_MAX_PIN) && Z_MAX_PIN > -1
SERIAL_PROTOCOLPGM(MSG_Z_MAX);
SERIAL_PROTOCOLLN(((READ(Z_MAX_PIN)^Z_ENDSTOPS_INVERTING)?MSG_ENDSTOP_HIT:MSG_ENDSTOP_OPEN));
SERIAL_PROTOCOLLN(((READ(Z_MAX_PIN)^Z_MAX_ENDSTOP_INVERTING)?MSG_ENDSTOP_HIT:MSG_ENDSTOP_OPEN));
#endif
break;
//TODO: update for all axis, use for loop
@ -1699,7 +1699,7 @@ void process_commands()
}
}
break;
#if NUM_SERVOS > 0
case 280: // M280 - set servo position absolute. P: servo index, S: angle or microseconds
{
@ -1987,7 +1987,7 @@ void process_commands()
delay(3);
WRITE(BEEPER,LOW);
delay(3);
#else
#else
lcd_buzz(1000/6,100);
#endif
}
@ -2103,8 +2103,8 @@ void process_commands()
active_extruder = tmp_extruder;
axis_is_at_home(X_AXIS); //this function updates X min/max values.
current_position[X_AXIS] = inactive_x_carriage_pos;
inactive_x_carriage_pos = tmp_x_pos;
#else
inactive_x_carriage_pos = tmp_x_pos;
#else
// Offset extruder (only by XY)
int i;
for(i = 0; i < 2; i++) {
@ -2340,10 +2340,10 @@ void prepare_arc_move(char isclockwise) {
#if defined(CONTROLLERFAN_PIN) && CONTROLLERFAN_PIN > -1
#if defined(FAN_PIN)
#if CONTROLLERFAN_PIN == FAN_PIN
#if CONTROLLERFAN_PIN == FAN_PIN
#error "You cannot set CONTROLLERFAN_PIN equal to FAN_PIN"
#endif
#endif
#endif
unsigned long lastMotor = 0; //Save the time for when a motor was turned on last
unsigned long lastMotorCheck = 0;
@ -2368,17 +2368,17 @@ void controllerFan()
{
lastMotor = millis(); //... set time to NOW so the fan will turn on
}
if ((millis() - lastMotor) >= (CONTROLLERFAN_SECS*1000UL) || lastMotor == 0) //If the last time any driver was enabled, is longer since than CONTROLLERSEC...
if ((millis() - lastMotor) >= (CONTROLLERFAN_SECS*1000UL) || lastMotor == 0) //If the last time any driver was enabled, is longer since than CONTROLLERSEC...
{
digitalWrite(CONTROLLERFAN_PIN, 0);
analogWrite(CONTROLLERFAN_PIN, 0);
digitalWrite(CONTROLLERFAN_PIN, 0);
analogWrite(CONTROLLERFAN_PIN, 0);
}
else
{
// allows digital or PWM fan output to be used (see M42 handling)
digitalWrite(CONTROLLERFAN_PIN, CONTROLLERFAN_SPEED);
analogWrite(CONTROLLERFAN_PIN, CONTROLLERFAN_SPEED);
analogWrite(CONTROLLERFAN_PIN, CONTROLLERFAN_SPEED);
}
}
}
@ -2445,7 +2445,7 @@ void kill()
#if defined(PS_ON_PIN) && PS_ON_PIN > -1
pinMode(PS_ON_PIN,INPUT);
#endif
#endif
SERIAL_ERROR_START;
SERIAL_ERRORLNPGM(MSG_ERR_KILLED);
LCD_ALERTMESSAGEPGM(MSG_KILLED);

View File

@ -141,7 +141,7 @@
#define TEMP_SENSOR_BED 0
// This makes temp sensor 1 a redundant sensor for sensor 0. If the temperatures difference between these sensors is to high the print will be aborted.
//#define TEMP_SENSOR_1_AS_REDUNDANT
//#define TEMP_SENSOR_1_AS_REDUNDANT
#define MAX_REDUNDANT_TEMP_SENSOR_DIFF 10
// Actual temperature must be close to target for this long before M109 returns success
@ -278,9 +278,12 @@
#endif
// The pullups are needed if you directly connect a mechanical endswitch between the signal and ground pins.
const bool X_ENDSTOPS_INVERTING = false; // set to true to invert the logic of the endstops.
const bool Y_ENDSTOPS_INVERTING = false; // set to true to invert the logic of the endstops.
const bool Z_ENDSTOPS_INVERTING = false; // set to true to invert the logic of the endstops.
const bool X_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
const bool Y_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
const bool X_MAX_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
const bool Y_MAX_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
const bool Z_MAX_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
// deltas never have min endstops
#define DISABLE_MIN_ENDSTOPS
@ -386,7 +389,7 @@ const bool Z_ENDSTOPS_INVERTING = false; // set to true to invert the logic of t
//#define EEPROM_CHITCHAT
// Preheat Constants
#define PLA_PREHEAT_HOTEND_TEMP 180
#define PLA_PREHEAT_HOTEND_TEMP 180
#define PLA_PREHEAT_HPB_TEMP 70
#define PLA_PREHEAT_FAN_SPEED 255 // Insert Value between 0 and 255
@ -471,7 +474,7 @@ const bool Z_ENDSTOPS_INVERTING = false; // set to true to invert the logic of t
#define LCD_I2C_TYPE_PCF8575
#define LCD_I2C_ADDRESS 0x27 // I2C Address of the port expander
#define NEWPANEL
#define ULTIPANEL
#define ULTIPANEL
#endif
// PANELOLU2 LCD with status LEDs, separate encoder and click inputs
@ -480,13 +483,13 @@ const bool Z_ENDSTOPS_INVERTING = false; // set to true to invert the logic of t
// This uses the LiquidTWI2 library v1.2.3 or later ( https://github.com/lincomatic/LiquidTWI2 )
// Make sure the LiquidTWI2 directory is placed in the Arduino or Sketchbook libraries subdirectory.
// (v1.2.3 no longer requires you to define PANELOLU in the LiquidTWI2.h library header file)
// Note: The PANELOLU2 encoder click input can either be directly connected to a pin
// (if BTN_ENC defined to != -1) or read through I2C (when BTN_ENC == -1).
// Note: The PANELOLU2 encoder click input can either be directly connected to a pin
// (if BTN_ENC defined to != -1) or read through I2C (when BTN_ENC == -1).
#define LCD_I2C_TYPE_MCP23017
#define LCD_I2C_ADDRESS 0x20 // I2C Address of the port expander
#define LCD_USE_I2C_BUZZER //comment out to disable buzzer on LCD
#define NEWPANEL
#define ULTIPANEL
#define ULTIPANEL
#endif
// Panucatt VIKI LCD with status LEDs, integrated click & L/R/U/P buttons, separate encoder inputs
@ -496,11 +499,11 @@ const bool Z_ENDSTOPS_INVERTING = false; // set to true to invert the logic of t
// Make sure the LiquidTWI2 directory is placed in the Arduino or Sketchbook libraries subdirectory.
// Note: The pause/stop/resume LCD button pin should be connected to the Arduino
// BTN_ENC pin (or set BTN_ENC to -1 if not used)
#define LCD_I2C_TYPE_MCP23017
#define LCD_I2C_TYPE_MCP23017
#define LCD_I2C_ADDRESS 0x20 // I2C Address of the port expander
#define LCD_USE_I2C_BUZZER //comment out to disable buzzer on LCD (requires LiquidTWI2 v1.2.3 or later)
#define NEWPANEL
#define ULTIPANEL
#define ULTIPANEL
#endif
#ifdef ULTIPANEL
@ -572,10 +575,10 @@ const bool Z_ENDSTOPS_INVERTING = false; // set to true to invert the logic of t
//#define NUM_SERVOS 3 // Servo index starts with 0 for M280 command
// Servo Endstops
//
//
// This allows for servo actuated endstops, primary usage is for the Z Axis to eliminate calibration or bed height changes.
// Use M206 command to correct for switch height offset to actual nozzle height. Store that setting with M500.
//
//
//#define SERVO_ENDSTOPS {-1, -1, 0} // Servo index for X, Y, Z. Disable with -1
//#define SERVO_ENDSTOP_ANGLES {0,0, 0,0, 70,0} // X,Y,Z Axis Extend and Retract angles

View File

@ -48,8 +48,8 @@ block_t *current_block; // A pointer to the block currently being traced
// Variables used by The Stepper Driver Interrupt
static unsigned char out_bits; // The next stepping-bits to be output
static long counter_x, // Counter variables for the bresenham line tracer
counter_y,
counter_z,
counter_y,
counter_z,
counter_e;
volatile static unsigned long step_events_completed; // The number of step events executed in the current block
#ifdef ADVANCE
@ -224,27 +224,27 @@ void enable_endstops(bool check)
// | BLOCK 1 | BLOCK 2 | d
//
// time ----->
//
// 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
//
// 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
// 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 leib ramp alghorithm.
void st_wake_up() {
// TCNT1 = 0;
ENABLE_STEPPER_DRIVER_INTERRUPT();
ENABLE_STEPPER_DRIVER_INTERRUPT();
}
void step_wait(){
for(int8_t i=0; i < 6; i++){
}
}
FORCE_INLINE unsigned short calc_timer(unsigned short step_rate) {
unsigned short timer;
if(step_rate > MAX_STEP_FREQUENCY) step_rate = MAX_STEP_FREQUENCY;
if(step_rate > 20000) { // If steprate > 20kHz >> step 4 times
step_rate = (step_rate >> 2)&0x3fff;
step_loops = 4;
@ -255,11 +255,11 @@ FORCE_INLINE unsigned short calc_timer(unsigned short step_rate) {
}
else {
step_loops = 1;
}
}
if(step_rate < (F_CPU/500000)) step_rate = (F_CPU/500000);
step_rate -= (F_CPU/500000); // Correct for minimal speed
if(step_rate >= (8*256)){ // higher step rate
if(step_rate >= (8*256)){ // higher step rate
unsigned short table_address = (unsigned short)&speed_lookuptable_fast[(unsigned char)(step_rate>>8)][0];
unsigned char tmp_step_rate = (step_rate & 0x00ff);
unsigned short gain = (unsigned short)pgm_read_word_near(table_address+2);
@ -276,7 +276,7 @@ FORCE_INLINE unsigned short calc_timer(unsigned short step_rate) {
return timer;
}
// Initializes the trapezoid generator from the current block. Called whenever a new
// Initializes the trapezoid generator from the current block. Called whenever a new
// block begins.
FORCE_INLINE void trapezoid_generator_reset() {
#ifdef ADVANCE
@ -284,7 +284,7 @@ FORCE_INLINE void trapezoid_generator_reset() {
final_advance = current_block->final_advance;
// Do E steps + advance steps
e_steps[current_block->active_extruder] += ((advance >>8) - old_advance);
old_advance = advance >>8;
old_advance = advance >>8;
#endif
deceleration_time = 0;
// step_rate to timer interval
@ -294,7 +294,7 @@ FORCE_INLINE void trapezoid_generator_reset() {
acc_step_rate = current_block->initial_rate;
acceleration_time = calc_timer(acc_step_rate);
OCR1A = acceleration_time;
// SERIAL_ECHO_START;
// SERIAL_ECHOPGM("advance :");
// SERIAL_ECHO(current_block->advance/256.0);
@ -304,13 +304,13 @@ FORCE_INLINE void trapezoid_generator_reset() {
// SERIAL_ECHO(current_block->initial_advance/256.0);
// SERIAL_ECHOPGM("final advance :");
// SERIAL_ECHOLN(current_block->final_advance/256.0);
}
// "The Stepper Driver Interrupt" - This timer interrupt is the workhorse.
// It pops blocks from the block_buffer and executes them by pulsing the stepper pins appropriately.
// "The Stepper Driver Interrupt" - This timer interrupt is the workhorse.
// It pops blocks from the block_buffer and executes them by pulsing the stepper pins appropriately.
ISR(TIMER1_COMPA_vect)
{
{
// If there is no current block, attempt to pop one from the buffer
if (current_block == NULL) {
// Anything in the buffer?
@ -322,24 +322,24 @@ ISR(TIMER1_COMPA_vect)
counter_y = counter_x;
counter_z = counter_x;
counter_e = counter_x;
step_events_completed = 0;
#ifdef Z_LATE_ENABLE
step_events_completed = 0;
#ifdef Z_LATE_ENABLE
if(current_block->steps_z > 0) {
enable_z();
OCR1A = 2000; //1ms wait
return;
}
#endif
// #ifdef ADVANCE
// e_steps[current_block->active_extruder] = 0;
// #endif
}
}
else {
OCR1A=2000; // 1kHz.
}
}
}
}
if (current_block != NULL) {
// Set directions TO DO This should be done once during init of trapezoid. Endstops -> interrupt
@ -352,7 +352,7 @@ ISR(TIMER1_COMPA_vect)
if (active_extruder != 0)
WRITE(X2_DIR_PIN,INVERT_X_DIR);
else
#endif
#endif
WRITE(X_DIR_PIN, INVERT_X_DIR);
count_direction[X_AXIS]=-1;
}
@ -361,7 +361,7 @@ ISR(TIMER1_COMPA_vect)
if (active_extruder != 0)
WRITE(X2_DIR_PIN,!INVERT_X_DIR);
else
#endif
#endif
WRITE(X_DIR_PIN, !INVERT_X_DIR);
count_direction[X_AXIS]=1;
}
@ -373,7 +373,7 @@ ISR(TIMER1_COMPA_vect)
WRITE(Y_DIR_PIN, !INVERT_Y_DIR);
count_direction[Y_AXIS]=1;
}
// Set direction en check limit switches
#ifndef COREXY
if ((out_bits & (1<<X_AXIS)) != 0) { // stepping along -X axis
@ -385,10 +385,10 @@ ISR(TIMER1_COMPA_vect)
#ifdef DUAL_X_CARRIAGE
// with 2 x-carriages, endstops are only checked in the homing direction for the active extruder
if ((active_extruder == 0 && X_HOME_DIR == -1) || (active_extruder != 0 && X2_HOME_DIR == -1))
#endif
#endif
{
#if defined(X_MIN_PIN) && X_MIN_PIN > -1
bool x_min_endstop=(READ(X_MIN_PIN) != X_ENDSTOPS_INVERTING);
bool x_min_endstop=(READ(X_MIN_PIN) != X_MIN_ENDSTOP_INVERTING);
if(x_min_endstop && old_x_min_endstop && (current_block->steps_x > 0)) {
endstops_trigsteps[X_AXIS] = count_position[X_AXIS];
endstop_x_hit=true;
@ -400,15 +400,15 @@ ISR(TIMER1_COMPA_vect)
}
}
else { // +direction
CHECK_ENDSTOPS
CHECK_ENDSTOPS
{
#ifdef DUAL_X_CARRIAGE
// with 2 x-carriages, endstops are only checked in the homing direction for the active extruder
if ((active_extruder == 0 && X_HOME_DIR == 1) || (active_extruder != 0 && X2_HOME_DIR == 1))
#endif
#endif
{
#if defined(X_MAX_PIN) && X_MAX_PIN > -1
bool x_max_endstop=(READ(X_MAX_PIN) != X_ENDSTOPS_INVERTING);
bool x_max_endstop=(READ(X_MAX_PIN) != X_MAX_ENDSTOP_INVERTING);
if(x_max_endstop && old_x_max_endstop && (current_block->steps_x > 0)){
endstops_trigsteps[X_AXIS] = count_position[X_AXIS];
endstop_x_hit=true;
@ -416,7 +416,7 @@ ISR(TIMER1_COMPA_vect)
}
old_x_max_endstop = x_max_endstop;
#endif
}
}
}
}
@ -428,7 +428,7 @@ ISR(TIMER1_COMPA_vect)
CHECK_ENDSTOPS
{
#if defined(Y_MIN_PIN) && Y_MIN_PIN > -1
bool y_min_endstop=(READ(Y_MIN_PIN) != Y_ENDSTOPS_INVERTING);
bool y_min_endstop=(READ(Y_MIN_PIN) != Y_MIN_ENDSTOP_INVERTING);
if(y_min_endstop && old_y_min_endstop && (current_block->steps_y > 0)) {
endstops_trigsteps[Y_AXIS] = count_position[Y_AXIS];
endstop_y_hit=true;
@ -442,7 +442,7 @@ ISR(TIMER1_COMPA_vect)
CHECK_ENDSTOPS
{
#if defined(Y_MAX_PIN) && Y_MAX_PIN > -1
bool y_max_endstop=(READ(Y_MAX_PIN) != Y_ENDSTOPS_INVERTING);
bool y_max_endstop=(READ(Y_MAX_PIN) != Y_MAX_ENDSTOP_INVERTING);
if(y_max_endstop && old_y_max_endstop && (current_block->steps_y > 0)){
endstops_trigsteps[Y_AXIS] = count_position[Y_AXIS];
endstop_y_hit=true;
@ -455,16 +455,16 @@ ISR(TIMER1_COMPA_vect)
if ((out_bits & (1<<Z_AXIS)) != 0) { // -direction
WRITE(Z_DIR_PIN,INVERT_Z_DIR);
#ifdef Z_DUAL_STEPPER_DRIVERS
WRITE(Z2_DIR_PIN,INVERT_Z_DIR);
#endif
count_direction[Z_AXIS]=-1;
CHECK_ENDSTOPS
{
#if defined(Z_MIN_PIN) && Z_MIN_PIN > -1
bool z_min_endstop=(READ(Z_MIN_PIN) != Z_ENDSTOPS_INVERTING);
bool z_min_endstop=(READ(Z_MIN_PIN) != Z_MIN_ENDSTOP_INVERTING);
if(z_min_endstop && old_z_min_endstop && (current_block->steps_z > 0)) {
endstops_trigsteps[Z_AXIS] = count_position[Z_AXIS];
endstop_z_hit=true;
@ -485,7 +485,7 @@ ISR(TIMER1_COMPA_vect)
CHECK_ENDSTOPS
{
#if defined(Z_MAX_PIN) && Z_MAX_PIN > -1
bool z_max_endstop=(READ(Z_MAX_PIN) != Z_ENDSTOPS_INVERTING);
bool z_max_endstop=(READ(Z_MAX_PIN) != Z_MAX_ENDSTOP_INVERTING);
if(z_max_endstop && old_z_max_endstop && (current_block->steps_z > 0)) {
endstops_trigsteps[Z_AXIS] = count_position[Z_AXIS];
endstop_z_hit=true;
@ -506,10 +506,10 @@ ISR(TIMER1_COMPA_vect)
count_direction[E_AXIS]=1;
}
#endif //!ADVANCE
for(int8_t i=0; i < step_loops; i++) { // Take multiple steps per interrupt (For high speed moves)
for(int8_t i=0; i < step_loops; i++) { // Take multiple steps per interrupt (For high speed moves)
#ifndef AT90USB
MSerial.checkRx(); // Check for serial chars.
#endif
@ -524,7 +524,7 @@ ISR(TIMER1_COMPA_vect)
else {
e_steps[current_block->active_extruder]++;
}
}
}
#endif //ADVANCE
counter_x += current_block->steps_x;
@ -533,38 +533,38 @@ ISR(TIMER1_COMPA_vect)
if (active_extruder != 0)
WRITE(X2_STEP_PIN,!INVERT_X_STEP_PIN);
else
#endif
#endif
WRITE(X_STEP_PIN, !INVERT_X_STEP_PIN);
counter_x -= current_block->step_event_count;
count_position[X_AXIS]+=count_direction[X_AXIS];
count_position[X_AXIS]+=count_direction[X_AXIS];
#ifdef DUAL_X_CARRIAGE
if (active_extruder != 0)
WRITE(X2_STEP_PIN,INVERT_X_STEP_PIN);
else
#endif
#endif
WRITE(X_STEP_PIN, INVERT_X_STEP_PIN);
}
counter_y += current_block->steps_y;
if (counter_y > 0) {
WRITE(Y_STEP_PIN, !INVERT_Y_STEP_PIN);
counter_y -= current_block->step_event_count;
count_position[Y_AXIS]+=count_direction[Y_AXIS];
counter_y -= current_block->step_event_count;
count_position[Y_AXIS]+=count_direction[Y_AXIS];
WRITE(Y_STEP_PIN, INVERT_Y_STEP_PIN);
}
counter_z += current_block->steps_z;
if (counter_z > 0) {
WRITE(Z_STEP_PIN, !INVERT_Z_STEP_PIN);
#ifdef Z_DUAL_STEPPER_DRIVERS
WRITE(Z2_STEP_PIN, !INVERT_Z_STEP_PIN);
#endif
counter_z -= current_block->step_event_count;
count_position[Z_AXIS]+=count_direction[Z_AXIS];
WRITE(Z_STEP_PIN, INVERT_Z_STEP_PIN);
#ifdef Z_DUAL_STEPPER_DRIVERS
WRITE(Z2_STEP_PIN, INVERT_Z_STEP_PIN);
#endif
@ -579,17 +579,17 @@ ISR(TIMER1_COMPA_vect)
WRITE_E_STEP(INVERT_E_STEP_PIN);
}
#endif //!ADVANCE
step_events_completed += 1;
step_events_completed += 1;
if(step_events_completed >= current_block->step_event_count) break;
}
// Calculare new timer value
unsigned short timer;
unsigned short step_rate;
if (step_events_completed <= (unsigned long int)current_block->accelerate_until) {
MultiU24X24toH16(acc_step_rate, acceleration_time, current_block->acceleration_rate);
acc_step_rate += current_block->initial_rate;
// upper limit
if(acc_step_rate > current_block->nominal_rate)
acc_step_rate = current_block->nominal_rate;
@ -605,13 +605,13 @@ ISR(TIMER1_COMPA_vect)
//if(advance > current_block->advance) advance = current_block->advance;
// Do E steps + advance steps
e_steps[current_block->active_extruder] += ((advance >>8) - old_advance);
old_advance = advance >>8;
old_advance = advance >>8;
#endif
}
else if (step_events_completed > (unsigned long int)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);
if(step_rate > acc_step_rate) { // Check step_rate stays positive
step_rate = current_block->final_rate;
}
@ -634,7 +634,7 @@ ISR(TIMER1_COMPA_vect)
if(advance < final_advance) advance = final_advance;
// Do E steps + advance steps
e_steps[current_block->active_extruder] += ((advance >>8) - old_advance);
old_advance = advance >>8;
old_advance = advance >>8;
#endif //ADVANCE
}
else {
@ -643,12 +643,12 @@ ISR(TIMER1_COMPA_vect)
step_loops = step_loops_nominal;
}
// If current block is finished, reset pointer
// If current block is finished, reset pointer
if (step_events_completed >= current_block->step_event_count) {
current_block = NULL;
plan_discard_current_block();
}
}
}
}
}
#ifdef ADVANCE
@ -667,7 +667,7 @@ ISR(TIMER1_COMPA_vect)
WRITE(E0_DIR_PIN, INVERT_E0_DIR);
e_steps[0]++;
WRITE(E0_STEP_PIN, !INVERT_E_STEP_PIN);
}
}
else if (e_steps[0] > 0) {
WRITE(E0_DIR_PIN, !INVERT_E0_DIR);
e_steps[0]--;
@ -681,7 +681,7 @@ ISR(TIMER1_COMPA_vect)
WRITE(E1_DIR_PIN, INVERT_E1_DIR);
e_steps[1]++;
WRITE(E1_STEP_PIN, !INVERT_E_STEP_PIN);
}
}
else if (e_steps[1] > 0) {
WRITE(E1_DIR_PIN, !INVERT_E1_DIR);
e_steps[1]--;
@ -696,7 +696,7 @@ ISR(TIMER1_COMPA_vect)
WRITE(E2_DIR_PIN, INVERT_E2_DIR);
e_steps[2]++;
WRITE(E2_STEP_PIN, !INVERT_E_STEP_PIN);
}
}
else if (e_steps[2] > 0) {
WRITE(E2_DIR_PIN, !INVERT_E2_DIR);
e_steps[2]--;
@ -712,7 +712,7 @@ void st_init()
{
digipot_init(); //Initialize Digipot Motor Current
microstep_init(); //Initialize Microstepping Pins
//Initialize Dir Pins
#if defined(X_DIR_PIN) && X_DIR_PIN > -1
SET_OUTPUT(X_DIR_PIN);
@ -720,17 +720,17 @@ void st_init()
#if defined(X2_DIR_PIN) && X2_DIR_PIN > -1
SET_OUTPUT(X2_DIR_PIN);
#endif
#if defined(Y_DIR_PIN) && Y_DIR_PIN > -1
#if defined(Y_DIR_PIN) && Y_DIR_PIN > -1
SET_OUTPUT(Y_DIR_PIN);
#endif
#if defined(Z_DIR_PIN) && Z_DIR_PIN > -1
#if defined(Z_DIR_PIN) && Z_DIR_PIN > -1
SET_OUTPUT(Z_DIR_PIN);
#if defined(Z_DUAL_STEPPER_DRIVERS) && defined(Z2_DIR_PIN) && (Z2_DIR_PIN > -1)
SET_OUTPUT(Z2_DIR_PIN);
#endif
#endif
#if defined(E0_DIR_PIN) && E0_DIR_PIN > -1
#if defined(E0_DIR_PIN) && E0_DIR_PIN > -1
SET_OUTPUT(E0_DIR_PIN);
#endif
#if defined(E1_DIR_PIN) && (E1_DIR_PIN > -1)
@ -757,7 +757,7 @@ void st_init()
#if defined(Z_ENABLE_PIN) && Z_ENABLE_PIN > -1
SET_OUTPUT(Z_ENABLE_PIN);
if(!Z_ENABLE_ON) WRITE(Z_ENABLE_PIN,HIGH);
#if defined(Z_DUAL_STEPPER_DRIVERS) && defined(Z2_ENABLE_PIN) && (Z2_ENABLE_PIN > -1)
SET_OUTPUT(Z2_ENABLE_PIN);
if(!Z_ENABLE_ON) WRITE(Z2_ENABLE_PIN,HIGH);
@ -777,67 +777,67 @@ void st_init()
#endif
//endstops and pullups
#if defined(X_MIN_PIN) && X_MIN_PIN > -1
SET_INPUT(X_MIN_PIN);
SET_INPUT(X_MIN_PIN);
#ifdef ENDSTOPPULLUP_XMIN
WRITE(X_MIN_PIN,HIGH);
#endif
#endif
#if defined(Y_MIN_PIN) && Y_MIN_PIN > -1
SET_INPUT(Y_MIN_PIN);
SET_INPUT(Y_MIN_PIN);
#ifdef ENDSTOPPULLUP_YMIN
WRITE(Y_MIN_PIN,HIGH);
#endif
#endif
#if defined(Z_MIN_PIN) && Z_MIN_PIN > -1
SET_INPUT(Z_MIN_PIN);
SET_INPUT(Z_MIN_PIN);
#ifdef ENDSTOPPULLUP_ZMIN
WRITE(Z_MIN_PIN,HIGH);
#endif
#endif
#if defined(X_MAX_PIN) && X_MAX_PIN > -1
SET_INPUT(X_MAX_PIN);
SET_INPUT(X_MAX_PIN);
#ifdef ENDSTOPPULLUP_XMAX
WRITE(X_MAX_PIN,HIGH);
#endif
#endif
#if defined(Y_MAX_PIN) && Y_MAX_PIN > -1
SET_INPUT(Y_MAX_PIN);
SET_INPUT(Y_MAX_PIN);
#ifdef ENDSTOPPULLUP_YMAX
WRITE(Y_MAX_PIN,HIGH);
#endif
#endif
#if defined(Z_MAX_PIN) && Z_MAX_PIN > -1
SET_INPUT(Z_MAX_PIN);
SET_INPUT(Z_MAX_PIN);
#ifdef ENDSTOPPULLUP_ZMAX
WRITE(Z_MAX_PIN,HIGH);
#endif
#endif
//Initialize Step Pins
#if defined(X_STEP_PIN) && (X_STEP_PIN > -1)
#if defined(X_STEP_PIN) && (X_STEP_PIN > -1)
SET_OUTPUT(X_STEP_PIN);
WRITE(X_STEP_PIN,INVERT_X_STEP_PIN);
disable_x();
#endif
#if defined(X2_STEP_PIN) && (X2_STEP_PIN > -1)
#endif
#if defined(X2_STEP_PIN) && (X2_STEP_PIN > -1)
SET_OUTPUT(X2_STEP_PIN);
WRITE(X2_STEP_PIN,INVERT_X_STEP_PIN);
disable_x();
#endif
#if defined(Y_STEP_PIN) && (Y_STEP_PIN > -1)
#endif
#if defined(Y_STEP_PIN) && (Y_STEP_PIN > -1)
SET_OUTPUT(Y_STEP_PIN);
WRITE(Y_STEP_PIN,INVERT_Y_STEP_PIN);
disable_y();
#endif
#if defined(Z_STEP_PIN) && (Z_STEP_PIN > -1)
#endif
#if defined(Z_STEP_PIN) && (Z_STEP_PIN > -1)
SET_OUTPUT(Z_STEP_PIN);
WRITE(Z_STEP_PIN,INVERT_Z_STEP_PIN);
#if defined(Z_DUAL_STEPPER_DRIVERS) && defined(Z2_STEP_PIN) && (Z2_STEP_PIN > -1)
@ -845,33 +845,33 @@ void st_init()
WRITE(Z2_STEP_PIN,INVERT_Z_STEP_PIN);
#endif
disable_z();
#endif
#if defined(E0_STEP_PIN) && (E0_STEP_PIN > -1)
#endif
#if defined(E0_STEP_PIN) && (E0_STEP_PIN > -1)
SET_OUTPUT(E0_STEP_PIN);
WRITE(E0_STEP_PIN,INVERT_E_STEP_PIN);
disable_e0();
#endif
#if defined(E1_STEP_PIN) && (E1_STEP_PIN > -1)
#endif
#if defined(E1_STEP_PIN) && (E1_STEP_PIN > -1)
SET_OUTPUT(E1_STEP_PIN);
WRITE(E1_STEP_PIN,INVERT_E_STEP_PIN);
disable_e1();
#endif
#if defined(E2_STEP_PIN) && (E2_STEP_PIN > -1)
#endif
#if defined(E2_STEP_PIN) && (E2_STEP_PIN > -1)
SET_OUTPUT(E2_STEP_PIN);
WRITE(E2_STEP_PIN,INVERT_E_STEP_PIN);
disable_e2();
#endif
#endif
// waveform generation = 0100 = CTC
TCCR1B &= ~(1<<WGM13);
TCCR1B |= (1<<WGM12);
TCCR1A &= ~(1<<WGM11);
TCCR1A &= ~(1<<WGM11);
TCCR1A &= ~(1<<WGM10);
// output mode = 00 (disconnected)
TCCR1A &= ~(3<<COM1A0);
TCCR1A &= ~(3<<COM1B0);
TCCR1A &= ~(3<<COM1A0);
TCCR1A &= ~(3<<COM1B0);
// Set the timer pre-scaler
// Generally we use a divider of 8, resulting in a 2MHz timer
// frequency on a 16MHz MCU. If you are going to change this, be
@ -881,19 +881,19 @@ void st_init()
OCR1A = 0x4000;
TCNT1 = 0;
ENABLE_STEPPER_DRIVER_INTERRUPT();
ENABLE_STEPPER_DRIVER_INTERRUPT();
#ifdef ADVANCE
#if defined(TCCR0A) && defined(WGM01)
TCCR0A &= ~(1<<WGM01);
TCCR0A &= ~(1<<WGM00);
#endif
#endif
e_steps[0] = 0;
e_steps[1] = 0;
e_steps[2] = 0;
TIMSK0 |= (1<<OCIE0A);
#endif //ADVANCE
enable_endstops(true); // Start with endstops active. After homing they can be disabled
sei();
}
@ -937,13 +937,13 @@ long st_get_position(uint8_t axis)
void finishAndDisableSteppers()
{
st_synchronize();
disable_x();
disable_y();
disable_z();
disable_e0();
disable_e1();
disable_e2();
st_synchronize();
disable_x();
disable_y();
disable_z();
disable_e0();
disable_e1();
disable_e2();
}
void quickStop()
@ -970,10 +970,10 @@ void digipot_init() //Initialize Digipot Motor Current
{
#if defined(DIGIPOTSS_PIN) && DIGIPOTSS_PIN > -1
const uint8_t digipot_motor_current[] = DIGIPOT_MOTOR_CURRENT;
SPI.begin();
pinMode(DIGIPOTSS_PIN, OUTPUT);
for(int i=0;i<=4;i++)
SPI.begin();
pinMode(DIGIPOTSS_PIN, OUTPUT);
for(int i=0;i<=4;i++)
//digitalPotWrite(digipot_ch[i], digipot_motor_current[i]);
digipot_current(i,digipot_motor_current[i]);
#endif