Commit 3444e44d authored by MagoKimbra's avatar MagoKimbra

Same fix

parent 77059690
/* -*- c++ -*- */
/*
Reprap firmware based on Marlin
Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
Copyright (C) 2014 MagoKimbra
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
/**
* Marlin Firmware
*
* Based on Sprinter and grbl.
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
* About Marlin
*
* This firmware is a mashup between Sprinter and grbl.
* - https://github.com/kliment/Sprinter
* - https://github.com/simen/grbl/tree
*
* It has preliminary support for Matthew Roberts advance algorithm
* - http://reprap.org/pipermail/reprap-dev/2011-May/003323.html
*/
#include "Marlin.h"
......@@ -93,7 +101,6 @@
* -------------------------------------------------------------------------------------
* "M" Codes
*
*
* M0 - Unconditional stop - Wait for user to press a button on the LCD (Only if ULTRA_LCD is enabled)
* M1 - Same as M0
* M3 - Put S<value> in laser beam control
......@@ -160,7 +167,7 @@
* M205 - advanced settings: minimum travel speed S=while printing T=travel only, B=minimum segment time X= maximum xy jerk, Z=maximum Z jerk, E=maximum E jerk
* M206 - Set additional homing offset
* M207 - Set retract length S[positive mm] F[feedrate mm/min] Z[additional zlift/hop], stays in mm regardless of M200 setting
* M208 - Set recover=unretract length S[positive mm surplus to the M207 S*] F[feedrate mm/sec]
* M208 - Set recover=unretract length S[positive mm surplus to the M207 S*] F[feedrate mm/min]
* M209 - S<1=true/0=false> enable automatic retract detect if the slicer did not support G10/11: every normal extrude-only move will be classified as retract depending on the direction.
* M218 - Set hotend offset (in mm): T<extruder_number> X<offset_on_X> Y<offset_on_Y>
* M220 - Set speed factor override percentage: S<factor in percent>
......@@ -210,6 +217,11 @@
* M928 - Start SD logging (M928 filename.g) - ended by M29
* M997 - NPR2 Color rotate
* M999 - Restart after being stopped by error
*
* "T" Codes
*
* T0-T3 - Select a tool by index (usually an extruder) [ F<mm/min> ]
*
*/
#ifdef SDSUPPORT
......@@ -1270,12 +1282,12 @@ static void setup_for_endstop_move() {
plan_bed_level_matrix.set_to_identity();
feedrate = homing_feedrate[Z_AXIS];
// move down until you find the bed
// Move down until the probe (or endstop?) is triggered
float zPosition = -10;
line_to_z(zPosition);
st_synchronize();
// we have to let the planner know where we are right now as it is not where we said to go.
// Tell the planner where we ended up - Get this from the stepper handler
zPosition = st_get_position_mm(Z_AXIS);
plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], zPosition, current_position[E_AXIS]);
......@@ -1341,7 +1353,7 @@ static void setup_for_endstop_move() {
#if SERVO_LEVELING
srv->attach(0);
#endif
srv->write(servo_endstop_angles[Z_AXIS * 2 + 1]);
#if SERVO_LEVELING
delay(PROBE_SERVO_DEACTIVATION_DELAY);
srv->detach();
......@@ -1359,20 +1371,20 @@ static void setup_for_endstop_move() {
};
// Probe bed height at position (x,y), returns the measured z value
static float probe_pt(float x, float y, float z_before, ProbeAction retract_action = ProbeDeployAndStow, int verbose_level = 1) {
static float probe_pt(float x, float y, float z_before, ProbeAction probe_action = ProbeDeployAndStow, int verbose_level = 1) {
// move to right place
do_blocking_move_to(current_position[X_AXIS], current_position[Y_AXIS], z_before);
do_blocking_move_to(x - X_PROBE_OFFSET_FROM_EXTRUDER, y - Y_PROBE_OFFSET_FROM_EXTRUDER, current_position[Z_AXIS]);
#ifndef Z_PROBE_SLED
if (retract_action & ProbeDeploy) deploy_z_probe();
if (probe_action & ProbeDeploy) deploy_z_probe();
#endif // Z_PROBE_SLED
run_z_probe();
float measured_z = current_position[Z_AXIS];
#ifndef Z_PROBE_SLED
if (retract_action & ProbeStow) stow_z_probe();
if (probe_action & ProbeStow) stow_z_probe();
#endif
if (verbose_level > 2) {
......@@ -1413,10 +1425,10 @@ static void setup_for_endstop_move() {
if (axis == Z_AXIS) {
if (axis_home_dir < 0) deploy_z_probe();
}
else
#endif
#if SERVO_LEVELING
{
if (axis != Z_AXIS) {
// Engage Servo endstop if enabled
if (servo_endstops[axis] > -1)
servo[servo_endstops[axis]].write(servo_endstop_angles[axis * 2]);
......@@ -1590,15 +1602,31 @@ static void setup_for_endstop_move() {
delta_diagonal_rod_2 = sq(delta_diagonal_rod);
// Effective X/Y positions of the three vertical towers.
delta_tower1_x = (delta_radius + tower_adj[3]) * cos((210 + tower_adj[0]) * PI/180); // front left tower
delta_tower1_y = (delta_radius + tower_adj[3]) * sin((210 + tower_adj[0]) * PI/180);
delta_tower2_x = (delta_radius + tower_adj[4]) * cos((330 + tower_adj[1]) * PI/180); // front right tower
delta_tower2_y = (delta_radius + tower_adj[4]) * sin((330 + tower_adj[1]) * PI/180);
delta_tower3_x = (delta_radius + tower_adj[5]) * cos((90 + tower_adj[2]) * PI/180); // back middle tower
delta_tower3_y = (delta_radius + tower_adj[5]) * sin((90 + tower_adj[2]) * PI/180);
delta_tower1_x = (delta_radius + tower_adj[3]) * cos((210 + tower_adj[0]) * M_PI/180); // front left tower
delta_tower1_y = (delta_radius + tower_adj[3]) * sin((210 + tower_adj[0]) * M_PI/180);
delta_tower2_x = (delta_radius + tower_adj[4]) * cos((330 + tower_adj[1]) * M_PI/180); // front right tower
delta_tower2_y = (delta_radius + tower_adj[4]) * sin((330 + tower_adj[1]) * M_PI/180);
delta_tower3_x = (delta_radius + tower_adj[5]) * cos((90 + tower_adj[2]) * M_PI/180); // back middle tower
delta_tower3_y = (delta_radius + tower_adj[5]) * sin((90 + tower_adj[2]) * M_PI/180);
}
void deploy_z_probe() {
#if NUM_SERVOS > 0
// Engage Z Servo endstop if enabled
if (servo_endstops[Z_AXIS] >= 0) {
Servo *srv = &servo[servo_endstops[Z_AXIS]];
#if SERVO_LEVELING
srv->attach(0);
#endif
srv->write(servo_endstop_angles[Z_AXIS * 2]);
#if SERVO_LEVELING_DELAY
delay(PROBE_SERVO_DEACTIVATION_DELAY);
srv->detach();
#endif
}
#endif //NUM_SERVOS > 0
feedrate = homing_feedrate[X_AXIS];
destination[X_AXIS] = z_probe_deploy_start_location[X_AXIS];
destination[Y_AXIS] = z_probe_deploy_start_location[Y_AXIS];
......@@ -1621,8 +1649,8 @@ static void setup_for_endstop_move() {
void retract_z_probe() {
feedrate = homing_feedrate[X_AXIS];
destination[Z_AXIS] = 50;
prepare_move_raw();
//destination[Z_AXIS] = 50;
//prepare_move_raw();
destination[X_AXIS] = z_probe_retract_start_location[X_AXIS];
destination[Y_AXIS] = z_probe_retract_start_location[Y_AXIS];
......@@ -1642,6 +1670,23 @@ static void setup_for_endstop_move() {
destination[Z_AXIS] = z_probe_retract_start_location[Z_AXIS];
prepare_move_raw();
st_synchronize();
#if NUM_SERVOS > 0
// Retract Z Servo endstop if enabled
if (servo_endstops[Z_AXIS] >= 0) {
// Change the Z servo angle
Servo *srv = &servo[servo_endstops[Z_AXIS]];
#if SERVO_LEVELING
srv->attach(0);
#endif
srv->write(servo_endstop_angles[Z_AXIS * 2 + 1]);
#if SERVO_LEVELING
delay(PROBE_SERVO_DEACTIVATION_DELAY);
srv->detach();
#endif
}
#endif //NUM_SERVOS > 0
}
float z_probe() {
......@@ -1671,9 +1716,10 @@ static void setup_for_endstop_move() {
sync_plan_position_delta();
// Save tower carriage positions for G30 diagnostic reports
for(int8_t i=0; i < 3; i++) {
saved_position[i] = st_get_position_mm(i);
for(int8_t i = 0; i < 3; i++) {
saved_position[i] = float((st_get_position(i)) / axis_steps_per_unit[i]);
}
feedrate = homing_feedrate[Z_AXIS];
destination[Z_AXIS] = mm + Z_RAISE_BETWEEN_PROBINGS;
prepare_move_raw();
......@@ -3441,8 +3487,8 @@ inline void gcode_G28(boolean home_x = false, boolean home_y = false) {
z_tmp = current_position[Z_AXIS],
real_z = (float)st_get_position(Z_AXIS) / axis_steps_per_unit[Z_AXIS]; //get the real Z (since the auto bed leveling is already correcting the plane)
apply_rotation_xyz(plan_bed_level_matrix, x_tmp, y_tmp, z_tmp); //Apply the correction sending the probe offset
current_position[Z_AXIS] = z_tmp - real_z + current_position[Z_AXIS]; //The difference is added to current position and sent to planner.
apply_rotation_xyz(plan_bed_level_matrix, x_tmp, y_tmp, z_tmp); //Apply the correction sending the probe offset
current_position[Z_AXIS] += z_tmp - real_z; //The difference is added to current position and sent to planner.
sync_plan_position();
}
......@@ -5800,12 +5846,13 @@ inline void gcode_M999() {
}
#ifdef CUSTOM_M_CODE_SET_Z_PROBE_OFFSET
inline void gcode_SET_Z_PROBE_OFFSET() {
float value;
if (code_seen('Z')) {
value = code_value();
if (Z_PROBE_OFFSET_RANGE_MIN <= value && value <= Z_PROBE_OFFSET_RANGE_MAX) {
zprobe_zoffset = -value; // compare w/ line 278 of ConfigurationStore.cpp
zprobe_zoffset = -value;
ECHO_LM(DB, MSG_ZPROBE_ZOFFSET " ok");
}
else {
......@@ -5821,8 +5868,13 @@ inline void gcode_M999() {
#endif // CUSTOM_M_CODE_SET_Z_PROBE_OFFSET
/**
* T0-T3: Switch tool, usually switching extruders
*
* F[mm/min] Set the movement feedrate
*/
inline void gcode_T() {
int tmp_extruder = code_value();
uint16_t tmp_extruder = code_value_short();
long csteps;
if (tmp_extruder >= EXTRUDERS) {
ECHO_SMV(DB, "T", tmp_extruder);
......@@ -6066,8 +6118,11 @@ void process_next_command() {
}
if(code_seen('G')) {
int gCode = code_value_short();
switch(gCode) {
int codenum = code_value_short();
switch (codenum) {
//G0 -> G1
case 0:
case 1:
......@@ -6078,7 +6133,7 @@ void process_next_command() {
#ifndef SCARA
case 2: // G2 - CW ARC
case 3: // G3 - CCW ARC
gcode_G2_G3(gCode == 2); break;
gcode_G2_G3(codenum == 2); break;
#endif
// G4 Dwell
......@@ -6088,7 +6143,7 @@ void process_next_command() {
#ifdef FWRETRACT
case 10: // G10: retract
case 11: // G11: retract_recover
gcode_G10_G11(gCode == 10); break;
gcode_G10_G11(codenum == 10); break;
#endif //FWRETRACT
case 28: //G28: Home all axes, one at a time
......@@ -6103,7 +6158,7 @@ void process_next_command() {
#else // Z_PROBE_SLED
case 31: // G31: dock the sled
case 32: // G32: undock the sled
dock_sled(gCode == 31); break;
dock_sled(codenum == 31); break;
#endif // Z_PROBE_SLED
#endif // ENABLE_AUTO_BED_LEVELING
......@@ -6696,83 +6751,82 @@ void prepare_move() {
#endif
#ifdef SCARA
void calculate_SCARA_forward_Transform(float f_scara[3])
{
// Perform forward kinematics, and place results in delta[3]
// The maths and first version has been done by QHARLEY . Integrated into masterbranch 06/2014 and slightly restructured by Joachim Cerny in June 2014
float x_sin, x_cos, y_sin, y_cos;
//ECHO_SMV(DB, "f_delta x=", f_scara[X_AXIS]);
//ECHO_MV(" y=", f_scara[Y_AXIS]);
x_sin = sin(f_scara[X_AXIS]/SCARA_RAD2DEG) * Linkage_1;
x_cos = cos(f_scara[X_AXIS]/SCARA_RAD2DEG) * Linkage_1;
y_sin = sin(f_scara[Y_AXIS]/SCARA_RAD2DEG) * Linkage_2;
y_cos = cos(f_scara[Y_AXIS]/SCARA_RAD2DEG) * Linkage_2;
//ECHO_MV(" x_sin=", x_sin);
//ECHO_MV(" x_cos=", x_cos);
//ECHO_MV(" y_sin=", y_sin);
//ECHO_MV(" y_cos=", y_cos);
delta[X_AXIS] = x_cos + y_cos + SCARA_offset_x; //theta
delta[Y_AXIS] = x_sin + y_sin + SCARA_offset_y; //theta+phi
//ECHO_MV(" delta[X_AXIS]=", delta[X_AXIS]);
//ECHO_EMV(" delta[Y_AXIS]=", delta[Y_AXIS]);
}
void calculate_delta(float cartesian[3]){
//reverse kinematics.
// Perform reversed kinematics, and place results in delta[3]
// The maths and first version has been done by QHARLEY . Integrated into masterbranch 06/2014 and slightly restructured by Joachim Cerny in June 2014
float SCARA_pos[2];
static float SCARA_C2, SCARA_S2, SCARA_K1, SCARA_K2, SCARA_theta, SCARA_psi;
SCARA_pos[X_AXIS] = cartesian[X_AXIS] * axis_scaling[X_AXIS] - SCARA_offset_x; //Translate SCARA to standard X Y
SCARA_pos[Y_AXIS] = cartesian[Y_AXIS] * axis_scaling[Y_AXIS] - SCARA_offset_y; // With scaling factor.
#if (Linkage_1 == Linkage_2)
SCARA_C2 = ( ( sq(SCARA_pos[X_AXIS]) + sq(SCARA_pos[Y_AXIS]) ) / (2 * (float)L1_2) ) - 1;
#else
SCARA_C2 = ( sq(SCARA_pos[X_AXIS]) + sq(SCARA_pos[Y_AXIS]) - (float)L1_2 - (float)L2_2 ) / 45000;
#endif
SCARA_S2 = sqrt( 1 - sq(SCARA_C2) );
SCARA_K1 = Linkage_1 + Linkage_2 * SCARA_C2;
SCARA_K2 = Linkage_2 * SCARA_S2;
SCARA_theta = ( atan2(SCARA_pos[X_AXIS],SCARA_pos[Y_AXIS])-atan2(SCARA_K1, SCARA_K2) ) * -1;
SCARA_psi = atan2(SCARA_S2,SCARA_C2);
delta[X_AXIS] = SCARA_theta * SCARA_RAD2DEG; // Multiply by 180/Pi - theta is support arm angle
delta[Y_AXIS] = (SCARA_theta + SCARA_psi) * SCARA_RAD2DEG; // - equal to sub arm angle (inverted motor)
delta[Z_AXIS] = cartesian[Z_AXIS];
/*
ECHO_SMV(DB, "cartesian x=", cartesian[X_AXIS]);
ECHO_MV(" y=", cartesian[Y_AXIS]);
ECHO_MV(" z=", cartesian[Z_AXIS]);
ECHO_MV("scara x=", SCARA_pos[X_AXIS]);
ECHO_MV(" y=", Y_AXIS]);
ECHO_MV("delta x=", delta[X_AXIS]);
ECHO_MV(" y=", delta[Y_AXIS]);
ECHO_MV(" z=", delta[Z_AXIS]);
ECHO_MV("C2=", SCARA_C2);
ECHO_MV(" S2=", SCARA_S2);
ECHO_MV(" Theta=", SCARA_theta);
ECHO_EMV(" Psi=", SCARA_psi);
*/
}
void calculate_SCARA_forward_Transform(float f_scara[3]) {
// Perform forward kinematics, and place results in delta[3]
// The maths and first version has been done by QHARLEY . Integrated into masterbranch 06/2014 and slightly restructured by Joachim Cerny in June 2014
float x_sin, x_cos, y_sin, y_cos;
#endif
//ECHO_SMV(DB, "f_delta x=", f_scara[X_AXIS]);
//ECHO_MV(" y=", f_scara[Y_AXIS]);
x_sin = sin(f_scara[X_AXIS]/SCARA_RAD2DEG) * Linkage_1;
x_cos = cos(f_scara[X_AXIS]/SCARA_RAD2DEG) * Linkage_1;
y_sin = sin(f_scara[Y_AXIS]/SCARA_RAD2DEG) * Linkage_2;
y_cos = cos(f_scara[Y_AXIS]/SCARA_RAD2DEG) * Linkage_2;
//ECHO_MV(" x_sin=", x_sin);
//ECHO_MV(" x_cos=", x_cos);
//ECHO_MV(" y_sin=", y_sin);
//ECHO_MV(" y_cos=", y_cos);
delta[X_AXIS] = x_cos + y_cos + SCARA_offset_x; //theta
delta[Y_AXIS] = x_sin + y_sin + SCARA_offset_y; //theta+phi
//ECHO_MV(" delta[X_AXIS]=", delta[X_AXIS]);
//ECHO_EMV(" delta[Y_AXIS]=", delta[Y_AXIS]);
}
void calculate_delta(float cartesian[3]) {
//reverse kinematics.
// Perform reversed kinematics, and place results in delta[3]
// The maths and first version has been done by QHARLEY . Integrated into masterbranch 06/2014 and slightly restructured by Joachim Cerny in June 2014
float SCARA_pos[2];
static float SCARA_C2, SCARA_S2, SCARA_K1, SCARA_K2, SCARA_theta, SCARA_psi;
SCARA_pos[X_AXIS] = cartesian[X_AXIS] * axis_scaling[X_AXIS] - SCARA_offset_x; //Translate SCARA to standard X Y
SCARA_pos[Y_AXIS] = cartesian[Y_AXIS] * axis_scaling[Y_AXIS] - SCARA_offset_y; // With scaling factor.
#if (Linkage_1 == Linkage_2)
SCARA_C2 = ( ( sq(SCARA_pos[X_AXIS]) + sq(SCARA_pos[Y_AXIS]) ) / (2 * (float)L1_2) ) - 1;
#else
SCARA_C2 = ( sq(SCARA_pos[X_AXIS]) + sq(SCARA_pos[Y_AXIS]) - (float)L1_2 - (float)L2_2 ) / 45000;
#endif
SCARA_S2 = sqrt( 1 - sq(SCARA_C2) );
SCARA_K1 = Linkage_1 + Linkage_2 * SCARA_C2;
SCARA_K2 = Linkage_2 * SCARA_S2;
SCARA_theta = ( atan2(SCARA_pos[X_AXIS],SCARA_pos[Y_AXIS])-atan2(SCARA_K1, SCARA_K2) ) * -1;
SCARA_psi = atan2(SCARA_S2,SCARA_C2);
delta[X_AXIS] = SCARA_theta * SCARA_RAD2DEG; // Multiply by 180/Pi - theta is support arm angle
delta[Y_AXIS] = (SCARA_theta + SCARA_psi) * SCARA_RAD2DEG; // - equal to sub arm angle (inverted motor)
delta[Z_AXIS] = cartesian[Z_AXIS];
/*
ECHO_SMV(DB, "cartesian x=", cartesian[X_AXIS]);
ECHO_MV(" y=", cartesian[Y_AXIS]);
ECHO_MV(" z=", cartesian[Z_AXIS]);
ECHO_MV("scara x=", SCARA_pos[X_AXIS]);
ECHO_MV(" y=", Y_AXIS]);
ECHO_MV("delta x=", delta[X_AXIS]);
ECHO_MV(" y=", delta[Y_AXIS]);
ECHO_MV(" z=", delta[Z_AXIS]);
ECHO_MV("C2=", SCARA_C2);
ECHO_MV(" S2=", SCARA_S2);
ECHO_MV(" Theta=", SCARA_theta);
ECHO_EMV(" Psi=", SCARA_psi);
*/
}
#endif // SCARA
#ifdef TEMP_STAT_LEDS
......@@ -7023,85 +7077,87 @@ void kill() {
}
#endif
void Stop() {
disable_all_heaters();
if (IsRunning()) {
Running = false;
Stopped_gcode_LastN = gcode_LastN; // Save last g_code for restart
ECHO_LM(ER, MSG_ERR_STOPPED);
ECHO_S(PAUSE);
ECHO_E;
LCD_MESSAGEPGM(MSG_STOPPED);
}
}
#ifdef FAST_PWM_FAN
void setPwmFrequency(uint8_t pin, int val) {
val &= 0x07;
switch(digitalPinToTimer(pin)) {
#if defined(TCCR0A)
case TIMER0A:
case TIMER0B:
// TCCR0B &= ~(_BV(CS00) | _BV(CS01) | _BV(CS02));
// TCCR0B |= val;
break;
case TIMER0A:
case TIMER0B:
// TCCR0B &= ~(_BV(CS00) | _BV(CS01) | _BV(CS02));
// TCCR0B |= val;
break;
#endif
#if defined(TCCR1A)
case TIMER1A:
case TIMER1B:
// TCCR1B &= ~(_BV(CS10) | _BV(CS11) | _BV(CS12));
// TCCR1B |= val;
break;
case TIMER1A:
case TIMER1B:
// TCCR1B &= ~(_BV(CS10) | _BV(CS11) | _BV(CS12));
// TCCR1B |= val;
break;
#endif
#if defined(TCCR2)
case TIMER2:
case TIMER2:
TCCR2 &= ~(_BV(CS10) | _BV(CS11) | _BV(CS12));
TCCR2 |= val;
break;
case TIMER2:
case TIMER2:
TCCR2 &= ~(_BV(CS10) | _BV(CS11) | _BV(CS12));
TCCR2 |= val;
break;
#endif
#if defined(TCCR2A)
case TIMER2A:
case TIMER2B:
TCCR2B &= ~(_BV(CS20) | _BV(CS21) | _BV(CS22));
TCCR2B |= val;
break;
case TIMER2A:
case TIMER2B:
TCCR2B &= ~(_BV(CS20) | _BV(CS21) | _BV(CS22));
TCCR2B |= val;
break;
#endif
#if defined(TCCR3A)
case TIMER3A:
case TIMER3B:
case TIMER3C:
TCCR3B &= ~(_BV(CS30) | _BV(CS31) | _BV(CS32));
TCCR3B |= val;
break;
case TIMER3A:
case TIMER3B:
case TIMER3C:
TCCR3B &= ~(_BV(CS30) | _BV(CS31) | _BV(CS32));
TCCR3B |= val;
break;
#endif
#if defined(TCCR4A)
case TIMER4A:
case TIMER4B:
case TIMER4C:
TCCR4B &= ~(_BV(CS40) | _BV(CS41) | _BV(CS42));
TCCR4B |= val;
break;
#endif
case TIMER4A:
case TIMER4B:
case TIMER4C:
TCCR4B &= ~(_BV(CS40) | _BV(CS41) | _BV(CS42));
TCCR4B |= val;
break;
#endif
#if defined(TCCR5A)
case TIMER5A:
case TIMER5B:
case TIMER5C:
TCCR5B &= ~(_BV(CS50) | _BV(CS51) | _BV(CS52));
TCCR5B |= val;
break;
#endif
case TIMER5A:
case TIMER5B:
case TIMER5C:
TCCR5B &= ~(_BV(CS50) | _BV(CS51) | _BV(CS52));
TCCR5B |= val;
break;
#endif
}
}
#endif //FAST_PWM_FAN
void Stop() {
disable_all_heaters();
if (IsRunning()) {
Running = false;
Stopped_gcode_LastN = gcode_LastN; // Save last g_code for restart
ECHO_LM(ER, MSG_ERR_STOPPED);
ECHO_S(PAUSE);
ECHO_E;
LCD_MESSAGEPGM(MSG_STOPPED);
}
}
bool setTargetedHotend(int code) {
target_extruder = active_extruder;
if (code_seen('T')) {
......
/*
stepper.c - stepper motor driver: executes motion plans using stepper motors
Part of Grbl
Copyright (c) 2009-2011 Simen Svale Skogsrud
Grbl is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
Grbl is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with Grbl. If not, see <http://www.gnu.org/licenses/>.
*/
/**
* stepper.cpp - stepper motor driver: executes motion plans using stepper motors
* Marlin Firmware
*
* Derived from Grbl
* Copyright (c) 2009-2011 Simen Svale Skogsrud
*
* Grbl is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Grbl is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Grbl. If not, see <http://www.gnu.org/licenses/>.
*/
/* The timer calculations of this module informed by the 'RepRap cartesian firmware' by Zack Smith
and Philipp Tiefenbacher. */
......@@ -45,7 +46,7 @@ block_t *current_block; // A pointer to the block currently being traced
//static makes it impossible to be called from outside of this file by extern.!
// Variables used by The Stepper Driver Interrupt
static unsigned char out_bits; // The next stepping-bits to be output
static unsigned char out_bits = 0; // The next stepping-bits to be output
static unsigned int cleaning_buffer_counter;
#ifdef Z_DUAL_ENDSTOPS
......@@ -66,7 +67,7 @@ volatile static unsigned long step_events_completed; // The number of step event
static long acceleration_time, deceleration_time;
//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 unsigned short OCR1A_nominal;
static unsigned short step_loops_nominal;
......@@ -75,10 +76,6 @@ volatile long endstops_trigsteps[3] = { 0 };
volatile long endstops_stepsTotal, endstops_stepsDone;
static volatile char endstop_hit_bits = 0; // use X_MIN, Y_MIN, Z_MIN and Z_PROBE as BIT value
#ifdef NPR2
static bool old_e_min_endstop = false;
#endif
#ifdef ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
bool abort_on_endstop_hit = false;
#endif
......@@ -112,6 +109,10 @@ static bool old_z_max_endstop = false;
static bool old_z_probe_endstop = false;
#endif
#ifdef NPR2
static bool old_e_min_endstop = false;
#endif
static bool check_endstops = true;
volatile long count_position[NUM_AXIS] = { 0 };
......@@ -412,17 +413,18 @@ void set_stepper_direction() {
NORM_E_DIR();
count_direction[E_AXIS] = 1;
}
#endif
#endif // !ADVANCE
}
// Initializes the trapezoid generator from the current block. Called whenever a new
// block begins.
FORCE_INLINE void trapezoid_generator_reset() {
// Set directions TO DO This should be done once during init of trapezoid. Endstops -> interrupt
out_bits = current_block->direction_bits;
set_stepper_direction();
if (current_block->direction_bits != out_bits) {
out_bits = current_block->direction_bits;
set_stepper_direction();
}
#ifdef ADVANCE
advance = current_block->initial_advance;
final_advance = current_block->final_advance;
......@@ -557,8 +559,7 @@ ISR(TIMER1_COMPA_vect) {
#ifdef COREXY
}
#endif
if (TEST(out_bits, Z_AXIS)) { // -direction
if (TEST(out_bits, Z_AXIS)) { // z -direction
#if HAS_Z_MIN
#ifdef Z_DUAL_ENDSTOPS
......@@ -601,8 +602,7 @@ ISR(TIMER1_COMPA_vect) {
old_z_probe_endstop = z_probe_endstop;
#endif
}
else { // +direction
else { // z +direction
#if HAS_Z_MAX
#ifdef Z_DUAL_ENDSTOPS
......@@ -992,12 +992,12 @@ void st_init() {
#endif
#endif
#if (defined(Z_PROBE_PIN) && Z_PROBE_PIN >= 0) && defined(Z_PROBE_ENDSTOP) // Check for Z_PROBE_ENDSTOP so we don't pull a pin high unless it's to be used.
SET_INPUT(Z_PROBE_PIN);
#ifdef ENDSTOPPULLUP_ZPROBE
WRITE(Z_PROBE_PIN, HIGH);
#if (defined(Z_PROBE_PIN) && Z_PROBE_PIN >= 0) && defined(Z_PROBE_ENDSTOP) // Check for Z_PROBE_ENDSTOP so we don't pull a pin high unless it's to be used.
SET_INPUT(Z_PROBE_PIN);
#ifdef ENDSTOPPULLUP_ZPROBE
WRITE(Z_PROBE_PIN, HIGH);
#endif
#endif
#endif
#define _STEP_INIT(AXIS) AXIS ##_STEP_INIT
#define _WRITE_STEP(AXIS, HIGHLOW) AXIS ##_STEP_WRITE(HIGHLOW)
......@@ -1076,6 +1076,8 @@ void st_init() {
enable_endstops(true); // Start with endstops active. After homing they can be disabled
sei();
set_stepper_direction(); // Init directions to out_bits = 0
}
......@@ -1111,10 +1113,13 @@ long st_get_position(uint8_t axis) {
return count_pos;
}
float st_get_position_mm(uint8_t axis) {
float steper_position_in_steps = st_get_position(axis);
return steper_position_in_steps / axis_steps_per_unit[axis];
}
#ifdef ENABLE_AUTO_BED_LEVELING
float st_get_position_mm(AxisEnum axis) {
return st_get_position(axis) / axis_steps_per_unit[axis];
}
#endif // ENABLE_AUTO_BED_LEVELING
void finishAndDisableSteppers() {
st_synchronize();
......
......@@ -70,8 +70,10 @@ void st_set_e_position(const long &e);
// Get current position in steps
long st_get_position(uint8_t axis);
// Get current position in mm
float st_get_position_mm(uint8_t axis);
#ifdef ENABLE_AUTO_BED_LEVELING
// Get current position in mm
float st_get_position_mm(AxisEnum axis);
#endif
// The stepper subsystem goes to sleep when it runs out of things to execute. Call this
// to notify the subsystem that it is time to go to work.
......
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