Updated README. Max step rate back at 30kHz. Acceleration minor bug fix.
- Returned the max step rate to 30kHz. The new arc algorithm works uses so much less CPU overhead, because the segments are longer, that the planner has no problem computing through them. - Fixed an issue with the acceleration independence scaling. Should now work with accelerations above 400mm/sec^2 or so. - Updated README
This commit is contained in:
parent
3dfffa622d
commit
5e7c25d480
@ -14,6 +14,9 @@ Grbl includes full acceleration management with look ahead. That means the contr
|
||||
- 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.
|
||||
- Maximum velocity independence: As with acceleration, the maximum velocity of individual axes may be defined. All seek/rapids motions will move at these maximum rates, but never exceed any one axes. So, when two or more axes move, the limiting axis will move at its maximum rate, while the other axes are scaled down.
|
||||
- Significantly improved arc performance: Arcs are now defined in terms of chordal tolerance, rather than segment length. Chordal tolerance will automatically scale all arc line segments depending on arc radius, such that the error does not exceed the tolerance value (default: 0.005 mm.) So, for larger radii arcs, Grbl can move faster through them, because the segments are always longer and the planner has more distance to plan with.
|
||||
- Feedrate overrides: In the works, but planner has begun to be re-factored for this feature.
|
||||
- Jogging controls: Methodology needs to be to figured out first. Last item on the agenda.
|
||||
|
||||
_The project was initially inspired by the Arduino GCode Interpreter by Mike Ellery_
|
||||
|
4
config.h
4
config.h
@ -114,7 +114,7 @@
|
||||
// frequency goes up. So there will be little left for other processes like arcs.
|
||||
// In future versions, more work will be done to increase the step rates but still stay around
|
||||
// 20kHz by performing two steps per step event, rather than just one.
|
||||
#define ISR_TICKS_PER_SECOND 20000L // Integer (Hz)
|
||||
#define ISR_TICKS_PER_SECOND 30000L // Integer (Hz)
|
||||
|
||||
// The temporal resolution of the acceleration management subsystem. Higher number give smoother
|
||||
// acceleration but may impact performance. If you run at very high feedrates (>15kHz or so) and
|
||||
@ -122,7 +122,7 @@
|
||||
// profiles and how the stepper program actually performs them. The correct value for this parameter
|
||||
// is machine dependent, so it's advised to set this only as high as needed. Approximate successful
|
||||
// values can widely range from 50 to 200 or more. Cannot be greater than ISR_TICKS_PER_SECOND/2.
|
||||
#define ACCELERATION_TICKS_PER_SECOND 100L
|
||||
#define ACCELERATION_TICKS_PER_SECOND 120L
|
||||
|
||||
// NOTE: Make sure this value is less than 256, when adjusting both dependent parameters.
|
||||
#define INTERRUPTS_PER_ACCELERATION_TICK (ISR_TICKS_PER_SECOND/ACCELERATION_TICKS_PER_SECOND)
|
||||
|
@ -146,8 +146,8 @@ void mc_arc(float *position, float *target, float *offset, uint8_t axis_0, uint8
|
||||
(second order sin() has too much error) holds for nearly all CNC applications, except for possibly very
|
||||
small radii (~0.5mm). In other words, theta_per_segment would need to be greater than 0.25 rad(14 deg)
|
||||
and N_ARC_CORRECTION would need to be large to cause an appreciable drift error (>5% of radius, for very
|
||||
small radii this is very, very small). N_ARC_CORRECTION~=20 should be more than small enough to correct
|
||||
for numerical drift error.
|
||||
small radii, 5% of 0.5mm is very, very small). N_ARC_CORRECTION~=20 should be more than small enough to
|
||||
correct for numerical drift error. Also decreasing the tolerance will improve the approximation too.
|
||||
|
||||
This approximation also allows mc_arc to immediately insert a line segment into the planner
|
||||
without the initial overhead of computing cos() or sin(). By the time the arc needs to be applied
|
||||
@ -156,7 +156,7 @@ void mc_arc(float *position, float *target, float *offset, uint8_t axis_0, uint8
|
||||
*/
|
||||
// Computes: cos_T = 1 - theta_per_segment^2/2, sin_T = theta_per_segment - theta_per_segment^3/6) in ~52usec
|
||||
float cos_T = 2 - theta_per_segment*theta_per_segment;
|
||||
float sin_T = theta_per_segment*0.1666667*(cos_T + 4);
|
||||
float sin_T = theta_per_segment*0.16666667*(cos_T + 4);
|
||||
cos_T *= 0.5;
|
||||
|
||||
float arc_target[N_AXIS];
|
||||
@ -164,7 +164,7 @@ void mc_arc(float *position, float *target, float *offset, uint8_t axis_0, uint8
|
||||
float cos_Ti;
|
||||
float r_axisi;
|
||||
uint16_t i;
|
||||
int8_t count = 0;
|
||||
uint8_t count = 0;
|
||||
|
||||
// Initialize the linear axis
|
||||
arc_target[axis_linear] = position[axis_linear];
|
||||
|
@ -31,7 +31,7 @@
|
||||
#include "config.h"
|
||||
#include "protocol.h"
|
||||
|
||||
#define SOME_LARGE_VALUE 1000000.0 // Used by rapids and acceleration maximization calculations. Just needs
|
||||
#define SOME_LARGE_VALUE 1.0E+38 // Used by rapids and acceleration maximization calculations. Just needs
|
||||
// to be larger than any feasible mm/min or mm/sec^2 value.
|
||||
|
||||
static block_t block_buffer[BLOCK_BUFFER_SIZE]; // A ring buffer for motion instructions
|
||||
@ -434,12 +434,12 @@ void plan_buffer_line(float x, float y, float z, float feed_rate, uint8_t invert
|
||||
uint8_t i;
|
||||
float unit_vec[N_AXIS], inverse_unit_vec_value;
|
||||
float inverse_millimeters = 1.0/block->millimeters; // Inverse millimeters to remove multiple float divides
|
||||
block->acceleration = SOME_LARGE_VALUE; // Scaled down to maximum acceleration
|
||||
block->acceleration = SOME_LARGE_VALUE; // Scaled down to maximum acceleration in loop
|
||||
for (i=0; i<N_AXIS; i++) {
|
||||
if (delta_mm[i] == 0) {
|
||||
unit_vec[i] = 0; // Store zero value. And avoid divide by zero.
|
||||
} else {
|
||||
// Compute absolute value unit vector
|
||||
// Compute unit vector and its absolute inverse value
|
||||
unit_vec[i] = delta_mm[i]*inverse_millimeters;
|
||||
inverse_unit_vec_value = abs(1.0/unit_vec[i]);
|
||||
// Check and limit feed rate against max axis velocities and scale accelerations to maximums
|
||||
@ -526,7 +526,7 @@ void plan_buffer_line(float x, float y, float z, float feed_rate, uint8_t invert
|
||||
planner_recalculate();
|
||||
}
|
||||
|
||||
// Reset the planner position vectors. Called by the system abort routine.
|
||||
// Reset the planner position vectors. Called by the system abort/initialization routine.
|
||||
void plan_set_current_position(int32_t x, int32_t y, int32_t z)
|
||||
{
|
||||
pl.position[X_AXIS] = x;
|
||||
|
Loading…
Reference in New Issue
Block a user