Limit pin internal pull-resistors enabled. Re-wrote read_double() function. Correctly changed all 'double's to 'float's.

- Limit pin internal pull-resistors now enabled. Normal high operation.
This will be the standard going forward.

- Updated all of the 'double' variable types to 'float' to reflect what
happens when compiled for the Arduino. Also done for compatibility
reasons to @jgeisler0303 's Grbl simulator code.

- G-code parser will now ignore 'E' exponent values, since they are
reserved g-code characters for some machines. Thanks @csdexter!

- The read_double() function was re-written and optimized for use in
Grbl. The strtod() avr lib was removed.
This commit is contained in:
Sonny Jeon 2012-10-08 15:57:58 -06:00
parent d30cb906f8
commit ff82489da7
16 changed files with 183 additions and 110 deletions

View File

@ -42,6 +42,7 @@
#define LIMIT_DDR DDRB #define LIMIT_DDR DDRB
#define LIMIT_PIN PINB #define LIMIT_PIN PINB
#define LIMIT_PORT PORTB
#define X_LIMIT_BIT 1 // Uno Digital Pin 9 #define X_LIMIT_BIT 1 // Uno Digital Pin 9
#define Y_LIMIT_BIT 2 // Uno Digital Pin 10 #define Y_LIMIT_BIT 2 // Uno Digital Pin 10
#define Z_LIMIT_BIT 3 // Uno Digital Pin 11 #define Z_LIMIT_BIT 3 // Uno Digital Pin 11
@ -175,7 +176,5 @@
// Limit step rate for homing // Limit step rate for homing
#define LIMIT_DEBOUNCE 50 // Limit switch debounce delay (in ms) #define LIMIT_DEBOUNCE 50 // Limit switch debounce delay (in ms)
// #define LIMIT_INVERT_MASK 0 //
// #define LIMIT_NORMAL_HIGH 1 // Normal low 0 or normal high 1
#endif #endif

31
gcode.c
View File

@ -77,8 +77,8 @@ typedef struct {
uint8_t program_flow; // {M0, M1, M2, M30} uint8_t program_flow; // {M0, M1, M2, M30}
int8_t spindle_direction; // 1 = CW, -1 = CCW, 0 = Stop {M3, M4, M5} int8_t spindle_direction; // 1 = CW, -1 = CCW, 0 = Stop {M3, M4, M5}
uint8_t coolant_mode; // 0 = Disable, 1 = Flood Enable {M8, M9} uint8_t coolant_mode; // 0 = Disable, 1 = Flood Enable {M8, M9}
double feed_rate, seek_rate; // Millimeters/second float feed_rate, seek_rate; // Millimeters/second
double position[3]; // Where the interpreter considers the tool to be at this point in the code float position[3]; // Where the interpreter considers the tool to be at this point in the code
uint8_t tool; uint8_t tool;
uint16_t spindle_speed; // RPM/100 uint16_t spindle_speed; // RPM/100
uint8_t plane_axis_0, uint8_t plane_axis_0,
@ -89,7 +89,7 @@ static parser_state_t gc;
#define FAIL(status) gc.status_code = status; #define FAIL(status) gc.status_code = status;
static int next_statement(char *letter, double *double_ptr, char *line, uint8_t *char_counter); static int next_statement(char *letter, float *float_ptr, char *line, uint8_t *char_counter);
static void select_plane(uint8_t axis_0, uint8_t axis_1, uint8_t axis_2) static void select_plane(uint8_t axis_0, uint8_t axis_1, uint8_t axis_2)
{ {
@ -120,7 +120,7 @@ void gc_clear_position()
clear_vector(gc.position); clear_vector(gc.position);
} }
static float to_millimeters(double value) static float to_millimeters(float value)
{ {
return(gc.inches_mode ? (value * MM_PER_INCH) : value); return(gc.inches_mode ? (value * MM_PER_INCH) : value);
} }
@ -133,17 +133,17 @@ uint8_t gc_execute_line(char *line)
{ {
uint8_t char_counter = 0; uint8_t char_counter = 0;
char letter; char letter;
double value; float value;
int int_value; int int_value;
uint16_t modal_group_words = 0; // Bitflag variable to track and check modal group words in block uint16_t modal_group_words = 0; // Bitflag variable to track and check modal group words in block
uint8_t axis_words = 0; // Bitflag to track which XYZ(ABC) parameters exist in block uint8_t axis_words = 0; // Bitflag to track which XYZ(ABC) parameters exist in block
double inverse_feed_rate = -1; // negative inverse_feed_rate means no inverse_feed_rate specified float inverse_feed_rate = -1; // negative inverse_feed_rate means no inverse_feed_rate specified
uint8_t absolute_override = false; // true(1) = absolute motion for this block only {G53} uint8_t absolute_override = false; // true(1) = absolute motion for this block only {G53}
uint8_t non_modal_action = NON_MODAL_NONE; // Tracks the actions of modal group 0 (non-modal) uint8_t non_modal_action = NON_MODAL_NONE; // Tracks the actions of modal group 0 (non-modal)
double target[3], offset[3]; float target[3], offset[3];
clear_vector(target); // XYZ(ABC) axes parameters. clear_vector(target); // XYZ(ABC) axes parameters.
clear_vector(offset); // IJK Arc offsets are incremental. Value of zero indicates no change. clear_vector(offset); // IJK Arc offsets are incremental. Value of zero indicates no change.
@ -248,11 +248,12 @@ uint8_t gc_execute_line(char *line)
/* Pass 2: Parameters. All units converted according to current block commands. Position /* Pass 2: Parameters. All units converted according to current block commands. Position
parameters are converted and flagged to indicate a change. These can have multiple connotations parameters are converted and flagged to indicate a change. These can have multiple connotations
for different commands. Each will be converted to their proper value upon execution. */ for different commands. Each will be converted to their proper value upon execution. */
double p = 0, r = 0; float p = 0, r = 0;
uint8_t l = 0; uint8_t l = 0;
char_counter = 0; char_counter = 0;
while(next_statement(&letter, &value, line, &char_counter)) { while(next_statement(&letter, &value, line, &char_counter)) {
switch(letter) { switch(letter) {
case 'G': case 'M': break; // Ignore command statements
case 'F': case 'F':
if (value <= 0) { FAIL(STATUS_INVALID_COMMAND); } // Must be greater than zero if (value <= 0) { FAIL(STATUS_INVALID_COMMAND); } // Must be greater than zero
if (gc.inverse_feed_rate_mode) { if (gc.inverse_feed_rate_mode) {
@ -276,6 +277,7 @@ uint8_t gc_execute_line(char *line)
case 'X': target[X_AXIS] = to_millimeters(value); bit_true(axis_words,bit(X_AXIS)); break; case 'X': target[X_AXIS] = to_millimeters(value); bit_true(axis_words,bit(X_AXIS)); break;
case 'Y': target[Y_AXIS] = to_millimeters(value); bit_true(axis_words,bit(Y_AXIS)); break; case 'Y': target[Y_AXIS] = to_millimeters(value); bit_true(axis_words,bit(Y_AXIS)); break;
case 'Z': target[Z_AXIS] = to_millimeters(value); bit_true(axis_words,bit(Z_AXIS)); break; case 'Z': target[Z_AXIS] = to_millimeters(value); bit_true(axis_words,bit(Z_AXIS)); break;
default: FAIL(STATUS_UNSUPPORTED_STATEMENT);
} }
} }
@ -342,7 +344,6 @@ uint8_t gc_execute_line(char *line)
mc_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], settings.default_seek_rate, false); mc_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], settings.default_seek_rate, false);
} }
mc_go_home(); mc_go_home();
// clear_vector(gc.position); // Assumes home is at [0,0,0]
axis_words = 0; // Axis words used. Lock out from motion modes by clearing flags. axis_words = 0; // Axis words used. Lock out from motion modes by clearing flags.
break; break;
case NON_MODAL_SET_COORDINATE_OFFSET: case NON_MODAL_SET_COORDINATE_OFFSET:
@ -473,11 +474,11 @@ uint8_t gc_execute_line(char *line)
*/ */
// Calculate the change in position along each selected axis // Calculate the change in position along each selected axis
double x = target[gc.plane_axis_0]-gc.position[gc.plane_axis_0]; float x = target[gc.plane_axis_0]-gc.position[gc.plane_axis_0];
double y = target[gc.plane_axis_1]-gc.position[gc.plane_axis_1]; float y = target[gc.plane_axis_1]-gc.position[gc.plane_axis_1];
clear_vector(offset); clear_vector(offset);
double h_x2_div_d = -sqrt(4 * r*r - x*x - y*y)/hypot(x,y); // == -(h * 2 / d) float h_x2_div_d = -sqrt(4 * r*r - x*x - y*y)/hypot(x,y); // == -(h * 2 / d)
// If r is smaller than d, the arc is now traversing the complex plane beyond the reach of any // If r is smaller than d, the arc is now traversing the complex plane beyond the reach of any
// real CNC, and thus - for practical reasons - we will terminate promptly: // real CNC, and thus - for practical reasons - we will terminate promptly:
if(isnan(h_x2_div_d)) { FAIL(STATUS_FLOATING_POINT_ERROR); return(gc.status_code); } if(isnan(h_x2_div_d)) { FAIL(STATUS_FLOATING_POINT_ERROR); return(gc.status_code); }
@ -535,7 +536,7 @@ uint8_t gc_execute_line(char *line)
// As far as the parser is concerned, the position is now == target. In reality the // As far as the parser is concerned, the position is now == target. In reality the
// motion control system might still be processing the action and the real tool position // motion control system might still be processing the action and the real tool position
// in any intermediate location. // in any intermediate location.
memcpy(gc.position, target, sizeof(double)*3); // gc.position[] = target[]; memcpy(gc.position, target, sizeof(float)*3); // gc.position[] = target[];
} }
// M0,M1,M2,M30: Perform non-running program flow actions. During a program pause, the buffer may // M0,M1,M2,M30: Perform non-running program flow actions. During a program pause, the buffer may
@ -556,7 +557,7 @@ uint8_t gc_execute_line(char *line)
// Parses the next statement and leaves the counter on the first character following // Parses the next statement and leaves the counter on the first character following
// the statement. Returns 1 if there was a statements, 0 if end of string was reached // the statement. Returns 1 if there was a statements, 0 if end of string was reached
// or there was an error (check state.status_code). // or there was an error (check state.status_code).
static int next_statement(char *letter, double *double_ptr, char *line, uint8_t *char_counter) static int next_statement(char *letter, float *float_ptr, char *line, uint8_t *char_counter)
{ {
if (line[*char_counter] == 0) { if (line[*char_counter] == 0) {
return(0); // No more statements return(0); // No more statements
@ -568,7 +569,7 @@ static int next_statement(char *letter, double *double_ptr, char *line, uint8_t
return(0); return(0);
} }
(*char_counter)++; (*char_counter)++;
if (!read_double(line, char_counter, double_ptr)) { if (!read_float(line, char_counter, float_ptr)) {
FAIL(STATUS_BAD_NUMBER_FORMAT); FAIL(STATUS_BAD_NUMBER_FORMAT);
return(0); return(0);
}; };

View File

@ -35,18 +35,19 @@
void limits_init() void limits_init()
{ {
LIMIT_DDR &= ~(LIMIT_MASK); LIMIT_DDR &= ~(LIMIT_MASK); // Input pin
LIMIT_PORT |= (LIMIT_MASK); // Enable internal pull-up resistors for normal high
} }
// Moves all specified axes in same specified direction (positive=true, negative=false) // Moves all specified axes in same specified direction (positive=true, negative=false)
// and at the homing rate. Homing is a special motion case, where there is only an // and at the homing rate. Homing is a special motion case, where there is only an
// acceleration followed by abrupt asynchronous stops by each axes reaching their limit // acceleration followed by abrupt asynchronous stops by each axes reaching their limit
// switch independently. Instead of showhorning homing cycles into the main stepper // switch independently. Instead of shoehorning homing cycles into the main stepper
// algorithm and overcomplicate things, a stripped-down, lite version of the stepper // algorithm and overcomplicate things, a stripped-down, lite version of the stepper
// algorithm is written here. This also lets users hack and tune this code freely for // algorithm is written here. This also lets users hack and tune this code freely for
// their own particular needs without affecting the rest of Grbl. // their own particular needs without affecting the rest of Grbl.
// NOTE: Only the abort runtime command can interrupt this process. // NOTE: Only the abort runtime command can interrupt this process.
static void homing_cycle(bool x_axis, bool y_axis, bool z_axis, int8_t pos_dir, double homing_rate) static void homing_cycle(bool x_axis, bool y_axis, bool z_axis, int8_t pos_dir, float homing_rate)
{ {
// Determine governing axes with finest step resolution per distance for the Bresenham // Determine governing axes with finest step resolution per distance for the Bresenham
// algorithm. This solves the issue when homing multiple axes that have different // algorithm. This solves the issue when homing multiple axes that have different
@ -67,7 +68,7 @@ static void homing_cycle(bool x_axis, bool y_axis, bool z_axis, int8_t pos_dir,
// used in the main planner to account for distance traveled when moving multiple axes. // used in the main planner to account for distance traveled when moving multiple axes.
// NOTE: When axis acceleration independence is installed, this will be updated to move // NOTE: When axis acceleration independence is installed, this will be updated to move
// all axes at their maximum acceleration and rate. // all axes at their maximum acceleration and rate.
double ds = step_event_count/sqrt(x_axis+y_axis+z_axis); float ds = step_event_count/sqrt(x_axis+y_axis+z_axis);
// Compute the adjusted step rate change with each acceleration tick. (in step/min/acceleration_tick) // Compute the adjusted step rate change with each acceleration tick. (in step/min/acceleration_tick)
uint32_t delta_rate = ceil( ds*settings.acceleration/(60*ACCELERATION_TICKS_PER_SECOND)); uint32_t delta_rate = ceil( ds*settings.acceleration/(60*ACCELERATION_TICKS_PER_SECOND));
@ -180,5 +181,5 @@ void limits_go_home()
limit_switches_present & (1<<X_LIMIT_BIT), limit_switches_present & (1<<X_LIMIT_BIT),
limit_switches_present & (1<<Y_LIMIT_BIT), limit_switches_present & (1<<Y_LIMIT_BIT),
limit_switches_present & (1<<Z_LIMIT_BIT)); limit_switches_present & (1<<Z_LIMIT_BIT));
delay_ms(LIMIT_DEBOUNCE); // Delay to debounce signal before leaving limit switches delay_ms(LIMIT_DEBOUNCE); // Delay to debounce signal before exiting routine
} }

2
main.c
View File

@ -62,7 +62,7 @@ int main(void)
// releases will auto-reset the machine position back to [0,0,0] if an abort is used while // releases will auto-reset the machine position back to [0,0,0] if an abort is used while
// grbl is moving the machine. // grbl is moving the machine.
int32_t last_position[3]; int32_t last_position[3];
double last_coord_system[N_COORDINATE_SYSTEM][3]; float last_coord_system[N_COORDINATE_SYSTEM][3];
memcpy(last_position, sys.position, sizeof(sys.position)); // last_position[] = sys.position[] memcpy(last_position, sys.position, sizeof(sys.position)); // last_position[] = sys.position[]
memcpy(last_coord_system, sys.coord_system, sizeof(sys.coord_system)); // last_coord_system[] = sys.coord_system[] memcpy(last_coord_system, sys.coord_system, sizeof(sys.coord_system)); // last_coord_system[] = sys.coord_system[]

View File

@ -45,7 +45,7 @@
// However, this keeps the memory requirements lower since it doesn't have to call and hold two // However, this keeps the memory requirements lower since it doesn't have to call and hold two
// plan_buffer_lines in memory. Grbl only has to retain the original line input variables during a // plan_buffer_lines in memory. Grbl only has to retain the original line input variables during a
// backlash segment(s). // backlash segment(s).
void mc_line(double x, double y, double z, double feed_rate, uint8_t invert_feed_rate) void mc_line(float x, float y, float z, float feed_rate, uint8_t invert_feed_rate)
{ {
// TODO: Backlash compensation may be installed here. Only need direction info to track when // TODO: Backlash compensation may be installed here. Only need direction info to track when
// to insert a backlash line motion(s) before the intended line motion. Requires its own // to insert a backlash line motion(s) before the intended line motion. Requires its own
@ -80,23 +80,23 @@ void mc_line(double x, double y, double z, double feed_rate, uint8_t invert_feed
// for vector transformation direction. // for vector transformation direction.
// The arc is approximated by generating a huge number of tiny, linear segments. The length of each // The arc is approximated by generating a huge number of tiny, linear segments. The length of each
// segment is configured in settings.mm_per_arc_segment. // segment is configured in settings.mm_per_arc_segment.
void mc_arc(double *position, double *target, double *offset, uint8_t axis_0, uint8_t axis_1, void mc_arc(float *position, float *target, float *offset, uint8_t axis_0, uint8_t axis_1,
uint8_t axis_linear, double feed_rate, uint8_t invert_feed_rate, double radius, uint8_t isclockwise) uint8_t axis_linear, float feed_rate, uint8_t invert_feed_rate, float radius, uint8_t isclockwise)
{ {
double center_axis0 = position[axis_0] + offset[axis_0]; float center_axis0 = position[axis_0] + offset[axis_0];
double center_axis1 = position[axis_1] + offset[axis_1]; float center_axis1 = position[axis_1] + offset[axis_1];
double linear_travel = target[axis_linear] - position[axis_linear]; float linear_travel = target[axis_linear] - position[axis_linear];
double r_axis0 = -offset[axis_0]; // Radius vector from center to current location float r_axis0 = -offset[axis_0]; // Radius vector from center to current location
double r_axis1 = -offset[axis_1]; float r_axis1 = -offset[axis_1];
double rt_axis0 = target[axis_0] - center_axis0; float rt_axis0 = target[axis_0] - center_axis0;
double rt_axis1 = target[axis_1] - center_axis1; float rt_axis1 = target[axis_1] - center_axis1;
// CCW angle between position and target from circle center. Only one atan2() trig computation required. // CCW angle between position and target from circle center. Only one atan2() trig computation required.
double angular_travel = atan2(r_axis0*rt_axis1-r_axis1*rt_axis0, r_axis0*rt_axis0+r_axis1*rt_axis1); float angular_travel = atan2(r_axis0*rt_axis1-r_axis1*rt_axis0, r_axis0*rt_axis0+r_axis1*rt_axis1);
if (angular_travel < 0) { angular_travel += 2*M_PI; } if (angular_travel < 0) { angular_travel += 2*M_PI; }
if (isclockwise) { angular_travel -= 2*M_PI; } if (isclockwise) { angular_travel -= 2*M_PI; }
double millimeters_of_travel = hypot(angular_travel*radius, fabs(linear_travel)); float millimeters_of_travel = hypot(angular_travel*radius, fabs(linear_travel));
if (millimeters_of_travel == 0.0) { return; } if (millimeters_of_travel == 0.0) { return; }
uint16_t segments = floor(millimeters_of_travel/settings.mm_per_arc_segment); uint16_t segments = floor(millimeters_of_travel/settings.mm_per_arc_segment);
// Multiply inverse feed_rate to compensate for the fact that this movement is approximated // Multiply inverse feed_rate to compensate for the fact that this movement is approximated
@ -104,8 +104,8 @@ void mc_arc(double *position, double *target, double *offset, uint8_t axis_0, ui
// all segments. // all segments.
if (invert_feed_rate) { feed_rate *= segments; } if (invert_feed_rate) { feed_rate *= segments; }
double theta_per_segment = angular_travel/segments; float theta_per_segment = angular_travel/segments;
double linear_per_segment = linear_travel/segments; float linear_per_segment = linear_travel/segments;
/* Vector rotation by transformation matrix: r is the original vector, r_T is the rotated vector, /* Vector rotation by transformation matrix: r is the original vector, r_T is the rotated vector,
and phi is the angle of rotation. Based on the solution approach by Jens Geisler. and phi is the angle of rotation. Based on the solution approach by Jens Geisler.
@ -133,13 +133,13 @@ void mc_arc(double *position, double *target, double *offset, uint8_t axis_0, ui
This is important when there are successive arc motions. This is important when there are successive arc motions.
*/ */
// Vector rotation matrix values // Vector rotation matrix values
double cos_T = 1-0.5*theta_per_segment*theta_per_segment; // Small angle approximation float cos_T = 1-0.5*theta_per_segment*theta_per_segment; // Small angle approximation
double sin_T = theta_per_segment; float sin_T = theta_per_segment;
double arc_target[3]; float arc_target[3];
double sin_Ti; float sin_Ti;
double cos_Ti; float cos_Ti;
double r_axisi; float r_axisi;
uint16_t i; uint16_t i;
int8_t count = 0; int8_t count = 0;
@ -179,7 +179,7 @@ void mc_arc(double *position, double *target, double *offset, uint8_t axis_0, ui
// Execute dwell in seconds. // Execute dwell in seconds.
void mc_dwell(double seconds) void mc_dwell(float seconds)
{ {
uint16_t i = floor(1000/DWELL_TIME_STEP*seconds); uint16_t i = floor(1000/DWELL_TIME_STEP*seconds);
plan_synchronize(); plan_synchronize();
@ -200,5 +200,5 @@ void mc_go_home()
// Upon completion, reset all internal position vectors (g-code parser, planner, system) // Upon completion, reset all internal position vectors (g-code parser, planner, system)
gc_clear_position(); gc_clear_position();
plan_clear_position(); plan_clear_position();
clear_vector_double(sys.position); clear_vector_float(sys.position);
} }

View File

@ -28,17 +28,17 @@
// Execute linear motion in absolute millimeter coordinates. Feed rate given in millimeters/second // Execute linear motion in absolute millimeter coordinates. Feed rate given in millimeters/second
// unless invert_feed_rate is true. Then the feed_rate means that the motion should be completed in // unless invert_feed_rate is true. Then the feed_rate means that the motion should be completed in
// (1 minute)/feed_rate time. // (1 minute)/feed_rate time.
void mc_line(double x, double y, double z, double feed_rate, uint8_t invert_feed_rate); void mc_line(float x, float y, float z, float feed_rate, uint8_t invert_feed_rate);
// Execute an arc in offset mode format. position == current xyz, target == target xyz, // Execute an arc in offset mode format. position == current xyz, target == target xyz,
// offset == offset from current xyz, axis_XXX defines circle plane in tool space, axis_linear is // offset == offset from current xyz, axis_XXX defines circle plane in tool space, axis_linear is
// the direction of helical travel, radius == circle radius, isclockwise boolean. Used // the direction of helical travel, radius == circle radius, isclockwise boolean. Used
// for vector transformation direction. // for vector transformation direction.
void mc_arc(double *position, double *target, double *offset, uint8_t axis_0, uint8_t axis_1, void mc_arc(float *position, float *target, float *offset, uint8_t axis_0, uint8_t axis_1,
uint8_t axis_linear, double feed_rate, uint8_t invert_feed_rate, double radius, uint8_t isclockwise); uint8_t axis_linear, float feed_rate, uint8_t invert_feed_rate, float radius, uint8_t isclockwise);
// Dwell for a specific number of seconds // Dwell for a specific number of seconds
void mc_dwell(double seconds); void mc_dwell(float seconds);
// Send the tool home (not implemented) // Send the tool home (not implemented)
void mc_go_home(); void mc_go_home();

View File

@ -24,20 +24,92 @@
#include <stdlib.h> #include <stdlib.h>
#include <util/delay.h> #include <util/delay.h>
int read_double(char *line, uint8_t *char_counter, double *double_ptr) #define MAX_INT_DIGITS 8 // Maximum number of digits in int32 (and float)
{ extern float __floatunsisf (unsigned long);
char *start = line + *char_counter;
char *end;
*double_ptr = strtod(start, &end);
if(end == start) {
return(false);
};
*char_counter = end - line; // Extracts a floating point value from a string. The following code is based loosely on
// the avr-libc strtod() function by Michael Stumpf and Dmitry Xmelkov and many freely
// available conversion method examples, but has been highly optimized for Grbl. For known
// CNC applications, the typical decimal value is expected to be in the range of E0 to E-4.
// Scientific notation is officially not supported by g-code, and the 'E' character may
// be a g-code word on some CNC systems. So, 'E' notation will not be recognized.
// NOTE: Thanks to Radu-Eosif Mihailescu for identifying the issues with using strtod().
int read_float(char *line, uint8_t *char_counter, float *float_ptr)
{
char *ptr = line + *char_counter;
unsigned char c;
// Grab first character and increment pointer. No spaces assumed in line.
c = *ptr++;
// Capture initial positive/minus character
bool isnegative = false;
if (c == '-') {
isnegative = true;
c = *ptr++;
} else if (c == '+') {
c = *ptr++;
}
// Extract number into fast integer. Track decimal in terms of exponent value.
uint32_t intval = 0;
int8_t exp = 0;
uint8_t ndigit = 0;
bool isdecimal = false;
while(1) {
c -= '0';
if (c <= 9) {
ndigit++;
if (ndigit <= MAX_INT_DIGITS) {
if (isdecimal) { exp--; }
intval = (((intval << 2) + intval) << 1) + c; // intval*10 + c
} else {
if (!(isdecimal)) { exp++; } // Drop overflow digits
}
} else if (c == (('.'-'0') & 0xff) && !(isdecimal)) {
isdecimal = true;
} else {
break;
}
c = *ptr++;
}
// Return if no digits have been read.
if (!ndigit) { return(false); };
// Convert integer into floating point.
float fval;
fval = __floatunsisf(intval);
// Apply decimal. Should perform no more than two floating point multiplications for the
// expected range of E0 to E-4.
if (fval != 0) {
while (exp <= -2) {
fval *= 0.01;
exp += 2;
}
if (exp < 0) {
fval *= 0.1;
} else if (exp > 0) {
do {
fval *= 10.0;
} while (--exp > 0);
}
}
// Assign floating point value with correct sign.
if (isnegative) {
*float_ptr = -fval;
} else {
*float_ptr = fval;
}
*char_counter = ptr - line - 1; // Set char_counter to next statement
return(true); return(true);
} }
// Delays variable defined milliseconds. Compiler compatibility fix for _delay_ms(), // Delays variable defined milliseconds. Compiler compatibility fix for _delay_ms(),
// which only accepts constants in future compiler releases. // which only accepts constants in future compiler releases.
void delay_ms(uint16_t ms) void delay_ms(uint16_t ms)
@ -45,6 +117,7 @@ void delay_ms(uint16_t ms)
while ( ms-- ) { _delay_ms(1); } while ( ms-- ) { _delay_ms(1); }
} }
// Delays variable defined microseconds. Compiler compatibility fix for _delay_us(), // Delays variable defined microseconds. Compiler compatibility fix for _delay_us(),
// which only accepts constants in future compiler releases. Written to perform more // which only accepts constants in future compiler releases. Written to perform more
// efficiently with larger delays, as the counter adds parasitic time in each iteration. // efficiently with larger delays, as the counter adds parasitic time in each iteration.

View File

@ -38,7 +38,7 @@
// Useful macros // Useful macros
#define clear_vector(a) memset(a, 0, sizeof(a)) #define clear_vector(a) memset(a, 0, sizeof(a))
#define clear_vector_double(a) memset(a, 0.0, sizeof(a)) #define clear_vector_float(a) memset(a, 0.0, sizeof(a))
#define max(a,b) (((a) > (b)) ? (a) : (b)) #define max(a,b) (((a) > (b)) ? (a) : (b))
#define min(a,b) (((a) < (b)) ? (a) : (b)) #define min(a,b) (((a) < (b)) ? (a) : (b))
@ -74,10 +74,10 @@ typedef struct {
// NOTE: This may need to be a volatile variable, if problems arise. // NOTE: This may need to be a volatile variable, if problems arise.
uint8_t coord_select; // Active work coordinate system number. Default: 0=G54. uint8_t coord_select; // Active work coordinate system number. Default: 0=G54.
double coord_system[N_COORDINATE_SYSTEM][3]; // Work coordinate systems (G54+). Stores offset from float coord_system[N_COORDINATE_SYSTEM][3]; // Work coordinate systems (G54+). Stores offset from
// absolute machine position in mm. // absolute machine position in mm.
// Rows: Work system number (0=G54,1=G55,...5=G59), Columns: XYZ Offsets // Rows: Work system number (0=G54,1=G55,...5=G59), Columns: XYZ Offsets
double coord_offset[3]; // Retains the G92 coordinate offset (work coordinates) relative to float coord_offset[3]; // Retains the G92 coordinate offset (work coordinates) relative to
// machine zero in mm. // machine zero in mm.
volatile uint8_t cycle_start; // Cycle start flag. Set by stepper subsystem or main program. volatile uint8_t cycle_start; // Cycle start flag. Set by stepper subsystem or main program.
@ -86,9 +86,9 @@ typedef struct {
extern system_t sys; extern system_t sys;
// Read a floating point value from a string. Line points to the input buffer, char_counter // Read a floating point value from a string. Line points to the input buffer, char_counter
// is the indexer pointing to the current character of the line, while double_ptr is // is the indexer pointing to the current character of the line, while float_ptr is
// a pointer to the result variable. Returns true when it succeeds // a pointer to the result variable. Returns true when it succeeds
int read_double(char *line, uint8_t *char_counter, double *double_ptr); int read_float(char *line, uint8_t *char_counter, float *float_ptr);
// Delays variable-defined milliseconds. Compiler compatibility fix for _delay_ms(). // Delays variable-defined milliseconds. Compiler compatibility fix for _delay_ms().
void delay_ms(uint16_t ms); void delay_ms(uint16_t ms);

View File

@ -46,8 +46,8 @@ typedef struct {
int32_t position[3]; // The planner position of the tool in absolute steps. Kept separate int32_t position[3]; // The planner position of the tool in absolute steps. Kept separate
// from g-code position for movements requiring multiple line motions, // from g-code position for movements requiring multiple line motions,
// i.e. arcs, canned cycles, and backlash compensation. // i.e. arcs, canned cycles, and backlash compensation.
double previous_unit_vec[3]; // Unit vector of previous path line segment float previous_unit_vec[3]; // Unit vector of previous path line segment
double previous_nominal_speed; // Nominal speed of previous path line segment float previous_nominal_speed; // Nominal speed of previous path line segment
} planner_t; } planner_t;
static planner_t pl; static planner_t pl;
@ -72,7 +72,7 @@ static uint8_t prev_block_index(uint8_t block_index)
// Calculates the distance (not time) it takes to accelerate from initial_rate to target_rate using the // Calculates the distance (not time) it takes to accelerate from initial_rate to target_rate using the
// given acceleration: // given acceleration:
static double estimate_acceleration_distance(double initial_rate, double target_rate, double acceleration) static float estimate_acceleration_distance(float initial_rate, float target_rate, float acceleration)
{ {
return( (target_rate*target_rate-initial_rate*initial_rate)/(2*acceleration) ); return( (target_rate*target_rate-initial_rate*initial_rate)/(2*acceleration) );
} }
@ -91,7 +91,7 @@ static double estimate_acceleration_distance(double initial_rate, double target_
// you started at speed initial_rate and accelerated until this point and want to end at the final_rate after // you started at speed initial_rate and accelerated until this point and want to end at the final_rate after
// a total travel of distance. This can be used to compute the intersection point between acceleration and // 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) // deceleration in the cases where the trapezoid has no plateau (i.e. never reaches maximum speed)
static double intersection_distance(double initial_rate, double final_rate, double acceleration, double distance) static float intersection_distance(float initial_rate, float final_rate, float acceleration, float distance)
{ {
return( (2*acceleration*distance-initial_rate*initial_rate+final_rate*final_rate)/(4*acceleration) ); return( (2*acceleration*distance-initial_rate*initial_rate+final_rate*final_rate)/(4*acceleration) );
} }
@ -102,7 +102,7 @@ static double intersection_distance(double initial_rate, double final_rate, doub
// NOTE: sqrt() reimplimented here from prior version due to improved planner logic. Increases speed // NOTE: sqrt() reimplimented here from prior version due to improved planner logic. Increases speed
// in time critical computations, i.e. arcs or rapid short lines from curves. Guaranteed to not exceed // in time critical computations, i.e. arcs or rapid short lines from curves. Guaranteed to not exceed
// BLOCK_BUFFER_SIZE calls per planner cycle. // BLOCK_BUFFER_SIZE calls per planner cycle.
static double max_allowable_speed(double acceleration, double target_velocity, double distance) static float max_allowable_speed(float acceleration, float target_velocity, float distance)
{ {
return( sqrt(target_velocity*target_velocity-2*acceleration*distance) ); return( sqrt(target_velocity*target_velocity-2*acceleration*distance) );
} }
@ -162,7 +162,7 @@ static void planner_forward_pass_kernel(block_t *previous, block_t *current, blo
// If nominal length is true, max junction speed is guaranteed to be reached. No need to recheck. // If nominal length is true, max junction speed is guaranteed to be reached. No need to recheck.
if (!previous->nominal_length_flag) { if (!previous->nominal_length_flag) {
if (previous->entry_speed < current->entry_speed) { if (previous->entry_speed < current->entry_speed) {
double entry_speed = min( current->entry_speed, float entry_speed = min( current->entry_speed,
max_allowable_speed(-settings.acceleration,previous->entry_speed,previous->millimeters) ); max_allowable_speed(-settings.acceleration,previous->entry_speed,previous->millimeters) );
// Check for junction speed change // Check for junction speed change
@ -205,7 +205,7 @@ static void planner_forward_pass()
// The factors represent a factor of braking and must be in the range 0.0-1.0. // The factors represent a factor of braking and must be in the range 0.0-1.0.
// This converts the planner parameters to the data required by the stepper controller. // This converts the planner parameters to the data required by the stepper controller.
// NOTE: Final rates must be computed in terms of their respective blocks. // NOTE: Final rates must be computed in terms of their respective blocks.
static void calculate_trapezoid_for_block(block_t *block, double entry_factor, double exit_factor) static void calculate_trapezoid_for_block(block_t *block, float entry_factor, float exit_factor)
{ {
block->initial_rate = ceil(block->nominal_rate*entry_factor); // (step/min) block->initial_rate = ceil(block->nominal_rate*entry_factor); // (step/min)
block->final_rate = ceil(block->nominal_rate*exit_factor); // (step/min) block->final_rate = ceil(block->nominal_rate*exit_factor); // (step/min)
@ -347,7 +347,7 @@ void plan_synchronize()
// All position data passed to the planner must be in terms of machine position to keep the planner // All position data passed to the planner must be in terms of machine position to keep the planner
// independent of any coordinate system changes and offsets, which are handled by the g-code parser. // independent of any coordinate system changes and offsets, which are handled by the g-code parser.
// NOTE: Assumes buffer is available. Buffer checks are handled at a higher level by motion_control. // NOTE: Assumes buffer is available. Buffer checks are handled at a higher level by motion_control.
void plan_buffer_line(double x, double y, double z, double feed_rate, uint8_t invert_feed_rate) void plan_buffer_line(float x, float y, float z, float feed_rate, uint8_t invert_feed_rate)
{ {
// Prepare to set up new block // Prepare to set up new block
block_t *block = &block_buffer[block_buffer_head]; block_t *block = &block_buffer[block_buffer_head];
@ -374,17 +374,17 @@ void plan_buffer_line(double x, double y, double z, double feed_rate, uint8_t in
if (block->step_event_count == 0) { return; }; if (block->step_event_count == 0) { return; };
// Compute path vector in terms of absolute step target and current positions // Compute path vector in terms of absolute step target and current positions
double delta_mm[3]; float delta_mm[3];
delta_mm[X_AXIS] = (target[X_AXIS]-pl.position[X_AXIS])/settings.steps_per_mm[X_AXIS]; delta_mm[X_AXIS] = (target[X_AXIS]-pl.position[X_AXIS])/settings.steps_per_mm[X_AXIS];
delta_mm[Y_AXIS] = (target[Y_AXIS]-pl.position[Y_AXIS])/settings.steps_per_mm[Y_AXIS]; delta_mm[Y_AXIS] = (target[Y_AXIS]-pl.position[Y_AXIS])/settings.steps_per_mm[Y_AXIS];
delta_mm[Z_AXIS] = (target[Z_AXIS]-pl.position[Z_AXIS])/settings.steps_per_mm[Z_AXIS]; delta_mm[Z_AXIS] = (target[Z_AXIS]-pl.position[Z_AXIS])/settings.steps_per_mm[Z_AXIS];
block->millimeters = sqrt(delta_mm[X_AXIS]*delta_mm[X_AXIS] + delta_mm[Y_AXIS]*delta_mm[Y_AXIS] + block->millimeters = sqrt(delta_mm[X_AXIS]*delta_mm[X_AXIS] + delta_mm[Y_AXIS]*delta_mm[Y_AXIS] +
delta_mm[Z_AXIS]*delta_mm[Z_AXIS]); delta_mm[Z_AXIS]*delta_mm[Z_AXIS]);
double inverse_millimeters = 1.0/block->millimeters; // Inverse millimeters to remove multiple divides float inverse_millimeters = 1.0/block->millimeters; // Inverse millimeters to remove multiple divides
// Calculate speed in mm/minute for each axis. No divide by zero due to previous checks. // Calculate speed in mm/minute for each axis. No divide by zero due to previous checks.
// NOTE: Minimum stepper speed is limited by MINIMUM_STEPS_PER_MINUTE in stepper.c // NOTE: Minimum stepper speed is limited by MINIMUM_STEPS_PER_MINUTE in stepper.c
double inverse_minute; float inverse_minute;
if (!invert_feed_rate) { if (!invert_feed_rate) {
inverse_minute = feed_rate * inverse_millimeters; inverse_minute = feed_rate * inverse_millimeters;
} else { } else {
@ -404,7 +404,7 @@ void plan_buffer_line(double x, double y, double z, double feed_rate, uint8_t in
settings.acceleration / (60 * ACCELERATION_TICKS_PER_SECOND )); // (step/min/acceleration_tick) settings.acceleration / (60 * ACCELERATION_TICKS_PER_SECOND )); // (step/min/acceleration_tick)
// Compute path unit vector // Compute path unit vector
double unit_vec[3]; float unit_vec[3];
unit_vec[X_AXIS] = delta_mm[X_AXIS]*inverse_millimeters; unit_vec[X_AXIS] = delta_mm[X_AXIS]*inverse_millimeters;
unit_vec[Y_AXIS] = delta_mm[Y_AXIS]*inverse_millimeters; unit_vec[Y_AXIS] = delta_mm[Y_AXIS]*inverse_millimeters;
@ -419,13 +419,13 @@ void plan_buffer_line(double x, double y, double z, double feed_rate, uint8_t in
// path width or max_jerk in the previous grbl version. This approach does not actually deviate // path width or max_jerk in the previous grbl version. This approach does not actually deviate
// from path, but used as a robust way to compute cornering speeds, as it takes into account the // from path, but used as a robust way to compute cornering speeds, as it takes into account the
// nonlinearities of both the junction angle and junction velocity. // nonlinearities of both the junction angle and junction velocity.
double vmax_junction = MINIMUM_PLANNER_SPEED; // Set default max junction speed float vmax_junction = MINIMUM_PLANNER_SPEED; // Set default max junction speed
// Skip first block or when previous_nominal_speed is used as a flag for homing and offset cycles. // Skip first block or when previous_nominal_speed is used as a flag for homing and offset cycles.
if ((block_buffer_head != block_buffer_tail) && (pl.previous_nominal_speed > 0.0)) { if ((block_buffer_head != block_buffer_tail) && (pl.previous_nominal_speed > 0.0)) {
// Compute cosine of angle between previous and current path. (prev_unit_vec is negative) // Compute cosine of angle between previous and current path. (prev_unit_vec is negative)
// NOTE: Max junction velocity is computed without sin() or acos() by trig half angle identity. // NOTE: Max junction velocity is computed without sin() or acos() by trig half angle identity.
double cos_theta = - pl.previous_unit_vec[X_AXIS] * unit_vec[X_AXIS] float cos_theta = - pl.previous_unit_vec[X_AXIS] * unit_vec[X_AXIS]
- pl.previous_unit_vec[Y_AXIS] * unit_vec[Y_AXIS] - pl.previous_unit_vec[Y_AXIS] * unit_vec[Y_AXIS]
- pl.previous_unit_vec[Z_AXIS] * unit_vec[Z_AXIS] ; - pl.previous_unit_vec[Z_AXIS] * unit_vec[Z_AXIS] ;
@ -435,7 +435,7 @@ void plan_buffer_line(double x, double y, double z, double feed_rate, uint8_t in
// Skip and avoid divide by zero for straight junctions at 180 degrees. Limit to min() of nominal speeds. // Skip and avoid divide by zero for straight junctions at 180 degrees. Limit to min() of nominal speeds.
if (cos_theta > -0.95) { if (cos_theta > -0.95) {
// Compute maximum junction velocity based on maximum acceleration and junction deviation // Compute maximum junction velocity based on maximum acceleration and junction deviation
double sin_theta_d2 = sqrt(0.5*(1.0-cos_theta)); // Trig half angle identity. Always positive. float sin_theta_d2 = sqrt(0.5*(1.0-cos_theta)); // Trig half angle identity. Always positive.
vmax_junction = min(vmax_junction, vmax_junction = min(vmax_junction,
sqrt(settings.acceleration * settings.junction_deviation * sin_theta_d2/(1.0-sin_theta_d2)) ); sqrt(settings.acceleration * settings.junction_deviation * sin_theta_d2/(1.0-sin_theta_d2)) );
} }
@ -444,7 +444,7 @@ void plan_buffer_line(double x, double y, double z, double feed_rate, uint8_t in
block->max_entry_speed = vmax_junction; block->max_entry_speed = vmax_junction;
// Initialize block entry speed. Compute based on deceleration to user-defined MINIMUM_PLANNER_SPEED. // Initialize block entry speed. Compute based on deceleration to user-defined MINIMUM_PLANNER_SPEED.
double v_allowable = max_allowable_speed(-settings.acceleration,MINIMUM_PLANNER_SPEED,block->millimeters); float v_allowable = max_allowable_speed(-settings.acceleration,MINIMUM_PLANNER_SPEED,block->millimeters);
block->entry_speed = min(vmax_junction, v_allowable); block->entry_speed = min(vmax_junction, v_allowable);
// Initialize planner efficiency flags // Initialize planner efficiency flags

View File

@ -34,10 +34,10 @@ typedef struct {
int32_t step_event_count; // The number of step events required to complete this block int32_t step_event_count; // The number of step events required to complete this block
// Fields used by the motion planner to manage acceleration // Fields used by the motion planner to manage acceleration
double nominal_speed; // The nominal speed for this block in mm/min float nominal_speed; // The nominal speed for this block in mm/min
double entry_speed; // Entry speed at previous-current block junction in mm/min float entry_speed; // Entry speed at previous-current block junction in mm/min
double max_entry_speed; // Maximum allowable junction entry speed in mm/min float max_entry_speed; // Maximum allowable junction entry speed in mm/min
double millimeters; // The total travel of this block in mm float millimeters; // The total travel of this block in mm
uint8_t recalculate_flag; // Planner flag to recalculate trapezoids on entry junction uint8_t recalculate_flag; // Planner flag to recalculate trapezoids on entry junction
uint8_t nominal_length_flag; // Planner flag for nominal speed always reached uint8_t nominal_length_flag; // Planner flag for nominal speed always reached
@ -57,7 +57,7 @@ void plan_init();
// Add a new linear movement to the buffer. x, y and z is the signed, absolute target position in // Add a new linear movement to the buffer. x, y and z is the signed, absolute target position in
// millimaters. Feed rate specifies the speed of the motion. If feed rate is inverted, the feed // millimaters. Feed rate specifies the speed of the motion. If feed rate is inverted, the feed
// rate is taken to mean "frequency" and would complete the operation in 1/feed_rate minutes. // rate is taken to mean "frequency" and would complete the operation in 1/feed_rate minutes.
void plan_buffer_line(double x, double y, double z, double feed_rate, uint8_t invert_feed_rate); void plan_buffer_line(float x, float y, float z, float feed_rate, uint8_t invert_feed_rate);
// Called when the current block is no longer needed. Discards the block and makes the memory // Called when the current block is no longer needed. Discards the block and makes the memory
// availible for new blocks. // availible for new blocks.

View File

@ -105,7 +105,7 @@ void printInteger(long n)
print_uint32_base10(n); print_uint32_base10(n);
} }
void printFloat(double n) void printFloat(float n)
{ {
if (n < 0) { if (n < 0) {
serial_write('-'); serial_write('-');

View File

@ -33,6 +33,6 @@ void printInteger(long n);
void print_uint8_base2(uint8_t n); void print_uint8_base2(uint8_t n);
void printFloat(double n); void printFloat(float n);
#endif #endif

View File

@ -245,7 +245,7 @@ void protocol_process()
// Enable comments flag and ignore all characters until ')' or EOL. // Enable comments flag and ignore all characters until ')' or EOL.
iscomment = true; iscomment = true;
} else if (char_counter >= LINE_BUFFER_SIZE-1) { } else if (char_counter >= LINE_BUFFER_SIZE-1) {
// Throw away any characters beyond the end of the line buffer // Throw away any characters beyond the end of the line buffer
} else if (c >= 'a' && c <= 'z') { // Upcase lowercase } else if (c >= 'a' && c <= 'z') { // Upcase lowercase
line[char_counter++] = c-'a'+'A'; line[char_counter++] = c-'a'+'A';
} else { } else {

View File

@ -33,13 +33,13 @@ settings_t settings;
// Version 1 outdated settings record // Version 1 outdated settings record
typedef struct { typedef struct {
double steps_per_mm[3]; float steps_per_mm[3];
uint8_t microsteps; uint8_t microsteps;
uint8_t pulse_microseconds; uint8_t pulse_microseconds;
double default_feed_rate; float default_feed_rate;
double default_seek_rate; float default_seek_rate;
uint8_t invert_mask; uint8_t invert_mask;
double mm_per_arc_segment; float mm_per_arc_segment;
} settings_v1_t; } settings_v1_t;
// Default settings (used when resetting eeprom-settings) // Default settings (used when resetting eeprom-settings)
@ -89,20 +89,20 @@ void settings_dump() {
// Parameter lines are on the form '$4=374.3' or '$' to dump current settings // Parameter lines are on the form '$4=374.3' or '$' to dump current settings
uint8_t settings_execute_line(char *line) { uint8_t settings_execute_line(char *line) {
uint8_t char_counter = 1; uint8_t char_counter = 1;
double parameter, value; float parameter, value;
if(line[0] != '$') { if(line[0] != '$') {
return(STATUS_UNSUPPORTED_STATEMENT); return(STATUS_UNSUPPORTED_STATEMENT);
} }
if(line[char_counter] == 0) { if(line[char_counter] == 0) {
settings_dump(); return(STATUS_OK); settings_dump(); return(STATUS_OK);
} }
if(!read_double(line, &char_counter, &parameter)) { if(!read_float(line, &char_counter, &parameter)) {
return(STATUS_BAD_NUMBER_FORMAT); return(STATUS_BAD_NUMBER_FORMAT);
}; };
if(line[char_counter++] != '=') { if(line[char_counter++] != '=') {
return(STATUS_UNSUPPORTED_STATEMENT); return(STATUS_UNSUPPORTED_STATEMENT);
} }
if(!read_double(line, &char_counter, &value)) { if(!read_float(line, &char_counter, &value)) {
return(STATUS_BAD_NUMBER_FORMAT); return(STATUS_BAD_NUMBER_FORMAT);
} }
if(line[char_counter] != 0) { if(line[char_counter] != 0) {
@ -158,7 +158,7 @@ int read_settings() {
} }
// A helper method to set settings from command line // A helper method to set settings from command line
void settings_store_setting(int parameter, double value) { void settings_store_setting(int parameter, float value) {
switch(parameter) { switch(parameter) {
case 0: case 1: case 2: case 0: case 1: case 2:
if (value <= 0.0) { if (value <= 0.0) {

View File

@ -33,15 +33,15 @@
// Current global settings (persisted in EEPROM from byte 1 onwards) // Current global settings (persisted in EEPROM from byte 1 onwards)
typedef struct { typedef struct {
double steps_per_mm[3]; float steps_per_mm[3];
uint8_t microsteps; uint8_t microsteps;
uint8_t pulse_microseconds; uint8_t pulse_microseconds;
double default_feed_rate; float default_feed_rate;
double default_seek_rate; float default_seek_rate;
uint8_t invert_mask; uint8_t invert_mask;
double mm_per_arc_segment; float mm_per_arc_segment;
double acceleration; float acceleration;
double junction_deviation; float junction_deviation;
} settings_t; } settings_t;
extern settings_t settings; extern settings_t settings;
@ -55,6 +55,6 @@ void settings_dump();
uint8_t settings_execute_line(char *line); uint8_t settings_execute_line(char *line);
// A helper method to set new settings from command line // A helper method to set new settings from command line
void settings_store_setting(int parameter, double value); void settings_store_setting(int parameter, float value);
#endif #endif

View File

@ -304,8 +304,10 @@ ISR(TIMER1_COMPA_vect)
// This interrupt is set up by ISR_TIMER1_COMPAREA when it sets the motor port bits. It resets // This interrupt is set up by ISR_TIMER1_COMPAREA when it sets the motor port bits. It resets
// the motor port after a short period (settings.pulse_microseconds) completing one step cycle. // the motor port after a short period (settings.pulse_microseconds) completing one step cycle.
// TODO: It is possible for the serial interrupts to delay this interrupt by a few microseconds, if // NOTE: Interrupt collisions between the serial and stepper interrupts can cause delays by
// they execute right before this interrupt. Not a big deal, but could use some TLC at some point. // a few microseconds, if they execute right before one another. Not a big deal, but can
// cause issues at high step rates if another high frequency asynchronous interrupt is
// added to Grbl.
ISR(TIMER2_OVF_vect) ISR(TIMER2_OVF_vect)
{ {
// Reset stepping pins (leave the direction pins) // Reset stepping pins (leave the direction pins)
@ -355,12 +357,11 @@ void st_init()
// Configure Timer 2 // Configure Timer 2
TCCR2A = 0; // Normal operation TCCR2A = 0; // Normal operation
TCCR2B = 0; // Disable timer until needed. TCCR2B = 0; // Disable timer until needed.
TIMSK2 |= (1<<TOIE2); TIMSK2 |= (1<<TOIE2); // Enable Timer2 Overflow interrupt
#ifdef STEP_PULSE_DELAY #ifdef STEP_PULSE_DELAY
TIMSK2 |= (1<<OCIE2A); // Enable Timer2 Compare Match A interrupt TIMSK2 |= (1<<OCIE2A); // Enable Timer2 Compare Match A interrupt
#endif #endif
// Start in the idle state // Start in the idle state
st_go_idle(); st_go_idle();
} }
@ -452,5 +453,3 @@ void st_cycle_reinitialize()
} }
sys.feed_hold = false; // Release feed hold. Cycle is ready to re-start. sys.feed_hold = false; // Release feed hold. Cycle is ready to re-start.
} }