Commit 9d9893ae authored by MagoKimbra's avatar MagoKimbra

Fix

parent c6ae23a5
......@@ -219,7 +219,7 @@
bool Running = true;
uint8_t debugLevel = DEBUG_INFO|DEBUG_COMMUNICATION;
uint8_t debugLevel = DEBUG_INFO|DEBUG_DRYRUN;
static float feedrate = 1500.0, next_feedrate, saved_feedrate;
float current_position[NUM_AXIS] = { 0.0 };
......@@ -542,7 +542,7 @@ bool enqueuecommand(const char *cmd) {
// This is dangerous if a mixing of serial and this happens
char *command = command_queue[cmd_queue_index_w];
strcpy(command, cmd);
ECHO_LMV(OK, MSG_ENQUEUEING,command);
ECHO_LMV(DB, MSG_ENQUEUEING, command);
cmd_queue_index_w = (cmd_queue_index_w + 1) % BUFSIZE;
commands_in_queue++;
return true;
......@@ -675,14 +675,14 @@ void setup() {
// Check startup - does nothing if bootloader sets MCUSR to 0
byte mcu = MCUSR;
if (mcu & 1) ECHO_LM(OK,MSG_POWERUP);
if (mcu & 2) ECHO_LM(OK,MSG_EXTERNAL_RESET);
if (mcu & 4) ECHO_LM(OK,MSG_BROWNOUT_RESET);
if (mcu & 8) ECHO_LM(OK,MSG_WATCHDOG_RESET);
if (mcu & 32) ECHO_LM(OK,MSG_SOFTWARE_RESET);
if (mcu & 1) ECHO_EM(MSG_POWERUP);
if (mcu & 2) ECHO_EM(MSG_EXTERNAL_RESET);
if (mcu & 4) ECHO_EM(MSG_BROWNOUT_RESET);
if (mcu & 8) ECHO_EM(MSG_WATCHDOG_RESET);
if (mcu & 32) ECHO_EM(MSG_SOFTWARE_RESET);
MCUSR = 0;
ECHO_LM(OK, MSG_MARLIN " " STRING_VERSION);
ECHO_EM(MSG_MARLIN " " STRING_VERSION);
#ifdef STRING_VERSION_CONFIG_H
#ifdef STRING_CONFIG_H_AUTHOR
......@@ -690,9 +690,8 @@ void setup() {
#endif // STRING_CONFIG_H_AUTHOR
#endif // STRING_VERSION_CONFIG_H
ECHO_SMV(OK, MSG_FREE_MEMORY, freeMemory());
ECHO_M(MSG_PLANNER_BUFFER_BYTES);
ECHO_EV((int)sizeof(block_t)*BLOCK_BUFFER_SIZE);
ECHO_SMV(DB, MSG_FREE_MEMORY, freeMemory());
ECHO_EMV(MSG_PLANNER_BUFFER_BYTES, (int)sizeof(block_t)*BLOCK_BUFFER_SIZE);
#ifdef SDSUPPORT
for (int8_t i = 0; i < BUFSIZE; i++) fromsd[i] = false;
......@@ -833,8 +832,7 @@ void get_command() {
strchr_pointer = strchr(command, 'N');
gcode_N = (strtol(strchr_pointer + 1, NULL, 10));
if (gcode_N != gcode_LastN + 1 && strstr_P(command, PSTR("M110")) == NULL) {
ECHO_SMV(ER, MSG_ERR_LINE_NO1, gcode_LastN + 1);
ECHO_EMV(MSG_ERR_LINE_NO2, gcode_N);
ECHO_LMV(ER, MSG_ERR_LINE_NO, gcode_LastN);
FlushSerialRequestResend();
serial_count = 0;
return;
......@@ -880,7 +878,7 @@ void get_command() {
case 2:
case 3:
if (IsStopped()) {
ECHO_LM(ER,MSG_ERR_STOPPED);
ECHO_LM(ER, MSG_ERR_STOPPED);
LCD_MESSAGEPGM(MSG_STOPPED);
}
break;
......@@ -936,7 +934,7 @@ void get_command() {
millis_t t = (print_job_stop_ms - print_job_start_ms) / 1000;
int hours = t / 60 / 60, minutes = (t / 60) % 60;
sprintf_P(time, PSTR("%i " MSG_END_HOUR " %i " MSG_END_MINUTE), hours, minutes);
ECHO_LV(DB,time);
ECHO_LV(DB, time);
lcd_setstatus(time, true);
card.printingHasFinished();
card.checkautostart(true);
......@@ -1961,7 +1959,7 @@ inline void set_destination_to_current() { memcpy(destination, current_position,
float h_endstop = -100, l_endstop = 100;
float probe_error, ftemp;
ECHO_SMV(DB,"Starting Auto Calibration... Calibration precision: +/- ", ac_prec, 3);
ECHO_SMV(DB, "Starting Auto Calibration... Calibration precision: +/- ", ac_prec, 3);
ECHO_EMV("mm Total Iteration: ", iterations);
LCD_MESSAGEPGM("Auto Calibration...");
......@@ -2019,7 +2017,7 @@ inline void set_destination_to_current() { memcpy(destination, current_position,
else {
if ((bed_level_x < -ac_prec) or (bed_level_x > ac_prec) or (bed_level_y < -ac_prec) or (bed_level_y > ac_prec) or (bed_level_z < -ac_prec) or (bed_level_z > ac_prec)) {
//Endstop req adjustment
ECHO_LM(DB,"Adjusting Endstop..");
ECHO_LM(DB, "Adjusting Endstop..");
endstop_adj[0] += bed_level_x / 1.05;
endstop_adj[1] += bed_level_y / 1.05;
endstop_adj[2] += bed_level_z / 1.05;
......@@ -2036,12 +2034,12 @@ inline void set_destination_to_current() { memcpy(destination, current_position,
}
max_pos[Z_AXIS] -= h_endstop + 2;
set_delta_constants();
ECHO_SMV(DB,"Adjusting Z-Height to: ", max_pos[Z_AXIS]);
ECHO_SMV(DB, "Adjusting Z-Height to: ", max_pos[Z_AXIS]);
ECHO_EM(" mm..");
}
}
else {
ECHO_LM(DB,"Endstop: OK");
ECHO_LM(DB, "Endstop: OK");
adj_r_target = (bed_level_x + bed_level_y + bed_level_z) / 3;
adj_dr_target = (bed_level_ox + bed_level_oy + bed_level_oz) / 3;
......@@ -2054,7 +2052,7 @@ inline void set_destination_to_current() { memcpy(destination, current_position,
else adj_tower_done = true;
if ((adj_r_done == false) or (adj_dr_done == false) or (adj_tower_done == false)) {
//delta geometry adjustment required
ECHO_LM(DB,"Adjusting Delta Geometry..");
ECHO_LM(DB, "Adjusting Delta Geometry..");
//set initial direction and magnitude for delta radius & diagonal rod adjustment
if (adj_r == 0) {
if (adj_r_target > bed_level_c) adj_r = 1;
......@@ -2073,7 +2071,7 @@ inline void set_destination_to_current() { memcpy(destination, current_position,
do {
//Apply adjustments
if (adj_r_done == false) {
ECHO_SMV(DB,"Adjusting Delta Radius (", delta_radius);
ECHO_SMV(DB, "Adjusting Delta Radius (", delta_radius);
ECHO_MV(" -> ", delta_radius + adj_r);
ECHO_EM(")");
delta_radius += adj_r;
......@@ -2081,7 +2079,7 @@ inline void set_destination_to_current() { memcpy(destination, current_position,
if (adj_dr_allowed == false) adj_dr_done = true;
if (adj_dr_done == false) {
ECHO_SMV(DB,"Adjusting Diagonal Rod Length (", delta_diagonal_rod);
ECHO_SMV(DB, "Adjusting Diagonal Rod Length (", delta_diagonal_rod);
ECHO_MV(" -> ", delta_diagonal_rod + adj_dr);
ECHO_EM(")");
delta_diagonal_rod += adj_dr;
......@@ -2447,7 +2445,7 @@ inline void wait_heater() {
{ // while loop
if (millis() > temp_ms + 1000UL) { //Print temp & remaining time every 1s while waiting
ECHO_SMV(OK, "T:", degHotend(target_extruder),1);
ECHO_MV("T:", degHotend(target_extruder),1);
ECHO_MV(" E:", target_extruder);
#ifdef TEMP_RESIDENCY_TIME
ECHO_M(" W:");
......@@ -2494,7 +2492,7 @@ inline void wait_bed() {
if (ms > temp_ms + 1000UL) { //Print Temp Reading every 1 second while heating up.
temp_ms = ms;
float tt = degHotend(active_extruder);
ECHO_SMV(OK, "T:", tt);
ECHO_MV("T:", tt);
ECHO_MV(" E:", active_extruder);
ECHO_EMV(" B:", degBed(), 1);
}
......@@ -3674,7 +3672,7 @@ inline void gcode_M31() {
int min = t / 60, sec = t % 60;
char time[30];
sprintf_P(time, PSTR("%i min, %i sec"), min, sec);
ECHO_LV(OK, time);
ECHO_LV(DB, time);
lcd_setstatus(time);
autotempShutdown();
}
......@@ -6270,6 +6268,10 @@ void ClearToSend() {
#endif
ECHO_S(OK);
ECHO_E;
#ifdef ADVANCED_OK
ECHO_MV(" N", gcode_LastN);
ECHO_EMV(" S", commands_in_queue);
#endif
}
void get_coordinates() {
......
......@@ -99,8 +99,7 @@
#define MSG_OK "ok"
#define MSG_WAIT "wait"
#define MSG_FILE_SAVED "Done saving file."
#define MSG_ERR_LINE_NO1 "Line Number out of sequence. Expected: "
#define MSG_ERR_LINE_NO2 " Got: "
#define MSG_ERR_LINE_NO "Line Number is not Last Line Number+1, Last Line: "
#define MSG_ERR_CHECKSUM_MISMATCH "checksum mismatch, Last Line: "
#define MSG_ERR_NO_CHECKSUM "No Checksum with line number, Last Line: "
#define MSG_ERR_NO_LINENUMBER_WITH_CHECKSUM "No Line Number with checksum, Last Line: "
......
/*
planner.c - buffers movement commands and manages the acceleration profile plan
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/>.
*/
/* The ring buffer implementation gleaned from the wiring_serial library by David A. Mellis. */
/*
Reasoning behind the mathematics in this module (in the key of 'Mathematica'):
s == speed, a == acceleration, t == time, d == distance
Basic definitions:
Speed[s_, a_, t_] := s + (a*t)
Travel[s_, a_, t_] := Integrate[Speed[s, a, t], t]
Distance to reach a specific speed with a constant acceleration:
Solve[{Speed[s, a, t] == m, Travel[s, a, t] == d}, d, t]
d -> (m^2 - s^2)/(2 a) --> estimate_acceleration_distance()
Speed after a given distance of travel with constant acceleration:
Solve[{Speed[s, a, t] == m, Travel[s, a, t] == d}, m, t]
m -> Sqrt[2 a d + s^2]
DestinationSpeed[s_, a_, d_] := Sqrt[2 a d + s^2]
When to start braking (di) to reach a specified destination speed (s2) after accelerating
from initial speed s1 without ever stopping at a plateau:
Solve[{DestinationSpeed[s1, a, di] == DestinationSpeed[s2, a, d - di]}, di]
di -> (2 a d - s1^2 + s2^2)/(4 a) --> intersection_distance()
IntersectionDistance[s1_, s2_, a_, d_] := (2 a d - s1^2 + s2^2)/(4 a)
/**
* planner.cpp - Buffer movement commands and manage the acceleration profile plan
* 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/>.
*
*
* The ring buffer implementation gleaned from the wiring_serial library by David A. Mellis.
*
*
* Reasoning behind the mathematics in this module (in the key of 'Mathematica'):
*
* s == speed, a == acceleration, t == time, d == distance
*
* Basic definitions:
* Speed[s_, a_, t_] := s + (a*t)
* Travel[s_, a_, t_] := Integrate[Speed[s, a, t], t]
*
* Distance to reach a specific speed with a constant acceleration:
* Solve[{Speed[s, a, t] == m, Travel[s, a, t] == d}, d, t]
* d -> (m^2 - s^2)/(2 a) --> estimate_acceleration_distance()
*
* Speed after a given distance of travel with constant acceleration:
* Solve[{Speed[s, a, t] == m, Travel[s, a, t] == d}, m, t]
* m -> Sqrt[2 a d + s^2]
*
* DestinationSpeed[s_, a_, d_] := Sqrt[2 a d + s^2]
*
* When to start braking (di) to reach a specified destination speed (s2) after accelerating
* from initial speed s1 without ever stopping at a plateau:
* Solve[{DestinationSpeed[s1, a, di] == DestinationSpeed[s2, a, d - di]}, di]
* di -> (2 a d - s1^2 + s2^2)/(4 a) --> intersection_distance()
*
* IntersectionDistance[s1_, s2_, a_, d_] := (2 a d - s1^2 + s2^2)/(4 a)
*
*/
#include "Marlin.h"
......@@ -68,28 +65,23 @@ float max_retraction_feedrate[EXTRUDERS]; // set the max speeds for retraction
float axis_steps_per_unit[3 + EXTRUDERS];
unsigned long max_acceleration_units_per_sq_second[3 + EXTRUDERS]; // Use M201 to override by software
float minimumfeedrate;
float acceleration; // Normal acceleration mm/s^2 THIS IS THE DEFAULT ACCELERATION for all printing moves. M204 SXXXX
float retract_acceleration; // mm/s^2 filament pull-pack and push-forward while standing still in the other axis M204 TXXXX
float travel_acceleration; // Travel acceleration mm/s^2 THIS IS THE DEFAULT ACCELERATION for all NON printing moves. M204 MXXXX
float max_xy_jerk; //speed than can be stopped at once, if i understand correctly.
float acceleration; // Normal acceleration mm/s^2 DEFAULT ACCELERATION for all printing moves. M204 SXXXX
float retract_acceleration; // Retract acceleration mm/s^2 filament pull-back and push-forward while standing still in the other axes M204 TXXXX
float travel_acceleration; // Travel acceleration mm/s^2 DEFAULT ACCELERATION for all NON printing moves. M204 MXXXX
float max_xy_jerk; // The largest speed change requiring no acceleration
float max_z_jerk;
float max_e_jerk;
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
// Transform required 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
long position[NUM_AXIS]; //rescaled from extern when axis_steps_per_unit are changed by gcode
static float previous_speed[NUM_AXIS]; // Speed of previous path line segment
static float previous_nominal_speed; // Nominal speed of previous path line segment
#endif // ENABLE_AUTO_BED_LEVELING
#ifdef AUTOTEMP
float autotemp_max = 250;
......@@ -98,24 +90,31 @@ static float previous_nominal_speed; // Nominal speed of previous path line segm
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 instructions
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
//===========================================================================
//=============================private variables ============================
//============================ private variables ============================
//===========================================================================
// The current position of the tool in absolute steps
long position[NUM_AXIS]; // Rescaled from extern when axis_steps_per_unit are changed by gcode
static float previous_speed[NUM_AXIS]; // Speed of previous path line segment
static float previous_nominal_speed; // Nominal speed of previous path line segment
unsigned char g_uc_extruder_last_move[4] = {0,0,0,0};
#ifdef XY_FREQUENCY_LIMIT
// Used for the frequency limit
#define MAX_FREQ_TIME (1000000.0/XY_FREQUENCY_LIMIT)
// Old direction bits. Used for speed calculations
static unsigned char old_direction_bits = 0;
// Segment times (in us). Used for speed calculations
// Segment times (in µs). Used for speed calculations
static long axis_segment_time[2][3] = { {MAX_FREQ_TIME+1,0,0}, {MAX_FREQ_TIME+1,0,0} };
#endif
......@@ -123,15 +122,15 @@ volatile unsigned char block_buffer_tail; // Index of the block to process now
static char meas_sample; //temporary variable to hold filament measurement sample
#endif
//===========================================================================
//================================ functions ================================
//===========================================================================
// Get the next / previous index of the next block in the ring buffer
// NOTE: Using & here (not %) because BLOCK_BUFFER_SIZE is always a power of 2
FORCE_INLINE int8_t next_block_index(int8_t block_index) { return BLOCK_MOD(block_index + 1); }
FORCE_INLINE int8_t prev_block_index(int8_t block_index) { return BLOCK_MOD(block_index - 1); }
//===========================================================================
//================================ Functions ================================
//===========================================================================
// 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) {
......@@ -176,10 +175,10 @@ void calculate_trapezoid_for_block(block_t *block, float entry_factor, float exi
plateau_steps = 0;
}
#ifdef 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
#endif // ADVANCE
// block->accelerate_until = accelerate_steps;
// block->decelerate_after = accelerate_steps+plateau_steps;
......@@ -192,7 +191,7 @@ void calculate_trapezoid_for_block(block_t *block, float entry_factor, float exi
#ifdef ADVANCE
block->initial_advance = initial_advance;
block->final_advance = final_advance;
#endif //ADVANCE
#endif
}
CRITICAL_SECTION_END;
}
......@@ -358,6 +357,7 @@ void plan_init() {
previous_nominal_speed = 0.0;
}
#ifdef AUTOTEMP
void getHighESpeed() {
static float oldt = 0;
......@@ -993,11 +993,8 @@ float junction_deviation = 0.1;
block->advance_rate = acc_dist ? advance / (float)acc_dist : 0;
}
/*
ECHO_S(OK);
ECHO_M("advance :");
ECHO_V(block->advance/256.0);
ECHO_M("advance rate :");
ECHO_EV(block->advance_rate/256.0);
ECHO_SMV(OK, "advance :", block->advance/256);
ECHO_EMV("advance rate :", block->advance_rate/256);
*/
#endif // ADVANCE
......@@ -1020,7 +1017,7 @@ float junction_deviation = 0.1;
vector_3 position = vector_3(st_get_position_mm(X_AXIS), st_get_position_mm(Y_AXIS), st_get_position_mm(Z_AXIS));
//position.debug("in plan_get position");
//plan_bed_level_matrix.debug("in plan_get bed_level");
//plan_bed_level_matrix.debug("in plan_get_position");
matrix_3x3 inverse = matrix_3x3::transpose(plan_bed_level_matrix);
//inverse.debug("in plan_get inverse");
position.apply_rotation(inverse);
......@@ -1037,10 +1034,10 @@ float junction_deviation = 0.1;
void plan_set_position(const float &x, const float &y, const float &z, const float &e) {
#endif // ENABLE_AUTO_BED_LEVELING
float nx = position[X_AXIS] = lround(x * axis_steps_per_unit[X_AXIS]);
float ny = position[Y_AXIS] = lround(y * axis_steps_per_unit[Y_AXIS]);
float nz = position[Z_AXIS] = lround(z * axis_steps_per_unit[Z_AXIS]);
float ne = position[E_AXIS] = lround(e * axis_steps_per_unit[E_AXIS + active_extruder]);
float nx = position[X_AXIS] = lround(x * axis_steps_per_unit[X_AXIS]),
ny = position[Y_AXIS] = lround(y * axis_steps_per_unit[Y_AXIS]),
nz = position[Z_AXIS] = lround(z * axis_steps_per_unit[Z_AXIS]),
ne = position[E_AXIS] = lround(e * axis_steps_per_unit[E_AXIS + active_extruder]);
st_set_position(nx, ny, nz, ne);
previous_nominal_speed = 0.0; // Resets planner junction speeds. Assumes start from rest.
......
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