1
0
mirror of https://github.com/bdring/Grbl_Esp32.git synced 2025-09-02 19:02:35 +02:00

Merge pull request #131 from bdring/Devt

updates from devt branch
This commit is contained in:
bdring
2019-04-28 14:07:23 -05:00
committed by GitHub
8 changed files with 1061 additions and 825 deletions

View File

@@ -49,6 +49,7 @@ Some features should not be changed. See notes below.
#define CPU_MAP_ESP32 // these are defined in cpu_map.h #define CPU_MAP_ESP32 // these are defined in cpu_map.h
#define VERBOSE_HELP // adds addition help info, but could confuse some senders #define VERBOSE_HELP // adds addition help info, but could confuse some senders
// Serial baud rate // Serial baud rate
#define BAUD_RATE 115200 #define BAUD_RATE 115200
@@ -501,6 +502,15 @@ Some features should not be changed. See notes below.
// time step. Also, keep in mind that the Arduino delay timer is not very accurate for long delays. // time step. Also, keep in mind that the Arduino delay timer is not very accurate for long delays.
#define DWELL_TIME_STEP 50 // Integer (1-255) (milliseconds) #define DWELL_TIME_STEP 50 // Integer (1-255) (milliseconds)
// For test use only. This uses the ESP32's RMT perifieral to generate step pulses
// It allows the use of the STEP_PULSE_DELAY (see below) and it automatically ends the
// pulse in one operation.
// Dir Pin ____|--------------------
// Step Pin _______|--|____________
// While this is experimental, it is intended to be the future default method after testing
//#define USE_RMT_STEPS
// Creates a delay between the direction pin setting and corresponding step pulse by creating // Creates a delay between the direction pin setting and corresponding step pulse by creating
// another interrupt (Timer2 compare) to manage it. The main Grbl interrupt (Timer1 compare) // another interrupt (Timer2 compare) to manage it. The main Grbl interrupt (Timer1 compare)
// sets the direction pins, and does not immediately set the stepper pins, as it would in // sets the direction pins, and does not immediately set the stepper pins, as it would in
@@ -510,8 +520,8 @@ Some features should not be changed. See notes below.
// NOTE: Uncomment to enable. The recommended delay must be > 3us, and, when added with the // NOTE: Uncomment to enable. The recommended delay must be > 3us, and, when added with the
// user-supplied step pulse time, the total time must not exceed 127us. Reported successful // user-supplied step pulse time, the total time must not exceed 127us. Reported successful
// values for certain setups have ranged from 5 to 20us. // values for certain setups have ranged from 5 to 20us.
// !!!!! ESP32 Not currently implemented // must use #define USE_RMT_STEPS for this to work
// #define STEP_PULSE_DELAY 10 // Step pulse delay in microseconds. Default disabled. //#define STEP_PULSE_DELAY 10 // Step pulse delay in microseconds. Default disabled.
// The number of linear motions in the planner buffer to be planned at any give time. The vast // The number of linear motions in the planner buffer to be planned at any give time. The vast
// majority of RAM that Grbl uses is based on this buffer size. Only increase if there is extra // majority of RAM that Grbl uses is based on this buffer size. Only increase if there is extra
@@ -551,14 +561,11 @@ Some features should not be changed. See notes below.
// #define RX_BUFFER_SIZE 128 // (1-254) Uncomment to override defaults in serial.h // #define RX_BUFFER_SIZE 128 // (1-254) Uncomment to override defaults in serial.h
// #define TX_BUFFER_SIZE 100 // (1-254) // #define TX_BUFFER_SIZE 100 // (1-254)
// A simple software debouncing feature for hard limit switches. When enabled, the interrupt // A simple software debouncing feature for hard limit switches. When enabled, the limit
// monitoring the hard limit switch pins will enable the Arduino's watchdog timer to re-check // switch interrupt unblock a waiting task which will recheck the limit switch pins after
// the limit pin state after a delay of about 32msec. This can help with CNC machines with // a short delay. Default disabled
// problematic false triggering of their hard limit switches, but it WILL NOT fix issues with //#define ENABLE_SOFTWARE_DEBOUNCE // Default disabled. Uncomment to enable.
// electrical interference on the signal cables from external sources. It's recommended to first #define DEBOUNCE_PERIOD 32 // in milliseconds default 32 microseconds
// use shielded signal cables with their shielding connected to ground (old USB/computer cables
// work well and are cheap to find) and wire in a low-pass circuit into each limit pin.
// #define ENABLE_SOFTWARE_DEBOUNCE // Default disabled. Uncomment to enable.
// Configures the position after a probing cycle during Grbl's check mode. Disabled sets // Configures the position after a probing cycle during Grbl's check mode. Disabled sets
// the position to the probe target, when enabled sets the position to the start position. // the position to the probe target, when enabled sets the position to the start position.

View File

@@ -36,6 +36,8 @@
*/ */
#ifdef CPU_MAP_ESP32 #ifdef CPU_MAP_ESP32
// This is the CPU Map for the ESP32 CNC Controller R2 // This is the CPU Map for the ESP32 CNC Controller R2
@@ -44,12 +46,16 @@
// form the pins. Grbl will virtually move the axis. This could // form the pins. Grbl will virtually move the axis. This could
// be handy if you are using a servo, etc. for another axis. // be handy if you are using a servo, etc. for another axis.
#define X_STEP_PIN GPIO_NUM_12 #define X_STEP_PIN GPIO_NUM_12
#define Y_STEP_PIN GPIO_NUM_14
#define Z_STEP_PIN GPIO_NUM_27
#define X_DIRECTION_PIN GPIO_NUM_26 #define X_DIRECTION_PIN GPIO_NUM_26
#define X_RMT_CHANNEL 0
#define Y_STEP_PIN GPIO_NUM_14
#define Y_DIRECTION_PIN GPIO_NUM_25 #define Y_DIRECTION_PIN GPIO_NUM_25
#define Y_RMT_CHANNEL 1
#define Z_STEP_PIN GPIO_NUM_27
#define Z_DIRECTION_PIN GPIO_NUM_33 #define Z_DIRECTION_PIN GPIO_NUM_33
#define Z_RMT_CHANNEL 2
// OK to comment out to use pin for other features // OK to comment out to use pin for other features
#define STEPPERS_DISABLE_PIN GPIO_NUM_13 #define STEPPERS_DISABLE_PIN GPIO_NUM_13
@@ -851,4 +857,3 @@
#endif #endif

Binary file not shown.

View File

@@ -27,7 +27,7 @@
#include "grbl.h" #include "grbl.h"
xQueueHandle limit_sw_queue; // used by limit switch debouncing
// Homing axis search distance multiplier. Computed by this value times the cycle travel. // Homing axis search distance multiplier. Computed by this value times the cycle travel.
#ifndef HOMING_AXIS_SEARCH_SCALAR #ifndef HOMING_AXIS_SEARCH_SCALAR
@@ -47,6 +47,12 @@ void IRAM_ATTR isr_limit_switches()
if ( ( sys.state != STATE_ALARM) & (bit_isfalse(sys.state, STATE_HOMING)) ) { if ( ( sys.state != STATE_ALARM) & (bit_isfalse(sys.state, STATE_HOMING)) ) {
if (!(sys_rt_exec_alarm)) { if (!(sys_rt_exec_alarm)) {
#ifdef ENABLE_SOFTWARE_DEBOUNCE
// we will start a task that will recheck the switches after a small delay
int evt;
xQueueSendFromISR(limit_sw_queue, &evt, NULL);
#else
#ifdef HARD_LIMIT_FORCE_STATE_CHECK #ifdef HARD_LIMIT_FORCE_STATE_CHECK
// Check limit pin state. // Check limit pin state.
if (limits_get_state()) { if (limits_get_state()) {
@@ -57,6 +63,7 @@ void IRAM_ATTR isr_limit_switches()
mc_reset(); // Initiate system kill. mc_reset(); // Initiate system kill.
system_set_exec_alarm(EXEC_ALARM_HARD_LIMIT); // Indicate hard limit critical event system_set_exec_alarm(EXEC_ALARM_HARD_LIMIT); // Indicate hard limit critical event
#endif #endif
#endif
} }
} }
} }
@@ -300,15 +307,17 @@ void limits_init()
limits_disable(); limits_disable();
} }
// setup task used for debouncing
limit_sw_queue = xQueueCreate(10, sizeof( int ));
xTaskCreate(limitCheckTask,
"limitCheckTask",
2048,
NULL,
5, // priority
NULL);
// TODO Debounce
/*
#ifdef ENABLE_SOFTWARE_DEBOUNCE
MCUSR &= ~(1<<WDRF);
WDTCSR |= (1<<WDCE) | (1<<WDE);
WDTCSR = (1<<WDP0); // Set time-out at ~32msec.
#endif
*/
} }
@@ -332,9 +341,11 @@ uint8_t limits_get_state()
#ifdef X_LIMIT_PIN #ifdef X_LIMIT_PIN
pin += digitalRead(X_LIMIT_PIN); pin += digitalRead(X_LIMIT_PIN);
#endif #endif
#ifdef Y_LIMIT_PIN #ifdef Y_LIMIT_PIN
pin += (digitalRead(Y_LIMIT_PIN) << Y_AXIS); pin += (digitalRead(Y_LIMIT_PIN) << Y_AXIS);
#endif #endif
#ifdef Z_LIMIT_PIN #ifdef Z_LIMIT_PIN
pin += (digitalRead(Z_LIMIT_PIN) << Z_AXIS); pin += (digitalRead(Z_LIMIT_PIN) << Z_AXIS);
#endif #endif
@@ -343,8 +354,7 @@ uint8_t limits_get_state()
pin ^= INVERT_LIMIT_PIN_MASK; pin ^= INVERT_LIMIT_PIN_MASK;
#endif #endif
if (bit_istrue(settings.flags,BITFLAG_INVERT_LIMIT_PINS)) if (bit_istrue(settings.flags,BITFLAG_INVERT_LIMIT_PINS)) {
{
pin ^= LIMIT_MASK; pin ^= LIMIT_MASK;
} }
@@ -356,16 +366,8 @@ uint8_t limits_get_state()
} }
return(limit_state); return(limit_state);
} }
// Performs a soft limit check. Called from mc_line() only. Assumes the machine has been homed, // Performs a soft limit check. Called from mc_line() only. Assumes the machine has been homed,
// the workspace volume is in all negative space, and the system is in normal operation. // the workspace volume is in all negative space, and the system is in normal operation.
// NOTE: Used by jogging to limit travel within soft-limit volume. // NOTE: Used by jogging to limit travel within soft-limit volume.
@@ -383,6 +385,7 @@ void limits_soft_check(float *target)
if (sys.abort) { return; } if (sys.abort) { return; }
} while ( sys.state != STATE_IDLE ); } while ( sys.state != STATE_IDLE );
} }
mc_reset(); // Issue system reset and ensure spindle and coolant are shutdown. mc_reset(); // Issue system reset and ensure spindle and coolant are shutdown.
system_set_exec_alarm(EXEC_ALARM_SOFT_LIMIT); // Indicate soft limit critical event system_set_exec_alarm(EXEC_ALARM_SOFT_LIMIT); // Indicate soft limit critical event
protocol_execute_realtime(); // Execute to enter critical event loop and system abort protocol_execute_realtime(); // Execute to enter critical event loop and system abort
@@ -390,6 +393,21 @@ void limits_soft_check(float *target)
} }
} }
// this is the task
void limitCheckTask(void *pvParameters)
{
while(true) {
int evt;
xQueueReceive(limit_sw_queue, &evt, portMAX_DELAY); // block until receive queue
vTaskDelay( DEBOUNCE_PERIOD / portTICK_PERIOD_MS ); // delay a while
if (limits_get_state()) {
mc_reset(); // Initiate system kill.
system_set_exec_alarm(EXEC_ALARM_HARD_LIMIT); // Indicate hard limit critical event
}
}
}
// return true if the axis is defined as a squared axis // return true if the axis is defined as a squared axis
// Squaring: is used on gantry type axes that have two motors // Squaring: is used on gantry type axes that have two motors
// Each motor with touch off its own switch to square the axis // Each motor with touch off its own switch to square the axis

View File

@@ -32,8 +32,6 @@
#define SQUARING_MODE_A 1 // A motor runs #define SQUARING_MODE_A 1 // A motor runs
#define SQUARING_MODE_B 2 // B motor runs #define SQUARING_MODE_B 2 // B motor runs
// Initialize the limits module // Initialize the limits module
void limits_init(); void limits_init();
@@ -53,4 +51,7 @@ void isr_limit_switches();
bool axis_is_squared(uint8_t axis_mask); bool axis_is_squared(uint8_t axis_mask);
// A task that runs after a limit switch interrupt.
void limitCheckTask(void *pvParameters);
#endif #endif

View File

@@ -37,9 +37,9 @@ typedef struct {
uint32_t steps[N_AXIS]; uint32_t steps[N_AXIS];
uint32_t step_event_count; uint32_t step_event_count;
uint8_t direction_bits; uint8_t direction_bits;
#ifdef VARIABLE_SPINDLE #ifdef VARIABLE_SPINDLE
uint8_t is_pwm_rate_adjusted; // Tracks motions that require constant laser power/rate uint8_t is_pwm_rate_adjusted; // Tracks motions that require constant laser power/rate
#endif #endif
} st_block_t; } st_block_t;
static st_block_t st_block_buffer[SEGMENT_BUFFER_SIZE-1]; static st_block_t st_block_buffer[SEGMENT_BUFFER_SIZE-1];
@@ -51,14 +51,14 @@ typedef struct {
uint16_t n_step; // Number of step events to be executed for this segment uint16_t n_step; // Number of step events to be executed for this segment
uint16_t cycles_per_tick; // Step distance traveled per ISR tick, aka step rate. uint16_t cycles_per_tick; // Step distance traveled per ISR tick, aka step rate.
uint8_t st_block_index; // Stepper block data index. Uses this information to execute this segment. uint8_t st_block_index; // Stepper block data index. Uses this information to execute this segment.
#ifdef ADAPTIVE_MULTI_AXIS_STEP_SMOOTHING #ifdef ADAPTIVE_MULTI_AXIS_STEP_SMOOTHING
uint8_t amass_level; // Indicates AMASS level for the ISR to execute this segment uint8_t amass_level; // Indicates AMASS level for the ISR to execute this segment
#else #else
uint8_t prescaler; // Without AMASS, a prescaler is required to adjust for slow timing. uint8_t prescaler; // Without AMASS, a prescaler is required to adjust for slow timing.
#endif #endif
#ifdef VARIABLE_SPINDLE #ifdef VARIABLE_SPINDLE
uint8_t spindle_pwm; uint8_t spindle_pwm;
#endif #endif
} segment_t; } segment_t;
static segment_t segment_buffer[SEGMENT_BUFFER_SIZE]; static segment_t segment_buffer[SEGMENT_BUFFER_SIZE];
@@ -68,17 +68,17 @@ typedef struct {
uint32_t counter_x, // Counter variables for the bresenham line tracer uint32_t counter_x, // Counter variables for the bresenham line tracer
counter_y, counter_y,
counter_z; counter_z;
#ifdef STEP_PULSE_DELAY #ifdef STEP_PULSE_DELAY
uint8_t step_bits; // Stores out_bits output to complete the step pulse delay uint8_t step_bits; // Stores out_bits output to complete the step pulse delay
#endif #endif
uint8_t execute_step; // Flags step execution for each interrupt. uint8_t execute_step; // Flags step execution for each interrupt.
uint8_t step_pulse_time; // Step pulse reset time after step rise uint8_t step_pulse_time; // Step pulse reset time after step rise
uint8_t step_outbits; // The next stepping-bits to be output uint8_t step_outbits; // The next stepping-bits to be output
uint8_t dir_outbits; uint8_t dir_outbits;
#ifdef ADAPTIVE_MULTI_AXIS_STEP_SMOOTHING #ifdef ADAPTIVE_MULTI_AXIS_STEP_SMOOTHING
uint32_t steps[N_AXIS]; uint32_t steps[N_AXIS];
#endif #endif
uint16_t step_count; // Steps remaining in line segment motion uint16_t step_count; // Steps remaining in line segment motion
uint8_t exec_block_index; // Tracks the current st_block index. Change indicates new block. uint8_t exec_block_index; // Tracks the current st_block index. Change indicates new block.
@@ -119,12 +119,12 @@ typedef struct {
float step_per_mm; float step_per_mm;
float req_mm_increment; float req_mm_increment;
#ifdef PARKING_ENABLE #ifdef PARKING_ENABLE
uint8_t last_st_block_index; uint8_t last_st_block_index;
float last_steps_remaining; float last_steps_remaining;
float last_step_per_mm; float last_step_per_mm;
float last_dt_remainder; float last_dt_remainder;
#endif #endif
uint8_t ramp_type; // Current segment ramp state uint8_t ramp_type; // Current segment ramp state
float mm_complete; // End of velocity profile from end of current planner block in (mm). float mm_complete; // End of velocity profile from end of current planner block in (mm).
@@ -135,10 +135,10 @@ typedef struct {
float accelerate_until; // Acceleration ramp end measured from end of block (mm) float accelerate_until; // Acceleration ramp end measured from end of block (mm)
float decelerate_after; // Deceleration ramp start measured from end of block (mm) float decelerate_after; // Deceleration ramp start measured from end of block (mm)
#ifdef VARIABLE_SPINDLE #ifdef VARIABLE_SPINDLE
float inv_rate; // Used by PWM laser mode to speed up segment calculations. float inv_rate; // Used by PWM laser mode to speed up segment calculations.
uint8_t current_spindle_pwm; uint8_t current_spindle_pwm;
#endif #endif
} st_prep_t; } st_prep_t;
static st_prep_t prep; static st_prep_t prep;
@@ -209,18 +209,18 @@ void IRAM_ATTR onStepperDriverTimer(void *para) // ISR It is time to take a ste
TIMERG0.int_clr_timers.t0 = 1; TIMERG0.int_clr_timers.t0 = 1;
if (busy) { return; } // The busy-flag is used to avoid reentering this interrupt if (busy) {
return; // The busy-flag is used to avoid reentering this interrupt
}
// Set the direction pins a couple of nanoseconds before we step the steppers
set_direction_pins_on(st.dir_outbits); set_direction_pins_on(st.dir_outbits);
// TO DO ... do we need a direction change delay?
#ifdef USE_RMT_STEPS
stepperRMT_Outputs();
#else
set_stepper_pins_on(st.step_outbits); set_stepper_pins_on(st.step_outbits);
step_pulse_off_time = esp_timer_get_time() + (settings.pulse_microseconds); // determine when to turn off pulse step_pulse_off_time = esp_timer_get_time() + (settings.pulse_microseconds); // determine when to turn off pulse
#endif
busy = true; busy = true;
// If there is no step segment, attempt to pop one from the stepper buffer // If there is no step segment, attempt to pop one from the stepper buffer
@@ -245,25 +245,27 @@ void IRAM_ATTR onStepperDriverTimer(void *para) // ISR It is time to take a ste
} }
st.dir_outbits = st.exec_block->direction_bits ^ settings.dir_invert_mask; st.dir_outbits = st.exec_block->direction_bits ^ settings.dir_invert_mask;
#ifdef ADAPTIVE_MULTI_AXIS_STEP_SMOOTHING #ifdef ADAPTIVE_MULTI_AXIS_STEP_SMOOTHING
// With AMASS enabled, adjust Bresenham axis increment counters according to AMASS level. // With AMASS enabled, adjust Bresenham axis increment counters according to AMASS level.
st.steps[X_AXIS] = st.exec_block->steps[X_AXIS] >> st.exec_segment->amass_level; st.steps[X_AXIS] = st.exec_block->steps[X_AXIS] >> st.exec_segment->amass_level;
st.steps[Y_AXIS] = st.exec_block->steps[Y_AXIS] >> st.exec_segment->amass_level; st.steps[Y_AXIS] = st.exec_block->steps[Y_AXIS] >> st.exec_segment->amass_level;
st.steps[Z_AXIS] = st.exec_block->steps[Z_AXIS] >> st.exec_segment->amass_level; st.steps[Z_AXIS] = st.exec_block->steps[Z_AXIS] >> st.exec_segment->amass_level;
#endif #endif
#ifdef VARIABLE_SPINDLE #ifdef VARIABLE_SPINDLE
// Set real-time spindle output as segment is loaded, just prior to the first step. // Set real-time spindle output as segment is loaded, just prior to the first step.
spindle_set_speed(st.exec_segment->spindle_pwm); spindle_set_speed(st.exec_segment->spindle_pwm);
#endif #endif
} else { } else {
// Segment buffer empty. Shutdown. // Segment buffer empty. Shutdown.
st_go_idle(); st_go_idle();
#ifdef VARIABLE_SPINDLE #ifdef VARIABLE_SPINDLE
// Ensure pwm is set properly upon completion of rate-controlled motion. // Ensure pwm is set properly upon completion of rate-controlled motion.
if (st.exec_block->is_pwm_rate_adjusted) { spindle_set_speed(SPINDLE_PWM_OFF_VALUE); } if (st.exec_block->is_pwm_rate_adjusted) {
#endif spindle_set_speed(SPINDLE_PWM_OFF_VALUE);
}
#endif
system_set_exec_state_flag(EXEC_CYCLE_STOP); // Flag main program for cycle end system_set_exec_state_flag(EXEC_CYCLE_STOP); // Flag main program for cycle end
return; // Nothing to do but exit. return; // Nothing to do but exit.
} }
@@ -271,65 +273,80 @@ void IRAM_ATTR onStepperDriverTimer(void *para) // ISR It is time to take a ste
// Check probing state. // Check probing state.
if (sys_probe_state == PROBE_ACTIVE) { probe_state_monitor(); } if (sys_probe_state == PROBE_ACTIVE) {
probe_state_monitor();
}
// Reset step out bits. // Reset step out bits.
st.step_outbits = 0; st.step_outbits = 0;
// Execute step displacement profile by Bresenham line algorithm // Execute step displacement profile by Bresenham line algorithm
#ifdef ADAPTIVE_MULTI_AXIS_STEP_SMOOTHING #ifdef ADAPTIVE_MULTI_AXIS_STEP_SMOOTHING
st.counter_x += st.steps[X_AXIS]; st.counter_x += st.steps[X_AXIS];
#else #else
st.counter_x += st.exec_block->steps[X_AXIS]; st.counter_x += st.exec_block->steps[X_AXIS];
#endif #endif
if (st.counter_x > st.exec_block->step_event_count) { if (st.counter_x > st.exec_block->step_event_count) {
st.step_outbits |= (1<<X_STEP_BIT); st.step_outbits |= (1<<X_STEP_BIT);
st.counter_x -= st.exec_block->step_event_count; st.counter_x -= st.exec_block->step_event_count;
if (st.exec_block->direction_bits & (1<<X_DIRECTION_BIT)) { sys_position[X_AXIS]--; } if (st.exec_block->direction_bits & (1<<X_DIRECTION_BIT)) {
else { sys_position[X_AXIS]++; } sys_position[X_AXIS]--;
} else {
sys_position[X_AXIS]++;
} }
#ifdef ADAPTIVE_MULTI_AXIS_STEP_SMOOTHING }
#ifdef ADAPTIVE_MULTI_AXIS_STEP_SMOOTHING
st.counter_y += st.steps[Y_AXIS]; st.counter_y += st.steps[Y_AXIS];
#else #else
st.counter_y += st.exec_block->steps[Y_AXIS]; st.counter_y += st.exec_block->steps[Y_AXIS];
#endif #endif
if (st.counter_y > st.exec_block->step_event_count) { if (st.counter_y > st.exec_block->step_event_count) {
st.step_outbits |= (1<<Y_STEP_BIT); st.step_outbits |= (1<<Y_STEP_BIT);
st.counter_y -= st.exec_block->step_event_count; st.counter_y -= st.exec_block->step_event_count;
if (st.exec_block->direction_bits & (1<<Y_DIRECTION_BIT)) { sys_position[Y_AXIS]--; } if (st.exec_block->direction_bits & (1<<Y_DIRECTION_BIT)) {
else { sys_position[Y_AXIS]++; } sys_position[Y_AXIS]--;
} else {
sys_position[Y_AXIS]++;
} }
#ifdef ADAPTIVE_MULTI_AXIS_STEP_SMOOTHING }
#ifdef ADAPTIVE_MULTI_AXIS_STEP_SMOOTHING
st.counter_z += st.steps[Z_AXIS]; st.counter_z += st.steps[Z_AXIS];
#else #else
st.counter_z += st.exec_block->steps[Z_AXIS]; st.counter_z += st.exec_block->steps[Z_AXIS];
#endif #endif
if (st.counter_z > st.exec_block->step_event_count) { if (st.counter_z > st.exec_block->step_event_count) {
st.step_outbits |= (1<<Z_STEP_BIT); st.step_outbits |= (1<<Z_STEP_BIT);
st.counter_z -= st.exec_block->step_event_count; st.counter_z -= st.exec_block->step_event_count;
if (st.exec_block->direction_bits & (1<<Z_DIRECTION_BIT)) { sys_position[Z_AXIS]--; } if (st.exec_block->direction_bits & (1<<Z_DIRECTION_BIT)) {
else { sys_position[Z_AXIS]++; } sys_position[Z_AXIS]--;
} else {
sys_position[Z_AXIS]++;
}
} }
// During a homing cycle, lock out and prevent desired axes from moving. // During a homing cycle, lock out and prevent desired axes from moving.
if (sys.state == STATE_HOMING) { st.step_outbits &= sys.homing_axis_lock; } if (sys.state == STATE_HOMING) {
st.step_outbits &= sys.homing_axis_lock;
}
st.step_count--; // Decrement step events count st.step_count--; // Decrement step events count
if (st.step_count == 0) { if (st.step_count == 0) {
// Segment is complete. Discard current segment and advance segment indexing. // Segment is complete. Discard current segment and advance segment indexing.
st.exec_segment = NULL; st.exec_segment = NULL;
if ( ++segment_buffer_tail == SEGMENT_BUFFER_SIZE) { segment_buffer_tail = 0; } if ( ++segment_buffer_tail == SEGMENT_BUFFER_SIZE) {
segment_buffer_tail = 0;
}
} }
#ifndef USE_RMT_STEPS
st.step_outbits ^= step_port_invert_mask; // Apply step port invert mask 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 // 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) while (esp_timer_get_time() < step_pulse_off_time) {
{
NOP(); // spin here until time to turn off step NOP(); // spin here until time to turn off step
} }
set_stepper_pins_on(0); // turn all off set_stepper_pins_on(0); // turn all off
#endif
TIMERG0.hw_timer[STEP_TIMER_INDEX].config.alarm_en = TIMER_ALARM_EN; TIMERG0.hw_timer[STEP_TIMER_INDEX].config.alarm_en = TIMER_ALARM_EN;
@@ -340,17 +357,11 @@ void IRAM_ATTR onStepperDriverTimer(void *para) // ISR It is time to take a ste
void stepper_init() void stepper_init()
{ {
// make the direction pins outputs #ifdef USE_RMT_STEPS
#ifdef X_DIRECTION_PIN grbl_send(CLIENT_SERIAL, "[MSG:Using RMT Steps}\r\n");
pinMode(X_DIRECTION_PIN, OUTPUT); initRMT();
#endif #else
#ifdef Y_DIRECTION_PIN grbl_send(CLIENT_SERIAL, "[MSG:Using Timed Steps}\r\n");
pinMode(Y_DIRECTION_PIN, OUTPUT);
#endif
#ifdef Z_DIRECTION_PIN
pinMode(Z_DIRECTION_PIN, OUTPUT);
#endif
// make the step pins outputs // make the step pins outputs
#ifdef X_STEP_PIN #ifdef X_STEP_PIN
pinMode(X_STEP_PIN, OUTPUT); pinMode(X_STEP_PIN, OUTPUT);
@@ -372,6 +383,20 @@ void stepper_init()
#ifdef Z_STEP_B_PIN #ifdef Z_STEP_B_PIN
pinMode(Z_STEP_B_PIN, OUTPUT); pinMode(Z_STEP_B_PIN, OUTPUT);
#endif #endif
#endif
// make the direction pins outputs
#ifdef X_DIRECTION_PIN
pinMode(X_DIRECTION_PIN, OUTPUT);
#endif
#ifdef Y_DIRECTION_PIN
pinMode(Y_DIRECTION_PIN, OUTPUT);
#endif
#ifdef Z_DIRECTION_PIN
pinMode(Z_DIRECTION_PIN, OUTPUT);
#endif
// make the stepper disable pin an output // make the stepper disable pin an output
#ifdef STEPPERS_DISABLE_PIN #ifdef STEPPERS_DISABLE_PIN
@@ -379,7 +404,7 @@ void stepper_init()
set_stepper_disable(true); set_stepper_disable(true);
#endif #endif
// setup stepper timer interrupt // setup stepper timer interrupt
/* /*
stepperDriverTimer = timerBegin( 0, // timer number stepperDriverTimer = timerBegin( 0, // timer number
@@ -404,15 +429,99 @@ void stepper_init()
timer_isr_register(STEP_TIMER_GROUP, STEP_TIMER_INDEX, onStepperDriverTimer, NULL, 0, NULL); timer_isr_register(STEP_TIMER_GROUP, STEP_TIMER_INDEX, onStepperDriverTimer, NULL, 0, NULL);
}
void initRMT()
{
rmt_item32_t rmtItem[2];
rmt_config_t rmtConfig;
rmtConfig.rmt_mode = RMT_MODE_TX;
rmtConfig.clk_div = 20;
rmtConfig.mem_block_num = 2;
rmtConfig.tx_config.loop_en = false;
rmtConfig.tx_config.carrier_en = false;
rmtConfig.tx_config.carrier_freq_hz = 0;
rmtConfig.tx_config.carrier_duty_percent = 50;
rmtConfig.tx_config.carrier_level = RMT_CARRIER_LEVEL_LOW;
rmtConfig.tx_config.idle_output_en = true;
#ifdef STEP_PULSE_DELAY
rmtItem[0].duration0 = STEP_PULSE_DELAY * 4;
#else
rmtItem[0].duration0 = 1;
#endif
rmtItem[0].duration1 = 4 * settings.pulse_microseconds;
rmtItem[1].duration0 = 0;
rmtItem[1].duration1 = 0;
#ifdef X_STEP_PIN
rmt_set_source_clk( (rmt_channel_t)X_RMT_CHANNEL, RMT_BASECLK_APB);
rmtConfig.channel = (rmt_channel_t)X_RMT_CHANNEL;
rmtConfig.tx_config.idle_level = bit_istrue(settings.step_invert_mask, X_AXIS) ? RMT_IDLE_LEVEL_HIGH : RMT_IDLE_LEVEL_LOW;
rmtConfig.gpio_num = X_STEP_PIN;
rmtItem[0].level0 = rmtConfig.tx_config.idle_level;
rmtItem[0].level1 = !rmtConfig.tx_config.idle_level;
rmt_config(&rmtConfig);
rmt_fill_tx_items(rmtConfig.channel, &rmtItem[0], rmtConfig.mem_block_num, 0);
#endif
#ifdef X_STEP_B_PIN
rmt_set_source_clk( (rmt_channel_t)X_B_RMT_CHANNEL, RMT_BASECLK_APB);
rmtConfig.channel = (rmt_channel_t)X_B_RMT_CHANNEL;
rmtConfig.tx_config.idle_level = bit_istrue(settings.step_invert_mask, X_AXIS) ? RMT_IDLE_LEVEL_HIGH : RMT_IDLE_LEVEL_LOW;
rmtConfig.gpio_num = X_STEP_B_PIN;
rmtItem[0].level0 = rmtConfig.tx_config.idle_level;
rmtItem[0].level1 = !rmtConfig.tx_config.idle_level;
rmt_config(&rmtConfig);
rmt_fill_tx_items(rmtConfig.channel, &rmtItem[0], rmtConfig.mem_block_num, 0);
#endif
#ifdef Y_STEP_PIN
rmt_set_source_clk( (rmt_channel_t)Y_RMT_CHANNEL, RMT_BASECLK_APB);
rmtConfig.channel = (rmt_channel_t)Y_RMT_CHANNEL;
rmtConfig.tx_config.idle_level = bit_istrue(settings.step_invert_mask, Y_AXIS) ? RMT_IDLE_LEVEL_HIGH : RMT_IDLE_LEVEL_LOW;
rmtConfig.gpio_num = Y_STEP_PIN;
rmtItem[0].level0 = rmtConfig.tx_config.idle_level;
rmtItem[0].level1 = !rmtConfig.tx_config.idle_level;
rmt_config(&rmtConfig);
rmt_fill_tx_items(rmtConfig.channel, &rmtItem[0], rmtConfig.mem_block_num, 0);
#endif
#ifdef Y_STEP_B_PIN
rmt_set_source_clk( (rmt_channel_t)Y_B_RMT_CHANNEL, RMT_BASECLK_APB);
rmtConfig.channel = (rmt_channel_t)Y_B_RMT_CHANNEL;
rmtConfig.tx_config.idle_level = bit_istrue(settings.step_invert_mask, Y_AXIS) ? RMT_IDLE_LEVEL_HIGH : RMT_IDLE_LEVEL_LOW;
rmtConfig.gpio_num = Y_STEP_B_PIN;
rmtItem[0].level0 = rmtConfig.tx_config.idle_level;
rmtItem[0].level1 = !rmtConfig.tx_config.idle_level;
rmt_config(&rmtConfig);
rmt_fill_tx_items(rmtConfig.channel, &rmtItem[0], rmtConfig.mem_block_num, 0);
#endif
#ifdef Z_STEP_PIN
rmt_set_source_clk( (rmt_channel_t)Z_RMT_CHANNEL, RMT_BASECLK_APB);
rmtConfig.channel = (rmt_channel_t)Z_RMT_CHANNEL;
rmtConfig.tx_config.idle_level = bit_istrue(settings.step_invert_mask, Z_AXIS) ? RMT_IDLE_LEVEL_HIGH : RMT_IDLE_LEVEL_LOW;
rmtConfig.gpio_num = Z_STEP_PIN;
rmtItem[0].level0 = rmtConfig.tx_config.idle_level;
rmtItem[0].level1 = !rmtConfig.tx_config.idle_level;
rmt_config(&rmtConfig);
rmt_fill_tx_items(rmtConfig.channel, &rmtItem[0], rmtConfig.mem_block_num, 0);
#endif
} }
// enabled. Startup init and limits call this function but shouldn't start the cycle. // enabled. Startup init and limits call this function but shouldn't start the cycle.
void st_wake_up() void st_wake_up()
{ {
#ifdef ESP_DEBUG #ifdef ESP_DEBUG
//Serial.println("st_wake_up()"); //Serial.println("st_wake_up()");
#endif #endif
// Enable stepper drivers. // Enable stepper drivers.
set_stepper_disable(false); set_stepper_disable(false);
@@ -425,12 +534,12 @@ void st_wake_up()
st.step_outbits = step_port_invert_mask; st.step_outbits = step_port_invert_mask;
// Initialize step pulse timing from settings. Here to ensure updating after re-writing. // Initialize step pulse timing from settings. Here to ensure updating after re-writing.
#ifdef STEP_PULSE_DELAY #ifdef STEP_PULSE_DELAY
// Step pulse delay handling is not require with ESP32...the RMT function does it. // Step pulse delay handling is not require with ESP32...the RMT function does it.
#else // Normal operation #else // Normal operation
// Set step pulse time. Ad hoc computation from oscilloscope. Uses two's complement. // Set step pulse time. Ad hoc computation from oscilloscope. Uses two's complement.
st.step_pulse_time = -(((settings.pulse_microseconds-2)*TICKS_PER_MICROSECOND) >> 3); st.step_pulse_time = -(((settings.pulse_microseconds-2)*TICKS_PER_MICROSECOND) >> 3);
#endif #endif
// Enable Stepper Driver Interrupt // Enable Stepper Driver Interrupt
Stepper_Timer_Start(); Stepper_Timer_Start();
@@ -440,9 +549,9 @@ void st_wake_up()
void st_reset() void st_reset()
{ {
#ifdef ESP_DEBUG #ifdef ESP_DEBUG
//Serial.println("st_reset()"); //Serial.println("st_reset()");
#endif #endif
// Initialize stepper driver idle state. // Initialize stepper driver idle state.
st_go_idle(); st_go_idle();
@@ -470,74 +579,125 @@ void st_reset()
void set_direction_pins_on(uint8_t onMask) void set_direction_pins_on(uint8_t onMask)
{ {
// inverts are applied in step generation // inverts are applied in step generation
#ifdef X_DIRECTION_PIN #ifdef X_DIRECTION_PIN
digitalWrite(X_DIRECTION_PIN, (onMask & (1<<X_AXIS))); digitalWrite(X_DIRECTION_PIN, (onMask & (1<<X_AXIS)));
#endif #endif
#ifdef Y_DIRECTION_PIN #ifdef Y_DIRECTION_PIN
digitalWrite(Y_DIRECTION_PIN, (onMask & (1<<Y_AXIS))); digitalWrite(Y_DIRECTION_PIN, (onMask & (1<<Y_AXIS)));
#endif #endif
#ifdef Z_DIRECTION_PIN #ifdef Z_DIRECTION_PIN
digitalWrite(Z_DIRECTION_PIN, (onMask & (1<<Z_AXIS))); digitalWrite(Z_DIRECTION_PIN, (onMask & (1<<Z_AXIS)));
#endif #endif
} }
#ifndef USE_GANGED_AXES #ifndef USE_GANGED_AXES
// basic one motor per axis // basic one motor per axis
void set_stepper_pins_on(uint8_t onMask) void set_stepper_pins_on(uint8_t onMask)
{ {
onMask ^= settings.step_invert_mask; // invert pins as required by invert mask onMask ^= settings.step_invert_mask; // invert pins as required by invert mask
#ifdef X_STEP_PIN #ifdef X_STEP_PIN
digitalWrite(X_STEP_PIN, (onMask & (1<<X_AXIS))); digitalWrite(X_STEP_PIN, (onMask & (1<<X_AXIS)));
#endif #endif
#ifdef Y_STEP_PIN #ifdef Y_STEP_PIN
digitalWrite(Y_STEP_PIN, (onMask & (1<<Y_AXIS))); digitalWrite(Y_STEP_PIN, (onMask & (1<<Y_AXIS)));
#endif #endif
#ifdef Z_STEP_PIN #ifdef Z_STEP_PIN
digitalWrite(Z_STEP_PIN, (onMask & (1<<Z_AXIS))); digitalWrite(Z_STEP_PIN, (onMask & (1<<Z_AXIS)));
#endif #endif
} }
#else // we use ganged axes #else // we use ganged axes
void set_stepper_pins_on(uint8_t onMask) void set_stepper_pins_on(uint8_t onMask)
{ {
onMask ^= settings.step_invert_mask; // invert pins as required by invert mask onMask ^= settings.step_invert_mask; // invert pins as required by invert mask
#ifdef X_STEP_PIN #ifdef X_STEP_PIN
#ifndef X_STEP_B_PIN // if not a ganged axis #ifndef X_STEP_B_PIN // if not a ganged axis
digitalWrite(X_STEP_PIN, (onMask & (1<<X_AXIS))); digitalWrite(X_STEP_PIN, (onMask & (1<<X_AXIS)));
#else // is a ganged axis #else // is a ganged axis
if ( (ganged_mode == SQUARING_MODE_DUAL) || (ganged_mode == SQUARING_MODE_A) ) if ( (ganged_mode == SQUARING_MODE_DUAL) || (ganged_mode == SQUARING_MODE_A) ) {
digitalWrite(X_STEP_PIN, (onMask & (1<<X_AXIS))); digitalWrite(X_STEP_PIN, (onMask & (1<<X_AXIS)));
}
if ( (ganged_mode == SQUARING_MODE_DUAL) || (ganged_mode == SQUARING_MODE_B) ) if ( (ganged_mode == SQUARING_MODE_DUAL) || (ganged_mode == SQUARING_MODE_B) ) {
digitalWrite(X_STEP_B_PIN, (onMask & (1<<X_AXIS))); digitalWrite(X_STEP_B_PIN, (onMask & (1<<X_AXIS)));
#endif }
#endif #endif
#endif
#ifdef Y_STEP_PIN #ifdef Y_STEP_PIN
#ifndef Y_STEP_B_PIN // if not a ganged axis #ifndef Y_STEP_B_PIN // if not a ganged axis
digitalWrite(Y_STEP_PIN, (onMask & (1<<Y_AXIS))); digitalWrite(Y_STEP_PIN, (onMask & (1<<Y_AXIS)));
#else // is a ganged axis #else // is a ganged axis
if ( (ganged_mode == SQUARING_MODE_DUAL) || (ganged_mode == SQUARING_MODE_A) ) if ( (ganged_mode == SQUARING_MODE_DUAL) || (ganged_mode == SQUARING_MODE_A) ) {
digitalWrite(Y_STEP_PIN, (onMask & (1<<Y_AXIS))); digitalWrite(Y_STEP_PIN, (onMask & (1<<Y_AXIS)));
}
if ( (ganged_mode == SQUARING_MODE_DUAL) || (ganged_mode == SQUARING_MODE_B) ) if ( (ganged_mode == SQUARING_MODE_DUAL) || (ganged_mode == SQUARING_MODE_B) ) {
digitalWrite(Y_STEP_B_PIN, (onMask & (1<<Y_AXIS))); digitalWrite(Y_STEP_B_PIN, (onMask & (1<<Y_AXIS)));
#endif }
#endif #endif
#endif
// ganged z not supported yet // ganged z not supported yet
#ifdef Z_STEP_PIN #ifdef Z_STEP_PIN
digitalWrite(Z_STEP_PIN, (onMask & (1<<Z_AXIS))); digitalWrite(Z_STEP_PIN, (onMask & (1<<Z_AXIS)));
#endif #endif
} }
#endif #endif
// Set stepper pulse output pins
inline IRAM_ATTR static void stepperRMT_Outputs()
{
#ifdef X_STEP_PIN
if(st.step_outbits & (1<<X_AXIS)) {
#ifndef X_STEP_B_PIN // if not a ganged axis
RMT.conf_ch[X_RMT_CHANNEL].conf1.mem_rd_rst = 1;
RMT.conf_ch[X_RMT_CHANNEL].conf1.tx_start = 1;
#else // it is a ganged axis
if ( (ganged_mode == SQUARING_MODE_DUAL) || (ganged_mode == SQUARING_MODE_A) ) {
RMT.conf_ch[X_RMT_CHANNEL].conf1.mem_rd_rst = 1;
RMT.conf_ch[X_RMT_CHANNEL].conf1.tx_start = 1; }
if ( (ganged_mode == SQUARING_MODE_DUAL) || (ganged_mode == SQUARING_MODE_B) ) {
RMT.conf_ch[X_B_RMT_CHANNEL].conf1.mem_rd_rst = 1;
RMT.conf_ch[X_B_RMT_CHANNEL].conf1.tx_start = 1;
}
#endif
}
#endif
#ifdef Y_STEP_PIN
if(st.step_outbits & (1<<Y_AXIS)) {
#ifndef Y_STEP_B_PIN // if not a ganged axis
RMT.conf_ch[Y_RMT_CHANNEL].conf1.mem_rd_rst = 1;
RMT.conf_ch[Y_RMT_CHANNEL].conf1.tx_start = 1;
#else // it is a ganged axis
if ( (ganged_mode == SQUARING_MODE_DUAL) || (ganged_mode == SQUARING_MODE_A) ) {
RMT.conf_ch[Y_RMT_CHANNEL].conf1.mem_rd_rst = 1;
RMT.conf_ch[Y_RMT_CHANNEL].conf1.tx_start = 1;
}
if ( (ganged_mode == SQUARING_MODE_DUAL) || (ganged_mode == SQUARING_MODE_B) ) {
RMT.conf_ch[Y_B_RMT_CHANNEL].conf1.mem_rd_rst = 1;
RMT.conf_ch[Y_B_RMT_CHANNEL].conf1.tx_start = 1;
}
#endif
}
#endif
#ifdef Z_STEP_PIN
if(st.step_outbits & (1<<Z_AXIS)) {
RMT.conf_ch[Z_RMT_CHANNEL].conf1.mem_rd_rst = 1;
RMT.conf_ch[Z_RMT_CHANNEL].conf1.tx_start = 1;
}
#endif
}
// Stepper shutdown // Stepper shutdown
void st_go_idle() void st_go_idle()
@@ -560,16 +720,14 @@ void st_go_idle()
//vTaskDelay(settings.stepper_idle_lock_time / portTICK_PERIOD_MS); // this probably does not work when called from ISR //vTaskDelay(settings.stepper_idle_lock_time / portTICK_PERIOD_MS); // this probably does not work when called from ISR
//pin_state = true; //pin_state = true;
} } else {
else
{
set_stepper_disable(pin_state); set_stepper_disable(pin_state);
} }
set_stepper_pins_on(0); set_stepper_pins_on(0);
} }
// Called by planner_recalculate() when the executing block is updated by the new plan. // Called by planner_recalculate() when the executing block is updated by the new plan.
void st_update_plan_block_parameters() void st_update_plan_block_parameters()
{ {
if (pl_block != NULL) { // Ignore if at start of a new block. if (pl_block != NULL) { // Ignore if at start of a new block.
@@ -580,9 +738,9 @@ void st_update_plan_block_parameters()
} }
#ifdef PARKING_ENABLE #ifdef PARKING_ENABLE
// Changes the run state of the step segment buffer to execute the special parking motion. // Changes the run state of the step segment buffer to execute the special parking motion.
void st_parking_setup_buffer() void st_parking_setup_buffer()
{ {
// Store step execution data of partially completed block, if necessary. // Store step execution data of partially completed block, if necessary.
if (prep.recalculate_flag & PREP_FLAG_HOLD_PARTIAL_BLOCK) { if (prep.recalculate_flag & PREP_FLAG_HOLD_PARTIAL_BLOCK) {
prep.last_st_block_index = prep.st_block_index; prep.last_st_block_index = prep.st_block_index;
@@ -594,12 +752,12 @@ void st_update_plan_block_parameters()
prep.recalculate_flag |= PREP_FLAG_PARKING; prep.recalculate_flag |= PREP_FLAG_PARKING;
prep.recalculate_flag &= ~(PREP_FLAG_RECALCULATE); prep.recalculate_flag &= ~(PREP_FLAG_RECALCULATE);
pl_block = NULL; // Always reset parking motion to reload new block. pl_block = NULL; // Always reset parking motion to reload new block.
} }
// Restores the step segment buffer to the normal run state after a parking motion. // Restores the step segment buffer to the normal run state after a parking motion.
void st_parking_restore_buffer() void st_parking_restore_buffer()
{ {
// Restore step execution data and flags of partially completed block, if necessary. // Restore step execution data and flags of partially completed block, if necessary.
if (prep.recalculate_flag & PREP_FLAG_HOLD_PARTIAL_BLOCK) { if (prep.recalculate_flag & PREP_FLAG_HOLD_PARTIAL_BLOCK) {
st_prep_block = &st_block_buffer[prep.last_st_block_index]; st_prep_block = &st_block_buffer[prep.last_st_block_index];
@@ -613,7 +771,7 @@ void st_update_plan_block_parameters()
prep.recalculate_flag = false; prep.recalculate_flag = false;
} }
pl_block = NULL; // Set to reload next block. pl_block = NULL; // Set to reload next block.
} }
#endif #endif
// Generates the step and direction port invert masks used in the Stepper Interrupt Driver. // Generates the step and direction port invert masks used in the Stepper Interrupt Driver.
@@ -637,7 +795,9 @@ void st_generate_step_dir_invert_masks()
static uint8_t st_next_block_index(uint8_t block_index) static uint8_t st_next_block_index(uint8_t block_index)
{ {
block_index++; block_index++;
if ( block_index == (SEGMENT_BUFFER_SIZE-1) ) { return(0); } if ( block_index == (SEGMENT_BUFFER_SIZE-1) ) {
return(0);
}
return(block_index); return(block_index);
} }
@@ -657,7 +817,9 @@ static uint8_t st_next_block_index(uint8_t block_index)
void st_prep_buffer() void st_prep_buffer()
{ {
// Block step prep buffer, while in a suspend state and there is no suspend motion to execute. // Block step prep buffer, while in a suspend state and there is no suspend motion to execute.
if (bit_istrue(sys.step_control,STEP_CONTROL_END_MOTION)) { return; } if (bit_istrue(sys.step_control,STEP_CONTROL_END_MOTION)) {
return;
}
while (segment_buffer_tail != segment_next_head) { // Check if we need to fill the buffer. while (segment_buffer_tail != segment_next_head) { // Check if we need to fill the buffer.
@@ -665,19 +827,27 @@ void st_prep_buffer()
if (pl_block == NULL) { if (pl_block == NULL) {
// Query planner for a queued block // Query planner for a queued block
if (sys.step_control & STEP_CONTROL_EXECUTE_SYS_MOTION) { pl_block = plan_get_system_motion_block(); } if (sys.step_control & STEP_CONTROL_EXECUTE_SYS_MOTION) {
else { pl_block = plan_get_current_block(); } pl_block = plan_get_system_motion_block();
if (pl_block == NULL) { return; } // No planner blocks. Exit. } else {
pl_block = plan_get_current_block();
}
if (pl_block == NULL) {
return; // No planner blocks. Exit.
}
// Check if we need to only recompute the velocity profile or load a new block. // Check if we need to only recompute the velocity profile or load a new block.
if (prep.recalculate_flag & PREP_FLAG_RECALCULATE) { if (prep.recalculate_flag & PREP_FLAG_RECALCULATE) {
#ifdef PARKING_ENABLE #ifdef PARKING_ENABLE
if (prep.recalculate_flag & PREP_FLAG_PARKING) { prep.recalculate_flag &= ~(PREP_FLAG_RECALCULATE); } if (prep.recalculate_flag & PREP_FLAG_PARKING) {
else { prep.recalculate_flag = false; } prep.recalculate_flag &= ~(PREP_FLAG_RECALCULATE);
#else } else {
prep.recalculate_flag = false; prep.recalculate_flag = false;
#endif }
#else
prep.recalculate_flag = false;
#endif
} else { } else {
@@ -690,16 +860,20 @@ void st_prep_buffer()
st_prep_block = &st_block_buffer[prep.st_block_index]; st_prep_block = &st_block_buffer[prep.st_block_index];
st_prep_block->direction_bits = pl_block->direction_bits; st_prep_block->direction_bits = pl_block->direction_bits;
uint8_t idx; uint8_t idx;
#ifndef ADAPTIVE_MULTI_AXIS_STEP_SMOOTHING #ifndef ADAPTIVE_MULTI_AXIS_STEP_SMOOTHING
for (idx=0; idx<N_AXIS; idx++) { st_prep_block->steps[idx] = pl_block->steps[idx]; } for (idx=0; idx<N_AXIS; idx++) {
st_prep_block->steps[idx] = pl_block->steps[idx];
}
st_prep_block->step_event_count = pl_block->step_event_count; st_prep_block->step_event_count = pl_block->step_event_count;
#else #else
// With AMASS enabled, simply bit-shift multiply all Bresenham data by the max AMASS // With AMASS enabled, simply bit-shift multiply all Bresenham data by the max AMASS
// level, such that we never divide beyond the original data anywhere in the algorithm. // level, such that we never divide beyond the original data anywhere in the algorithm.
// If the original data is divided, we can lose a step from integer roundoff. // If the original data is divided, we can lose a step from integer roundoff.
for (idx=0; idx<N_AXIS; idx++) { st_prep_block->steps[idx] = pl_block->steps[idx] << MAX_AMASS_LEVEL; } for (idx=0; idx<N_AXIS; idx++) {
st_prep_block->steps[idx] = pl_block->steps[idx] << MAX_AMASS_LEVEL;
}
st_prep_block->step_event_count = pl_block->step_event_count << MAX_AMASS_LEVEL; st_prep_block->step_event_count = pl_block->step_event_count << MAX_AMASS_LEVEL;
#endif #endif
// Initialize segment buffer data for generating the segments. // Initialize segment buffer data for generating the segments.
prep.steps_remaining = (float)pl_block->step_event_count; prep.steps_remaining = (float)pl_block->step_event_count;
@@ -716,7 +890,7 @@ void st_prep_buffer()
prep.current_speed = sqrt(pl_block->entry_speed_sqr); prep.current_speed = sqrt(pl_block->entry_speed_sqr);
} }
#ifdef VARIABLE_SPINDLE #ifdef VARIABLE_SPINDLE
// Setup laser mode variables. PWM rate adjusted motions will always complete a motion with the // Setup laser mode variables. PWM rate adjusted motions will always complete a motion with the
// spindle off. // spindle off.
st_prep_block->is_pwm_rate_adjusted = false; st_prep_block->is_pwm_rate_adjusted = false;
@@ -727,7 +901,7 @@ void st_prep_buffer()
st_prep_block->is_pwm_rate_adjusted = true; st_prep_block->is_pwm_rate_adjusted = true;
} }
} }
#endif #endif
} }
/* --------------------------------------------------------------------------------- /* ---------------------------------------------------------------------------------
@@ -821,9 +995,9 @@ void st_prep_buffer()
} }
} }
#ifdef VARIABLE_SPINDLE #ifdef VARIABLE_SPINDLE
bit_true(sys.step_control, STEP_CONTROL_UPDATE_SPINDLE_PWM); // Force update whenever updating block. bit_true(sys.step_control, STEP_CONTROL_UPDATE_SPINDLE_PWM); // Force update whenever updating block.
#endif #endif
} }
// Initialize new segment // Initialize new segment
@@ -853,7 +1027,9 @@ void st_prep_buffer()
float speed_var; // Speed worker variable float speed_var; // Speed worker variable
float mm_remaining = pl_block->millimeters; // New segment distance from end of block. float mm_remaining = pl_block->millimeters; // New segment distance from end of block.
float minimum_mm = mm_remaining-prep.req_mm_increment; // Guarantee at least one step. float minimum_mm = mm_remaining-prep.req_mm_increment; // Guarantee at least one step.
if (minimum_mm < 0.0) { minimum_mm = 0.0; } if (minimum_mm < 0.0) {
minimum_mm = 0.0;
}
do { do {
switch (prep.ramp_type) { switch (prep.ramp_type) {
@@ -879,8 +1055,11 @@ void st_prep_buffer()
// Acceleration-cruise, acceleration-deceleration ramp junction, or end of block. // Acceleration-cruise, acceleration-deceleration ramp junction, or end of block.
mm_remaining = prep.accelerate_until; // NOTE: 0.0 at EOB mm_remaining = prep.accelerate_until; // NOTE: 0.0 at EOB
time_var = 2.0*(pl_block->millimeters-mm_remaining)/(prep.current_speed+prep.maximum_speed); time_var = 2.0*(pl_block->millimeters-mm_remaining)/(prep.current_speed+prep.maximum_speed);
if (mm_remaining == prep.decelerate_after) { prep.ramp_type = RAMP_DECEL; } if (mm_remaining == prep.decelerate_after) {
else { prep.ramp_type = RAMP_CRUISE; } prep.ramp_type = RAMP_DECEL;
} else {
prep.ramp_type = RAMP_CRUISE;
}
prep.current_speed = prep.maximum_speed; prep.current_speed = prep.maximum_speed;
} else { // Acceleration only. } else { // Acceleration only.
prep.current_speed += speed_var; prep.current_speed += speed_var;
@@ -918,8 +1097,9 @@ void st_prep_buffer()
prep.current_speed = prep.exit_speed; prep.current_speed = prep.exit_speed;
} }
dt += time_var; // Add computed ramp time to total segment time. dt += time_var; // Add computed ramp time to total segment time.
if (dt < dt_max) { time_var = dt_max - dt; } // **Incomplete** At ramp junction. if (dt < dt_max) {
else { time_var = dt_max - dt; // **Incomplete** At ramp junction.
} else {
if (mm_remaining > minimum_mm) { // Check for very slow segments with zero steps. if (mm_remaining > minimum_mm) { // Check for very slow segments with zero steps.
// Increase segment time to ensure at least one step in segment. Override and loop // Increase segment time to ensure at least one step in segment. Override and loop
// through distance calculations until minimum_mm or mm_complete. // through distance calculations until minimum_mm or mm_complete.
@@ -931,7 +1111,7 @@ void st_prep_buffer()
} }
} while (mm_remaining > prep.mm_complete); // **Complete** Exit loop. Profile complete. } while (mm_remaining > prep.mm_complete); // **Complete** Exit loop. Profile complete.
#ifdef VARIABLE_SPINDLE #ifdef VARIABLE_SPINDLE
/* ----------------------------------------------------------------------------------- /* -----------------------------------------------------------------------------------
Compute spindle speed PWM output for step segment Compute spindle speed PWM output for step segment
*/ */
@@ -940,7 +1120,9 @@ void st_prep_buffer()
if (pl_block->condition & (PL_COND_FLAG_SPINDLE_CW | PL_COND_FLAG_SPINDLE_CCW)) { if (pl_block->condition & (PL_COND_FLAG_SPINDLE_CW | PL_COND_FLAG_SPINDLE_CCW)) {
float rpm = pl_block->spindle_speed; float rpm = pl_block->spindle_speed;
// NOTE: Feed and rapid overrides are independent of PWM value and do not alter laser power/rate. // NOTE: Feed and rapid overrides are independent of PWM value and do not alter laser power/rate.
if (st_prep_block->is_pwm_rate_adjusted) { rpm *= (prep.current_speed * prep.inv_rate); } if (st_prep_block->is_pwm_rate_adjusted) {
rpm *= (prep.current_speed * prep.inv_rate);
}
// If current_speed is zero, then may need to be rpm_min*(100/MAX_SPINDLE_SPEED_OVERRIDE) // If current_speed is zero, then may need to be rpm_min*(100/MAX_SPINDLE_SPEED_OVERRIDE)
// but this would be instantaneous only and during a motion. May not matter at all. // but this would be instantaneous only and during a motion. May not matter at all.
prep.current_spindle_pwm = spindle_compute_pwm_value(rpm); prep.current_spindle_pwm = spindle_compute_pwm_value(rpm);
@@ -952,7 +1134,7 @@ void st_prep_buffer()
} }
prep_segment->spindle_pwm = prep.current_spindle_pwm; // Reload segment PWM value prep_segment->spindle_pwm = prep.current_spindle_pwm; // Reload segment PWM value
#endif #endif
/* ----------------------------------------------------------------------------------- /* -----------------------------------------------------------------------------------
Compute segment step rate, steps to execute, and apply necessary rate corrections. Compute segment step rate, steps to execute, and apply necessary rate corrections.
@@ -975,9 +1157,11 @@ void st_prep_buffer()
// Less than one step to decelerate to zero speed, but already very close. AMASS // Less than one step to decelerate to zero speed, but already very close. AMASS
// requires full steps to execute. So, just bail. // requires full steps to execute. So, just bail.
bit_true(sys.step_control,STEP_CONTROL_END_MOTION); bit_true(sys.step_control,STEP_CONTROL_END_MOTION);
#ifdef PARKING_ENABLE #ifdef PARKING_ENABLE
if (!(prep.recalculate_flag & PREP_FLAG_PARKING)) { prep.recalculate_flag |= PREP_FLAG_HOLD_PARTIAL_BLOCK; } if (!(prep.recalculate_flag & PREP_FLAG_PARKING)) {
#endif prep.recalculate_flag |= PREP_FLAG_HOLD_PARTIAL_BLOCK;
}
#endif
return; // Segment not generated, but current step data still retained. return; // Segment not generated, but current step data still retained.
} }
} }
@@ -996,20 +1180,28 @@ void st_prep_buffer()
// Compute CPU cycles per step for the prepped segment. // Compute CPU cycles per step for the prepped segment.
uint32_t cycles = ceil( (TICKS_PER_MICROSECOND*1000000*60)*inv_rate ); // (cycles/step) uint32_t cycles = ceil( (TICKS_PER_MICROSECOND*1000000*60)*inv_rate ); // (cycles/step)
#ifdef ADAPTIVE_MULTI_AXIS_STEP_SMOOTHING #ifdef ADAPTIVE_MULTI_AXIS_STEP_SMOOTHING
// Compute step timing and multi-axis smoothing level. // Compute step timing and multi-axis smoothing level.
// NOTE: AMASS overdrives the timer with each level, so only one prescalar is required. // NOTE: AMASS overdrives the timer with each level, so only one prescalar is required.
if (cycles < AMASS_LEVEL1) { prep_segment->amass_level = 0; } if (cycles < AMASS_LEVEL1) {
else { prep_segment->amass_level = 0;
if (cycles < AMASS_LEVEL2) { prep_segment->amass_level = 1; } } else {
else if (cycles < AMASS_LEVEL3) { prep_segment->amass_level = 2; } if (cycles < AMASS_LEVEL2) {
else { prep_segment->amass_level = 3; } prep_segment->amass_level = 1;
} else if (cycles < AMASS_LEVEL3) {
prep_segment->amass_level = 2;
} else {
prep_segment->amass_level = 3;
}
cycles >>= prep_segment->amass_level; cycles >>= prep_segment->amass_level;
prep_segment->n_step <<= prep_segment->amass_level; prep_segment->n_step <<= prep_segment->amass_level;
} }
if (cycles < (1UL << 16)) { prep_segment->cycles_per_tick = cycles; } // < 65536 (4.1ms @ 16MHz) if (cycles < (1UL << 16)) {
else { prep_segment->cycles_per_tick = 0xffff; } // Just set the slowest speed possible. prep_segment->cycles_per_tick = cycles; // < 65536 (4.1ms @ 16MHz)
#else } else {
prep_segment->cycles_per_tick = 0xffff; // Just set the slowest speed possible.
}
#else
// Compute step timing and timer prescalar for normal step generation. // Compute step timing and timer prescalar for normal step generation.
if (cycles < (1UL << 16)) { // < 65536 (4.1ms @ 16MHz) if (cycles < (1UL << 16)) { // < 65536 (4.1ms @ 16MHz)
prep_segment->prescaler = 1; // prescaler: 0 prep_segment->prescaler = 1; // prescaler: 0
@@ -1025,11 +1217,13 @@ void st_prep_buffer()
prep_segment->cycles_per_tick = 0xffff; prep_segment->cycles_per_tick = 0xffff;
} }
} }
#endif #endif
// Segment complete! Increment segment buffer indices, so stepper ISR can immediately execute it. // Segment complete! Increment segment buffer indices, so stepper ISR can immediately execute it.
segment_buffer_head = segment_next_head; segment_buffer_head = segment_next_head;
if ( ++segment_next_head == SEGMENT_BUFFER_SIZE ) { segment_next_head = 0; } if ( ++segment_next_head == SEGMENT_BUFFER_SIZE ) {
segment_next_head = 0;
}
// Update the appropriate planner and segment data. // Update the appropriate planner and segment data.
pl_block->millimeters = mm_remaining; pl_block->millimeters = mm_remaining;
@@ -1044,9 +1238,11 @@ void st_prep_buffer()
// the segment queue, where realtime protocol will set new state upon receiving the // the segment queue, where realtime protocol will set new state upon receiving the
// cycle stop flag from the ISR. Prep_segment is blocked until then. // cycle stop flag from the ISR. Prep_segment is blocked until then.
bit_true(sys.step_control,STEP_CONTROL_END_MOTION); bit_true(sys.step_control,STEP_CONTROL_END_MOTION);
#ifdef PARKING_ENABLE #ifdef PARKING_ENABLE
if (!(prep.recalculate_flag & PREP_FLAG_PARKING)) { prep.recalculate_flag |= PREP_FLAG_HOLD_PARTIAL_BLOCK; } if (!(prep.recalculate_flag & PREP_FLAG_PARKING)) {
#endif prep.recalculate_flag |= PREP_FLAG_HOLD_PARTIAL_BLOCK;
}
#endif
return; // Bail! return; // Bail!
} else { // End of planner block } else { // End of planner block
// The planner block is complete. All steps are set to be executed in the segment buffer. // The planner block is complete. All steps are set to be executed in the segment buffer.
@@ -1070,7 +1266,7 @@ void st_prep_buffer()
// divided by the ACCELERATION TICKS PER SECOND in seconds. // divided by the ACCELERATION TICKS PER SECOND in seconds.
float st_get_realtime_rate() float st_get_realtime_rate()
{ {
if (sys.state & (STATE_CYCLE | STATE_HOMING | STATE_HOLD | STATE_JOG | STATE_SAFETY_DOOR)){ if (sys.state & (STATE_CYCLE | STATE_HOMING | STATE_HOLD | STATE_JOG | STATE_SAFETY_DOOR)) {
return prep.current_speed; return prep.current_speed;
} }
return 0.0f; return 0.0f;
@@ -1083,9 +1279,9 @@ void IRAM_ATTR Stepper_Timer_WritePeriod(uint64_t alarm_val)
void IRAM_ATTR Stepper_Timer_Start() void IRAM_ATTR Stepper_Timer_Start()
{ {
#ifdef ESP_DEBUG #ifdef ESP_DEBUG
//Serial.println("ST Start"); //Serial.println("ST Start");
#endif #endif
timer_set_counter_value(STEP_TIMER_GROUP, STEP_TIMER_INDEX, 0x00000000ULL); timer_set_counter_value(STEP_TIMER_GROUP, STEP_TIMER_INDEX, 0x00000000ULL);
@@ -1096,9 +1292,9 @@ void IRAM_ATTR Stepper_Timer_Start()
void IRAM_ATTR Stepper_Timer_Stop() void IRAM_ATTR Stepper_Timer_Stop()
{ {
#ifdef ESP_DEBUG #ifdef ESP_DEBUG
//Serial.println("ST Stop"); //Serial.println("ST Stop");
#endif #endif
timer_pause(STEP_TIMER_GROUP, STEP_TIMER_INDEX); timer_pause(STEP_TIMER_GROUP, STEP_TIMER_INDEX);
@@ -1107,21 +1303,24 @@ void IRAM_ATTR Stepper_Timer_Stop()
void set_stepper_disable(uint8_t isOn) // isOn = true // to disable void set_stepper_disable(uint8_t isOn) // isOn = true // to disable
{ {
if (bit_istrue(settings.flags,BITFLAG_INVERT_ST_ENABLE)) { isOn = !isOn; } // Apply pin invert. if (bit_istrue(settings.flags,BITFLAG_INVERT_ST_ENABLE)) {
isOn = !isOn; // Apply pin invert.
}
#ifdef STEPPERS_DISABLE_PIN #ifdef STEPPERS_DISABLE_PIN
digitalWrite(STEPPERS_DISABLE_PIN, isOn ); digitalWrite(STEPPERS_DISABLE_PIN, isOn );
#endif #endif
} }
bool get_stepper_disable() { // returns true if steppers are disabled bool get_stepper_disable() // returns true if steppers are disabled
{
bool disabled = false; bool disabled = false;
#ifdef STEPPERS_DISABLE_PIN #ifdef STEPPERS_DISABLE_PIN
disabled = digitalRead(STEPPERS_DISABLE_PIN); disabled = digitalRead(STEPPERS_DISABLE_PIN);
#else #else
return false; // thery are never disabled if there is no pin defined return false; // thery are never disabled if there is no pin defined
#endif #endif
if (bit_istrue(settings.flags,BITFLAG_INVERT_ST_ENABLE)) { if (bit_istrue(settings.flags,BITFLAG_INVERT_ST_ENABLE)) {
disabled = !disabled; // Apply pin invert. disabled = !disabled; // Apply pin invert.

View File

@@ -82,6 +82,8 @@ extern uint8_t ganged_mode;
void IRAM_ATTR onSteppertimer(); void IRAM_ATTR onSteppertimer();
void IRAM_ATTR onStepperOffTimer(); void IRAM_ATTR onStepperOffTimer();
void stepper_init(); void stepper_init();
void initRMT();
inline IRAM_ATTR static void stepperRMT_Outputs();
// Enable steppers, but cycle does not start unless called by motion control or realtime command. // Enable steppers, but cycle does not start unless called by motion control or realtime command.
void st_wake_up(); void st_wake_up();

View File

@@ -522,6 +522,10 @@ void Web_Server::handle_web_command ()
uint8_t sindex = 0; uint8_t sindex = 0;
scmd = get_Splited_Value(cmd,'\n', sindex); scmd = get_Splited_Value(cmd,'\n', sindex);
while ( scmd != "" ){ while ( scmd != "" ){
if ((scmd.length() == 2) && (scmd[0] == 0xC2)){
scmd[0]=scmd[1];
scmd.remove(1,1);
}
if (scmd.length() > 1)scmd += "\n"; if (scmd.length() > 1)scmd += "\n";
else if (!is_realtime_cmd(scmd[0]) )scmd += "\n"; else if (!is_realtime_cmd(scmd[0]) )scmd += "\n";
if (!Serial2Socket.push(scmd.c_str()))res = "Error"; if (!Serial2Socket.push(scmd.c_str()))res = "Error";