1
0
mirror of https://github.com/bdring/Grbl_Esp32.git synced 2025-08-29 01:00:00 +02:00

Changed pulse timing method and bug fixes.

- Changed step pulse and disable timing to use short while loops, because alarms were not working right.
- Fixed coolant_init() to only set the mist pinmode if #ENABLE_M7 is defined
- Changed mist and flood coolant pin definitions from ...BIT to ...PIN for consistency
- Added additional help text via #define VERBOSE_HELP
This commit is contained in:
bdring
2018-07-26 16:40:43 -05:00
parent 97407d1fde
commit 6aa29675ed
6 changed files with 129 additions and 64 deletions

View File

@@ -47,6 +47,7 @@ Some features should not be changed. See notes below.
// If doing so, simply comment out these two defines and see instructions below.
#define DEFAULTS_GENERIC
#define CPU_MAP_ESP32 // currently not required
#define VERBOSE_HELP // adds addition help info, but could confuse some senders
// Serial baud rate
#define BAUD_RATE 115200
@@ -180,7 +181,7 @@ Some features should not be changed. See notes below.
// Enables a second coolant control pin via the mist coolant g-code command M7 on the Arduino Uno
// analog pin 4. Only use this option if you require a second coolant control pin.
// NOTE: The M8 flood coolant control pin on analog pin 3 will still be functional regardless.
#define ENABLE_M7 // Disabled by default. Uncomment to enable.
//#define ENABLE_M7 // Disabled by default. Uncomment to enable.
// This option causes the feed hold input to act as a safety door switch. A safety door, when triggered,
// immediately forces a feed hold and then safely de-energizes the machine. Resuming is blocked until

View File

@@ -26,8 +26,10 @@
void coolant_init()
{
pinMode(COOLANT_FLOOD_BIT, OUTPUT);
pinMode(COOLANT_MIST_BIT, OUTPUT);
pinMode(COOLANT_FLOOD_PIN, OUTPUT);
#ifdef ENABLE_M7
pinMode(COOLANT_MIST_PIN, OUTPUT);
#endif
coolant_stop();
}
@@ -38,17 +40,17 @@ uint8_t coolant_get_state()
uint8_t cl_state = COOLANT_STATE_DISABLE;
#ifdef INVERT_COOLANT_FLOOD_PIN
if (! digitalRead(COOLANT_FLOOD_BIT)) {
if (! digitalRead(COOLANT_FLOOD_PIN)) {
#else
if (digitalRead(COOLANT_FLOOD_BIT)) {
if (digitalRead(COOLANT_FLOOD_PIN)) {
#endif
cl_state |= COOLANT_STATE_FLOOD;
}
#ifdef ENABLE_M7
#ifdef INVERT_COOLANT_MIST_PIN
if (! digitalRead(COOLANT_MIST_BIT)) {
if (! digitalRead(COOLANT_MIST_PIN)) {
#else
if (digitalRead(COOLANT_MIST_BIT)) {
if (digitalRead(COOLANT_MIST_PIN)) {
#endif
cl_state |= COOLANT_STATE_MIST;
}
@@ -64,15 +66,15 @@ uint8_t coolant_get_state()
void coolant_stop()
{
#ifdef INVERT_COOLANT_FLOOD_PIN
digitalWrite(COOLANT_FLOOD_BIT, 1);
digitalWrite(COOLANT_FLOOD_PIN, 1);
#else
digitalWrite(COOLANT_FLOOD_BIT, 0);
digitalWrite(COOLANT_FLOOD_PIN, 0);
#endif
#ifdef ENABLE_M7
#ifdef INVERT_COOLANT_MIST_PIN
digitalWrite(COOLANT_MIST_BIT, 1);
digitalWrite(COOLANT_MIST_PIN, 1);
#else
digitalWrite(COOLANT_MIST_BIT, 0);
digitalWrite(COOLANT_MIST_PIN, 0);
#endif
#endif
}
@@ -94,18 +96,18 @@ void coolant_set_state(uint8_t mode)
if (mode & COOLANT_FLOOD_ENABLE) {
#ifdef INVERT_COOLANT_FLOOD_PIN
digitalWrite(COOLANT_FLOOD_BIT, 0);
digitalWrite(COOLANT_FLOOD_PIN, 0);
#else
digitalWrite(COOLANT_FLOOD_BIT, 1);
digitalWrite(COOLANT_FLOOD_PIN, 1);
#endif
}
#ifdef ENABLE_M7
if (mode & COOLANT_MIST_ENABLE) {
#ifdef INVERT_COOLANT_MIST_PIN
digitalWrite(COOLANT_MIST_BIT, 0);
digitalWrite(COOLANT_MIST_PIN, 0);
#else
digitalWrite(COOLANT_MIST_BIT, 1);
digitalWrite(COOLANT_MIST_PIN, 1);
#endif
}
#endif

View File

@@ -55,10 +55,9 @@
#define Z_DIRECTION_PIN GPIO_NUM_33
#define STEPPERS_DISABLE_PIN GPIO_NUM_13
#define COOLANT_FLOOD_BIT GPIO_NUM_18
#define COOLANT_MIST_BIT GPIO_NUM_19
#define COOLANT_FLOOD_PIN GPIO_NUM_18
#define COOLANT_MIST_PIN GPIO_NUM_19
#define SPINDLE_PWM_PIN GPIO_NUM_17
#define SPINDLE_PWM_CHANNEL 0

View File

@@ -200,7 +200,10 @@ void report_init_message()
// Grbl help message
void report_grbl_help() {
printPgmString(PSTR("[HLP:$$ $# $G $I $N $x=val $Nx=line $J=line $SLP $C $X $H ~ ! ? ctrl-x]\r\n"));
printPgmString(PSTR("[HLP:$$ $# $G $I $N $x=val $Nx=line $J=line $SLP $C $X $H ~ ! ? ctrl-x]\r\n"));
#ifdef VERBOSE_HELP
settings_help();
#endif
}
@@ -657,6 +660,37 @@ void report_realtime_steps()
}
}
void settings_help()
{
Serial.println("[HLP ----------- Setting Descriptions -----------]");
Serial.println("[HLP $0=Step Pulse Delay (3-255)]");
Serial.println("[HLP $1=Step Idle Delay (0-254, 255 keeps motors on)]");
Serial.println("[HLP $2=Step Pulse Invert Mask(00000ZYZ)]");
Serial.println("[HLP $3=Direction Invert Mask(00000XYZ)]");
Serial.println("[HLP $4=Step Enable Invert (boolean)]");
Serial.println("[HLP $6=Invert Probe Pin (boolean)]");
Serial.println("[HLP $10Status Report Options (See Wiki)]");
Serial.println("[HLP $11=Junction Deviation (float millimeters)]");
Serial.println("[HLP $12=Arc Tolerance (float millimeters)]");
Serial.println("[HLP $13=Report in Inches (boolean)]");
Serial.println("[HLP $20=Soft Limits Enable (boolean)]");
Serial.println("[HLP $21=Hard Limits Enable (boolean)]");
Serial.println("[HLP $22=Homing Enable (boolean)]");
Serial.println("[HLP $23=Homing Direction Invert (00000ZYX)]");
Serial.println("[HLP $24=Homing Feed Rate (mm/min)]");
Serial.println("[HLP $25=Homing Seek Rate (mm/min)]");
Serial.println("[HLP $26=Homing Switch Debounce Delay (milliseconds)]");
Serial.println("[HLP $27=Homing Switch Pull-off Distance (millimeters)]");
Serial.println("[HLP $30=Max Spindle Speed (RPM)]");
Serial.println("[HLP $31=Min Spindle Speed (RPM)]");
Serial.println("[HLP $32=Laser Mode Enable (boolean)]");
Serial.println("[HLP $100-102= XYZ Axis Resolution (step/mm)]");
Serial.println("[HLP $110-112= XYZ Axis Max Rate (mm/min)]");
Serial.println("[HLP $120-122= XYZ Axis Acceleration (step/mm^2)]");
Serial.println("[HLP $130-132= XYZ Axis max Travel (step/mm)]");
}
#ifdef DEBUG
void report_realtime_debug()
{

View File

@@ -132,6 +132,6 @@ void report_build_info(char *line);
void report_realtime_debug();
#endif
void settings_help();
#endif

View File

@@ -162,18 +162,68 @@ rmt_item32_t rmt_items[1];
*/
void IRAM_ATTR onStepperOffTimer()
{
//digitalWrite(X_STEP_PIN, 0); // TODO ... inverted step pins
//digitalWrite(Y_STEP_PIN, 0); // TODO ... inverted step pins
//digitalWrite(Z_STEP_PIN, 0); // TODO ... inverted step pins
set_stepper_pins_on(0); // all off
}
/* "The Stepper Driver Interrupt" - This timer interrupt is the workhorse of Grbl. Grbl employs
the venerable Bresenham line algorithm to manage and exactly synchronize multi-axis moves.
Unlike the popular DDA algorithm, the Bresenham algorithm is not susceptible to numerical
round-off errors and only requires fast integer counters, meaning low computational overhead
and maximizing the Arduino's capabilities. However, the downside of the Bresenham algorithm
is, for certain multi-axis motions, the non-dominant axes may suffer from un-smooth step
pulse trains, or aliasing, which can lead to strange audible noises or shaking. This is
particularly noticeable or may cause motion issues at low step frequencies (0-5kHz), but
is usually not a physical problem at higher frequencies, although audible.
To improve Bresenham multi-axis performance, Grbl uses what we call an Adaptive Multi-Axis
Step Smoothing (AMASS) algorithm, which does what the name implies. At lower step frequencies,
AMASS artificially increases the Bresenham resolution without effecting the algorithm's
innate exactness. AMASS adapts its resolution levels automatically depending on the step
frequency to be executed, meaning that for even lower step frequencies the step smoothing
level increases. Algorithmically, AMASS is acheived by a simple bit-shifting of the Bresenham
step count for each AMASS level. For example, for a Level 1 step smoothing, we bit shift
the Bresenham step event count, effectively multiplying it by 2, while the axis step counts
remain the same, and then double the stepper ISR frequency. In effect, we are allowing the
non-dominant Bresenham axes step in the intermediate ISR tick, while the dominant axis is
stepping every two ISR ticks, rather than every ISR tick in the traditional sense. At AMASS
Level 2, we simply bit-shift again, so the non-dominant Bresenham axes can step within any
of the four ISR ticks, the dominant axis steps every four ISR ticks, and quadruple the
stepper ISR frequency. And so on. This, in effect, virtually eliminates multi-axis aliasing
issues with the Bresenham algorithm and does not significantly alter Grbl's performance, but
in fact, more efficiently utilizes unused CPU cycles overall throughout all configurations.
AMASS retains the Bresenham algorithm exactness by requiring that it always executes a full
Bresenham step, regardless of AMASS Level. Meaning that for an AMASS Level 2, all four
intermediate steps must be completed such that baseline Bresenham (Level 0) count is always
retained. Similarly, AMASS Level 3 means all eight intermediate steps must be executed.
Although the AMASS Levels are in reality arbitrary, where the baseline Bresenham counts can
be multiplied by any integer value, multiplication by powers of two are simply used to ease
CPU overhead with bitshift integer operations.
This interrupt is simple and dumb by design. All the computational heavy-lifting, as in
determining accelerations, is performed elsewhere. This interrupt pops pre-computed segments,
defined as constant velocity over n number of steps, from the step segment buffer and then
executes them by pulsing the stepper pins appropriately via the Bresenham algorithm. This
ISR is supported by The Stepper Port Reset Interrupt which it uses to reset the stepper port
after each pulse. The bresenham line tracer algorithm controls all stepper outputs
simultaneously with these two interrupts.
NOTE: This interrupt must be as efficient as possible and complete before the next ISR tick,
which for ESP32 Grbl must be less than xx.xusec (TBD). Oscilloscope measured time in
ISR is 5usec typical and 25usec maximum, well below requirement.
NOTE: This ISR expects at least one step to be executed per segment.
The complete step timing should look this...
Direction pin is set
An optional (via STEP_PULSE_DELAY in config.h) is put after this
The step pin is started
A pulse length is determine (via option $0 ... settings.pulse_microseconds)
The pulse is ended
Direction will remain the same until another step occurs with a change in direction.
*/
// TODO: Replace direct updating of the int32 position counters in the ISR somehow. Perhaps use smaller
// int8 variables and update position counters only when a segment completes. This can get complicated
// with probing and homing cycles that require true real-time positions.
void IRAM_ATTR onStepperDriverTimer() // ISR It is time to take a step =======================================================================================
{
uint64_t step_pulse_off_time;
if (busy) { return; } // The busy-flag is used to avoid reentering this interrupt
@@ -184,8 +234,8 @@ void IRAM_ATTR onStepperDriverTimer() // ISR It is time to take a step ========
set_stepper_pins_on(st.step_outbits);
step_pulse_off_time = esp_timer_get_time() + (settings.pulse_microseconds); // determine when to turn off pulse
set_stepper_pins_on(STEP_OFF_AFTER_DELAY); // turns on off timers
busy = true;
@@ -288,6 +338,16 @@ void IRAM_ATTR onStepperDriverTimer() // ISR It is time to take a step ========
}
st.step_outbits ^= step_port_invert_mask; // Apply step port invert mask
// wait for step pulse time to complete...some of it should have expired during code above
while (esp_timer_get_time() < step_pulse_off_time)
{
NOP(); // spin here until time to turn off step
}
set_stepper_pins_on(0); // turn all off
busy = false;
}
@@ -314,25 +374,8 @@ void stepper_init()
true // auto reload
);
// attach the interrupt
timerAttachInterrupt(stepperDriverTimer, &onStepperDriverTimer, true);
timerAttachInterrupt(stepperDriverTimer, &onStepperDriverTimer, true);
// setup the stepper pin off timer interrupt
stepPulseOffTimer = timerBegin( 1, // timer number
STEPPER_OFF_TIMER_PRESCALE, // prescaler
false // auto reload
);
// attach the interrupt
timerAttachInterrupt(stepPulseOffTimer, // the timer
&onStepperOffTimer, // the function to run
true // edge trigger
);
/*
timerAlarmWrite( stepPulseOffTimer, // the timer
STEPPER_OFF_PERIOD_uSEC * 10, // 10x because each tick is 0.1uSec
false // auto reload
);
*/
}
// enabled. Startup init and limits call this function but shouldn't start the cycle.
@@ -405,25 +448,11 @@ void set_direction_pins_on(uint8_t onMask)
}
void set_stepper_pins_on(uint8_t onMask)
{
if (onMask == 0xFF) // if all off use the timer to do it. This adds the step pulse delay
{
// setup the timer to turn them off
timerAlarmWrite(stepPulseOffTimer, (settings.pulse_microseconds * 10), false);
timerAlarmEnable(stepPulseOffTimer);
}
//else if (onMask == 0)
//{
// should already be off
//}
else
{
onMask ^= settings.step_invert_mask; // invert pins
{
onMask ^= settings.step_invert_mask; // invert pins as required by invert mask
digitalWrite(X_STEP_PIN, (onMask & (1<<X_AXIS)));
digitalWrite(Y_STEP_PIN, (onMask & (1<<Y_AXIS)));
digitalWrite(Z_STEP_PIN, (onMask & (1<<Z_AXIS)));
}
}