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

Conflicting files Devt/master

This commit is contained in:
Mitch Bradley
2020-05-07 11:34:59 -10:00
parent 4c3cf7ba9e
commit 9013e21d29
7 changed files with 156 additions and 120 deletions

View File

@@ -37,11 +37,25 @@
#define Y_LIMIT_PIN GPIO_NUM_4
#define Z_LIMIT_PIN GPIO_NUM_16
#ifdef HOMING_CYCLE_0
#undef HOMING_CYCLE_0
#endif
#define HOMING_CYCLE_0 (1<<Z_AXIS) // Z first
#ifdef HOMING_CYCLE_1
#undef HOMING_CYCLE_1
#endif
#define HOMING_CYCLE_1 ((1<<X_AXIS)|(1<<Y_AXIS))
#ifdef HOMING_CYCLE_2
#undef HOMING_CYCLE_2
#endif
// OK to comment out to use pin for other features
#define STEPPERS_DISABLE_PIN GPIO_NUM_13
#define SPINDLE_TYPE SPINDLE_TYPE_PWM
#define SPINDLE_PWM_PIN GPIO_NUM_2 // labeled SpinPWM
#define SPINDLE_OUTPUT_PIN GPIO_NUM_2 // labeled SpinPWM
#define SPINDLE_ENABLE_PIN GPIO_NUM_22 // labeled SpinEnbl
#define MIST_PIN GPIO_NUM_21 // labeled Mist
@@ -52,3 +66,5 @@
#define CONTROL_RESET_PIN GPIO_NUM_34 // labeled Reset, needs external pullup
#define CONTROL_FEED_HOLD_PIN GPIO_NUM_36 // labeled Hold, needs external pullup
#define CONTROL_CYCLE_START_PIN GPIO_NUM_39 // labeled Start, needs external pullup

View File

@@ -22,7 +22,7 @@
along with Grbl_ESP32. If not, see <http://www.gnu.org/licenses/>.
*/
#define MACHINE_NAME "External 4 Axis Driver Board"
#define MACHINE_NAME "External 4 Axis Driver Board V2"
#ifdef N_AXIS
#undef N_AXIS
@@ -35,20 +35,22 @@
#define Y_DIRECTION_PIN GPIO_NUM_15
#define Z_STEP_PIN GPIO_NUM_27
#define Z_DIRECTION_PIN GPIO_NUM_33
#define A_STEP_PIN GPIO_NUM_14
#define A_DIRECTION_PIN GPIO_NUM_12
#define A_STEP_PIN GPIO_NUM_12
#define A_DIRECTION_PIN GPIO_NUM_14
#define STEPPERS_DISABLE_PIN GPIO_NUM_13
/*
#define SPINDLE_TYPE SPINDLE_TYPE_PWM
#define SPINDLE_PWM_PIN GPIO_NUM_25
#define SPINDLE_ENABLE_PIN GPIO_NUM_22
#define SPINDLE_TYPE SPINDLE_TYPE_PWM // only one spindle at a time
*/
#define SPINDLE_TYPE SPINDLE_TYPE_HUANYANG
#define MODBUS_TX GPIO_NUM_17
#define MODBUS_RX GPIO_NUM_4
#define MODBUS_CTRL GPIO_NUM_16
#define SPINDLE_OUTPUT_PIN GPIO_NUM_25
#define SPINDLE_ENABLE_PIN GPIO_NUM_22
#define SPINDLE_TYPE SPINDLE_TYPE_HUANYANG // only one spindle at a time
#define HUANYANG_TXD_PIN GPIO_NUM_17
#define HUANYANG_RXD_PIN GPIO_NUM_4
#define HUANYANG_RTS_PIN GPIO_NUM_16
#define X_LIMIT_PIN GPIO_NUM_34
#define Y_LIMIT_PIN GPIO_NUM_35

View File

@@ -295,23 +295,16 @@ uint8_t gc_execute_line(char* line, uint8_t client) {
case 3:
case 4:
case 5:
#ifndef SPINDLE_PWM_PIN
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "No spindle pin defined");
#endif
word_bit = MODAL_GROUP_M7;
switch (int_value) {
case 3:
gc_block.modal.spindle = SPINDLE_ENABLE_CW;
break;
case 4: // Supported if SPINDLE_DIR_PIN is defined or laser mode is on.
#ifndef SPINDLE_DIR_PIN
// if laser mode is not on then this is an unsupported command
if bit_isfalse(settings.flags, BITFLAG_LASER_MODE) {
if (spindle->is_reversable || bit_istrue(settings.flags, BITFLAG_LASER_MODE))
gc_block.modal.spindle = SPINDLE_ENABLE_CCW;
else
FAIL(STATUS_GCODE_UNSUPPORTED_COMMAND);
break;
}
#endif
gc_block.modal.spindle = SPINDLE_ENABLE_CCW;
break;
case 5:
gc_block.modal.spindle = SPINDLE_DISABLE;
@@ -1088,16 +1081,12 @@ uint8_t gc_execute_line(char* line, uint8_t client) {
// [4. Set spindle speed ]:
if ((gc_state.spindle_speed != gc_block.values.s) || bit_istrue(gc_parser_flags, GC_PARSER_LASER_FORCE_SYNC)) {
if (gc_state.modal.spindle != SPINDLE_DISABLE) {
#ifdef VARIABLE_SPINDLE
if (bit_isfalse(gc_parser_flags, GC_PARSER_LASER_ISMOTION)) {
if (bit_istrue(gc_parser_flags, GC_PARSER_LASER_DISABLE))
spindle_sync(gc_state.modal.spindle, 0.0);
spindle->spindle_sync(gc_state.modal.spindle, 0);
else
spindle_sync(gc_state.modal.spindle, gc_block.values.s);
spindle->spindle_sync(gc_state.modal.spindle, (uint32_t)gc_block.values.s);
}
#else
spindle_sync(gc_state.modal.spindle, 0.0);
#endif
}
gc_state.spindle_speed = gc_block.values.s; // Update spindle speed state.
}
@@ -1118,7 +1107,7 @@ uint8_t gc_execute_line(char* line, uint8_t client) {
// Update spindle control and apply spindle speed when enabling it in this block.
// NOTE: All spindle state changes are synced, even in laser mode. Also, pl_data,
// rather than gc_state, is used to manage laser state for non-laser motions.
spindle_sync(gc_block.modal.spindle, pl_data->spindle_speed);
spindle->spindle_sync(gc_block.modal.spindle, (uint32_t)pl_data->spindle_speed);
gc_state.modal.spindle = gc_block.modal.spindle;
}
pl_data->condition |= gc_state.modal.spindle; // Set condition flag for planner use.
@@ -1294,7 +1283,7 @@ uint8_t gc_execute_line(char* line, uint8_t client) {
if (!(settings_read_coord_data(gc_state.modal.coord_select, gc_state.coord_system)))
FAIL(STATUS_SETTING_READ_FAIL);
system_flag_wco_change(); // Set to refresh immediately just in case something altered.
spindle_set_state(SPINDLE_DISABLE, 0.0);
spindle->set_state(SPINDLE_DISABLE, 0);
coolant_set_state(COOLANT_DISABLE);
}
report_feedback_message(MESSAGE_PROGRAM_END);

View File

@@ -464,7 +464,7 @@ void protocol_exec_rt_system() {
last_s_override = MIN(last_s_override, MAX_SPINDLE_SPEED_OVERRIDE);
last_s_override = MAX(last_s_override, MIN_SPINDLE_SPEED_OVERRIDE);
if (last_s_override != sys.spindle_speed_ovr) {
bit_true(sys.step_control, STEP_CONTROL_UPDATE_SPINDLE_PWM);
bit_true(sys.step_control, STEP_CONTROL_UPDATE_SPINDLE_RPM);
sys.spindle_speed_ovr = last_s_override;
sys.report_ovr_counter = 0; // Set to report change immediately
}
@@ -535,7 +535,6 @@ static void protocol_exec_rt_suspend() {
#endif
plan_block_t* block = plan_get_current_block();
uint8_t restore_condition;
#ifdef VARIABLE_SPINDLE
float restore_spindle_speed;
if (block == NULL) {
restore_condition = (gc_state.modal.spindle | gc_state.modal.coolant);
@@ -548,10 +547,7 @@ static void protocol_exec_rt_suspend() {
if (bit_istrue(settings.flags, BITFLAG_LASER_MODE))
system_set_exec_accessory_override_flag(EXEC_SPINDLE_OVR_STOP);
#endif
#else
if (block == NULL) restore_condition = (gc_state.modal.spindle | gc_state.modal.coolant);
else restore_condition = block->condition;
#endif
while (sys.suspend) {
if (sys.abort) return;
// Block until initial hold is complete and the machine has stopped motion.
@@ -564,7 +560,7 @@ static void protocol_exec_rt_suspend() {
// Ensure any prior spindle stop override is disabled at start of safety door routine.
sys.spindle_stop_ovr = SPINDLE_STOP_OVR_DISABLED;
#ifndef PARKING_ENABLE
spindle_set_state(SPINDLE_DISABLE, 0.0); // De-energize
spindle->set_state(SPINDLE_DISABLE, 0); // De-energize
coolant_set_state(COOLANT_DISABLE); // De-energize
#else
// Get current position and store restore location and spindle retract waypoint.
@@ -599,20 +595,20 @@ static void protocol_exec_rt_suspend() {
// NOTE: Clear accessory state after retract and after an aborted restore motion.
pl_data->condition = (PL_COND_FLAG_SYSTEM_MOTION | PL_COND_FLAG_NO_FEED_OVERRIDE);
pl_data->spindle_speed = 0.0;
spindle_set_state(SPINDLE_DISABLE, 0.0); // De-energize
coolant_set_state(COOLANT_DISABLE); // De-energize
// Execute fast parking retract motion to parking target location.
spindle->set_state((SPINDLE_DISABLE, 0); // De-energize
coolant_set_state(COOLANT_DISABLE); // De-energize
// Execute fast parking retract motion to parking target location.
if (parking_target[PARKING_AXIS] < PARKING_TARGET) {
parking_target[PARKING_AXIS] = PARKING_TARGET;
parking_target[PARKING_AXIS] = PARKING_TARGET;
pl_data->feed_rate = PARKING_RATE;
mc_parking_motion(parking_target, pl_data);
}
} else {
// Parking motion not possible. Just disable the spindle and coolant.
// NOTE: Laser mode does not start a parking motion to ensure the laser stops immediately.
spindle_set_state(SPINDLE_DISABLE, 0.0); // De-energize
coolant_set_state(COOLANT_DISABLE); // De-energize
}
->set_state((SPINDLE_DISABLE, 0.0); // De-energize
coolant_set_state(COOLANT_DISABLE); // De-energize
}
#endif
sys.suspend &= ~(SUSPEND_RESTART_RETRACT);
sys.suspend |= SUSPEND_RETRACT_COMPLETE;
@@ -620,7 +616,7 @@ static void protocol_exec_rt_suspend() {
if (sys.state == STATE_SLEEP) {
report_feedback_message(MESSAGE_SLEEP_MODE);
// Spindle and coolant should already be stopped, but do it again just to be sure.
spindle_set_state(SPINDLE_DISABLE, 0.0); // De-energize
spindle->set_state(SPINDLE_DISABLE, 0); // De-energize
coolant_set_state(COOLANT_DISABLE); // De-energize
st_go_idle(); // Disable steppers
while (!(sys.abort)) protocol_exec_rt_system(); // Do nothing until reset.
@@ -657,9 +653,9 @@ static void protocol_exec_rt_suspend() {
if (bit_isfalse(sys.suspend, SUSPEND_RESTART_RETRACT)) {
if (bit_istrue(settings.flags, BITFLAG_LASER_MODE)) {
// When in laser mode, ignore spindle spin-up delay. Set to turn on laser when cycle starts.
bit_true(sys.step_control, STEP_CONTROL_UPDATE_SPINDLE_PWM);
bit_true(sys.step_control, STEP_CONTROL_UPDATE_SPINDLE_RPM);
} else {
spindle_set_state((restore_condition & (PL_COND_FLAG_SPINDLE_CW | PL_COND_FLAG_SPINDLE_CCW)), restore_spindle_speed);
spindle->set_state((restore_condition & (PL_COND_FLAG_SPINDLE_CW | PL_COND_FLAG_SPINDLE_CCW)), (uint32_t)restore_spindle_speed);
delay_sec(SAFETY_DOOR_SPINDLE_DELAY, DELAY_MODE_SYS_SUSPEND);
}
}
@@ -705,7 +701,7 @@ static void protocol_exec_rt_suspend() {
// Handles beginning of spindle stop
if (sys.spindle_stop_ovr & SPINDLE_STOP_OVR_INITIATE) {
if (gc_state.modal.spindle != SPINDLE_DISABLE) {
spindle_set_state(SPINDLE_DISABLE, 0.0); // De-energize
spindle->set_state(SPINDLE_DISABLE, 0); // De-energize
sys.spindle_stop_ovr = SPINDLE_STOP_OVR_ENABLED; // Set stop override state to enabled, if de-energized.
} else {
sys.spindle_stop_ovr = SPINDLE_STOP_OVR_DISABLED; // Clear stop override state
@@ -716,9 +712,9 @@ static void protocol_exec_rt_suspend() {
report_feedback_message(MESSAGE_SPINDLE_RESTORE);
if (bit_istrue(settings.flags, BITFLAG_LASER_MODE)) {
// When in laser mode, ignore spindle spin-up delay. Set to turn on laser when cycle starts.
bit_true(sys.step_control, STEP_CONTROL_UPDATE_SPINDLE_PWM);
bit_true(sys.step_control, STEP_CONTROL_UPDATE_SPINDLE_RPM);
} else
spindle_set_state((restore_condition & (PL_COND_FLAG_SPINDLE_CW | PL_COND_FLAG_SPINDLE_CCW)), restore_spindle_speed);
spindle->set_state((restore_condition & (PL_COND_FLAG_SPINDLE_CW | PL_COND_FLAG_SPINDLE_CCW)), (uint32_t)restore_spindle_speed);
}
if (sys.spindle_stop_ovr & SPINDLE_STOP_OVR_RESTORE_CYCLE) {
system_set_exec_state_flag(EXEC_CYCLE_START); // Set to resume program.
@@ -727,10 +723,10 @@ static void protocol_exec_rt_suspend() {
}
} else {
// Handles spindle state during hold. NOTE: Spindle speed overrides may be altered during hold state.
// NOTE: STEP_CONTROL_UPDATE_SPINDLE_PWM is automatically reset upon resume in step generator.
if (bit_istrue(sys.step_control, STEP_CONTROL_UPDATE_SPINDLE_PWM)) {
spindle_set_state((restore_condition & (PL_COND_FLAG_SPINDLE_CW | PL_COND_FLAG_SPINDLE_CCW)), restore_spindle_speed);
bit_false(sys.step_control, STEP_CONTROL_UPDATE_SPINDLE_PWM);
// NOTE: STEP_CONTROL_UPDATE_SPINDLE_RPM is automatically reset upon resume in step generator.
if (bit_istrue(sys.step_control, STEP_CONTROL_UPDATE_SPINDLE_RPM)) {
spindle->set_state((restore_condition & (PL_COND_FLAG_SPINDLE_CW | PL_COND_FLAG_SPINDLE_CCW)), (uint32_t)restore_spindle_speed);
bit_false(sys.step_control, STEP_CONTROL_UPDATE_SPINDLE_RPM);
}
}
}

View File

@@ -97,7 +97,7 @@ void grbl_sendf(uint8_t client, const char* format, ...) {
void grbl_msg_sendf(uint8_t client, uint8_t level, const char* format, ...) {
if (client == CLIENT_INPUT) return;
if (level > GRBL_MSG_LEVEL) return;
char loc_buf[64];
char loc_buf[100];
char* temp = loc_buf;
va_list arg;
va_list copy;
@@ -113,7 +113,7 @@ void grbl_msg_sendf(uint8_t client, uint8_t level, const char* format, ...) {
len = vsnprintf(temp, len + 1, format, arg);
grbl_sendf(client, "[MSG:%s]\r\n", temp);
va_end(arg);
if (len > 64)
if (len > 100)
delete[] temp;
}
@@ -308,11 +308,8 @@ void report_grbl_settings(uint8_t client, uint8_t show_extended) {
sprintf(setting, "$27=%4.3f\r\n", settings.homing_pulloff); strcat(rpt, setting);
sprintf(setting, "$30=%4.3f\r\n", settings.rpm_max); strcat(rpt, setting);
sprintf(setting, "$31=%4.3f\r\n", settings.rpm_min); strcat(rpt, setting);
#ifdef VARIABLE_SPINDLE
sprintf(setting, "$32=%d\r\n", bit_istrue(settings.flags, BITFLAG_LASER_MODE)); strcat(rpt, setting);
#else
strcat(rpt, "$32=0\r\n");
#endif
if (show_extended) {
sprintf(setting, "$33=%5.3f\r\n", settings.spindle_pwm_freq); strcat(rpt, setting);
sprintf(setting, "$34=%3.3f\r\n", settings.spindle_pwm_off_value); strcat(rpt, setting);
@@ -471,10 +468,8 @@ void report_gcode_modes(uint8_t client) {
else
sprintf(temp, " F%.0f", gc_state.feed_rate);
strcat(modes_rpt, temp);
#ifdef VARIABLE_SPINDLE
sprintf(temp, " S%4.3f", gc_state.spindle_speed);
strcat(modes_rpt, temp);
#endif
strcat(modes_rpt, "]\r\n");
grbl_send(client, modes_rpt);
}
@@ -497,12 +492,8 @@ void report_build_info(char* line, uint8_t client) {
strcpy(build_info, "[VER:" GRBL_VERSION "." GRBL_VERSION_BUILD ":");
strcat(build_info, line);
strcat(build_info, "]\r\n[OPT:");
#ifdef VARIABLE_SPINDLE
strcat(build_info, "V");
#endif
#ifdef USE_LINE_NUMBERS
strcat(build_info, "V"); // variable spindle..always on now
strcat(build_info, "N");
#endif
#ifdef COOLANT_MIST_PIN
strcat(build_info, "M"); // TODO Need to deal with M8...it could be disabled
#endif
@@ -558,6 +549,7 @@ void report_build_info(char* line, uint8_t client) {
// These will likely have a comma delimiter to separate them.
strcat(build_info, "]\r\n");
grbl_send(client, build_info); // ok to send to all
report_machine_type(client);
#if defined (ENABLE_WIFI)
grbl_send(client, (char*)wifi_config.info());
#endif
@@ -679,19 +671,11 @@ void report_realtime_status(uint8_t client) {
#endif
// Report realtime feed speed
#ifdef REPORT_FIELD_CURRENT_FEED_SPEED
#ifdef VARIABLE_SPINDLE
if (bit_istrue(settings.flags, BITFLAG_REPORT_INCHES))
sprintf(temp, "|FS:%.1f,%.0f", st_get_realtime_rate(), sys.spindle_speed / MM_PER_INCH);
sprintf(temp, "|FS:%.1f,%d", st_get_realtime_rate()/ MM_PER_INCH, sys.spindle_speed);
else
sprintf(temp, "|FS:%.0f,%.0f", st_get_realtime_rate(), sys.spindle_speed);
sprintf(temp, "|FS:%.0f,%d", st_get_realtime_rate(), sys.spindle_speed);
strcat(status, temp);
#else
if (bit_istrue(settings.flags, BITFLAG_REPORT_INCHES))
sprintf(temp, "|F:%.1f", st_get_realtime_rate() / MM_PER_INCH);
else
sprintf(temp, "|F:%.0f", st_get_realtime_rate());
strcat(status, temp);
#endif
#endif
#ifdef REPORT_FIELD_PIN_STATE
uint8_t lim_pin_state = limits_get_state();
@@ -744,7 +728,7 @@ void report_realtime_status(uint8_t client) {
} else sys.report_ovr_counter = (REPORT_OVR_REFRESH_IDLE_COUNT - 1);
sprintf(temp, "|Ov:%d,%d,%d", sys.f_override, sys.r_override, sys.spindle_speed_ovr);
strcat(status, temp);
uint8_t sp_state = spindle_get_state();
uint8_t sp_state = spindle->get_state();
uint8_t cl_state = coolant_get_state();
if (sp_state || cl_state) {
strcat(status, "|A:");
@@ -790,4 +774,54 @@ void report_gcode_comment(char* comment) {
msg[index - offset] = 0; // null terminate
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "GCode Comment...%s", msg);
}
}
void report_machine_type(uint8_t client) {
grbl_msg_sendf(client, MSG_LEVEL_INFO, "Using machine:%s", MACHINE_NAME);
}
/*
Print a message in hex format
Ex: report_hex_msg(msg, "Rx:", 6);
Would would print something like ... [MSG Rx: 0x01 0x03 0x01 0x08 0x31 0xbf]
*/
void report_hex_msg(char* buf, const char* prefix, int len) {
char report[200];
char temp[20];
sprintf(report, "%s", prefix);
for (int i = 0; i < len; i++) {
sprintf(temp, " 0x%02X", buf[i]);
strcat(report, temp);
}
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "%s", report);
}
char report_get_axis_letter(uint8_t axis) {
switch (axis) {
case X_AXIS:
return 'X';
case Y_AXIS:
return 'Y';
case Z_AXIS:
return 'Z';
case A_AXIS:
return 'A';
case B_AXIS:
return 'B';
case C_AXIS:
return 'C';
default:
return '?';
}
}
// used to report the pin nhumber or -1 for undefined.
int16_t report_pin_number(uint8_t pin_number) {
if (pin_number == UNDEFINED_PIN)
return -1;
else
return (int16_t)pin_number;
}

View File

@@ -170,6 +170,11 @@ void report_gcode_comment(char* comment);
void report_realtime_debug();
#endif
void report_machine_type(uint8_t client);
void report_hex_msg(char* buf, const char *prefix, int len);
char report_get_axis_letter(uint8_t axis);
int16_t report_pin_number(uint8_t pin_number);
#endif

View File

@@ -1,5 +1,3 @@
#include "grbl.h"
/*
stepper.c - stepper motor driver: executes motion plans using stepper motors
Part of Grbl
@@ -37,9 +35,7 @@ typedef struct {
uint32_t steps[N_AXIS];
uint32_t step_event_count;
uint8_t direction_bits;
#ifdef VARIABLE_SPINDLE
uint8_t is_pwm_rate_adjusted; // Tracks motions that require constant laser power/rate
#endif
} st_block_t;
static st_block_t st_block_buffer[SEGMENT_BUFFER_SIZE - 1];
@@ -56,9 +52,7 @@ typedef struct {
#else
uint8_t prescaler; // Without AMASS, a prescaler is required to adjust for slow timing.
#endif
#ifdef VARIABLE_SPINDLE
uint16_t spindle_pwm;
#endif
uint16_t spindle_rpm; // TODO get rid of this.
} segment_t;
static segment_t segment_buffer[SEGMENT_BUFFER_SIZE];
@@ -145,10 +139,11 @@ typedef struct {
float accelerate_until; // Acceleration ramp end measured from end of block (mm)
float decelerate_after; // Deceleration ramp start measured from end of block (mm)
#ifdef VARIABLE_SPINDLE
float inv_rate; // Used by PWM laser mode to speed up segment calculations.
uint16_t current_spindle_pwm;
#endif
//uint16_t current_spindle_pwm; // todo remove
float current_spindle_rpm;
} st_prep_t;
static st_prep_t prep;
@@ -283,20 +278,18 @@ void IRAM_ATTR onStepperDriverTimer(void* para) { // ISR It is time to take a st
st.steps[C_AXIS] = st.exec_block->steps[C_AXIS] >> st.exec_segment->amass_level;
#endif
#endif
#ifdef VARIABLE_SPINDLE
// Set real-time spindle output as segment is loaded, just prior to the first step.
spindle_set_speed(st.exec_segment->spindle_pwm);
#endif
spindle->set_rpm(st.exec_segment->spindle_rpm);
} else {
// Segment buffer empty. Shutdown.
st_go_idle();
#if ( (defined VARIABLE_SPINDLE) && (defined SPINDLE_PWM_PIN) )
if (!(sys.state & STATE_JOG)) { // added to prevent ... jog after probing crash
// 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) {
spindle->set_rpm(0);
}
}
#endif
system_set_exec_state_flag(EXEC_CYCLE_STOP); // Flag main program for cycle end
return; // Nothing to do but exit.
}
@@ -688,37 +681,37 @@ void set_direction_pins_on(uint8_t onMask) {
#ifdef X_DIRECTION_PIN
digitalWrite(X_DIRECTION_PIN, (onMask & (1 << X_AXIS)));
#endif
#ifdef X2_DIRECTION_PIN // optional ganged axis
#ifdef X2_DIRECTION_PIN // optional ganged axis
digitalWrite(X2_DIRECTION_PIN, (onMask & (1 << X_AXIS)));
#endif
#ifdef Y_DIRECTION_PIN
digitalWrite(Y_DIRECTION_PIN, (onMask & (1 << Y_AXIS)));
#endif
#ifdef Y2_DIRECTION_PIN // optional ganged axis
#ifdef Y2_DIRECTION_PIN // optional ganged axis
digitalWrite(Y2_DIRECTION_PIN, (onMask & (1 << Y_AXIS)));
#endif
#ifdef Z_DIRECTION_PIN
digitalWrite(Z_DIRECTION_PIN, (onMask & (1 << Z_AXIS)));
#endif
#ifdef Z2_DIRECTION_PIN // optional ganged axis
#ifdef Z2_DIRECTION_PIN // optional ganged axis
digitalWrite(Z2_DIRECTION_PIN, (onMask & (1 << Z_AXIS)));
#endif
#ifdef A_DIRECTION_PIN
digitalWrite(A_DIRECTION_PIN, (onMask & (1 << A_AXIS)));
#endif
#ifdef A2_DIRECTION_PIN // optional ganged axis
#ifdef A2_DIRECTION_PIN // optional ganged axis
digitalWrite(A2_DIRECTION_PIN, (onMask & (1 << A_AXIS)));
#endif
#ifdef B_DIRECTION_PIN
digitalWrite(B_DIRECTION_PIN, (onMask & (1 << B_AXIS)));
#endif
#ifdef B2_DIRECTION_PIN // optional ganged axis
#ifdef B2_DIRECTION_PIN // optional ganged axis
digitalWrite(B2_DIRECTION_PIN, (onMask & (1 << B_AXIS)));
#endif
#ifdef C_DIRECTION_PIN
digitalWrite(C_DIRECTION_PIN, (onMask & (1 << C_AXIS)));
#endif
#ifdef C2_DIRECTION_PIN // optional ganged axis
#ifdef C2_DIRECTION_PIN // optional ganged axis
digitalWrite(C2_DIRECTION_PIN, (onMask & (1 << C_AXIS)));
#endif
}
@@ -1010,18 +1003,16 @@ void st_prep_buffer() {
prep.recalculate_flag &= ~(PREP_FLAG_DECEL_OVERRIDE);
} else
prep.current_speed = sqrt(pl_block->entry_speed_sqr);
#ifdef VARIABLE_SPINDLE
// Setup laser mode variables. PWM rate adjusted motions will always complete a motion with the
// spindle off.
st_prep_block->is_pwm_rate_adjusted = false;
if (settings.flags & BITFLAG_LASER_MODE) {
if (spindle->isRateAdjusted() ){ // settings.flags & BITFLAG_LASER_MODE) {
if (pl_block->condition & PL_COND_FLAG_SPINDLE_CCW) {
// Pre-compute inverse programmed rate to speed up PWM updating per step segment.
prep.inv_rate = 1.0 / pl_block->programmed_rate;
st_prep_block->is_pwm_rate_adjusted = true;
}
}
#endif
}
/* ---------------------------------------------------------------------------------
Compute the velocity profile of a new planner block based on its entry and exit
@@ -1107,9 +1098,9 @@ void st_prep_buffer() {
prep.maximum_speed = prep.exit_speed;
}
}
#ifdef VARIABLE_SPINDLE
bit_true(sys.step_control, STEP_CONTROL_UPDATE_SPINDLE_PWM); // Force update whenever updating block.
#endif
bit_true(sys.step_control, STEP_CONTROL_UPDATE_SPINDLE_RPM); // Force update whenever updating block.
}
// Initialize new segment
segment_t* prep_segment = &segment_buffer[segment_buffer_head];
@@ -1213,29 +1204,32 @@ void st_prep_buffer() {
}
}
} while (mm_remaining > prep.mm_complete); // **Complete** Exit loop. Profile complete.
#ifdef VARIABLE_SPINDLE
/* -----------------------------------------------------------------------------------
Compute spindle speed PWM output for step segment
*/
if (st_prep_block->is_pwm_rate_adjusted || (sys.step_control & STEP_CONTROL_UPDATE_SPINDLE_PWM)) {
if (st_prep_block->is_pwm_rate_adjusted || (sys.step_control & STEP_CONTROL_UPDATE_SPINDLE_RPM)) {
if (pl_block->condition & (PL_COND_FLAG_SPINDLE_CW | PL_COND_FLAG_SPINDLE_CCW)) {
float rpm = pl_block->spindle_speed;
// 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)
if (st_prep_block->is_pwm_rate_adjusted) {
rpm *= (prep.current_speed * prep.inv_rate);
//grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "RPM %.2f", rpm);
//grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Rates CV %.2f IV %.2f RPM %.2f", prep.current_speed, prep.inv_rate, rpm);
}
// 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.
prep.current_spindle_pwm = spindle_compute_pwm_value(rpm);
prep.current_spindle_rpm = rpm;
} else {
sys.spindle_speed = 0.0;
#if ( (defined VARIABLE_SPINDLE) && (defined SPINDLE_PWM_PIN) )
prep.current_spindle_pwm = spindle_pwm_off_value ;
#endif
prep.current_spindle_rpm = 0.0;
}
bit_false(sys.step_control, STEP_CONTROL_UPDATE_SPINDLE_PWM);
bit_false(sys.step_control, STEP_CONTROL_UPDATE_SPINDLE_RPM);
}
prep_segment->spindle_pwm = prep.current_spindle_pwm; // Reload segment PWM value
#endif
prep_segment->spindle_rpm = prep.current_spindle_rpm; // Reload segment PWM value
/* -----------------------------------------------------------------------------------
Compute segment step rate, steps to execute, and apply necessary rate corrections.
NOTE: Steps are computed by direct scalar conversion of the millimeter distance
@@ -1404,4 +1398,4 @@ bool get_stepper_disable() { // returns true if steppers are disabled
disabled = !disabled; // Apply pin invert.
}
return disabled;
}
}