mirror of
https://github.com/bdring/Grbl_Esp32.git
synced 2025-01-17 14:18:16 +01:00
Added M62 & M63 (Digital I/O control)
This commit is contained in:
parent
16dd8b3541
commit
515ce82672
@ -85,7 +85,7 @@
|
|||||||
#define X_DIRECTION_PIN GPIO_NUM_14
|
#define X_DIRECTION_PIN GPIO_NUM_14
|
||||||
#define Y_STEP_PIN GPIO_NUM_26
|
#define Y_STEP_PIN GPIO_NUM_26
|
||||||
#define Y_DIRECTION_PIN GPIO_NUM_15
|
#define Y_DIRECTION_PIN GPIO_NUM_15
|
||||||
#define COOLANT_FLOOD_PIN GPIO_NUM_25
|
//#define COOLANT_FLOOD_PIN GPIO_NUM_25
|
||||||
#define SPINDLE_PWM_PIN GPIO_NUM_2
|
#define SPINDLE_PWM_PIN GPIO_NUM_2
|
||||||
#define X_LIMIT_PIN GPIO_NUM_17
|
#define X_LIMIT_PIN GPIO_NUM_17
|
||||||
#define Z_LIMIT_PIN GPIO_NUM_16
|
#define Z_LIMIT_PIN GPIO_NUM_16
|
||||||
@ -94,7 +94,7 @@
|
|||||||
#define X_DIRECTION_PIN GPIO_NUM_26
|
#define X_DIRECTION_PIN GPIO_NUM_26
|
||||||
#define Y_STEP_PIN GPIO_NUM_14
|
#define Y_STEP_PIN GPIO_NUM_14
|
||||||
#define Y_DIRECTION_PIN GPIO_NUM_25
|
#define Y_DIRECTION_PIN GPIO_NUM_25
|
||||||
#define COOLANT_FLOOD_PIN GPIO_NUM_16
|
//#define COOLANT_FLOOD_PIN GPIO_NUM_16
|
||||||
#define SPINDLE_PWM_PIN GPIO_NUM_17
|
#define SPINDLE_PWM_PIN GPIO_NUM_17
|
||||||
#define X_LIMIT_PIN GPIO_NUM_2
|
#define X_LIMIT_PIN GPIO_NUM_2
|
||||||
#define Z_LIMIT_PIN GPIO_NUM_15
|
#define Z_LIMIT_PIN GPIO_NUM_15
|
||||||
@ -114,8 +114,9 @@
|
|||||||
// 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
|
||||||
|
|
||||||
#define COOLANT_MIST_PIN GPIO_NUM_21
|
//#define COOLANT_MIST_PIN GPIO_NUM_21
|
||||||
|
#define USER_DIGITAL_PIN_1 GPIO_NUM_21
|
||||||
|
#define USER_DIGITAL_PIN_2 GPIO_NUM_25
|
||||||
|
|
||||||
|
|
||||||
#define SPINDLE_PWM_CHANNEL 0
|
#define SPINDLE_PWM_CHANNEL 0
|
||||||
|
@ -368,7 +368,23 @@ uint8_t gc_execute_line(char *line, uint8_t client)
|
|||||||
FAIL(STATUS_GCODE_UNSUPPORTED_COMMAND); // [Unsupported M command]
|
FAIL(STATUS_GCODE_UNSUPPORTED_COMMAND); // [Unsupported M command]
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
default:
|
case 62:
|
||||||
|
case 63:
|
||||||
|
//grbl_sendf(CLIENT_SERIAL,"M%d...\r\n", int_value);
|
||||||
|
word_bit = MODAL_GROUP_M10;
|
||||||
|
switch (int_value) {
|
||||||
|
case 62:
|
||||||
|
gc_block.modal.io_control = NON_MODAL_IO_ENABLE;
|
||||||
|
break;
|
||||||
|
case 63:
|
||||||
|
gc_block.modal.io_control = NON_MODAL_IO_DISABLE;
|
||||||
|
break;
|
||||||
|
default:
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
|
break;
|
||||||
|
default:
|
||||||
FAIL(STATUS_GCODE_UNSUPPORTED_COMMAND); // [Unsupported M command]
|
FAIL(STATUS_GCODE_UNSUPPORTED_COMMAND); // [Unsupported M command]
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -618,6 +634,13 @@ uint8_t gc_execute_line(char *line, uint8_t client)
|
|||||||
}
|
}
|
||||||
bit_false(value_words,bit(WORD_P));
|
bit_false(value_words,bit(WORD_P));
|
||||||
}
|
}
|
||||||
|
|
||||||
|
if ( (gc_block.modal.io_control == NON_MODAL_IO_ENABLE) || (gc_block.modal.io_control == NON_MODAL_IO_DISABLE)) {
|
||||||
|
if (bit_isfalse(value_words,bit(WORD_P))) {
|
||||||
|
FAIL(STATUS_GCODE_VALUE_WORD_MISSING); // [P word missing]
|
||||||
|
}
|
||||||
|
bit_false(value_words,bit(WORD_P));
|
||||||
|
}
|
||||||
|
|
||||||
// [11. Set active plane ]: N/A
|
// [11. Set active plane ]: N/A
|
||||||
switch (gc_block.modal.plane_select) {
|
switch (gc_block.modal.plane_select) {
|
||||||
@ -1216,6 +1239,16 @@ uint8_t gc_execute_line(char *line, uint8_t client)
|
|||||||
}
|
}
|
||||||
pl_data->condition |= gc_state.modal.coolant; // Set condition flag for planner use.
|
pl_data->condition |= gc_state.modal.coolant; // Set condition flag for planner use.
|
||||||
|
|
||||||
|
// turn on/off an i/o pin
|
||||||
|
if ( (gc_block.modal.io_control == NON_MODAL_IO_ENABLE) || (gc_block.modal.io_control == NON_MODAL_IO_DISABLE) ) {
|
||||||
|
if (gc_block.values.p <= MAX_USER_DIGITAL_PIN) {
|
||||||
|
sys_io_control(1<<(int)gc_block.values.p, (gc_block.modal.io_control == NON_MODAL_IO_ENABLE));
|
||||||
|
}
|
||||||
|
else {
|
||||||
|
FAIL(STATUS_P_PARAM_MAX_EXCEEDED);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
// [9. Enable/disable feed rate or spindle overrides ]: NOT SUPPORTED. Always enabled.
|
// [9. Enable/disable feed rate or spindle overrides ]: NOT SUPPORTED. Always enabled.
|
||||||
|
|
||||||
// [10. Dwell ]:
|
// [10. Dwell ]:
|
||||||
|
@ -46,6 +46,7 @@
|
|||||||
#define MODAL_GROUP_M4 11 // [M0,M1,M2,M30] Stopping
|
#define MODAL_GROUP_M4 11 // [M0,M1,M2,M30] Stopping
|
||||||
#define MODAL_GROUP_M7 12 // [M3,M4,M5] Spindle turning
|
#define MODAL_GROUP_M7 12 // [M3,M4,M5] Spindle turning
|
||||||
#define MODAL_GROUP_M8 13 // [M7,M8,M9] Coolant control
|
#define MODAL_GROUP_M8 13 // [M7,M8,M9] Coolant control
|
||||||
|
#define MODAL_GROUP_M10 14 // [M62, M63] User Defined http://linuxcnc.org/docs/html/gcode/overview.html#_modal_groups
|
||||||
|
|
||||||
// #define OTHER_INPUT_F 14
|
// #define OTHER_INPUT_F 14
|
||||||
// #define OTHER_INPUT_S 15
|
// #define OTHER_INPUT_S 15
|
||||||
@ -124,10 +125,17 @@
|
|||||||
#define COOLANT_FLOOD_ENABLE PL_COND_FLAG_COOLANT_FLOOD // M8 (NOTE: Uses planner condition bit flag)
|
#define COOLANT_FLOOD_ENABLE PL_COND_FLAG_COOLANT_FLOOD // M8 (NOTE: Uses planner condition bit flag)
|
||||||
#define COOLANT_MIST_ENABLE PL_COND_FLAG_COOLANT_MIST // M7 (NOTE: Uses planner condition bit flag)
|
#define COOLANT_MIST_ENABLE PL_COND_FLAG_COOLANT_MIST // M7 (NOTE: Uses planner condition bit flag)
|
||||||
|
|
||||||
|
// modal Group M10: User I/O control
|
||||||
|
#define NON_MODAL_IO_ENABLE 1
|
||||||
|
#define NON_MODAL_IO_DISABLE 2
|
||||||
|
#define MAX_USER_DIGITAL_PIN 4
|
||||||
|
|
||||||
// Modal Group G8: Tool length offset
|
// Modal Group G8: Tool length offset
|
||||||
#define TOOL_LENGTH_OFFSET_CANCEL 0 // G49 (Default: Must be zero)
|
#define TOOL_LENGTH_OFFSET_CANCEL 0 // G49 (Default: Must be zero)
|
||||||
#define TOOL_LENGTH_OFFSET_ENABLE_DYNAMIC 1 // G43.1
|
#define TOOL_LENGTH_OFFSET_ENABLE_DYNAMIC 1 // G43.1
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
// Modal Group G12: Active work coordinate system
|
// Modal Group G12: Active work coordinate system
|
||||||
// N/A: Stores coordinate system value (54-59) to change to.
|
// N/A: Stores coordinate system value (54-59) to change to.
|
||||||
|
|
||||||
@ -192,6 +200,7 @@ typedef struct {
|
|||||||
uint8_t program_flow; // {M0,M1,M2,M30}
|
uint8_t program_flow; // {M0,M1,M2,M30}
|
||||||
uint8_t coolant; // {M7,M8,M9}
|
uint8_t coolant; // {M7,M8,M9}
|
||||||
uint8_t spindle; // {M3,M4,M5}
|
uint8_t spindle; // {M3,M4,M5}
|
||||||
|
uint8_t io_control; // {M62, M63}
|
||||||
} gc_modal_t;
|
} gc_modal_t;
|
||||||
|
|
||||||
typedef struct {
|
typedef struct {
|
||||||
|
@ -20,7 +20,7 @@
|
|||||||
|
|
||||||
// Grbl versioning system
|
// Grbl versioning system
|
||||||
#define GRBL_VERSION "1.1f"
|
#define GRBL_VERSION "1.1f"
|
||||||
#define GRBL_VERSION_BUILD "20191011"
|
#define GRBL_VERSION_BUILD "20191015"
|
||||||
|
|
||||||
//#include <sdkconfig.h>
|
//#include <sdkconfig.h>
|
||||||
#include <Arduino.h>
|
#include <Arduino.h>
|
||||||
|
@ -418,7 +418,9 @@ void mc_reset()
|
|||||||
|
|
||||||
// Kill spindle and coolant.
|
// Kill spindle and coolant.
|
||||||
spindle_stop();
|
spindle_stop();
|
||||||
coolant_stop();
|
coolant_stop();
|
||||||
|
// turn off all digital I/O
|
||||||
|
sys_io_control(0xFF, false);
|
||||||
|
|
||||||
#ifdef ENABLE_SD_CARD
|
#ifdef ENABLE_SD_CARD
|
||||||
// do we need to stop a running SD job?
|
// do we need to stop a running SD job?
|
||||||
|
@ -62,6 +62,7 @@
|
|||||||
#define STATUS_GCODE_UNUSED_WORDS 36
|
#define STATUS_GCODE_UNUSED_WORDS 36
|
||||||
#define STATUS_GCODE_G43_DYNAMIC_AXIS_ERROR 37
|
#define STATUS_GCODE_G43_DYNAMIC_AXIS_ERROR 37
|
||||||
#define STATUS_GCODE_MAX_VALUE_EXCEEDED 38
|
#define STATUS_GCODE_MAX_VALUE_EXCEEDED 38
|
||||||
|
#define STATUS_P_PARAM_MAX_EXCEEDED 39
|
||||||
|
|
||||||
#define STATUS_SD_FAILED_MOUNT 60 // SD Failed to mount
|
#define STATUS_SD_FAILED_MOUNT 60 // SD Failed to mount
|
||||||
#define STATUS_SD_FAILED_READ 61 // SD Failed to read file
|
#define STATUS_SD_FAILED_READ 61 // SD Failed to read file
|
||||||
|
@ -26,62 +26,82 @@ xQueueHandle control_sw_queue; // used by control switch debouncing
|
|||||||
void system_ini() // Renamed from system_init() due to conflict with esp32 files
|
void system_ini() // Renamed from system_init() due to conflict with esp32 files
|
||||||
{
|
{
|
||||||
// setup control inputs
|
// setup control inputs
|
||||||
#ifndef IGNORE_CONTROL_PINS
|
#ifndef IGNORE_CONTROL_PINS
|
||||||
|
|
||||||
#ifdef CONTROL_SAFETY_DOOR_PIN
|
|
||||||
pinMode(CONTROL_SAFETY_DOOR_PIN, INPUT);
|
|
||||||
attachInterrupt(digitalPinToInterrupt(CONTROL_SAFETY_DOOR_PIN), isr_control_inputs, CHANGE);
|
|
||||||
#endif
|
|
||||||
#ifdef CONTROL_RESET_PIN
|
|
||||||
pinMode(CONTROL_RESET_PIN, INPUT);
|
|
||||||
attachInterrupt(digitalPinToInterrupt(CONTROL_RESET_PIN), isr_control_inputs, CHANGE);
|
|
||||||
#endif
|
|
||||||
#ifdef CONTROL_FEED_HOLD_PIN
|
|
||||||
pinMode(CONTROL_FEED_HOLD_PIN, INPUT);
|
|
||||||
attachInterrupt(digitalPinToInterrupt(CONTROL_FEED_HOLD_PIN), isr_control_inputs, CHANGE);
|
|
||||||
#endif
|
|
||||||
#ifdef CONTROL_CYCLE_START_PIN
|
|
||||||
pinMode(CONTROL_CYCLE_START_PIN, INPUT);
|
|
||||||
attachInterrupt(digitalPinToInterrupt(CONTROL_CYCLE_START_PIN), isr_control_inputs, CHANGE);
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef MACRO_BUTTON_0_PIN
|
|
||||||
pinMode(MACRO_BUTTON_0_PIN, INPUT_PULLUP);
|
|
||||||
attachInterrupt(digitalPinToInterrupt(MACRO_BUTTON_0_PIN), isr_control_inputs, CHANGE);
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef MACRO_BUTTON_1_PIN
|
|
||||||
pinMode(MACRO_BUTTON_1_PIN, INPUT_PULLUP);
|
|
||||||
attachInterrupt(digitalPinToInterrupt(MACRO_BUTTON_1_PIN), isr_control_inputs, CHANGE);
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef MACRO_BUTTON_2_PIN
|
|
||||||
pinMode(MACRO_BUTTON_2_PIN, INPUT_PULLUP);
|
|
||||||
attachInterrupt(digitalPinToInterrupt(MACRO_BUTTON_2_PIN), isr_control_inputs, CHANGE);
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef MACRO_BUTTON_3_PIN
|
|
||||||
pinMode(MACRO_BUTTON_3_PIN, INPUT_PULLUP);
|
|
||||||
attachInterrupt(digitalPinToInterrupt(MACRO_BUTTON_3_PIN), isr_control_inputs, CHANGE);
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef ENABLE_CONTROL_SW_DEBOUNCE
|
|
||||||
// setup task used for debouncing
|
|
||||||
control_sw_queue = xQueueCreate(10, sizeof( int ));
|
|
||||||
|
|
||||||
xTaskCreate(controlCheckTask,
|
#ifdef CONTROL_SAFETY_DOOR_PIN
|
||||||
"controlCheckTask",
|
pinMode(CONTROL_SAFETY_DOOR_PIN, INPUT);
|
||||||
2048,
|
attachInterrupt(digitalPinToInterrupt(CONTROL_SAFETY_DOOR_PIN), isr_control_inputs, CHANGE);
|
||||||
NULL,
|
#endif
|
||||||
5, // priority
|
#ifdef CONTROL_RESET_PIN
|
||||||
NULL);
|
pinMode(CONTROL_RESET_PIN, INPUT);
|
||||||
|
attachInterrupt(digitalPinToInterrupt(CONTROL_RESET_PIN), isr_control_inputs, CHANGE);
|
||||||
|
#endif
|
||||||
|
#ifdef CONTROL_FEED_HOLD_PIN
|
||||||
|
pinMode(CONTROL_FEED_HOLD_PIN, INPUT);
|
||||||
|
attachInterrupt(digitalPinToInterrupt(CONTROL_FEED_HOLD_PIN), isr_control_inputs, CHANGE);
|
||||||
|
#endif
|
||||||
|
#ifdef CONTROL_CYCLE_START_PIN
|
||||||
|
pinMode(CONTROL_CYCLE_START_PIN, INPUT);
|
||||||
|
attachInterrupt(digitalPinToInterrupt(CONTROL_CYCLE_START_PIN), isr_control_inputs, CHANGE);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef MACRO_BUTTON_0_PIN
|
||||||
|
pinMode(MACRO_BUTTON_0_PIN, INPUT_PULLUP);
|
||||||
|
attachInterrupt(digitalPinToInterrupt(MACRO_BUTTON_0_PIN), isr_control_inputs, CHANGE);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef MACRO_BUTTON_1_PIN
|
||||||
|
pinMode(MACRO_BUTTON_1_PIN, INPUT_PULLUP);
|
||||||
|
attachInterrupt(digitalPinToInterrupt(MACRO_BUTTON_1_PIN), isr_control_inputs, CHANGE);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef MACRO_BUTTON_2_PIN
|
||||||
|
pinMode(MACRO_BUTTON_2_PIN, INPUT_PULLUP);
|
||||||
|
attachInterrupt(digitalPinToInterrupt(MACRO_BUTTON_2_PIN), isr_control_inputs, CHANGE);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef MACRO_BUTTON_3_PIN
|
||||||
|
pinMode(MACRO_BUTTON_3_PIN, INPUT_PULLUP);
|
||||||
|
attachInterrupt(digitalPinToInterrupt(MACRO_BUTTON_3_PIN), isr_control_inputs, CHANGE);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef ENABLE_CONTROL_SW_DEBOUNCE
|
||||||
|
// setup task used for debouncing
|
||||||
|
control_sw_queue = xQueueCreate(10, sizeof( int ));
|
||||||
|
|
||||||
|
xTaskCreate(controlCheckTask,
|
||||||
|
"controlCheckTask",
|
||||||
|
2048,
|
||||||
|
NULL,
|
||||||
|
5, // priority
|
||||||
|
NULL);
|
||||||
|
#endif
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#endif
|
//customize pin definition if needed
|
||||||
//customize pin definition if needed
|
#if (GRBL_SPI_SS != -1) || (GRBL_SPI_MISO != -1) || (GRBL_SPI_MOSI != -1) || (GRBL_SPI_SCK != -1)
|
||||||
#if (GRBL_SPI_SS != -1) || (GRBL_SPI_MISO != -1) || (GRBL_SPI_MOSI != -1) || (GRBL_SPI_SCK != -1)
|
SPI.begin(GRBL_SPI_SCK, GRBL_SPI_MISO, GRBL_SPI_MOSI, GRBL_SPI_SS);
|
||||||
SPI.begin(GRBL_SPI_SCK, GRBL_SPI_MISO, GRBL_SPI_MOSI, GRBL_SPI_SS);
|
#endif
|
||||||
#endif
|
|
||||||
|
// Setup USER_DIGITAL_PINs controlled by M62 and M63
|
||||||
|
#ifdef USER_DIGITAL_PIN_1
|
||||||
|
pinMode(USER_DIGITAL_PIN_1, OUTPUT);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef USER_DIGITAL_PIN_2
|
||||||
|
pinMode(USER_DIGITAL_PIN_2, OUTPUT);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef USER_DIGITAL_PIN_3
|
||||||
|
pinMode(USER_DIGITAL_PIN_3, OUTPUT);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef USER_DIGITAL_PIN_4
|
||||||
|
pinMode(USER_DIGITAL_PIN_4, OUTPUT);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
sys_io_control(0xFF, false); // turn them all off
|
||||||
}
|
}
|
||||||
|
|
||||||
#ifdef ENABLE_CONTROL_SW_DEBOUNCE
|
#ifdef ENABLE_CONTROL_SW_DEBOUNCE
|
||||||
@ -518,7 +538,7 @@ void system_exec_control_pin(uint8_t pin) {
|
|||||||
bit_true(sys_rt_exec_state, EXEC_FEED_HOLD);
|
bit_true(sys_rt_exec_state, EXEC_FEED_HOLD);
|
||||||
}
|
}
|
||||||
else if (bit_istrue(pin,CONTROL_PIN_INDEX_SAFETY_DOOR)) {
|
else if (bit_istrue(pin,CONTROL_PIN_INDEX_SAFETY_DOOR)) {
|
||||||
bit_true(sys_rt_exec_state, EXEC_SAFETY_DOOR);
|
bit_true(sys_rt_exec_state, EXEC_SAFETY_DOOR);
|
||||||
}
|
}
|
||||||
#ifdef MACRO_BUTTON_0_PIN
|
#ifdef MACRO_BUTTON_0_PIN
|
||||||
else if (pin == 96) {
|
else if (pin == 96) {
|
||||||
@ -552,4 +572,33 @@ int32_t system_convert_corexy_to_y_axis_steps(int32_t *steps)
|
|||||||
return( (steps[A_MOTOR] - steps[B_MOTOR])/2 );
|
return( (steps[A_MOTOR] - steps[B_MOTOR])/2 );
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// io_num is the virtual pin# and has nothing to do with the actual esp32 GPIO_NUM_xx
|
||||||
|
// It uses a mask so all can be turned of in ms_reset
|
||||||
|
void sys_io_control(uint8_t io_num_mask, bool turnOn) {
|
||||||
|
protocol_buffer_synchronize();
|
||||||
|
#ifdef USER_DIGITAL_PIN_1
|
||||||
|
if (io_num_mask & 1<<1) {
|
||||||
|
digitalWrite(USER_DIGITAL_PIN_1, turnOn);
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
#ifdef USER_DIGITAL_PIN_2
|
||||||
|
if (io_num_mask & 1<<2) {
|
||||||
|
digitalWrite(USER_DIGITAL_PIN_2, turnOn);
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
#ifdef USER_DIGITAL_PIN_3
|
||||||
|
if (io_num_mask & 1<<3) {
|
||||||
|
digitalWrite(USER_DIGITAL_PIN_3, turnOn);
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
#ifdef USER_DIGITAL_PIN_4
|
||||||
|
if (io_num_mask & 1<<4) {
|
||||||
|
digitalWrite(USER_DIGITAL_PIN_4, turnOn);
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
grbl_sendf(CLIENT_SERIAL, "[MSG:Undefined IO pin...%d]\r\n", io_num_mask);
|
||||||
|
}
|
@ -225,5 +225,7 @@ int32_t system_convert_corexy_to_y_axis_steps(int32_t *steps);
|
|||||||
void controlCheckTask(void *pvParameters);
|
void controlCheckTask(void *pvParameters);
|
||||||
void system_exec_control_pin(uint8_t pin);
|
void system_exec_control_pin(uint8_t pin);
|
||||||
|
|
||||||
|
void sys_io_control(uint8_t io_num_mask, bool turnOn);
|
||||||
|
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
@ -35,6 +35,7 @@
|
|||||||
"36","Invalid gcode ID:36","Unused value words found in block."
|
"36","Invalid gcode ID:36","Unused value words found in block."
|
||||||
"37","Invalid gcode ID:37","G43.1 dynamic tool length offset is not assigned to configured tool length axis."
|
"37","Invalid gcode ID:37","G43.1 dynamic tool length offset is not assigned to configured tool length axis."
|
||||||
"38","Invalid gcode ID:38","Tool number greater than max supported value."
|
"38","Invalid gcode ID:38","Tool number greater than max supported value."
|
||||||
|
"39","Parameter P exceeded max ID:39","Parameter P exceeded max"
|
||||||
"60","SD failed to mount"
|
"60","SD failed to mount"
|
||||||
"61","SD card failed to open file for reading"
|
"61","SD card failed to open file for reading"
|
||||||
"62","SD card failed to open directory"
|
"62","SD card failed to open directory"
|
||||||
|
Can't render this file because it has a wrong number of fields in line 39.
|
BIN
doc/script/piecewise_example.png
Normal file
BIN
doc/script/piecewise_example.png
Normal file
Binary file not shown.
After Width: | Height: | Size: 38 KiB |
Loading…
x
Reference in New Issue
Block a user