kopia lustrzana https://github.com/gnea/grbl
Acceleration independence installed. Initial re-work of planner for feedrate overrides.
NOTE: This push is a work-in-progress and there are known bugs that need to be fixed, like homing acceleration being incompatible. Released for testing. Settings will definitely be overwritten, as new settings were needed. - Acceleration independence installed in planner. Each axis can now have different accelerations and Grbl will maximize the accelerations depending on the direction its moving. Very useful for users like on the ShapeOko with vastly different Z-axis properties. - More planner optimizations and re-factoring. Slightly improved some of the older calculations, but new acceleration calculations offset these improvements. Overall no change in processing speed. - Removed planner nominal length checks. It was arguable whether or not this improved planner efficiency, especially in the worst case scenario of arcs. - Updated readme and changed to markdown format.pull/1/head
rodzic
37549986df
commit
cc4df3e14b
|
@ -1,3 +1,4 @@
|
|||
*.hex
|
||||
*.o
|
||||
*.elf
|
||||
*.DS_Store
|
||||
|
|
|
@ -0,0 +1,19 @@
|
|||
#Grbl - An embedded g-code interpreter and motion-controller for the Arduino/AVR328 microcontroller
|
||||
------------
|
||||
|
||||
Grbl is a no-compromise, high performance, low cost alternative to parallel-port-based motion control for CNC milling. It will run on a vanilla Arduino (Duemillanove/Uno) as long as it sports an Atmega 328.
|
||||
|
||||
The controller is written in highly optimized C utilizing every clever feature of the AVR-chips to achieve precise timing and asynchronous operation. It is able to m aintain more than 30kHz of stable, jitter free control pulses.
|
||||
|
||||
It accepts standards-compliant G-code and has been tested with the output of several CAM tools with no problems. Arcs, circles and helical motion are fully supported, as well as, other basic functional g-code commands. Functions and variables are not currently supported, but may be included in future releases in a form of a pre-processor.
|
||||
|
||||
Grbl includes full acceleration management with look ahead. That means the controller will look up to 18 motions into the future and plan its velocities ahead to deliver smooth acceleration and jerk-free cornering.
|
||||
|
||||
##Changelog for v0.9 from v0.8
|
||||
- **ALPHA status: Under heavy development.**
|
||||
- New stepper algorithm: Based on the Pramod Ranade inverse time algorithm, but modified to ensure steps are executed exactly. This algorithm performs a constant timer tick and has a hard limit of 30kHz maximum step frequency. It is also highly tuneable and should be very easy to port to other microcontroller architectures.
|
||||
- Planner optimizations: Multiple changes to increase planner execution speed and removed redundant variables.
|
||||
- Acceleration independence: Each axes may be defined with different acceleration parameters and Grbl will automagically calculate the maximum acceleration through a path depending on the direction traveled. This is very useful for machine that have very different axes properties, like the ShapeOko z-axis.
|
||||
- Feedrate overrides: In the works, but planner has begun to be re-factored for this feature.
|
||||
|
||||
_The project was initially inspired by the Arduino GCode Interpreter by Mike Ellery_
|
2
limits.c
2
limits.c
|
@ -121,7 +121,7 @@ static void homing_cycle(uint8_t cycle_mask, int8_t pos_dir, bool invert_pin, fl
|
|||
float ds = step_event_count/sqrt(dist);
|
||||
|
||||
// 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[X_AXIS]/(60*ACCELERATION_TICKS_PER_SECOND));
|
||||
|
||||
#ifdef HOMING_RATE_ADJUST
|
||||
// Adjust homing rate so a multiple axes moves all at the homing rate independently.
|
||||
|
|
129
planner.c
129
planner.c
|
@ -43,6 +43,7 @@ typedef struct {
|
|||
// i.e. arcs, canned cycles, and backlash compensation.
|
||||
float previous_unit_vec[N_AXIS]; // Unit vector of previous path line segment
|
||||
float previous_nominal_speed_sqr; // Nominal speed of previous path line segment
|
||||
float inverse_steps_per_mm[N_AXIS];
|
||||
} planner_t;
|
||||
static planner_t pl;
|
||||
|
||||
|
@ -92,10 +93,14 @@ static void calculate_trapezoid_for_block(block_t *block, float entry_speed_sqr,
|
|||
{
|
||||
// Compute new initial rate for stepper algorithm
|
||||
block->initial_rate = ceil(sqrt(entry_speed_sqr)*(RANADE_MULTIPLIER/(60*ISR_TICKS_PER_SECOND))); // (mult*mm/isr_tic)
|
||||
|
||||
// TODO: Compute new nominal rate if a feedrate override occurs.
|
||||
// block->nominal_rate = ceil(feed_rate*(RANADE_MULTIPLIER/(60.0*ISR_TICKS_PER_SECOND))); // (mult*mm/isr_tic)
|
||||
|
||||
|
||||
// Compute efficiency variable for following calculations. Removes a float divide and multiply.
|
||||
// TODO: If memory allows, this can be kept in the block buffer since it doesn't change, even after feed holds.
|
||||
float steps_per_mm_div_2_acc = block->step_event_count/(2*settings.acceleration*block->millimeters);
|
||||
float steps_per_mm_div_2_acc = block->step_event_count/(2*block->acceleration*block->millimeters);
|
||||
|
||||
// First determine intersection distance (in steps) from the exit point for a triangular profile.
|
||||
// Computes: steps_intersect = steps/mm * ( distance/2 + (v_entry^2-v_exit^2)/(4*acceleration) )
|
||||
|
@ -154,7 +159,7 @@ static void calculate_trapezoid_for_block(block_t *block, float entry_speed_sqr,
|
|||
NOTE: As executing blocks complete and incoming streaming blocks are appended to the planner buffer, this
|
||||
function is constantly re-calculating and must be as efficient as possible. For example, in situations like
|
||||
arc generation or complex curves, the short, rapid line segments can execute faster than new blocks can be
|
||||
added, and the planner buffer will starve and empty, leading to weird hiccup-like jerky motions.
|
||||
added, and the planner buffer will then starve and empty, leading to weird hiccup-like jerky motions.
|
||||
*/
|
||||
static void planner_recalculate()
|
||||
{
|
||||
|
@ -165,6 +170,7 @@ static void planner_recalculate()
|
|||
// if (block_buffer_head != block_buffer_tail) {
|
||||
|
||||
float entry_speed_sqr;
|
||||
float max_entry_speed_sqr;
|
||||
|
||||
// Perform reverse planner pass. Skip the head(end) block since it is already initialized, and skip the
|
||||
// tail(first) block to prevent over-writing of the initial entry speed.
|
||||
|
@ -174,25 +180,30 @@ static void planner_recalculate()
|
|||
if (block_index != block_buffer_tail) { block_index = prev_block_index( block_index ); }
|
||||
while (block_index != block_buffer_tail) {
|
||||
next = current;
|
||||
current = &block_buffer[block_index];
|
||||
current = &block_buffer[block_index];
|
||||
|
||||
// Determine maximum entry speed at junction. Computed here since feedrate overrides can alter
|
||||
// the planner nominal speeds at any time.
|
||||
max_entry_speed_sqr = current->max_entry_speed_sqr;
|
||||
if (max_entry_speed_sqr > current->nominal_speed_sqr) { max_entry_speed_sqr = current->nominal_speed_sqr; }
|
||||
if (max_entry_speed_sqr > next->nominal_speed_sqr) { max_entry_speed_sqr = next->nominal_speed_sqr; }
|
||||
|
||||
// If entry speed is already at the maximum entry speed, no need to recheck. Block is cruising.
|
||||
// If not, block in state of acceleration or deceleration. Reset entry speed to maximum and
|
||||
// check for maximum allowable speed reductions to ensure maximum possible planned speed.
|
||||
if (current->entry_speed_sqr != current->max_entry_speed_sqr) {
|
||||
// If nominal length true, max junction speed is guaranteed to be reached. Only compute
|
||||
// for max allowable speed if block is decelerating and nominal length is false.
|
||||
if (current->entry_speed_sqr != max_entry_speed_sqr) {
|
||||
|
||||
current->entry_speed_sqr = current->max_entry_speed_sqr;
|
||||
current->entry_speed_sqr = max_entry_speed_sqr;
|
||||
current->recalculate_flag = true; // Almost always changes. So force recalculate.
|
||||
|
||||
if ((!current->nominal_length_flag) && (current->max_entry_speed_sqr > next->entry_speed_sqr)) {
|
||||
if (max_entry_speed_sqr > next->entry_speed_sqr) {
|
||||
// Computes: v_entry^2 = v_exit^2 + 2*acceleration*distance
|
||||
entry_speed_sqr = next->entry_speed_sqr + 2*settings.acceleration*current->millimeters;
|
||||
if (entry_speed_sqr < current->max_entry_speed_sqr) {
|
||||
entry_speed_sqr = next->entry_speed_sqr + 2*current->acceleration*current->millimeters;
|
||||
if (entry_speed_sqr < max_entry_speed_sqr) {
|
||||
current->entry_speed_sqr = entry_speed_sqr;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
block_index = prev_block_index( block_index );
|
||||
}
|
||||
|
||||
|
@ -207,20 +218,17 @@ static void planner_recalculate()
|
|||
// If the current block is an acceleration block, but it is not long enough to complete the
|
||||
// full speed change within the block, we need to adjust the exit speed accordingly. Entry
|
||||
// speeds have already been reset, maximized, and reverse planned by reverse planner.
|
||||
// If nominal length is true, max junction speed is guaranteed to be reached. So skip block.
|
||||
if (!current->nominal_length_flag) {
|
||||
if (current->entry_speed_sqr < next->entry_speed_sqr) {
|
||||
// Compute block exit speed based on the current block speed and distance
|
||||
// Computes: v_exit^2 = v_entry^2 + 2*acceleration*distance
|
||||
entry_speed_sqr = current->entry_speed_sqr + 2*settings.acceleration*current->millimeters;
|
||||
|
||||
// If it's less than the stored value, update the exit speed and set recalculate flag.
|
||||
if (entry_speed_sqr < next->entry_speed_sqr) {
|
||||
next->entry_speed_sqr = entry_speed_sqr;
|
||||
next->recalculate_flag = true;
|
||||
}
|
||||
if (current->entry_speed_sqr < next->entry_speed_sqr) {
|
||||
// Compute block exit speed based on the current block speed and distance
|
||||
// Computes: v_exit^2 = v_entry^2 + 2*acceleration*distance
|
||||
entry_speed_sqr = current->entry_speed_sqr + 2*current->acceleration*current->millimeters;
|
||||
|
||||
// If it's less than the stored value, update the exit speed and set recalculate flag.
|
||||
if (entry_speed_sqr < next->entry_speed_sqr) {
|
||||
next->entry_speed_sqr = entry_speed_sqr;
|
||||
next->recalculate_flag = true;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// Recalculate if current block entry or exit junction speed has changed.
|
||||
if (current->recalculate_flag || next->recalculate_flag) {
|
||||
|
@ -249,6 +257,9 @@ void plan_init()
|
|||
{
|
||||
plan_reset_buffer();
|
||||
memset(&pl, 0, sizeof(pl)); // Clear planner struct
|
||||
pl.inverse_steps_per_mm[X_AXIS] = 1/settings.steps_per_mm[X_AXIS];
|
||||
pl.inverse_steps_per_mm[Y_AXIS] = 1/settings.steps_per_mm[Y_AXIS];
|
||||
pl.inverse_steps_per_mm[Z_AXIS] = 1/settings.steps_per_mm[Z_AXIS];
|
||||
}
|
||||
|
||||
inline void plan_discard_current_block()
|
||||
|
@ -289,6 +300,8 @@ void plan_synchronize()
|
|||
// NOTE: Assumes buffer is available. Buffer checks are handled at a higher level by motion_control.
|
||||
void plan_buffer_line(float x, float y, float z, float feed_rate, uint8_t invert_feed_rate)
|
||||
{
|
||||
// SPINDLE_ENABLE_PORT ^= 1<<SPINDLE_ENABLE_BIT;
|
||||
|
||||
// Prepare to set up new block
|
||||
block_t *block = &block_buffer[block_buffer_head];
|
||||
|
||||
|
@ -309,21 +322,35 @@ void plan_buffer_line(float x, float y, float z, float feed_rate, uint8_t invert
|
|||
|
||||
// Compute path vector in terms of absolute step target and current positions
|
||||
// TODO: Store last xyz in memory to remove steps_per_mm divides. Or come up with another way to save cycles.
|
||||
// Or store pl.inverse_steps_per_mm to speed this up. Would be computed at initialization.
|
||||
float delta_mm[3];
|
||||
delta_mm[X_AXIS] = block->steps_x/settings.steps_per_mm[X_AXIS];
|
||||
delta_mm[Y_AXIS] = block->steps_y/settings.steps_per_mm[Y_AXIS];
|
||||
delta_mm[Z_AXIS] = block->steps_z/settings.steps_per_mm[Z_AXIS];
|
||||
// delta_mm[X_AXIS] = block->steps_x/settings.steps_per_mm[X_AXIS]; // 110 usec
|
||||
// delta_mm[Y_AXIS] = block->steps_y/settings.steps_per_mm[Y_AXIS];
|
||||
// delta_mm[Z_AXIS] = block->steps_z/settings.steps_per_mm[Z_AXIS];
|
||||
delta_mm[X_AXIS] = block->steps_x*pl.inverse_steps_per_mm[X_AXIS]; // 50usec
|
||||
delta_mm[Y_AXIS] = block->steps_y*pl.inverse_steps_per_mm[Y_AXIS];
|
||||
delta_mm[Z_AXIS] = block->steps_z*pl.inverse_steps_per_mm[Z_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]);
|
||||
float inverse_millimeters = 1.0/block->millimeters; // Inverse millimeters to remove multiple divides
|
||||
|
||||
// Compute path unit vector
|
||||
// Compute absolute value of the path unit vector for acceleration calculations.
|
||||
float unit_vec[3];
|
||||
float inverse_millimeters = 1.0/block->millimeters; // Inverse millimeters to remove multiple divides
|
||||
unit_vec[X_AXIS] = delta_mm[X_AXIS]*inverse_millimeters;
|
||||
unit_vec[Y_AXIS] = delta_mm[Y_AXIS]*inverse_millimeters;
|
||||
unit_vec[Z_AXIS] = delta_mm[Z_AXIS]*inverse_millimeters;
|
||||
|
||||
// Compute direction bits and correct unit vector directions
|
||||
// Calculate block acceleration based on the maximum possible axes acceleration parameters.
|
||||
// NOTE: This calculation assumes all axes are orthogonal (Cartesian) and works with ABC-axes,
|
||||
// if they are also orthogonal/independent. Operates on the absolute value of the unit vector.
|
||||
// TODO: Install pl.inverse_acceleration to possibly speed up this calculation.
|
||||
float accel_inv_scalar = 0.0;
|
||||
if (unit_vec[X_AXIS]) { accel_inv_scalar = max(accel_inv_scalar,unit_vec[X_AXIS]/settings.acceleration[X_AXIS]); }
|
||||
if (unit_vec[Y_AXIS]) { accel_inv_scalar = max(accel_inv_scalar,unit_vec[Y_AXIS]/settings.acceleration[Y_AXIS]); }
|
||||
if (unit_vec[Z_AXIS]) { accel_inv_scalar = max(accel_inv_scalar,unit_vec[Z_AXIS]/settings.acceleration[Z_AXIS]); }
|
||||
block->acceleration = 1.0/accel_inv_scalar;
|
||||
|
||||
// Compute direction bits and apply unit vector directions for junction speed calculations
|
||||
block->direction_bits = 0;
|
||||
if (target[X_AXIS] < pl.position[X_AXIS]) {
|
||||
block->direction_bits |= (1<<X_DIRECTION_BIT);
|
||||
|
@ -348,10 +375,10 @@ void plan_buffer_line(float x, float y, float z, float feed_rate, uint8_t invert
|
|||
// each block. This could save some 2*acceleration multiplications elsewhere. Need to check though.
|
||||
|
||||
// Compute the acceleration and distance traveled per step event for the stepper algorithm.
|
||||
block->rate_delta = ceil(settings.acceleration*
|
||||
((RANADE_MULTIPLIER/(60*60))/(ISR_TICKS_PER_SECOND*ACCELERATION_TICKS_PER_SECOND))); // (mult*mm/isr_tic/accel_tic)
|
||||
block->rate_delta = ceil(block->acceleration*
|
||||
(RANADE_MULTIPLIER/(60.0*60.0*ISR_TICKS_PER_SECOND*ACCELERATION_TICKS_PER_SECOND))); // (mult*mm/isr_tic/accel_tic)
|
||||
block->d_next = ceil((block->millimeters*RANADE_MULTIPLIER)/block->step_event_count); // (mult*mm/step)
|
||||
|
||||
|
||||
// Compute maximum allowable entry speed at junction by centripetal acceleration approximation.
|
||||
// Let a circle be tangent to both previous and current path line segments, where the junction
|
||||
// deviation is defined as the distance from the junction to the closest edge of the circle,
|
||||
|
@ -367,9 +394,9 @@ void plan_buffer_line(float x, float y, float z, float feed_rate, uint8_t invert
|
|||
// is exactly the same. Instead of motioning all the way to junction point, the machine will
|
||||
// just follow the arc circle defined here. The Arduino doesn't have the CPU cycles to perform
|
||||
// a continuous mode path, but ARM-based microcontrollers most certainly do.
|
||||
float vmax_junction_sqr = MINIMUM_PLANNER_SPEED*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.
|
||||
block->max_entry_speed_sqr = MINIMUM_PLANNER_SPEED*MINIMUM_PLANNER_SPEED;
|
||||
if ((block_buffer_head != block_buffer_tail) && (pl.previous_nominal_speed_sqr > 0.0)) {
|
||||
// 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.
|
||||
|
@ -379,33 +406,25 @@ void plan_buffer_line(float x, float y, float z, float feed_rate, uint8_t invert
|
|||
|
||||
// Skip and use default max junction speed for 0 degree acute junction.
|
||||
if (cos_theta < 0.95) {
|
||||
vmax_junction_sqr = min(pl.previous_nominal_speed_sqr,block->nominal_speed_sqr);
|
||||
// Skip and avoid divide by zero for straight junctions at 180 degrees. Limit to min() of nominal speeds.
|
||||
if (cos_theta > -0.95) {
|
||||
// Compute maximum junction velocity based on maximum acceleration and junction deviation
|
||||
float sin_theta_d2 = sqrt(0.5*(1.0-cos_theta)); // Trig half angle identity. Always positive.
|
||||
vmax_junction_sqr = min(vmax_junction_sqr,
|
||||
settings.acceleration * settings.junction_deviation * sin_theta_d2/(1.0-sin_theta_d2) );
|
||||
block->max_entry_speed_sqr = block->acceleration * settings.junction_deviation * sin_theta_d2/(1.0-sin_theta_d2);
|
||||
} else {
|
||||
block->max_entry_speed_sqr = 1000000.0; //MAXIMUM_JUNCTION_SPEED;
|
||||
}
|
||||
}
|
||||
}
|
||||
block->max_entry_speed_sqr = vmax_junction_sqr;
|
||||
|
||||
// Initialize block entry speed. Compute block entry velocity backwards from user-defined MINIMUM_PLANNER_SPEED.
|
||||
float v_allowable_sqr = MINIMUM_PLANNER_SPEED*MINIMUM_PLANNER_SPEED + 2*settings.acceleration*block->millimeters;
|
||||
block->entry_speed_sqr = min(vmax_junction_sqr, v_allowable_sqr);
|
||||
}
|
||||
|
||||
// Initialize planner efficiency flags
|
||||
// Set flag if block will always reach maximum junction speed regardless of entry/exit speeds.
|
||||
// If a block can de/ac-celerate from nominal speed to zero within the length of the block, then
|
||||
// the current block and next block junction speeds are guaranteed to always be at their maximum
|
||||
// junction speeds in deceleration and acceleration, respectively. This is due to how the current
|
||||
// block nominal speed limits both the current and next maximum junction speeds. Hence, in both
|
||||
// the reverse and forward planners, the corresponding block junction speed will always be at the
|
||||
// the maximum junction speed and may always be ignored for any speed reduction checks.
|
||||
if (block->nominal_speed_sqr <= v_allowable_sqr) { block->nominal_length_flag = true; }
|
||||
else { block->nominal_length_flag = false; }
|
||||
block->recalculate_flag = true; // Always calculate trapezoid for new block
|
||||
// Initialize block entry speed. Compute block entry velocity backwards from user-defined MINIMUM_PLANNER_SPEED.
|
||||
block->entry_speed_sqr = MINIMUM_PLANNER_SPEED*MINIMUM_PLANNER_SPEED + 2*block->acceleration*block->millimeters;
|
||||
if (block->entry_speed_sqr > pl.previous_nominal_speed_sqr) { block->entry_speed_sqr = pl.previous_nominal_speed_sqr; }
|
||||
if (block->entry_speed_sqr > block->nominal_speed_sqr) { block->entry_speed_sqr = block->nominal_speed_sqr; }
|
||||
if (block->entry_speed_sqr > block->max_entry_speed_sqr) { block->entry_speed_sqr = block->max_entry_speed_sqr; }
|
||||
|
||||
// Set new block to be recalculated for conversion to stepper data.
|
||||
block->recalculate_flag = true;
|
||||
|
||||
// Update previous path unit_vector and nominal speed (squared)
|
||||
memcpy(pl.previous_unit_vec, unit_vec, sizeof(unit_vec)); // pl.previous_unit_vec[] = unit_vec[]
|
||||
|
@ -419,6 +438,7 @@ void plan_buffer_line(float x, float y, float z, float feed_rate, uint8_t invert
|
|||
memcpy(pl.position, target, sizeof(target)); // pl.position[] = target[]
|
||||
|
||||
planner_recalculate();
|
||||
// SPINDLE_ENABLE_PORT ^= 1<<SPINDLE_ENABLE_BIT;
|
||||
}
|
||||
|
||||
// Reset the planner position vector (in steps). Called by the system abort routine.
|
||||
|
@ -444,7 +464,6 @@ void plan_cycle_reinitialize(int32_t step_events_remaining)
|
|||
// Re-plan from a complete stop. Reset planner entry speeds and flags.
|
||||
block->entry_speed_sqr = 0.0;
|
||||
block->max_entry_speed_sqr = 0.0;
|
||||
block->nominal_length_flag = false;
|
||||
block->recalculate_flag = true;
|
||||
planner_recalculate();
|
||||
}
|
||||
|
|
|
@ -41,8 +41,8 @@ typedef struct {
|
|||
float entry_speed_sqr; // Entry speed at previous-current block junction in mm/min
|
||||
float max_entry_speed_sqr; // Maximum allowable junction entry speed in mm/min
|
||||
float millimeters; // The total travel of this block in mm
|
||||
float acceleration;
|
||||
uint8_t recalculate_flag; // Planner flag to recalculate trapezoids on entry junction
|
||||
uint8_t nominal_length_flag; // Planner flag for nominal speed always reached
|
||||
|
||||
// Settings for the trapezoid generator
|
||||
uint32_t initial_rate; // The step rate at start of block
|
||||
|
|
|
@ -1,38 +0,0 @@
|
|||
h1. Grbl - An embedded g-code interpreter and motion-controller for the Arduino/AVR328 microcontroller
|
||||
|
||||
Grbl is a no-compromise, high performance, low cost alternative to parallel-port-based motion control for CNC milling. It will run on a vanilla Arduino (Duemillanove/Uno) as long as it sports an Atmega 328.
|
||||
|
||||
The controller is written in highly optimized C utilizing every clever feature of the AVR-chips to achieve precise timing and asynchronous operation. It is able to maintain more than 30kHz of stable, jitter free control pulses.
|
||||
|
||||
It accepts standards-compliant G-code and has been tested with the output of several CAM tools with no problems. Arcs, circles and helical motion are fully supported, as well as, other basic functional g-code commands. Functions and variables are not currently supported, but may be included in future releases in a form of a pre-processor.
|
||||
|
||||
Grbl includes full acceleration management with look ahead. That means the controller will look up to 18 motions into the future and plan its velocities ahead to deliver smooth acceleration and jerk-free cornering.
|
||||
|
||||
*Changelog for v0.8 from v0.7:*
|
||||
- *BETA status: _Nearing official release!_*
|
||||
- Major structural overhaul to allow for multi-tasking events and new feature sets.
|
||||
- Run-time command control: Feed hold (pause), Cycle start (resume), Reset (abort), Status reporting (current position and state).
|
||||
- Controlled feed hold with deceleration to ensure no skipped steps and loss of location.
|
||||
- After feed hold, cycle accelerations are re-planned and may be resumed.
|
||||
- Advanced homing cycle with direction and speed configuration options. (Requires limit switches.) When enabled, homing is required before use to ensure safety.
|
||||
- Limit pins are held normal high with internal pull-up resistors. Wiring only requires a normally-open switch connected to ground. (For both ends of an axis, simply wire two in parallel into the same pin.)
|
||||
- Hard limits option and plays nice with homing cycle, so switches can be used for both homing and hard limits.
|
||||
- A check g-code mode has also been added to allow users to error check their programs.
|
||||
- Re-factored g-code parser with robust error-checking.
|
||||
- 6 work coordinate systems (G54-G59), offsets(G92), and machine coordinate system support. Work coordinate systems are stored in EEPROM and persistent.
|
||||
- G10 L2 and L20 work coordinate settings support. L2 sets one or more axes values. L20 sets the current machine position to the specified work origin.
|
||||
- G28.1 and G30.1 set home position support. These set the internal EEPROM parameter values to the current machine position. (G28 and G30 no longer perform homing cycle, '$H' does. They move to these stored positions.)
|
||||
- Program stop(M0,M2,M30) support.
|
||||
- Coolant control(M7*,M8,M9) support. (M7 is a compile-time option).
|
||||
- G-code parser state and '#' parameters feedback.
|
||||
- System reset re-initializes grbl without resetting the Arduino and retains machine/home position and work coordinates.
|
||||
- Settings overhauled and dozens of new settings and internal commands are now available, when most were compile-time only.
|
||||
- New startup line setting. Allows users to store a custom g-code block into Grbl's startup routine. Executes immediately upon startup or reset. May be used to set g-code defaults like G20/G21.
|
||||
- Pin-outs of the cycle-start, feed-hold, and soft-reset runtime commands on pins A0-A2.
|
||||
- Misc bug fixes and removed deprecated acceleration enabled code.
|
||||
- Advanced compile-time options: XON/XOFF flow control (limited support), direction and step pulse time delay, up to 5 startup lines, and homing sequence configurability.
|
||||
|
||||
|
||||
*Important note for Atmega 168 users:* Going forward, support for Atmega 168 will be dropped due to its limited memory and speed. However, legacy Grbl v0.51 "in the branch called 'v0_51' is still available for use.
|
||||
|
||||
_The project was initially inspired by the Arduino GCode Interpreter by Mike Ellery_
|
32
report.c
32
report.c
|
@ -152,22 +152,24 @@ void report_grbl_settings() {
|
|||
printPgmString(PSTR(" (default seek, mm/min)\r\n$6=")); printInteger(settings.invert_mask);
|
||||
printPgmString(PSTR(" (step port invert mask, int:")); print_uint8_base2(settings.invert_mask);
|
||||
printPgmString(PSTR(")\r\n$7=")); printInteger(settings.stepper_idle_lock_time);
|
||||
printPgmString(PSTR(" (step idle delay, msec)\r\n$8=")); printFloat(settings.acceleration/(60*60)); // Convert from mm/min^2 for human readability
|
||||
printPgmString(PSTR(" (acceleration, mm/sec^2)\r\n$9=")); printFloat(settings.junction_deviation);
|
||||
printPgmString(PSTR(" (junction deviation, mm)\r\n$10=")); printFloat(settings.mm_per_arc_segment);
|
||||
printPgmString(PSTR(" (arc, mm/segment)\r\n$11=")); printInteger(settings.n_arc_correction);
|
||||
printPgmString(PSTR(" (n-arc correction, int)\r\n$12=")); printInteger(settings.decimal_places);
|
||||
printPgmString(PSTR(" (n-decimals, int)\r\n$13=")); printInteger(bit_istrue(settings.flags,BITFLAG_REPORT_INCHES));
|
||||
printPgmString(PSTR(" (report inches, bool)\r\n$14=")); printInteger(bit_istrue(settings.flags,BITFLAG_AUTO_START));
|
||||
printPgmString(PSTR(" (auto start, bool)\r\n$15=")); printInteger(bit_istrue(settings.flags,BITFLAG_INVERT_ST_ENABLE));
|
||||
printPgmString(PSTR(" (invert step enable, bool)\r\n$16=")); printInteger(bit_istrue(settings.flags,BITFLAG_HARD_LIMIT_ENABLE));
|
||||
printPgmString(PSTR(" (hard limits, bool)\r\n$17=")); printInteger(bit_istrue(settings.flags,BITFLAG_HOMING_ENABLE));
|
||||
printPgmString(PSTR(" (homing cycle, bool)\r\n$18=")); printInteger(settings.homing_dir_mask);
|
||||
printPgmString(PSTR(" (step idle delay, msec)\r\n$8=")); printFloat(settings.acceleration[X_AXIS]/(60*60)); // Convert from mm/min^2 for human readability
|
||||
printPgmString(PSTR(" (x acceleration, mm/sec^2)\r\n$9=")); printFloat(settings.acceleration[Y_AXIS]/(60*60)); // Convert from mm/min^2 for human readability
|
||||
printPgmString(PSTR(" (y acceleration, mm/sec^2)\r\n$10=")); printFloat(settings.acceleration[Z_AXIS]/(60*60)); // Convert from mm/min^2 for human readability
|
||||
printPgmString(PSTR(" (z acceleration, mm/sec^2)\r\n$11=")); printFloat(settings.junction_deviation);
|
||||
printPgmString(PSTR(" (junction deviation, mm)\r\n$12=")); printFloat(settings.mm_per_arc_segment);
|
||||
printPgmString(PSTR(" (arc, mm/segment)\r\n$13=")); printInteger(settings.n_arc_correction);
|
||||
printPgmString(PSTR(" (n-arc correction, int)\r\n$14=")); printInteger(settings.decimal_places);
|
||||
printPgmString(PSTR(" (n-decimals, int)\r\n$15=")); printInteger(bit_istrue(settings.flags,BITFLAG_REPORT_INCHES));
|
||||
printPgmString(PSTR(" (report inches, bool)\r\n$16=")); printInteger(bit_istrue(settings.flags,BITFLAG_AUTO_START));
|
||||
printPgmString(PSTR(" (auto start, bool)\r\n$17=")); printInteger(bit_istrue(settings.flags,BITFLAG_INVERT_ST_ENABLE));
|
||||
printPgmString(PSTR(" (invert step enable, bool)\r\n$18=")); printInteger(bit_istrue(settings.flags,BITFLAG_HARD_LIMIT_ENABLE));
|
||||
printPgmString(PSTR(" (hard limits, bool)\r\n$19=")); printInteger(bit_istrue(settings.flags,BITFLAG_HOMING_ENABLE));
|
||||
printPgmString(PSTR(" (homing cycle, bool)\r\n$20=")); printInteger(settings.homing_dir_mask);
|
||||
printPgmString(PSTR(" (homing dir invert mask, int:")); print_uint8_base2(settings.homing_dir_mask);
|
||||
printPgmString(PSTR(")\r\n$19=")); printFloat(settings.homing_feed_rate);
|
||||
printPgmString(PSTR(" (homing feed, mm/min)\r\n$20=")); printFloat(settings.homing_seek_rate);
|
||||
printPgmString(PSTR(" (homing seek, mm/min)\r\n$21=")); printInteger(settings.homing_debounce_delay);
|
||||
printPgmString(PSTR(" (homing debounce, msec)\r\n$22=")); printFloat(settings.homing_pulloff);
|
||||
printPgmString(PSTR(")\r\n$21=")); printFloat(settings.homing_feed_rate);
|
||||
printPgmString(PSTR(" (homing feed, mm/min)\r\n$22=")); printFloat(settings.homing_seek_rate);
|
||||
printPgmString(PSTR(" (homing seek, mm/min)\r\n$23=")); printInteger(settings.homing_debounce_delay);
|
||||
printPgmString(PSTR(" (homing debounce, msec)\r\n$24=")); printFloat(settings.homing_pulloff);
|
||||
printPgmString(PSTR(" (homing pull-off, mm)\r\n"));
|
||||
}
|
||||
|
||||
|
|
36
settings.c
36
settings.c
|
@ -75,7 +75,9 @@ void settings_reset(bool reset_all) {
|
|||
settings.pulse_microseconds = DEFAULT_STEP_PULSE_MICROSECONDS;
|
||||
settings.default_feed_rate = DEFAULT_FEEDRATE;
|
||||
settings.default_seek_rate = DEFAULT_RAPID_FEEDRATE;
|
||||
settings.acceleration = DEFAULT_ACCELERATION;
|
||||
settings.acceleration[X_AXIS] = DEFAULT_ACCELERATION;
|
||||
settings.acceleration[Y_AXIS] = DEFAULT_ACCELERATION;
|
||||
settings.acceleration[Z_AXIS] = DEFAULT_ACCELERATION;
|
||||
settings.mm_per_arc_segment = DEFAULT_MM_PER_ARC_SEGMENT;
|
||||
settings.invert_mask = DEFAULT_STEPPING_INVERT_MASK;
|
||||
settings.junction_deviation = DEFAULT_JUNCTION_DEVIATION;
|
||||
|
@ -164,37 +166,39 @@ uint8_t settings_store_global_setting(int parameter, float value) {
|
|||
case 5: settings.default_seek_rate = value; break;
|
||||
case 6: settings.invert_mask = trunc(value); break;
|
||||
case 7: settings.stepper_idle_lock_time = round(value); break;
|
||||
case 8: settings.acceleration = value*60*60; break; // Convert to mm/min^2 for grbl internal use.
|
||||
case 9: settings.junction_deviation = fabs(value); break;
|
||||
case 10: settings.mm_per_arc_segment = value; break;
|
||||
case 11: settings.n_arc_correction = round(value); break;
|
||||
case 12: settings.decimal_places = round(value); break;
|
||||
case 13:
|
||||
case 8: settings.acceleration[X_AXIS] = value*60*60; break; // Convert to mm/min^2 for grbl internal use.
|
||||
case 9: settings.acceleration[Y_AXIS] = value*60*60; break; // Convert to mm/min^2 for grbl internal use.
|
||||
case 10: settings.acceleration[Z_AXIS] = value*60*60; break; // Convert to mm/min^2 for grbl internal use.
|
||||
case 11: settings.junction_deviation = fabs(value); break;
|
||||
case 12: settings.mm_per_arc_segment = value; break;
|
||||
case 13: settings.n_arc_correction = round(value); break;
|
||||
case 14: settings.decimal_places = round(value); break;
|
||||
case 15:
|
||||
if (value) { settings.flags |= BITFLAG_REPORT_INCHES; }
|
||||
else { settings.flags &= ~BITFLAG_REPORT_INCHES; }
|
||||
break;
|
||||
case 14: // Reset to ensure change. Immediate re-init may cause problems.
|
||||
case 16: // Reset to ensure change. Immediate re-init may cause problems.
|
||||
if (value) { settings.flags |= BITFLAG_AUTO_START; }
|
||||
else { settings.flags &= ~BITFLAG_AUTO_START; }
|
||||
break;
|
||||
case 15: // Reset to ensure change. Immediate re-init may cause problems.
|
||||
case 17: // Reset to ensure change. Immediate re-init may cause problems.
|
||||
if (value) { settings.flags |= BITFLAG_INVERT_ST_ENABLE; }
|
||||
else { settings.flags &= ~BITFLAG_INVERT_ST_ENABLE; }
|
||||
break;
|
||||
case 16:
|
||||
case 18:
|
||||
if (value) { settings.flags |= BITFLAG_HARD_LIMIT_ENABLE; }
|
||||
else { settings.flags &= ~BITFLAG_HARD_LIMIT_ENABLE; }
|
||||
limits_init(); // Re-init to immediately change. NOTE: Nice to have but could be problematic later.
|
||||
break;
|
||||
case 17:
|
||||
case 19:
|
||||
if (value) { settings.flags |= BITFLAG_HOMING_ENABLE; }
|
||||
else { settings.flags &= ~BITFLAG_HOMING_ENABLE; }
|
||||
break;
|
||||
case 18: settings.homing_dir_mask = trunc(value); break;
|
||||
case 19: settings.homing_feed_rate = value; break;
|
||||
case 20: settings.homing_seek_rate = value; break;
|
||||
case 21: settings.homing_debounce_delay = round(value); break;
|
||||
case 22: settings.homing_pulloff = value; break;
|
||||
case 20: settings.homing_dir_mask = trunc(value); break;
|
||||
case 21: settings.homing_feed_rate = value; break;
|
||||
case 22: settings.homing_seek_rate = value; break;
|
||||
case 23: settings.homing_debounce_delay = round(value); break;
|
||||
case 24: settings.homing_pulloff = value; break;
|
||||
default:
|
||||
return(STATUS_INVALID_STATEMENT);
|
||||
}
|
||||
|
|
|
@ -29,7 +29,7 @@
|
|||
|
||||
// Version of the EEPROM data. Will be used to migrate existing data from older versions of Grbl
|
||||
// when firmware is upgraded. Always stored in byte 0 of eeprom
|
||||
#define SETTINGS_VERSION 5
|
||||
#define SETTINGS_VERSION 50
|
||||
|
||||
// Define bit flag masks for the boolean settings in settings.flag.
|
||||
#define BITFLAG_REPORT_INCHES bit(0)
|
||||
|
@ -56,14 +56,14 @@
|
|||
|
||||
// Global persistent settings (Stored from byte EEPROM_ADDR_GLOBAL onwards)
|
||||
typedef struct {
|
||||
float steps_per_mm[3];
|
||||
float steps_per_mm[N_AXIS];
|
||||
uint8_t microsteps;
|
||||
uint8_t pulse_microseconds;
|
||||
float default_feed_rate;
|
||||
float default_seek_rate;
|
||||
uint8_t invert_mask;
|
||||
float mm_per_arc_segment;
|
||||
float acceleration;
|
||||
float acceleration[N_AXIS];
|
||||
float junction_deviation;
|
||||
uint8_t flags; // Contains default boolean settings
|
||||
uint8_t homing_dir_mask;
|
||||
|
|
Ładowanie…
Reference in New Issue