mirror of
https://github.com/bdring/Grbl_Esp32.git
synced 2025-09-03 11:22:38 +02:00
Replaced #defines with enums in GCode.h (#572)
* Replaced #defines with enums in GCode.h * More #defines bit the dust * Resolved review comments * Some fixes * Added parser test * Fixed braces in GCode.cpp * Clang format * Revised delay value in tests/parser.nc
This commit is contained in:
@@ -105,7 +105,7 @@ void inverse_kinematics(float* target, plan_line_data_t* pl_data, float* positio
|
||||
// calculate the total X,Y axis move distance
|
||||
// Z axis is the same in both coord systems, so it is ignored
|
||||
dist = sqrt((dx * dx) + (dy * dy) + (dz * dz));
|
||||
if (pl_data->condition & PL_COND_FLAG_RAPID_MOTION) {
|
||||
if (pl_data->motion & PL_MOTION_RAPID_MOTION) {
|
||||
segment_count = 1; // rapid G0 motion is not used to draw, so skip the segmentation
|
||||
} else {
|
||||
segment_count = ceil(dist / SEGMENT_LENGTH); // determine the number of segments we need ... round up so there is at least 1
|
||||
|
@@ -233,7 +233,7 @@ Some features should not be changed. See notes below.
|
||||
// Number of homing cycles performed after when the machine initially jogs to limit switches.
|
||||
// This help in preventing overshoot and should improve repeatability. This value should be one or
|
||||
// greater.
|
||||
#define N_HOMING_LOCATE_CYCLE 1 // Integer (1-128)
|
||||
static const uint8_t NHomingLocateCycle = 1; // Integer (1-128)
|
||||
|
||||
// Enables single axis homing commands. $HX, $HY, and $HZ for X, Y, and Z-axis homing. The full homing
|
||||
// cycle is still invoked by the $H command. This is disabled by default. It's here only to address
|
||||
|
@@ -34,15 +34,15 @@ void coolant_init() {
|
||||
}
|
||||
|
||||
// Returns current coolant output state. Overrides may alter it from programmed state.
|
||||
uint8_t coolant_get_state() {
|
||||
uint8_t cl_state = COOLANT_STATE_DISABLE;
|
||||
CoolantMode coolant_get_state() {
|
||||
CoolantMode cl_state = CoolantMode::Disable;
|
||||
#ifdef COOLANT_FLOOD_PIN
|
||||
# ifdef INVERT_COOLANT_FLOOD_PIN
|
||||
if (!digitalRead(COOLANT_FLOOD_PIN)) {
|
||||
# else
|
||||
if (digitalRead(COOLANT_FLOOD_PIN)) {
|
||||
# endif
|
||||
cl_state |= COOLANT_STATE_FLOOD;
|
||||
cl_state |= CoolantMode::Flood;
|
||||
}
|
||||
#endif
|
||||
#ifdef COOLANT_MIST_PIN
|
||||
@@ -51,7 +51,7 @@ uint8_t coolant_get_state() {
|
||||
# else
|
||||
if (digitalRead(COOLANT_MIST_PIN)) {
|
||||
# endif
|
||||
cl_state |= COOLANT_STATE_MIST;
|
||||
cl_state |= CoolantMode::Mist;
|
||||
}
|
||||
#endif
|
||||
return (cl_state);
|
||||
@@ -80,14 +80,14 @@ void coolant_stop() {
|
||||
// if enabled. Also sets a flag to report an update to a coolant state.
|
||||
// Called by coolant toggle override, parking restore, parking retract, sleep mode, g-code
|
||||
// parser program end, and g-code parser coolant_sync().
|
||||
void coolant_set_state(uint8_t mode) {
|
||||
void coolant_set_state(CoolantMode mode) {
|
||||
if (sys.abort)
|
||||
return; // Block during abort.
|
||||
if (mode == COOLANT_DISABLE)
|
||||
if (mode == CoolantMode::Disable)
|
||||
coolant_stop();
|
||||
else {
|
||||
#ifdef COOLANT_FLOOD_PIN
|
||||
if (mode & COOLANT_FLOOD_ENABLE) {
|
||||
if (mode & CoolantMode::Enable) {
|
||||
# ifdef INVERT_COOLANT_FLOOD_PIN
|
||||
digitalWrite(COOLANT_FLOOD_PIN, 0);
|
||||
# else
|
||||
@@ -96,7 +96,7 @@ void coolant_set_state(uint8_t mode) {
|
||||
}
|
||||
#endif
|
||||
#ifdef COOLANT_MIST_PIN
|
||||
if (mode & COOLANT_MIST_ENABLE) {
|
||||
if (mode & CoolantMode::Mist) {
|
||||
# ifdef INVERT_COOLANT_MIST_PIN
|
||||
digitalWrite(COOLANT_MIST_PIN, 0);
|
||||
# else
|
||||
@@ -110,7 +110,7 @@ void coolant_set_state(uint8_t mode) {
|
||||
|
||||
// G-code parser entry-point for setting coolant state. Forces a planner buffer sync and bails
|
||||
// if an abort or check-mode is active.
|
||||
void coolant_sync(uint8_t mode) {
|
||||
void coolant_sync(CoolantMode mode) {
|
||||
if (sys.state == STATE_CHECK_MODE)
|
||||
return;
|
||||
protocol_buffer_synchronize(); // Ensure coolant turns on when specified in program.
|
||||
|
@@ -23,24 +23,17 @@
|
||||
along with Grbl. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#define COOLANT_NO_SYNC false
|
||||
#define COOLANT_FORCE_SYNC true
|
||||
|
||||
#define COOLANT_STATE_DISABLE 0 // Must be zero
|
||||
#define COOLANT_STATE_FLOOD bit(0)
|
||||
#define COOLANT_STATE_MIST bit(1)
|
||||
|
||||
// Initializes coolant control pins.
|
||||
void coolant_init();
|
||||
|
||||
// Returns current coolant output state. Overrides may alter it from programmed state.
|
||||
uint8_t coolant_get_state();
|
||||
CoolantMode coolant_get_state();
|
||||
|
||||
// Immediately disables coolant pins.
|
||||
void coolant_stop();
|
||||
|
||||
// Sets the coolant pins according to state specified.
|
||||
void coolant_set_state(uint8_t mode);
|
||||
void coolant_set_state(CoolantMode mode);
|
||||
|
||||
// G-code parser entry-point for setting coolant states. Checks for and executes additional conditions.
|
||||
void coolant_sync(uint8_t mode);
|
||||
void coolant_sync(CoolantMode mode);
|
||||
|
File diff suppressed because it is too large
Load Diff
@@ -30,28 +30,26 @@
|
||||
// a unique motion. These are defined in the NIST RS274-NGC v3 g-code standard, available online,
|
||||
// and are similar/identical to other g-code interpreters by manufacturers (Haas,Fanuc,Mazak,etc).
|
||||
// NOTE: Modal group define values must be sequential and starting from zero.
|
||||
#define MODAL_GROUP_G0 0 // [G4,G10,G28,G28.1,G30,G30.1,G53,G92,G92.1] Non-modal
|
||||
#define MODAL_GROUP_G1 1 // [G0,G1,G2,G3,G38.2,G38.3,G38.4,G38.5,G80] Motion
|
||||
#define MODAL_GROUP_G2 2 // [G17,G18,G19] Plane selection
|
||||
#define MODAL_GROUP_G3 3 // [G90,G91] Distance mode
|
||||
#define MODAL_GROUP_G4 4 // [G91.1] Arc IJK distance mode
|
||||
#define MODAL_GROUP_G5 5 // [G93,G94] Feed rate mode
|
||||
#define MODAL_GROUP_G6 6 // [G20,G21] Units
|
||||
#define MODAL_GROUP_G7 7 // [G40] Cutter radius compensation mode. G41/42 NOT SUPPORTED.
|
||||
#define MODAL_GROUP_G8 8 // [G43.1,G49] Tool length offset
|
||||
#define MODAL_GROUP_G12 9 // [G54,G55,G56,G57,G58,G59] Coordinate system selection
|
||||
#define MODAL_GROUP_G13 10 // [G61] Control mode
|
||||
|
||||
#define MODAL_GROUP_M4 11 // [M0,M1,M2,M30] Stopping
|
||||
#define MODAL_GROUP_M6 14 // [M6] Tool change
|
||||
#define MODAL_GROUP_M7 12 // [M3,M4,M5] Spindle turning
|
||||
#define MODAL_GROUP_M8 13 // [M7,M8,M9] Coolant control
|
||||
#define MODAL_GROUP_M9 14 // [M56] Override control
|
||||
#define MODAL_GROUP_M10 15 // [M62, M63] User Defined http://linuxcnc.org/docs/html/gcode/overview.html#_modal_groups
|
||||
|
||||
// #define OTHER_INPUT_F 14
|
||||
// #define OTHER_INPUT_S 15
|
||||
// #define OTHER_INPUT_T 16
|
||||
enum class ModalGroup : uint8_t {
|
||||
MG0 = 0, // [G4,G10,G28,G28.1,G30,G30.1,G53,G92,G92.1] Non-modal
|
||||
MG1 = 1, // [G0,G1,G2,G3,G38.2,G38.3,G38.4,G38.5,G80] Motion
|
||||
MG2 = 2, // [G17,G18,G19] Plane selection
|
||||
MG3 = 3, // [G90,G91] Distance mode
|
||||
MG4 = 4, // [G91.1] Arc IJK distance mode
|
||||
MG5 = 5, // [G93,G94] Feed rate mode
|
||||
MG6 = 6, // [G20,G21] Units
|
||||
MG7 = 7, // [G40] Cutter radius compensation mode. G41/42 NOT SUPPORTED.
|
||||
MG8 = 8, // [G43.1,G49] Tool length offset
|
||||
MG12 = 9, // [G54,G55,G56,G57,G58,G59] Coordinate system selection
|
||||
MG13 = 10, // [G61] Control mode
|
||||
MM4 = 11, // [M0,M1,M2,M30] Stopping
|
||||
MM6 = 14, // [M6] Tool change
|
||||
MM7 = 12, // [M3,M4,M5] Spindle turning
|
||||
MM8 = 13, // [M7,M8,M9] Coolant control
|
||||
MM9 = 14, // [M56] Override control
|
||||
MM10 = 15, // [M62, M63] User Defined http://linuxcnc.org/docs/html/gcode/overview.html#_modal_groups
|
||||
};
|
||||
|
||||
// Define command actions for within execution-type modal groups (motion, stopping, non-modal). Used
|
||||
// internally by the parser to know which command to execute.
|
||||
@@ -61,157 +59,189 @@
|
||||
// to see how they are used, if you need to alter them.
|
||||
|
||||
// Modal Group G0: Non-modal actions
|
||||
#define NON_MODAL_NO_ACTION 0 // (Default: Must be zero)
|
||||
#define NON_MODAL_DWELL 4 // G4 (Do not alter value)
|
||||
#define NON_MODAL_SET_COORDINATE_DATA 10 // G10 (Do not alter value)
|
||||
#define NON_MODAL_GO_HOME_0 28 // G28 (Do not alter value)
|
||||
#define NON_MODAL_SET_HOME_0 38 // G28.1 (Do not alter value)
|
||||
#define NON_MODAL_GO_HOME_1 30 // G30 (Do not alter value)
|
||||
#define NON_MODAL_SET_HOME_1 40 // G30.1 (Do not alter value)
|
||||
#define NON_MODAL_ABSOLUTE_OVERRIDE 53 // G53 (Do not alter value)
|
||||
#define NON_MODAL_SET_COORDINATE_OFFSET 92 // G92 (Do not alter value)
|
||||
#define NON_MODAL_RESET_COORDINATE_OFFSET 102 //G92.1 (Do not alter value)
|
||||
|
||||
enum class NonModal : uint8_t {
|
||||
NoAction = 0, // (Default: Must be zero)
|
||||
Dwell = 4, // G4 (Do not alter value)
|
||||
SetCoordinateData = 10, // G10 (Do not alter value)
|
||||
GoHome0 = 28, // G28 (Do not alter value)
|
||||
SetHome0 = 38, // G28.1 (Do not alter value)
|
||||
GoHome1 = 30, // G30 (Do not alter value)
|
||||
SetHome1 = 40, // G30.1 (Do not alter value)
|
||||
AbsoluteOverride = 53, // G53 (Do not alter value)
|
||||
SetCoordinateOffset = 92, // G92 (Do not alter value)
|
||||
ResetCoordinateOffset = 102, //G92.1 (Do not alter value)
|
||||
};
|
||||
|
||||
// Modal Group G1: Motion modes
|
||||
#define MOTION_MODE_SEEK 0 // G0 (Default: Must be zero)
|
||||
#define MOTION_MODE_LINEAR 1 // G1 (Do not alter value)
|
||||
#define MOTION_MODE_CW_ARC 2 // G2 (Do not alter value)
|
||||
#define MOTION_MODE_CCW_ARC 3 // G3 (Do not alter value)
|
||||
#define MOTION_MODE_PROBE_TOWARD 140 // G38.2 (Do not alter value)
|
||||
#define MOTION_MODE_PROBE_TOWARD_NO_ERROR 141 // G38.3 (Do not alter value)
|
||||
#define MOTION_MODE_PROBE_AWAY 142 // G38.4 (Do not alter value)
|
||||
#define MOTION_MODE_PROBE_AWAY_NO_ERROR 143 // G38.5 (Do not alter value)
|
||||
#define MOTION_MODE_NONE 80 // G80 (Do not alter value)
|
||||
enum class Motion : uint8_t {
|
||||
Seek = 0, // G0 (Default: Must be zero)
|
||||
Linear = 1, // G1 (Do not alter value)
|
||||
CwArc = 2, // G2 (Do not alter value)
|
||||
CcwArc = 3, // G3 (Do not alter value)
|
||||
ProbeToward = 140, // G38.2 (Do not alter value)
|
||||
ProbeTowardNoError = 141, // G38.3 (Do not alter value)
|
||||
ProbeAway = 142, // G38.4 (Do not alter value)
|
||||
ProbeAwayNoError = 143, // G38.5 (Do not alter value)
|
||||
None = 80, // G80 (Do not alter value)
|
||||
};
|
||||
|
||||
// Modal Group G2: Plane select
|
||||
#define PLANE_SELECT_XY 0 // G17 (Default: Must be zero)
|
||||
#define PLANE_SELECT_ZX 1 // G18 (Do not alter value)
|
||||
#define PLANE_SELECT_YZ 2 // G19 (Do not alter value)
|
||||
enum class Plane : uint8_t {
|
||||
XY = 0, // G17 (Default: Must be zero)
|
||||
ZX = 1, // G18 (Do not alter value)
|
||||
YZ = 2, // G19 (Do not alter value)
|
||||
};
|
||||
|
||||
// Modal Group G3: Distance mode
|
||||
#define DISTANCE_MODE_ABSOLUTE 0 // G90 (Default: Must be zero)
|
||||
#define DISTANCE_MODE_INCREMENTAL 1 // G91 (Do not alter value)
|
||||
enum class Distance : uint8_t {
|
||||
Absolute = 0, // G90 (Default: Must be zero)
|
||||
Incremental = 1, // G91 (Do not alter value)
|
||||
};
|
||||
|
||||
// Modal Group G4: Arc IJK distance mode
|
||||
#define DISTANCE_ARC_MODE_INCREMENTAL 0 // G91.1 (Default: Must be zero)
|
||||
enum class ArcDistance : uint8_t {
|
||||
Incremental = 0, // G91.1 (Default: Must be zero)
|
||||
Absolute = 1,
|
||||
};
|
||||
|
||||
// Modal Group M4: Program flow
|
||||
#define PROGRAM_FLOW_RUNNING 0 // (Default: Must be zero)
|
||||
#define PROGRAM_FLOW_PAUSED 3 // M0
|
||||
#define PROGRAM_FLOW_OPTIONAL_STOP 1 // M1 NOTE: Not supported, but valid and ignored.
|
||||
#define PROGRAM_FLOW_COMPLETED_M2 2 // M2 (Do not alter value)
|
||||
#define PROGRAM_FLOW_COMPLETED_M30 30 // M30 (Do not alter value)
|
||||
enum class ProgramFlow : uint8_t {
|
||||
Running = 0, // (Default: Must be zero)
|
||||
Paused = 3, // M0
|
||||
OptionalStop = 1, // M1 NOTE: Not supported, but valid and ignored.
|
||||
CompletedM2 = 2, // M2 (Do not alter value)
|
||||
CompletedM30 = 30, // M30 (Do not alter value)
|
||||
};
|
||||
|
||||
// Modal Group G5: Feed rate mode
|
||||
#define FEED_RATE_MODE_UNITS_PER_MIN 0 // G94 (Default: Must be zero)
|
||||
#define FEED_RATE_MODE_INVERSE_TIME 1 // G93 (Do not alter value)
|
||||
enum class FeedRate : uint8_t {
|
||||
UnitsPerMin = 0, // G94 (Default: Must be zero)
|
||||
InverseTime = 1, // G93 (Do not alter value)
|
||||
};
|
||||
|
||||
// Modal Group G6: Units mode
|
||||
#define UNITS_MODE_MM 0 // G21 (Default: Must be zero)
|
||||
#define UNITS_MODE_INCHES 1 // G20 (Do not alter value)
|
||||
enum class Units : uint8_t {
|
||||
Mm = 0, // G21 (Default: Must be zero)
|
||||
Inches = 1, // G20 (Do not alter value)
|
||||
};
|
||||
|
||||
// Modal Group G7: Cutter radius compensation mode
|
||||
#define CUTTER_COMP_DISABLE 0 // G40 (Default: Must be zero)
|
||||
enum class CutterCompensation : uint8_t {
|
||||
Disable = 0, // G40 (Default: Must be zero)
|
||||
Enable = 1,
|
||||
};
|
||||
|
||||
// Modal Group G13: Control mode
|
||||
#define CONTROL_MODE_EXACT_PATH 0 // G61 (Default: Must be zero)
|
||||
enum class ControlMode : uint8_t {
|
||||
ExactPath = 0, // G61 (Default: Must be zero)
|
||||
};
|
||||
|
||||
// Modal Group M7: Spindle control
|
||||
#define SPINDLE_DISABLE 0 // M5 (Default: Must be zero)
|
||||
#define SPINDLE_ENABLE_CW PL_COND_FLAG_SPINDLE_CW // M3 (NOTE: Uses planner condition bit flag)
|
||||
#define SPINDLE_ENABLE_CCW PL_COND_FLAG_SPINDLE_CCW // M4 (NOTE: Uses planner condition bit flag)
|
||||
enum class SpindleState : uint8_t {
|
||||
Disable = 0, // M5 (Default: Must be zero)
|
||||
Cw = 1, // M3
|
||||
Ccw = 2, // M4
|
||||
};
|
||||
|
||||
// Modal Group M8: Coolant control
|
||||
#define COOLANT_DISABLE 0 // M9 (Default: Must be zero)
|
||||
#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)
|
||||
enum class CoolantMode : uint8_t {
|
||||
Disable = 0, // M9 (Default: Must be zero)
|
||||
Flood = 1, // M8
|
||||
Mist = 2, // M7
|
||||
};
|
||||
|
||||
// Modal Group M9: Override control
|
||||
enum class Override : uint8_t {
|
||||
#ifdef DEACTIVATE_PARKING_UPON_INIT
|
||||
# define OVERRIDE_DISABLED 0 // (Default: Must be zero)
|
||||
# define OVERRIDE_PARKING_MOTION 1 // M56
|
||||
Disabled = 0, // (Default: Must be zero)
|
||||
ParkingMotion = 1, // M56
|
||||
#else
|
||||
# define OVERRIDE_PARKING_MOTION 0 // M56 (Default: Must be zero)
|
||||
# define OVERRIDE_DISABLED 1 // Parking disabled.
|
||||
ParkingMotion = 0, // M56 (Default: Must be zero)
|
||||
Disabled = 1, // Parking disabled.
|
||||
#endif
|
||||
};
|
||||
|
||||
// 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
|
||||
enum class IoControl : uint8_t {
|
||||
Enable = 1,
|
||||
Disable = 2,
|
||||
};
|
||||
|
||||
static const int MaxUserDigitalPin = 4;
|
||||
|
||||
// Modal Group G8: Tool length offset
|
||||
#define TOOL_LENGTH_OFFSET_CANCEL 0 // G49 (Default: Must be zero)
|
||||
#define TOOL_LENGTH_OFFSET_ENABLE_DYNAMIC 1 // G43.1
|
||||
enum class ToolLengthOffset : uint8_t {
|
||||
Cancel = 0, // G49 (Default: Must be zero)
|
||||
EnableDynamic = 1, // G43.1
|
||||
};
|
||||
|
||||
#define TOOL_CHANGE 1
|
||||
enum class ToolChange : uint8_t {
|
||||
Disable = 0,
|
||||
Enable = 1,
|
||||
};
|
||||
|
||||
// Modal Group G12: Active work coordinate system
|
||||
// N/A: Stores coordinate system value (54-59) to change to.
|
||||
|
||||
// Define parameter word mapping.
|
||||
#define WORD_F 0
|
||||
#define WORD_I 1
|
||||
#define WORD_J 2
|
||||
#define WORD_K 3
|
||||
#define WORD_L 4
|
||||
#define WORD_N 5
|
||||
#define WORD_P 6
|
||||
#define WORD_R 7
|
||||
#define WORD_S 8
|
||||
#define WORD_T 9
|
||||
#define WORD_X 10
|
||||
#define WORD_Y 11
|
||||
#define WORD_Z 12
|
||||
#define WORD_A 13
|
||||
#define WORD_B 14
|
||||
#define WORD_C 15
|
||||
enum class GCodeWord : uint8_t {
|
||||
F = 0,
|
||||
I = 1,
|
||||
J = 2,
|
||||
K = 3,
|
||||
L = 4,
|
||||
N = 5,
|
||||
P = 6,
|
||||
R = 7,
|
||||
S = 8,
|
||||
T = 9,
|
||||
X = 10,
|
||||
Y = 11,
|
||||
Z = 12,
|
||||
A = 13,
|
||||
B = 14,
|
||||
C = 15,
|
||||
};
|
||||
|
||||
// Define g-code parser position updating flags
|
||||
#define GC_UPDATE_POS_TARGET 0 // Must be zero
|
||||
#define GC_UPDATE_POS_SYSTEM 1
|
||||
#define GC_UPDATE_POS_NONE 2
|
||||
|
||||
// Define probe cycle exit states and assign proper position updating.
|
||||
#define GC_PROBE_FOUND GC_UPDATE_POS_SYSTEM
|
||||
#define GC_PROBE_ABORT GC_UPDATE_POS_NONE
|
||||
#define GC_PROBE_FAIL_INIT GC_UPDATE_POS_NONE
|
||||
#define GC_PROBE_FAIL_END GC_UPDATE_POS_TARGET
|
||||
#ifdef SET_CHECK_MODE_PROBE_TO_START
|
||||
# define GC_PROBE_CHECK_MODE GC_UPDATE_POS_NONE
|
||||
#else
|
||||
# define GC_PROBE_CHECK_MODE GC_UPDATE_POS_TARGET
|
||||
#endif
|
||||
enum class GCUpdatePos : uint8_t {
|
||||
Target = 0, // Must be zero
|
||||
System = 1,
|
||||
None = 2,
|
||||
};
|
||||
|
||||
// Define gcode parser flags for handling special cases.
|
||||
#define GC_PARSER_NONE 0 // Must be zero.
|
||||
#define GC_PARSER_JOG_MOTION bit(0)
|
||||
#define GC_PARSER_CHECK_MANTISSA bit(1)
|
||||
#define GC_PARSER_ARC_IS_CLOCKWISE bit(2)
|
||||
#define GC_PARSER_PROBE_IS_AWAY bit(3)
|
||||
#define GC_PARSER_PROBE_IS_NO_ERROR bit(4)
|
||||
#define GC_PARSER_LASER_FORCE_SYNC bit(5)
|
||||
#define GC_PARSER_LASER_DISABLE bit(6)
|
||||
#define GC_PARSER_LASER_ISMOTION bit(7)
|
||||
enum GCParserFlags {
|
||||
GCParserNone = 0, // Must be zero.
|
||||
GCParserJogMotion = bit(0),
|
||||
GCParserCheckMantissa = bit(1),
|
||||
GCParserArcIsClockwise = bit(2),
|
||||
GCParserProbeIsAway = bit(3),
|
||||
GCParserProbeIsNoError = bit(4),
|
||||
GCParserLaserForceSync = bit(5),
|
||||
GCParserLaserDisable = bit(6),
|
||||
GCParserLaserIsMotion = bit(7),
|
||||
};
|
||||
|
||||
// NOTE: When this struct is zeroed, the above defines set the defaults for the system.
|
||||
typedef struct {
|
||||
uint8_t motion; // {G0,G1,G2,G3,G38.2,G80}
|
||||
uint8_t feed_rate; // {G93,G94}
|
||||
uint8_t units; // {G20,G21}
|
||||
uint8_t distance; // {G90,G91}
|
||||
// uint8_t distance_arc; // {G91.1} NOTE: Don't track. Only default supported.
|
||||
uint8_t plane_select; // {G17,G18,G19}
|
||||
// uint8_t cutter_comp; // {G40} NOTE: Don't track. Only default supported.
|
||||
uint8_t tool_length; // {G43.1,G49}
|
||||
uint8_t coord_select; // {G54,G55,G56,G57,G58,G59}
|
||||
Motion motion; // {G0,G1,G2,G3,G38.2,G80}
|
||||
FeedRate feed_rate; // {G93,G94}
|
||||
Units units; // {G20,G21}
|
||||
Distance distance; // {G90,G91}
|
||||
// ArcDistance distance_arc; // {G91.1} NOTE: Don't track. Only default supported.
|
||||
Plane plane_select; // {G17,G18,G19}
|
||||
// CutterCompensation cutter_comp; // {G40} NOTE: Don't track. Only default supported.
|
||||
ToolLengthOffset tool_length; // {G43.1,G49}
|
||||
uint8_t coord_select; // {G54,G55,G56,G57,G58,G59}
|
||||
// uint8_t control; // {G61} NOTE: Don't track. Only default supported.
|
||||
uint8_t program_flow; // {M0,M1,M2,M30}
|
||||
uint8_t coolant; // {M7,M8,M9}
|
||||
uint8_t spindle; // {M3,M4,M5}
|
||||
uint8_t tool_change; // {M6}
|
||||
uint8_t io_control; // {M62, M63}
|
||||
uint8_t override; // {M56}
|
||||
ProgramFlow program_flow; // {M0,M1,M2,M30}
|
||||
CoolantMode coolant; // {M7,M8,M9}
|
||||
SpindleState spindle; // {M3,M4,M5}
|
||||
ToolChange tool_change; // {M6}
|
||||
IoControl io_control; // {M62, M63}
|
||||
Override override; // {M56}
|
||||
} gc_modal_t;
|
||||
|
||||
typedef struct {
|
||||
@@ -246,11 +276,18 @@ typedef struct {
|
||||
extern parser_state_t gc_state;
|
||||
|
||||
typedef struct {
|
||||
uint8_t non_modal_command;
|
||||
NonModal non_modal_command;
|
||||
gc_modal_t modal;
|
||||
gc_values_t values;
|
||||
} parser_block_t;
|
||||
|
||||
enum class AxisCommand : uint8_t {
|
||||
None = 0,
|
||||
NonModal = 1,
|
||||
MotionMode = 2,
|
||||
ToolLengthOffset = 3,
|
||||
};
|
||||
|
||||
// Initialize the parser
|
||||
void gc_init();
|
||||
|
||||
|
@@ -23,7 +23,7 @@
|
||||
// Grbl versioning system
|
||||
|
||||
#define GRBL_VERSION "1.3a"
|
||||
#define GRBL_VERSION_BUILD "20200828"
|
||||
#define GRBL_VERSION_BUILD "20200831"
|
||||
|
||||
//#include <sdkconfig.h>
|
||||
#include <Arduino.h>
|
||||
@@ -45,10 +45,10 @@
|
||||
#include "WebUI/Commands.h"
|
||||
#include "System.h"
|
||||
|
||||
#include "Planner.h"
|
||||
#include "CoolantControl.h"
|
||||
#include "Eeprom.h"
|
||||
#include "GCode.h"
|
||||
#include "Planner.h"
|
||||
#include "Eeprom.h"
|
||||
#include "CoolantControl.h"
|
||||
#include "Limits.h"
|
||||
#include "MotionControl.h"
|
||||
#include "Probe.h"
|
||||
|
@@ -28,7 +28,7 @@ uint8_t jog_execute(plan_line_data_t* pl_data, parser_block_t* gc_block) {
|
||||
// Initialize planner data struct for jogging motions.
|
||||
// NOTE: Spindle and coolant are allowed to fully function with overrides during a jog.
|
||||
pl_data->feed_rate = gc_block->values.f;
|
||||
pl_data->condition |= PL_COND_FLAG_NO_FEED_OVERRIDE;
|
||||
pl_data->motion |= PL_MOTION_NO_FEED_OVERRIDE;
|
||||
#ifdef USE_LINE_NUMBERS
|
||||
pl_data->line_number = gc_block->values.n;
|
||||
#endif
|
||||
|
@@ -27,7 +27,7 @@
|
||||
|
||||
#include "Grbl.h"
|
||||
|
||||
uint8_t n_homing_locate_cycle = N_HOMING_LOCATE_CYCLE;
|
||||
uint8_t n_homing_locate_cycle = NHomingLocateCycle;
|
||||
|
||||
xQueueHandle limit_sw_queue; // used by limit switch debouncing
|
||||
|
||||
@@ -82,7 +82,7 @@ void limits_go_home(uint8_t cycle_mask) {
|
||||
plan_line_data_t plan_data;
|
||||
plan_line_data_t* pl_data = &plan_data;
|
||||
memset(pl_data, 0, sizeof(plan_line_data_t));
|
||||
pl_data->condition = (PL_COND_FLAG_SYSTEM_MOTION | PL_COND_FLAG_NO_FEED_OVERRIDE);
|
||||
pl_data->motion = (PL_MOTION_SYSTEM_MOTION | PL_MOTION_NO_FEED_OVERRIDE);
|
||||
#ifdef USE_LINE_NUMBERS
|
||||
pl_data->line_number = HOMING_CYCLE_LINE_NUMBER;
|
||||
#endif
|
||||
|
@@ -135,9 +135,9 @@ void mc_arc(float* target,
|
||||
// Multiply inverse feed_rate to compensate for the fact that this movement is approximated
|
||||
// by a number of discrete segments. The inverse feed_rate should be correct for the sum of
|
||||
// all segments.
|
||||
if (pl_data->condition & PL_COND_FLAG_INVERSE_TIME) {
|
||||
if (pl_data->motion & PL_MOTION_INVERSE_TIME) {
|
||||
pl_data->feed_rate *= segments;
|
||||
bit_false(pl_data->condition, PL_COND_FLAG_INVERSE_TIME); // Force as feed absolute mode over arc segments.
|
||||
bit_false(pl_data->motion, PL_MOTION_INVERSE_TIME); // Force as feed absolute mode over arc segments.
|
||||
}
|
||||
float theta_per_segment = angular_travel / segments;
|
||||
float linear_per_segment = (target[axis_linear] - position[axis_linear]) / segments;
|
||||
@@ -277,7 +277,7 @@ void mc_homing_cycle(uint8_t cycle_mask) {
|
||||
limits_disable(); // Disable hard limits pin change register for cycle duration
|
||||
// -------------------------------------------------------------------------------------
|
||||
// Perform homing routine. NOTE: Special motion case. Only system reset works.
|
||||
n_homing_locate_cycle = N_HOMING_LOCATE_CYCLE;
|
||||
n_homing_locate_cycle = NHomingLocateCycle;
|
||||
#ifdef HOMING_SINGLE_AXIS_COMMANDS
|
||||
/*
|
||||
if (cycle_mask) { limits_go_home(cycle_mask); } // Perform homing cycle based on mask.
|
||||
@@ -291,7 +291,7 @@ void mc_homing_cycle(uint8_t cycle_mask) {
|
||||
n_homing_locate_cycle = 0; // don't do a second touch cycle
|
||||
limits_go_home(cycle_mask);
|
||||
ganged_mode = SquaringMode::A;
|
||||
n_homing_locate_cycle = N_HOMING_LOCATE_CYCLE; // restore to default value
|
||||
n_homing_locate_cycle = NHomingLocateCycle; // restore to default value
|
||||
limits_go_home(cycle_mask);
|
||||
ganged_mode = SquaringMode::B;
|
||||
limits_go_home(cycle_mask);
|
||||
@@ -309,7 +309,7 @@ void mc_homing_cycle(uint8_t cycle_mask) {
|
||||
n_homing_locate_cycle = 0; // don't do a second touch cycle
|
||||
limits_go_home(HOMING_CYCLE_0);
|
||||
ganged_mode = SquaringMode::A;
|
||||
n_homing_locate_cycle = N_HOMING_LOCATE_CYCLE; // restore to default value
|
||||
n_homing_locate_cycle = NHomingLocateCycle; // restore to default value
|
||||
limits_go_home(HOMING_CYCLE_0);
|
||||
ganged_mode = SquaringMode::B;
|
||||
limits_go_home(HOMING_CYCLE_0);
|
||||
@@ -323,7 +323,7 @@ void mc_homing_cycle(uint8_t cycle_mask) {
|
||||
n_homing_locate_cycle = 0; // don't do a second touch cycle
|
||||
limits_go_home(HOMING_CYCLE_1);
|
||||
ganged_mode = SquaringMode::A;
|
||||
n_homing_locate_cycle = N_HOMING_LOCATE_CYCLE; // restore to default value
|
||||
n_homing_locate_cycle = NHomingLocateCycle; // restore to default value
|
||||
limits_go_home(HOMING_CYCLE_1);
|
||||
ganged_mode = SquaringMode::B;
|
||||
limits_go_home(HOMING_CYCLE_1);
|
||||
@@ -338,7 +338,7 @@ void mc_homing_cycle(uint8_t cycle_mask) {
|
||||
n_homing_locate_cycle = 0; // don't do a second touch cycle
|
||||
limits_go_home(HOMING_CYCLE_2);
|
||||
ganged_mode = SquaringMode::A;
|
||||
n_homing_locate_cycle = N_HOMING_LOCATE_CYCLE; // restore to default value
|
||||
n_homing_locate_cycle = NHomingLocateCycle; // restore to default value
|
||||
limits_go_home(HOMING_CYCLE_2);
|
||||
ganged_mode = SquaringMode::B;
|
||||
limits_go_home(HOMING_CYCLE_2);
|
||||
@@ -374,17 +374,22 @@ void mc_homing_cycle(uint8_t cycle_mask) {
|
||||
|
||||
// Perform tool length probe cycle. Requires probe switch.
|
||||
// NOTE: Upon probe failure, the program will be stopped and placed into ALARM state.
|
||||
uint8_t mc_probe_cycle(float* target, plan_line_data_t* pl_data, uint8_t parser_flags) {
|
||||
GCUpdatePos mc_probe_cycle(float* target, plan_line_data_t* pl_data, uint8_t parser_flags) {
|
||||
// TODO: Need to update this cycle so it obeys a non-auto cycle start.
|
||||
if (sys.state == STATE_CHECK_MODE)
|
||||
return (GC_PROBE_CHECK_MODE);
|
||||
if (sys.state == STATE_CHECK_MODE) {
|
||||
#ifdef SET_CHECK_MODE_PROBE_TO_START
|
||||
return (GCUpdatePos::None);
|
||||
#else
|
||||
return (GCUpdatePos::Target);
|
||||
#endif
|
||||
}
|
||||
// Finish all queued commands and empty planner buffer before starting probe cycle.
|
||||
protocol_buffer_synchronize();
|
||||
if (sys.abort)
|
||||
return (GC_PROBE_ABORT); // Return if system reset has been issued.
|
||||
return (GCUpdatePos::None); // Return if system reset has been issued.
|
||||
// Initialize probing control variables
|
||||
uint8_t is_probe_away = bit_istrue(parser_flags, GC_PARSER_PROBE_IS_AWAY);
|
||||
uint8_t is_no_error = bit_istrue(parser_flags, GC_PARSER_PROBE_IS_NO_ERROR);
|
||||
uint8_t is_probe_away = bit_istrue(parser_flags, GCParserProbeIsAway);
|
||||
uint8_t is_no_error = bit_istrue(parser_flags, GCParserProbeIsNoError);
|
||||
sys.probe_succeeded = false; // Re-initialize probe history before beginning cycle.
|
||||
probe_configure_invert_mask(is_probe_away);
|
||||
// After syncing, check if probe is already triggered. If so, halt and issue alarm.
|
||||
@@ -393,7 +398,7 @@ uint8_t mc_probe_cycle(float* target, plan_line_data_t* pl_data, uint8_t parser_
|
||||
system_set_exec_alarm(EXEC_ALARM_PROBE_FAIL_INITIAL);
|
||||
protocol_execute_realtime();
|
||||
probe_configure_invert_mask(false); // Re-initialize invert mask before returning.
|
||||
return (GC_PROBE_FAIL_INIT); // Nothing else to do but bail.
|
||||
return (GCUpdatePos::None); // Nothing else to do but bail.
|
||||
}
|
||||
// Setup and queue probing motion. Auto cycle-start should not start the cycle.
|
||||
mc_line(target, pl_data);
|
||||
@@ -404,7 +409,7 @@ uint8_t mc_probe_cycle(float* target, plan_line_data_t* pl_data, uint8_t parser_
|
||||
do {
|
||||
protocol_execute_realtime();
|
||||
if (sys.abort)
|
||||
return (GC_PROBE_ABORT); // Check for system abort
|
||||
return (GCUpdatePos::None); // Check for system abort
|
||||
} while (sys.state != STATE_IDLE);
|
||||
// Probing cycle complete!
|
||||
// Set state variables and error out, if the probe failed and cycle with error is enabled.
|
||||
@@ -428,9 +433,9 @@ uint8_t mc_probe_cycle(float* target, plan_line_data_t* pl_data, uint8_t parser_
|
||||
report_probe_parameters(CLIENT_ALL);
|
||||
#endif
|
||||
if (sys.probe_succeeded)
|
||||
return (GC_PROBE_FOUND); // Successful probe cycle.
|
||||
return (GCUpdatePos::System); // Successful probe cycle.
|
||||
else
|
||||
return (GC_PROBE_FAIL_END); // Failed to trigger probe within travel. With or without error.
|
||||
return (GCUpdatePos::Target); // Failed to trigger probe within travel. With or without error.
|
||||
}
|
||||
|
||||
// Plans and executes the single special motion case for parking. Independent of main planner buffer.
|
||||
|
@@ -31,12 +31,6 @@
|
||||
#define PARKING_MOTION_LINE_NUMBER 0
|
||||
|
||||
#define HOMING_CYCLE_ALL 0 // Must be zero.
|
||||
#define HOMING_CYCLE_X bit(X_AXIS)
|
||||
#define HOMING_CYCLE_Y bit(Y_AXIS)
|
||||
#define HOMING_CYCLE_Z bit(Z_AXIS)
|
||||
#define HOMING_CYCLE_A bit(A_AXIS)
|
||||
#define HOMING_CYCLE_B bit(B_AXIS)
|
||||
#define HOMING_CYCLE_C bit(C_AXIS)
|
||||
|
||||
// Execute linear motion in absolute millimeter coordinates. Feed rate given in millimeters/second
|
||||
// unless invert_feed_rate is true. Then the feed_rate means that the motion should be completed in
|
||||
@@ -65,7 +59,7 @@ void mc_dwell(float seconds);
|
||||
void mc_homing_cycle(uint8_t cycle_mask);
|
||||
|
||||
// Perform tool length probe cycle. Requires probe switch.
|
||||
uint8_t mc_probe_cycle(float* target, plan_line_data_t* pl_data, uint8_t parser_flags);
|
||||
GCUpdatePos mc_probe_cycle(float* target, plan_line_data_t* pl_data, uint8_t parser_flags);
|
||||
|
||||
// Handles updating the override control state.
|
||||
void mc_override_ctrl_update(uint8_t override_state);
|
||||
|
@@ -22,8 +22,8 @@
|
||||
|
||||
#include "Config.h"
|
||||
|
||||
#define false 0
|
||||
#define true 1
|
||||
// #define false 0
|
||||
// #define true 1
|
||||
|
||||
#define SOME_LARGE_VALUE 1.0E+38
|
||||
|
||||
@@ -72,8 +72,11 @@
|
||||
#define isequal_position_vector(a, b) !(memcmp(a, b, sizeof(float) * N_AXIS))
|
||||
|
||||
// Bit field and masking macros
|
||||
//Arduino.h:104:0: note: this is the location of the previous definition
|
||||
//#define bit(n) (1 << n)
|
||||
// bit(n) is defined in Arduino.h. We redefine it here so we can apply
|
||||
// the static_cast, thus making it work with scoped enums
|
||||
#undef bit
|
||||
#define bit(n) (1 << static_cast<unsigned int>(n))
|
||||
|
||||
#define bit_true(x, mask) (x) |= (mask)
|
||||
#define bit_false(x, mask) (x) &= ~(mask)
|
||||
#define bit_istrue(x, mask) ((x & mask) != 0)
|
||||
|
@@ -240,10 +240,10 @@ uint8_t plan_check_full_buffer() {
|
||||
// NOTE: All system motion commands, such as homing/parking, are not subject to overrides.
|
||||
float plan_compute_profile_nominal_speed(plan_block_t* block) {
|
||||
float nominal_speed = block->programmed_rate;
|
||||
if (block->condition & PL_COND_FLAG_RAPID_MOTION)
|
||||
if (block->motion & PL_MOTION_RAPID_MOTION)
|
||||
nominal_speed *= (0.01 * sys.r_override);
|
||||
else {
|
||||
if (!(block->condition & PL_COND_FLAG_NO_FEED_OVERRIDE))
|
||||
if (!(block->motion & PL_MOTION_NO_FEED_OVERRIDE))
|
||||
nominal_speed *= (0.01 * sys.f_override);
|
||||
if (nominal_speed > block->rapid_rate)
|
||||
nominal_speed = block->rapid_rate;
|
||||
@@ -285,7 +285,9 @@ uint8_t plan_buffer_line(float* target, plan_line_data_t* pl_data) {
|
||||
// Prepare and initialize new block. Copy relevant pl_data for block execution.
|
||||
plan_block_t* block = &block_buffer[block_buffer_head];
|
||||
memset(block, 0, sizeof(plan_block_t)); // Zero all block values.
|
||||
block->condition = pl_data->condition;
|
||||
block->motion = pl_data->motion;
|
||||
block->coolant = pl_data->coolant;
|
||||
block->spindle = pl_data->spindle;
|
||||
block->spindle_speed = pl_data->spindle_speed;
|
||||
|
||||
#ifdef USE_LINE_NUMBERS
|
||||
@@ -296,7 +298,7 @@ uint8_t plan_buffer_line(float* target, plan_line_data_t* pl_data) {
|
||||
float unit_vec[N_AXIS], delta_mm;
|
||||
uint8_t idx;
|
||||
// Copy position data based on type of motion being planned.
|
||||
if (block->condition & PL_COND_FLAG_SYSTEM_MOTION) {
|
||||
if (block->motion & PL_MOTION_SYSTEM_MOTION) {
|
||||
#ifdef COREXY
|
||||
position_steps[X_AXIS] = system_convert_corexy_to_x_axis_steps(sys_position);
|
||||
position_steps[Y_AXIS] = system_convert_corexy_to_y_axis_steps(sys_position);
|
||||
@@ -352,15 +354,15 @@ uint8_t plan_buffer_line(float* target, plan_line_data_t* pl_data) {
|
||||
block->acceleration = limit_acceleration_by_axis_maximum(unit_vec);
|
||||
block->rapid_rate = limit_rate_by_axis_maximum(unit_vec);
|
||||
// Store programmed rate.
|
||||
if (block->condition & PL_COND_FLAG_RAPID_MOTION)
|
||||
if (block->motion & PL_MOTION_RAPID_MOTION)
|
||||
block->programmed_rate = block->rapid_rate;
|
||||
else {
|
||||
block->programmed_rate = pl_data->feed_rate;
|
||||
if (block->condition & PL_COND_FLAG_INVERSE_TIME)
|
||||
if (block->motion & PL_MOTION_INVERSE_TIME)
|
||||
block->programmed_rate *= block->millimeters;
|
||||
}
|
||||
// TODO: Need to check this method handling zero junction speeds when starting from rest.
|
||||
if ((block_buffer_head == block_buffer_tail) || (block->condition & PL_COND_FLAG_SYSTEM_MOTION)) {
|
||||
if ((block_buffer_head == block_buffer_tail) || (block->motion & PL_MOTION_SYSTEM_MOTION)) {
|
||||
// Initialize block entry speed as zero. Assume it will be starting from rest. Planner will correct this later.
|
||||
// If system motion, the system motion block always is assumed to start from rest and end at a complete stop.
|
||||
block->entry_speed_sqr = 0.0;
|
||||
@@ -412,7 +414,7 @@ uint8_t plan_buffer_line(float* target, plan_line_data_t* pl_data) {
|
||||
}
|
||||
}
|
||||
// Block system motion from updating this data to ensure next g-code motion is computed correctly.
|
||||
if (!(block->condition & PL_COND_FLAG_SYSTEM_MOTION)) {
|
||||
if (!(block->motion & PL_MOTION_SYSTEM_MOTION)) {
|
||||
float nominal_speed = plan_compute_profile_nominal_speed(block);
|
||||
plan_compute_profile_parameters(block, nominal_speed, pl.previous_nominal_speed);
|
||||
pl.previous_nominal_speed = nominal_speed;
|
||||
|
@@ -38,16 +38,10 @@
|
||||
#define PLAN_EMPTY_BLOCK false
|
||||
|
||||
// Define planner data condition flags. Used to denote running conditions of a block.
|
||||
#define PL_COND_FLAG_RAPID_MOTION bit(0)
|
||||
#define PL_COND_FLAG_SYSTEM_MOTION bit(1) // Single motion. Circumvents planner state. Used by home/park.
|
||||
#define PL_COND_FLAG_NO_FEED_OVERRIDE bit(2) // Motion does not honor feed override.
|
||||
#define PL_COND_FLAG_INVERSE_TIME bit(3) // Interprets feed rate value as inverse time when set.
|
||||
#define PL_COND_FLAG_SPINDLE_CW bit(4)
|
||||
#define PL_COND_FLAG_SPINDLE_CCW bit(5)
|
||||
#define PL_COND_FLAG_COOLANT_FLOOD bit(6)
|
||||
#define PL_COND_FLAG_COOLANT_MIST bit(7)
|
||||
#define PL_COND_MOTION_MASK (PL_COND_FLAG_RAPID_MOTION | PL_COND_FLAG_SYSTEM_MOTION | PL_COND_FLAG_NO_FEED_OVERRIDE)
|
||||
#define PL_COND_ACCESSORY_MASK (PL_COND_FLAG_SPINDLE_CW | PL_COND_FLAG_SPINDLE_CCW | PL_COND_FLAG_COOLANT_FLOOD | PL_COND_FLAG_COOLANT_MIST)
|
||||
#define PL_MOTION_RAPID_MOTION bit(0)
|
||||
#define PL_MOTION_SYSTEM_MOTION bit(1) // Single motion. Circumvents planner state. Used by home/park.
|
||||
#define PL_MOTION_NO_FEED_OVERRIDE bit(2) // Motion does not honor feed override.
|
||||
#define PL_MOTION_INVERSE_TIME bit(3) // Interprets feed rate value as inverse time when set.
|
||||
|
||||
// This struct stores a linear movement of a g-code block motion with its critical "nominal" values
|
||||
// are as specified in the source g-code.
|
||||
@@ -59,7 +53,9 @@ typedef struct {
|
||||
uint8_t direction_bits; // The direction bit set for this block (refers to *_DIRECTION_BIT in config.h)
|
||||
|
||||
// Block condition data to ensure correct execution depending on states and overrides.
|
||||
uint8_t condition; // Block bitflag variable defining block run conditions. Copied from pl_line_data.
|
||||
uint8_t motion; // Block bitflag motion conditions. Copied from pl_line_data.
|
||||
SpindleState spindle; // Spindle enable state
|
||||
CoolantMode coolant; // Coolant state
|
||||
#ifdef USE_LINE_NUMBERS
|
||||
int32_t line_number; // Block line number for real-time reporting. Copied from pl_line_data.
|
||||
#endif
|
||||
@@ -85,9 +81,11 @@ typedef struct {
|
||||
|
||||
// Planner data prototype. Must be used when passing new motions to the planner.
|
||||
typedef struct {
|
||||
float feed_rate; // Desired feed rate for line motion. Value is ignored, if rapid motion.
|
||||
uint32_t spindle_speed; // Desired spindle speed through line motion.
|
||||
uint8_t condition; // Bitflag variable to indicate planner conditions. See defines above.
|
||||
float feed_rate; // Desired feed rate for line motion. Value is ignored, if rapid motion.
|
||||
uint32_t spindle_speed; // Desired spindle speed through line motion.
|
||||
uint8_t motion; // Bitflag variable to indicate motion conditions. See defines above.
|
||||
SpindleState spindle; // Spindle enable state
|
||||
CoolantMode coolant; // Coolant state
|
||||
#ifdef USE_LINE_NUMBERS
|
||||
int32_t line_number; // Desired line number to report when executing.
|
||||
#endif
|
||||
|
@@ -10,12 +10,12 @@ bool auth_failed(Word* w, const char* value, WebUI::AuthenticationLevel auth_lev
|
||||
permissions_t permissions = w->getPermissions();
|
||||
switch (auth_level) {
|
||||
case WebUI::AuthenticationLevel::LEVEL_ADMIN: // Admin can do anything
|
||||
return false; // Nothing is an Admin auth fail
|
||||
return false; // Nothing is an Admin auth fail
|
||||
case WebUI::AuthenticationLevel::LEVEL_GUEST: // Guest can only access open settings
|
||||
return permissions != WG; // Anything other than RG is Guest auth fail
|
||||
return permissions != WG; // Anything other than RG is Guest auth fail
|
||||
case WebUI::AuthenticationLevel::LEVEL_USER: // User is complicated...
|
||||
if (!value) { // User can read anything
|
||||
return false; // No read is a User auth fail
|
||||
if (!value) { // User can read anything
|
||||
return false; // No read is a User auth fail
|
||||
}
|
||||
return permissions == WA; // User cannot write WA
|
||||
default: return true;
|
||||
@@ -239,22 +239,22 @@ err_t home_all(const char* value, WebUI::AuthenticationLevel auth_level, WebUI::
|
||||
return home(HOMING_CYCLE_ALL);
|
||||
}
|
||||
err_t home_x(const char* value, WebUI::AuthenticationLevel auth_level, WebUI::ESPResponseStream* out) {
|
||||
return home(HOMING_CYCLE_X);
|
||||
return home(X_AXIS);
|
||||
}
|
||||
err_t home_y(const char* value, WebUI::AuthenticationLevel auth_level, WebUI::ESPResponseStream* out) {
|
||||
return home(HOMING_CYCLE_Y);
|
||||
return home(Y_AXIS);
|
||||
}
|
||||
err_t home_z(const char* value, WebUI::AuthenticationLevel auth_level, WebUI::ESPResponseStream* out) {
|
||||
return home(HOMING_CYCLE_Z);
|
||||
return home(Z_AXIS);
|
||||
}
|
||||
err_t home_a(const char* value, WebUI::AuthenticationLevel auth_level, WebUI::ESPResponseStream* out) {
|
||||
return home(HOMING_CYCLE_A);
|
||||
return home(A_AXIS);
|
||||
}
|
||||
err_t home_b(const char* value, WebUI::AuthenticationLevel auth_level, WebUI::ESPResponseStream* out) {
|
||||
return home(HOMING_CYCLE_B);
|
||||
return home(B_AXIS);
|
||||
}
|
||||
err_t home_c(const char* value, WebUI::AuthenticationLevel auth_level, WebUI::ESPResponseStream* out) {
|
||||
return home(HOMING_CYCLE_C);
|
||||
return home(C_AXIS);
|
||||
}
|
||||
err_t sleep_grbl(const char* value, WebUI::AuthenticationLevel auth_level, WebUI::ESPResponseStream* out) {
|
||||
system_set_exec_state_flag(EXEC_SLEEP);
|
||||
|
@@ -472,7 +472,7 @@ void protocol_exec_rt_system() {
|
||||
sys.spindle_speed_ovr = last_s_override;
|
||||
sys.report_ovr_counter = 0; // Set to report change immediately
|
||||
// If spinlde is on, tell it the rpm has been overridden
|
||||
if (gc_state.modal.spindle != SPINDLE_DISABLE)
|
||||
if (gc_state.modal.spindle != SpindleState::Disable)
|
||||
spindle->set_rpm(gc_state.spindle_speed);
|
||||
}
|
||||
if (rt_exec & EXEC_SPINDLE_OVR_STOP) {
|
||||
@@ -489,21 +489,21 @@ void protocol_exec_rt_system() {
|
||||
// run state can be determined by checking the parser state.
|
||||
if (rt_exec & (EXEC_COOLANT_FLOOD_OVR_TOGGLE | EXEC_COOLANT_MIST_OVR_TOGGLE)) {
|
||||
if ((sys.state == STATE_IDLE) || (sys.state & (STATE_CYCLE | STATE_HOLD))) {
|
||||
uint8_t coolant_state = gc_state.modal.coolant;
|
||||
CoolantMode coolant_state = gc_state.modal.coolant;
|
||||
#ifdef COOLANT_FLOOD_PIN
|
||||
if (rt_exec & EXEC_COOLANT_FLOOD_OVR_TOGGLE) {
|
||||
if (coolant_state & COOLANT_FLOOD_ENABLE)
|
||||
bit_false(coolant_state, COOLANT_FLOOD_ENABLE);
|
||||
if (coolant_state & CoolantMode::Flood)
|
||||
bit_false(coolant_state, CoolantMode::Flood);
|
||||
else
|
||||
coolant_state |= COOLANT_FLOOD_ENABLE;
|
||||
coolant_state |= CoolantMode::Flood;
|
||||
}
|
||||
#endif
|
||||
#ifdef COOLANT_MIST_PIN
|
||||
if (rt_exec & EXEC_COOLANT_MIST_OVR_TOGGLE) {
|
||||
if (coolant_state & COOLANT_MIST_ENABLE)
|
||||
bit_false(coolant_state, COOLANT_MIST_ENABLE);
|
||||
if (coolant_state & CoolantMode::Mist)
|
||||
bit_false(coolant_state, CoolantMode::Mist);
|
||||
else
|
||||
coolant_state |= COOLANT_MIST_ENABLE;
|
||||
coolant_state |= CoolantMode::Mist;
|
||||
}
|
||||
#endif
|
||||
coolant_set_state(coolant_state); // Report counter set in coolant_set_state().
|
||||
@@ -536,19 +536,22 @@ static void protocol_exec_rt_suspend() {
|
||||
plan_line_data_t plan_data;
|
||||
plan_line_data_t* pl_data = &plan_data;
|
||||
memset(pl_data, 0, sizeof(plan_line_data_t));
|
||||
pl_data->condition = (PL_COND_FLAG_SYSTEM_MOTION | PL_COND_FLAG_NO_FEED_OVERRIDE);
|
||||
pl_data->motion = (PL_MOTION_SYSTEM_MOTION | PL_MOTION_NO_FEED_OVERRIDE);
|
||||
# ifdef USE_LINE_NUMBERS
|
||||
pl_data->line_number = PARKING_MOTION_LINE_NUMBER;
|
||||
# endif
|
||||
#endif
|
||||
plan_block_t* block = plan_get_current_block();
|
||||
uint8_t restore_condition;
|
||||
CoolantMode restore_coolant;
|
||||
SpindleState restore_spindle;
|
||||
float restore_spindle_speed;
|
||||
if (block == NULL) {
|
||||
restore_condition = (gc_state.modal.spindle | gc_state.modal.coolant);
|
||||
restore_coolant = gc_state.modal.coolant;
|
||||
restore_spindle = gc_state.modal.spindle;
|
||||
restore_spindle_speed = gc_state.spindle_speed;
|
||||
} else {
|
||||
restore_condition = block->condition;
|
||||
restore_coolant = block->coolant;
|
||||
restore_spindle = block->spindle;
|
||||
restore_spindle_speed = block->spindle_speed;
|
||||
}
|
||||
#ifdef DISABLE_LASER_DURING_HOLD
|
||||
@@ -569,8 +572,8 @@ 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); // De-energize
|
||||
coolant_set_state(COOLANT_DISABLE); // De-energize
|
||||
spindle->set_state(SpindleState::Disable, 0); // De-energize
|
||||
coolant_set_state(CoolantMode::Disable); // De-energize
|
||||
#else
|
||||
// Get current position and store restore location and spindle retract waypoint.
|
||||
system_convert_array_steps_to_mpos(parking_target, sys_position);
|
||||
@@ -588,16 +591,19 @@ static void protocol_exec_rt_suspend() {
|
||||
if (parking_target[PARKING_AXIS] < retract_waypoint) {
|
||||
parking_target[PARKING_AXIS] = retract_waypoint;
|
||||
pl_data->feed_rate = PARKING_PULLOUT_RATE;
|
||||
pl_data->condition |= (restore_condition & PL_COND_ACCESSORY_MASK); // Retain accessory state
|
||||
pl_data->spindle_speed = restore_spindle_speed;
|
||||
pl_data->coolant = restore_coolant;
|
||||
pl_data->spindle = restore_spindle;
|
||||
pl_data->spindle_speed = restore_spindle_speed;
|
||||
mc_parking_motion(parking_target, pl_data);
|
||||
}
|
||||
// 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 = SpindleState::Disable;
|
||||
pl_data->coolant = CoolantMode::Disable;
|
||||
pl_data->motion = (PL_MOTION_SYSTEM_MOTION | PL_MOTION_NO_FEED_OVERRIDE);
|
||||
pl_data->spindle_speed = 0.0;
|
||||
spindle->set_state(SPINDLE_DISABLE, 0); // De-energize
|
||||
coolant_set_state(COOLANT_DISABLE); // De-energize
|
||||
// Execute fast parking retract motion to parking target location.
|
||||
spindle->set_state(SpindleState::Disable, 0); // De-energize
|
||||
coolant_set_state(CoolantMode::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;
|
||||
pl_data->feed_rate = PARKING_RATE;
|
||||
@@ -606,8 +612,8 @@ static void protocol_exec_rt_suspend() {
|
||||
} 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); // De-energize
|
||||
coolant_set_state(COOLANT_DISABLE); // De-energize
|
||||
spindle->set_state(SpindleState::Disable, 0); // De-energize
|
||||
coolant_set_state(CoolantMode::Disable); // De-energize
|
||||
}
|
||||
#endif
|
||||
sys.suspend &= ~(SUSPEND_RESTART_RETRACT);
|
||||
@@ -616,9 +622,9 @@ 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); // De-energize
|
||||
coolant_set_state(COOLANT_DISABLE); // De-energize
|
||||
st_go_idle(); // Disable steppers
|
||||
spindle->set_state(SpindleState::Disable, 0); // De-energize
|
||||
coolant_set_state(CoolantMode::Disable); // De-energize
|
||||
st_go_idle(); // Disable steppers
|
||||
while (!(sys.abort))
|
||||
protocol_exec_rt_system(); // Do nothing until reset.
|
||||
return; // Abort received. Return to re-initialize.
|
||||
@@ -644,24 +650,23 @@ static void protocol_exec_rt_suspend() {
|
||||
}
|
||||
#endif
|
||||
// Delayed Tasks: Restart spindle and coolant, delay to power-up, then resume cycle.
|
||||
if (gc_state.modal.spindle != SPINDLE_DISABLE) {
|
||||
if (gc_state.modal.spindle != SpindleState::Disable) {
|
||||
// Block if safety door re-opened during prior restore actions.
|
||||
if (bit_isfalse(sys.suspend, SUSPEND_RESTART_RETRACT)) {
|
||||
if (laser_mode->get()) {
|
||||
// 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_RPM);
|
||||
} else {
|
||||
spindle->set_state((restore_condition & (PL_COND_FLAG_SPINDLE_CW | PL_COND_FLAG_SPINDLE_CCW)),
|
||||
(uint32_t)restore_spindle_speed);
|
||||
spindle->set_state(restore_spindle, (uint32_t)restore_spindle_speed);
|
||||
delay_sec(SAFETY_DOOR_SPINDLE_DELAY, DELAY_MODE_SYS_SUSPEND);
|
||||
}
|
||||
}
|
||||
}
|
||||
if (gc_state.modal.coolant != COOLANT_DISABLE) {
|
||||
if (gc_state.modal.coolant != CoolantMode::Disable) {
|
||||
// Block if safety door re-opened during prior restore actions.
|
||||
if (bit_isfalse(sys.suspend, SUSPEND_RESTART_RETRACT)) {
|
||||
// NOTE: Laser mode will honor this delay. An exhaust system is often controlled by this pin.
|
||||
coolant_set_state((restore_condition & (PL_COND_FLAG_COOLANT_FLOOD | PL_COND_FLAG_COOLANT_FLOOD)));
|
||||
coolant_set_state(restore_coolant);
|
||||
delay_sec(SAFETY_DOOR_COOLANT_DELAY, DELAY_MODE_SYS_SUSPEND);
|
||||
}
|
||||
}
|
||||
@@ -673,8 +678,9 @@ static void protocol_exec_rt_suspend() {
|
||||
// Regardless if the retract parking motion was a valid/safe motion or not, the
|
||||
// restore parking motion should logically be valid, either by returning to the
|
||||
// original position through valid machine space or by not moving at all.
|
||||
pl_data->feed_rate = PARKING_PULLOUT_RATE;
|
||||
pl_data->condition |= (restore_condition & PL_COND_ACCESSORY_MASK); // Restore accessory state
|
||||
pl_data->feed_rate = PARKING_PULLOUT_RATE;
|
||||
pl_data->spindle = restore_spindle;
|
||||
pl_data->coolant = restore_coolant;
|
||||
pl_data->spindle_speed = restore_spindle_speed;
|
||||
mc_parking_motion(restore_target, pl_data);
|
||||
}
|
||||
@@ -692,22 +698,22 @@ static void protocol_exec_rt_suspend() {
|
||||
if (sys.spindle_stop_ovr) {
|
||||
// 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); // De-energize
|
||||
if (gc_state.modal.spindle != SpindleState::Disable) {
|
||||
spindle->set_state(SpindleState::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
|
||||
}
|
||||
// Handles restoring of spindle state
|
||||
} else if (sys.spindle_stop_ovr & (SPINDLE_STOP_OVR_RESTORE | SPINDLE_STOP_OVR_RESTORE_CYCLE)) {
|
||||
if (gc_state.modal.spindle != SPINDLE_DISABLE) {
|
||||
if (gc_state.modal.spindle != SpindleState::Disable) {
|
||||
report_feedback_message(MESSAGE_SPINDLE_RESTORE);
|
||||
if (laser_mode->get()) {
|
||||
// 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_RPM);
|
||||
} else
|
||||
spindle->set_state((restore_condition & (PL_COND_FLAG_SPINDLE_CW | PL_COND_FLAG_SPINDLE_CCW)),
|
||||
(uint32_t)restore_spindle_speed);
|
||||
} else {
|
||||
spindle->set_state(restore_spindle, (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.
|
||||
@@ -718,8 +724,7 @@ static void protocol_exec_rt_suspend() {
|
||||
// Handles spindle state during hold. NOTE: Spindle speed overrides may be altered during hold state.
|
||||
// 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);
|
||||
spindle->set_state(restore_spindle, (uint32_t)restore_spindle_speed);
|
||||
bit_false(sys.step_control, STEP_CONTROL_UPDATE_SPINDLE_RPM);
|
||||
}
|
||||
}
|
||||
|
@@ -337,50 +337,92 @@ void report_ngc_parameters(uint8_t client) {
|
||||
|
||||
// Print current gcode parser mode state
|
||||
void report_gcode_modes(uint8_t client) {
|
||||
char temp[20];
|
||||
char modes_rpt[75];
|
||||
strcpy(modes_rpt, "[GC:G");
|
||||
if (gc_state.modal.motion >= MOTION_MODE_PROBE_TOWARD)
|
||||
sprintf(temp, "38.%d", gc_state.modal.motion - (MOTION_MODE_PROBE_TOWARD - 2));
|
||||
else
|
||||
sprintf(temp, "%d", gc_state.modal.motion);
|
||||
strcat(modes_rpt, temp);
|
||||
char temp[20];
|
||||
char modes_rpt[75];
|
||||
const char* mode = "";
|
||||
strcpy(modes_rpt, "[GC:");
|
||||
|
||||
switch (gc_state.modal.motion) {
|
||||
case Motion::None: mode = "G80"; break;
|
||||
case Motion::Seek: mode = "G0"; break;
|
||||
case Motion::Linear: mode = "G1"; break;
|
||||
case Motion::CwArc: mode = "G2"; break;
|
||||
case Motion::CcwArc: mode = "G3"; break;
|
||||
case Motion::ProbeToward: mode = "G38.1"; break;
|
||||
case Motion::ProbeTowardNoError: mode = "G38.2"; break;
|
||||
case Motion::ProbeAway: mode = "G38.3"; break;
|
||||
case Motion::ProbeAwayNoError: mode = "G38.4"; break;
|
||||
}
|
||||
strcat(modes_rpt, mode);
|
||||
|
||||
sprintf(temp, " G%d", gc_state.modal.coord_select + 54);
|
||||
strcat(modes_rpt, temp);
|
||||
sprintf(temp, " G%d", gc_state.modal.plane_select + 17);
|
||||
strcat(modes_rpt, temp);
|
||||
sprintf(temp, " G%d", 21 - gc_state.modal.units);
|
||||
strcat(modes_rpt, temp);
|
||||
sprintf(temp, " G%d", gc_state.modal.distance + 90);
|
||||
strcat(modes_rpt, temp);
|
||||
sprintf(temp, " G%d", 94 - gc_state.modal.feed_rate);
|
||||
strcat(modes_rpt, temp);
|
||||
if (gc_state.modal.program_flow) {
|
||||
//report_util_gcode_modes_M();
|
||||
switch (gc_state.modal.program_flow) {
|
||||
case PROGRAM_FLOW_PAUSED:
|
||||
strcat(modes_rpt, " M0"); //serial_write('0'); break;
|
||||
// case PROGRAM_FLOW_OPTIONAL_STOP : serial_write('1'); break; // M1 is ignored and not supported.
|
||||
case PROGRAM_FLOW_COMPLETED_M2:
|
||||
case PROGRAM_FLOW_COMPLETED_M30:
|
||||
sprintf(temp, " M%d", gc_state.modal.program_flow);
|
||||
strcat(modes_rpt, temp);
|
||||
break;
|
||||
|
||||
switch (gc_state.modal.plane_select) {
|
||||
case Plane::XY: mode = " G17"; break;
|
||||
case Plane::ZX: mode = " G18"; break;
|
||||
case Plane::YZ: mode = " G19"; break;
|
||||
}
|
||||
strcat(modes_rpt, mode);
|
||||
|
||||
switch (gc_state.modal.units) {
|
||||
case Units::Inches: mode = " G20"; break;
|
||||
case Units::Mm: mode = " G21"; break;
|
||||
}
|
||||
strcat(modes_rpt, mode);
|
||||
|
||||
switch (gc_state.modal.distance) {
|
||||
case Distance::Absolute: mode = " G90"; break;
|
||||
case Distance::Incremental: mode = " G91"; break;
|
||||
}
|
||||
strcat(modes_rpt, mode);
|
||||
|
||||
#if 0
|
||||
switch (gc_state.modal.arc_distance) {
|
||||
case ArcDistance::Absolute: mode = " G90.1"; break;
|
||||
case ArcDistance::Incremental: mode = " G91.1"; break;
|
||||
}
|
||||
strcat(modes_rpt, mode);
|
||||
#endif
|
||||
|
||||
switch (gc_state.modal.feed_rate) {
|
||||
case FeedRate::UnitsPerMin: mode = " G94"; break;
|
||||
case FeedRate::InverseTime: mode = " G93"; break;
|
||||
}
|
||||
strcat(modes_rpt, mode);
|
||||
|
||||
//report_util_gcode_modes_M();
|
||||
switch (gc_state.modal.program_flow) {
|
||||
case ProgramFlow::Running: mode = ""; break;
|
||||
case ProgramFlow::Paused: mode = " M0"; break;
|
||||
case ProgramFlow::OptionalStop: mode = " M1"; break;
|
||||
case ProgramFlow::CompletedM2: mode = " M2"; break;
|
||||
case ProgramFlow::CompletedM30: mode = " M30"; break;
|
||||
}
|
||||
strcat(modes_rpt, mode);
|
||||
|
||||
switch (gc_state.modal.spindle) {
|
||||
case SpindleState::Cw: mode = " M3"; break;
|
||||
case SpindleState::Ccw: mode = " M4"; break;
|
||||
case SpindleState::Disable: mode = " M5"; break;
|
||||
default: mode = "";
|
||||
}
|
||||
strcat(modes_rpt, mode);
|
||||
|
||||
//report_util_gcode_modes_M(); // optional M7 and M8 should have been dealt with by here
|
||||
if (gc_state.modal.coolant == CoolantMode::Disable) {
|
||||
mode = " M9";
|
||||
} else {
|
||||
uint8_t coolant = static_cast<uint8_t>(gc_state.modal.coolant);
|
||||
// Note: Multiple coolant states may be active at the same time.
|
||||
if (coolant & static_cast<uint8_t>(CoolantMode::Mist)) {
|
||||
mode = " M7";
|
||||
}
|
||||
if (coolant & static_cast<uint8_t>(CoolantMode::Flood)) {
|
||||
mode = " M8";
|
||||
}
|
||||
}
|
||||
switch (gc_state.modal.spindle) {
|
||||
case SPINDLE_ENABLE_CW: strcat(modes_rpt, " M3"); break;
|
||||
case SPINDLE_ENABLE_CCW: strcat(modes_rpt, " M4"); break;
|
||||
case SPINDLE_DISABLE: strcat(modes_rpt, " M5"); break;
|
||||
}
|
||||
//report_util_gcode_modes_M(); // optional M7 and M8 should have been dealt with by here
|
||||
if (gc_state.modal.coolant) { // Note: Multiple coolant states may be active at the same time.
|
||||
if (gc_state.modal.coolant & PL_COND_FLAG_COOLANT_MIST)
|
||||
strcat(modes_rpt, " M7");
|
||||
if (gc_state.modal.coolant & PL_COND_FLAG_COOLANT_FLOOD)
|
||||
strcat(modes_rpt, " M8");
|
||||
} else
|
||||
strcat(modes_rpt, " M9");
|
||||
strcat(modes_rpt, mode);
|
||||
|
||||
#ifdef ENABLE_PARKING_OVERRIDE_CONTROL
|
||||
if (sys.override_ctrl == OVERRIDE_PARKING_MOTION)
|
||||
@@ -664,20 +706,21 @@ void report_realtime_status(uint8_t client) {
|
||||
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 cl_state = coolant_get_state();
|
||||
if (sp_state || cl_state) {
|
||||
SpindleState sp_state = spindle->get_state();
|
||||
CoolantMode coolant_state = coolant_get_state();
|
||||
if (sp_state != SpindleState::Disable || coolant_state != CoolantMode::Disable) {
|
||||
strcat(status, "|A:");
|
||||
if (sp_state) { // != SPINDLE_STATE_DISABLE
|
||||
if (sp_state == SPINDLE_STATE_CW)
|
||||
strcat(status, "S"); // CW
|
||||
else
|
||||
strcat(status, "C"); // CCW
|
||||
switch (sp_state) {
|
||||
case SpindleState::Disable: break;
|
||||
case SpindleState::Cw: strcat(status, "S"); break;
|
||||
case SpindleState::Ccw: strcat(status, "C"); break;
|
||||
}
|
||||
if (cl_state & COOLANT_STATE_FLOOD)
|
||||
|
||||
uint8_t coolant = static_cast<uint8_t>(coolant_state);
|
||||
if (coolant & static_cast<uint8_t>(CoolantMode::Flood))
|
||||
strcat(status, "F");
|
||||
# ifdef COOLANT_MIST_PIN // TODO Deal with M8 - Flood
|
||||
if (cl_state & COOLANT_STATE_MIST)
|
||||
if (coolant & static_cast<uint8_t>(CoolantMode::Mist))
|
||||
strcat(status, "M");
|
||||
# endif
|
||||
}
|
||||
|
@@ -104,31 +104,31 @@ namespace Spindles {
|
||||
return rpm;
|
||||
}
|
||||
/*
|
||||
void _10v::set_state(uint8_t state, uint32_t rpm) {
|
||||
void _10v::set_state(SpindleState state, uint32_t rpm) {
|
||||
if (sys.abort)
|
||||
return; // Block during abort.
|
||||
|
||||
if (state == SPINDLE_DISABLE) { // Halt or set spindle direction and rpm.
|
||||
if (state == SpindleState::Disable) { // Halt or set spindle direction and rpm.
|
||||
sys.spindle_speed = 0;
|
||||
stop();
|
||||
} else {
|
||||
set_dir_pin(state == SPINDLE_ENABLE_CW);
|
||||
set_dir_pin(state == SpindleState:Cw);
|
||||
set_rpm(rpm);
|
||||
}
|
||||
|
||||
set_enable_pin(state != SPINDLE_DISABLE);
|
||||
set_enable_pin(state != SpindleState::Disable);
|
||||
|
||||
sys.report_ovr_counter = 0; // Set to report change immediately
|
||||
}
|
||||
|
||||
*/
|
||||
|
||||
uint8_t _10v::get_state() {
|
||||
SpindleState _10v::get_state() {
|
||||
if (_current_pwm_duty == 0 || _output_pin == UNDEFINED_PIN)
|
||||
return (SPINDLE_STATE_DISABLE);
|
||||
return (SpindleState::Disable);
|
||||
if (_direction_pin != UNDEFINED_PIN)
|
||||
return digitalRead(_direction_pin) ? SPINDLE_STATE_CW : SPINDLE_STATE_CCW;
|
||||
return (SPINDLE_STATE_CW);
|
||||
return digitalRead(_direction_pin) ? SpindleState::Cw : SpindleState::Ccw;
|
||||
return (SpindleState::Cw);
|
||||
}
|
||||
|
||||
void _10v::stop() {
|
||||
@@ -142,7 +142,6 @@ namespace Spindles {
|
||||
if (_off_with_zero_speed && sys.spindle_speed == 0)
|
||||
enable = false;
|
||||
|
||||
|
||||
if (spindle_enable_invert->get())
|
||||
enable = !enable;
|
||||
|
||||
|
@@ -41,10 +41,10 @@ namespace Spindles {
|
||||
void init() override;
|
||||
void config_message() override;
|
||||
uint32_t set_rpm(uint32_t rpm) override;
|
||||
//void set_state(uint8_t state, uint32_t rpm);
|
||||
//void set_state(SpindleState state, uint32_t rpm);
|
||||
|
||||
uint8_t get_state() override;
|
||||
void stop() override;
|
||||
SpindleState get_state() override;
|
||||
void stop() override;
|
||||
|
||||
virtual ~_10v() {}
|
||||
|
||||
|
@@ -41,7 +41,7 @@ namespace Spindles {
|
||||
uart.stop_bits = UART_STOP_BITS_1;
|
||||
}
|
||||
|
||||
void H2A::direction_command(uint8_t mode, ModbusCommand& data) {
|
||||
void H2A::direction_command(SpindleState mode, ModbusCommand& data) {
|
||||
// NOTE: data length is excluding the CRC16 checksum.
|
||||
data.tx_length = 6;
|
||||
data.rx_length = 6;
|
||||
@@ -50,7 +50,7 @@ namespace Spindles {
|
||||
data.msg[2] = 0x20; // Command ID 0x2000
|
||||
data.msg[3] = 0x00;
|
||||
data.msg[4] = 0x00;
|
||||
data.msg[5] = (mode == SPINDLE_ENABLE_CCW) ? 0x02 : (mode == SPINDLE_ENABLE_CW ? 0x01 : 0x06);
|
||||
data.msg[5] = (mode == SpindleState::Ccw) ? 0x02 : (mode == SpindleState::Cw ? 0x01 : 0x06);
|
||||
}
|
||||
|
||||
void H2A::set_speed_command(uint32_t rpm, ModbusCommand& data) {
|
||||
|
@@ -26,7 +26,7 @@ namespace Spindles {
|
||||
protected:
|
||||
void default_modbus_settings(uart_config_t& uart) override;
|
||||
|
||||
void direction_command(uint8_t mode, ModbusCommand& data) override;
|
||||
void direction_command(SpindleState mode, ModbusCommand& data) override;
|
||||
void set_speed_command(uint32_t rpm, ModbusCommand& data) override;
|
||||
|
||||
response_parser get_max_rpm(ModbusCommand& data) override;
|
||||
|
@@ -120,7 +120,7 @@ namespace Spindles {
|
||||
// Baud rate is set in the PD164 setting.
|
||||
}
|
||||
|
||||
void Huanyang::direction_command(uint8_t mode, ModbusCommand& data) {
|
||||
void Huanyang::direction_command(SpindleState mode, ModbusCommand& data) {
|
||||
// NOTE: data length is excluding the CRC16 checksum.
|
||||
data.tx_length = 4;
|
||||
data.rx_length = 4;
|
||||
@@ -130,9 +130,9 @@ namespace Spindles {
|
||||
data.msg[2] = 0x01;
|
||||
|
||||
switch (mode) {
|
||||
case SPINDLE_ENABLE_CW: data.msg[3] = 0x01; break;
|
||||
case SPINDLE_ENABLE_CCW: data.msg[3] = 0x11; break;
|
||||
default: // SPINDLE_DISABLE
|
||||
case SpindleState::Cw: data.msg[3] = 0x01; break;
|
||||
case SpindleState::Ccw: data.msg[3] = 0x11; break;
|
||||
default: // SpindleState::Disable
|
||||
data.msg[3] = 0x08;
|
||||
break;
|
||||
}
|
||||
|
@@ -30,7 +30,7 @@ namespace Spindles {
|
||||
protected:
|
||||
void default_modbus_settings(uart_config_t& uart) override;
|
||||
|
||||
void direction_command(uint8_t mode, ModbusCommand& data) override;
|
||||
void direction_command(SpindleState mode, ModbusCommand& data) override;
|
||||
void set_speed_command(uint32_t rpm, ModbusCommand& data) override;
|
||||
|
||||
response_parser get_status_ok(ModbusCommand& data) override;
|
||||
|
@@ -34,11 +34,11 @@ namespace Spindles {
|
||||
sys.spindle_speed = rpm;
|
||||
return rpm;
|
||||
}
|
||||
void Null::set_state(uint8_t state, uint32_t rpm) {
|
||||
void Null::set_state(SpindleState state, uint32_t rpm) {
|
||||
_current_state = state;
|
||||
sys.spindle_speed = rpm;
|
||||
}
|
||||
uint8_t Null::get_state() { return _current_state; }
|
||||
void Null::stop() {}
|
||||
void Null::config_message() { grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "No spindle"); }
|
||||
SpindleState Null::get_state() { return _current_state; }
|
||||
void Null::stop() {}
|
||||
void Null::config_message() { grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "No spindle"); }
|
||||
}
|
||||
|
@@ -35,12 +35,12 @@ namespace Spindles {
|
||||
Null& operator=(const Null&) = delete;
|
||||
Null& operator=(Null&&) = delete;
|
||||
|
||||
void init() override;
|
||||
uint32_t set_rpm(uint32_t rpm) override;
|
||||
void set_state(uint8_t state, uint32_t rpm) override;
|
||||
uint8_t get_state() override;
|
||||
void stop() override;
|
||||
void config_message() override;
|
||||
void init() override;
|
||||
uint32_t set_rpm(uint32_t rpm) override;
|
||||
void set_state(SpindleState state, uint32_t rpm) override;
|
||||
SpindleState get_state() override;
|
||||
void stop() override;
|
||||
void config_message() override;
|
||||
|
||||
virtual ~Null() {}
|
||||
};
|
||||
|
@@ -140,19 +140,19 @@ namespace Spindles {
|
||||
pwm_value = map_uint32_t(rpm, _min_rpm, _max_rpm, _pwm_min_value, _pwm_max_value);
|
||||
}
|
||||
|
||||
set_enable_pin(_current_state != SPINDLE_DISABLE);
|
||||
set_enable_pin(_current_state != SpindleState::Disable);
|
||||
set_output(pwm_value);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
void PWM::set_state(uint8_t state, uint32_t rpm) {
|
||||
void PWM::set_state(SpindleState state, uint32_t rpm) {
|
||||
if (sys.abort)
|
||||
return; // Block during abort.
|
||||
|
||||
_current_state = state;
|
||||
|
||||
if (_current_state == SPINDLE_DISABLE) { // Halt or set spindle direction and rpm.
|
||||
if (_current_state == SpindleState::Disable) { // Halt or set spindle direction and rpm.
|
||||
sys.spindle_speed = 0;
|
||||
stop();
|
||||
if (use_delays && (_current_state != state)) {
|
||||
@@ -161,9 +161,9 @@ namespace Spindles {
|
||||
//grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "SpinDown Done");
|
||||
}
|
||||
} else {
|
||||
set_dir_pin(_current_state == SPINDLE_ENABLE_CW);
|
||||
set_dir_pin(_current_state == SpindleState::Cw);
|
||||
set_rpm(rpm);
|
||||
set_enable_pin(_current_state != SPINDLE_DISABLE); // must be done after setting rpm for enable features to work
|
||||
set_enable_pin(_current_state != SpindleState::Disable); // must be done after setting rpm for enable features to work
|
||||
if (use_delays && (_current_state != state)) {
|
||||
//grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "SpinUp Start %d", rpm);
|
||||
mc_dwell(spindle_delay_spinup->get());
|
||||
@@ -176,12 +176,12 @@ namespace Spindles {
|
||||
sys.report_ovr_counter = 0; // Set to report change immediately
|
||||
}
|
||||
|
||||
uint8_t PWM::get_state() {
|
||||
SpindleState PWM::get_state() {
|
||||
if (_current_pwm_duty == 0 || _output_pin == UNDEFINED_PIN)
|
||||
return (SPINDLE_STATE_DISABLE);
|
||||
return (SpindleState::Disable);
|
||||
if (_direction_pin != UNDEFINED_PIN)
|
||||
return digitalRead(_direction_pin) ? SPINDLE_STATE_CW : SPINDLE_STATE_CCW;
|
||||
return (SPINDLE_STATE_CW);
|
||||
return digitalRead(_direction_pin) ? SpindleState::Cw : SpindleState::Ccw;
|
||||
return (SpindleState::Cw);
|
||||
}
|
||||
|
||||
void PWM::stop() {
|
||||
|
@@ -36,8 +36,8 @@ namespace Spindles {
|
||||
|
||||
void init() override;
|
||||
virtual uint32_t set_rpm(uint32_t rpm) override;
|
||||
void set_state(uint8_t state, uint32_t rpm) override;
|
||||
uint8_t get_state() override;
|
||||
void set_state(SpindleState state, uint32_t rpm) override;
|
||||
SpindleState get_state() override;
|
||||
void stop() override;
|
||||
void config_message() override;
|
||||
|
||||
@@ -66,7 +66,7 @@ namespace Spindles {
|
||||
virtual void set_output(uint32_t duty);
|
||||
virtual void set_enable_pin(bool enable_pin);
|
||||
|
||||
void get_pins_and_settings();
|
||||
uint8_t calc_pwm_precision(uint32_t freq);
|
||||
void get_pins_and_settings();
|
||||
uint8_t calc_pwm_precision(uint32_t freq);
|
||||
};
|
||||
}
|
||||
|
@@ -75,9 +75,10 @@ namespace Spindles {
|
||||
return false; // default for basic spindle is false
|
||||
}
|
||||
|
||||
void Spindle::sync(uint8_t state, uint32_t rpm) {
|
||||
if (sys.state == STATE_CHECK_MODE)
|
||||
void Spindle::sync(SpindleState state, uint32_t rpm) {
|
||||
if (sys.state == STATE_CHECK_MODE) {
|
||||
return;
|
||||
}
|
||||
protocol_buffer_synchronize(); // Empty planner buffer to ensure spindle is set when programmed.
|
||||
set_state(state, rpm);
|
||||
}
|
||||
|
@@ -26,10 +26,6 @@
|
||||
|
||||
*/
|
||||
|
||||
#define SPINDLE_STATE_DISABLE 0 // Must be zero.
|
||||
#define SPINDLE_STATE_CW bit(4) // matches PL_COND_FLAG_SPINDLE_CW
|
||||
#define SPINDLE_STATE_CCW bit(5) // matches PL_COND_FLAG_SPINDLE_CCW
|
||||
|
||||
#define SPINDLE_TYPE_NONE 0
|
||||
#define SPINDLE_TYPE_PWM 1
|
||||
#define SPINDLE_TYPE_RELAY 2
|
||||
@@ -58,20 +54,20 @@ namespace Spindles {
|
||||
Spindle& operator=(const Spindle&) = delete;
|
||||
Spindle& operator=(Spindle&&) = delete;
|
||||
|
||||
virtual void init() = 0; // not in constructor because this also gets called when $$ settings change
|
||||
virtual uint32_t set_rpm(uint32_t rpm) = 0;
|
||||
virtual void set_state(uint8_t state, uint32_t rpm) = 0;
|
||||
virtual uint8_t get_state() = 0;
|
||||
virtual void stop() = 0;
|
||||
virtual void config_message() = 0;
|
||||
virtual bool isRateAdjusted();
|
||||
virtual void sync(uint8_t state, uint32_t rpm);
|
||||
virtual void init() = 0; // not in constructor because this also gets called when $$ settings change
|
||||
virtual uint32_t set_rpm(uint32_t rpm) = 0;
|
||||
virtual void set_state(SpindleState state, uint32_t rpm) = 0;
|
||||
virtual SpindleState get_state() = 0;
|
||||
virtual void stop() = 0;
|
||||
virtual void config_message() = 0;
|
||||
virtual bool isRateAdjusted();
|
||||
virtual void sync(SpindleState state, uint32_t rpm);
|
||||
|
||||
virtual ~Spindle() {}
|
||||
|
||||
bool is_reversable;
|
||||
bool use_delays; // will SpinUp and SpinDown delays be used.
|
||||
volatile uint8_t _current_state = SPINDLE_DISABLE;
|
||||
bool is_reversable;
|
||||
bool use_delays; // will SpinUp and SpinDown delays be used.
|
||||
volatile SpindleState _current_state = SpindleState::Disable;
|
||||
|
||||
static void select();
|
||||
};
|
||||
|
@@ -283,7 +283,7 @@ namespace Spindles {
|
||||
|
||||
// Initially we initialize this to 0; over time, we might poll better information from the VFD.
|
||||
_current_rpm = 0;
|
||||
_current_state = SPINDLE_DISABLE;
|
||||
_current_state = SpindleState::Disable;
|
||||
|
||||
config_message();
|
||||
}
|
||||
@@ -335,17 +335,17 @@ namespace Spindles {
|
||||
pinName(_rts_pin).c_str());
|
||||
}
|
||||
|
||||
void VFD::set_state(uint8_t state, uint32_t rpm) {
|
||||
void VFD::set_state(SpindleState state, uint32_t rpm) {
|
||||
if (sys.abort) {
|
||||
return; // Block during abort.
|
||||
}
|
||||
|
||||
bool critical = (sys.state == STATE_CYCLE || state != SPINDLE_DISABLE);
|
||||
bool critical = (sys.state == STATE_CYCLE || state != SpindleState::Disable);
|
||||
|
||||
if (_current_state != state) { // already at the desired state. This function gets called a lot.
|
||||
set_mode(state, critical); // critical if we are in a job
|
||||
set_rpm(rpm);
|
||||
if (state == SPINDLE_DISABLE) {
|
||||
if (state == SpindleState::Disable) {
|
||||
sys.spindle_speed = 0;
|
||||
if (_current_state != state) {
|
||||
mc_dwell(spindle_delay_spindown->get());
|
||||
@@ -368,7 +368,7 @@ namespace Spindles {
|
||||
return;
|
||||
}
|
||||
|
||||
bool VFD::set_mode(uint8_t mode, bool critical) {
|
||||
bool VFD::set_mode(SpindleState mode, bool critical) {
|
||||
if (!vfd_ok) {
|
||||
return false;
|
||||
}
|
||||
@@ -378,7 +378,7 @@ namespace Spindles {
|
||||
|
||||
direction_command(mode, mode_cmd);
|
||||
|
||||
if (mode == SPINDLE_DISABLE) {
|
||||
if (mode == SpindleState::Disable) {
|
||||
if (!xQueueReset(vfd_cmd_queue)) {
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "VFD spindle off, queue could not be reset");
|
||||
}
|
||||
@@ -437,10 +437,10 @@ namespace Spindles {
|
||||
return rpm;
|
||||
}
|
||||
|
||||
void VFD::stop() { set_mode(SPINDLE_DISABLE, false); }
|
||||
void VFD::stop() { set_mode(SpindleState::Disable, false); }
|
||||
|
||||
// state is cached rather than read right now to prevent delays
|
||||
uint8_t VFD::get_state() { return _current_state; }
|
||||
SpindleState VFD::get_state() { return _current_state; }
|
||||
|
||||
// Calculate the CRC on all of the byte except the last 2
|
||||
// It then added the CRC to those last 2 bytes
|
||||
|
@@ -27,9 +27,9 @@ namespace Spindles {
|
||||
class VFD : public Spindle {
|
||||
private:
|
||||
static const int VFD_RS485_MAX_MSG_SIZE = 16; // more than enough for a modbus message
|
||||
static const int MAX_RETRIES = 3; // otherwise the spindle is marked 'unresponsive'
|
||||
static const int MAX_RETRIES = 3; // otherwise the spindle is marked 'unresponsive'
|
||||
|
||||
bool set_mode(uint8_t mode, bool critical);
|
||||
bool set_mode(SpindleState mode, bool critical);
|
||||
bool get_pins_and_settings();
|
||||
|
||||
uint8_t _txd_pin;
|
||||
@@ -48,7 +48,7 @@ namespace Spindles {
|
||||
|
||||
protected:
|
||||
struct ModbusCommand {
|
||||
bool critical; // TODO SdB: change into `uint8_t critical : 1;`: We want more flags...
|
||||
bool critical; // TODO SdB: change into `uint8_t critical : 1;`: We want more flags...
|
||||
|
||||
uint8_t tx_length;
|
||||
uint8_t rx_length;
|
||||
@@ -58,8 +58,8 @@ namespace Spindles {
|
||||
virtual void default_modbus_settings(uart_config_t& uart);
|
||||
|
||||
// Commands:
|
||||
virtual void direction_command(uint8_t mode, ModbusCommand& data) = 0;
|
||||
virtual void set_speed_command(uint32_t rpm, ModbusCommand& data) = 0;
|
||||
virtual void direction_command(SpindleState mode, ModbusCommand& data) = 0;
|
||||
virtual void set_speed_command(uint32_t rpm, ModbusCommand& data) = 0;
|
||||
|
||||
// Commands that return the status. Returns nullptr if unavailable by this VFD (default):
|
||||
using response_parser = bool (*)(const uint8_t* response, VFD* spindle);
|
||||
@@ -76,17 +76,17 @@ namespace Spindles {
|
||||
VFD& operator=(const VFD&) = delete;
|
||||
VFD& operator=(VFD&&) = delete;
|
||||
|
||||
// TODO FIXME: Have to make these public because of the parsers.
|
||||
// TODO FIXME: Have to make these public because of the parsers.
|
||||
// Should hide them and use a member function.
|
||||
volatile uint32_t _min_rpm;
|
||||
volatile uint32_t _max_rpm;
|
||||
|
||||
void init();
|
||||
void config_message();
|
||||
void set_state(uint8_t state, uint32_t rpm);
|
||||
uint8_t get_state();
|
||||
uint32_t set_rpm(uint32_t rpm);
|
||||
void stop();
|
||||
void init();
|
||||
void config_message();
|
||||
void set_state(SpindleState state, uint32_t rpm);
|
||||
SpindleState get_state();
|
||||
uint32_t set_rpm(uint32_t rpm);
|
||||
void stop();
|
||||
|
||||
virtual ~VFD() {}
|
||||
};
|
||||
|
@@ -502,8 +502,8 @@ void st_reset() {
|
||||
segment_buffer_head = 0; // empty = tail
|
||||
segment_next_head = 1;
|
||||
busy = false;
|
||||
st.step_outbits = 0;
|
||||
st.dir_outbits = dir_invert_mask->get(); // Initialize direction bits to default.
|
||||
st.step_outbits = 0;
|
||||
st.dir_outbits = dir_invert_mask->get(); // Initialize direction bits to default.
|
||||
// TODO do we need to turn step pins off?
|
||||
}
|
||||
|
||||
@@ -834,7 +834,7 @@ void st_prep_buffer() {
|
||||
prep.current_speed = sqrt(pl_block->entry_speed_sqr);
|
||||
|
||||
if (spindle->isRateAdjusted()) { // laser_mode->get() {
|
||||
if (pl_block->condition & PL_COND_FLAG_SPINDLE_CCW) {
|
||||
if (pl_block->spindle == SpindleState::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;
|
||||
@@ -1034,7 +1034,7 @@ void st_prep_buffer() {
|
||||
Compute spindle speed PWM output for step segment
|
||||
*/
|
||||
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)) {
|
||||
if (pl_block->spindle != SpindleState::Disable) {
|
||||
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) {
|
||||
|
665
Grbl_Esp32/src/tests/parser-result.txt
Normal file
665
Grbl_Esp32/src/tests/parser-result.txt
Normal file
@@ -0,0 +1,665 @@
|
||||
ets Jul 29 2019 12:21:46
|
||||
|
||||
rst:0x1 (POWERON_RESET),boot:0x13 (SPI_FAST_FLASH_BOOT)
|
||||
configsip: 0, SPIWP:0xee
|
||||
clk_drv:0x00,q_drv:0x00,d_drv:0x00,cs0_drv:0x00,hd_drv:0x00,wp_drv:0x00
|
||||
mode:DIO, clock div:1
|
||||
load:0x3fff0018,len:4
|
||||
load:0x3fff001c,len:1216
|
||||
ho 0 tail 12 room 4
|
||||
load:0x40078000,len:9720
|
||||
ho 0 tail 12 room 4
|
||||
load:0x40080400,len:6352
|
||||
entry 0x400806b8
|
||||
|
||||
[MSG:Grbl_ESP32 Ver 1.3a Date 20200831]
|
||||
[MSG:Compiled with ESP32 SDK:v3.2.3-14-gd3e562907]
|
||||
[MSG:Using machine:Test Drive - Demo Only No I/O!]
|
||||
[MSG:Axis count 3]
|
||||
[MSG:Timed Steps]
|
||||
[MSG:Init Motors]
|
||||
[MSG:No spindle]
|
||||
|
||||
[MSG:Client Started]
|
||||
[MSG:Connecting OpenWrt-Bradley]
|
||||
[MSG:Connecting.]
|
||||
[MSG:Connecting..]
|
||||
[MSG:Connecting...]
|
||||
[MSG:Connected with 192.168.2.198]
|
||||
[MSG:Start mDNS with hostname:http://grblesp.local/]
|
||||
[MSG:SSDP Started]
|
||||
[MSG:HTTP Started]
|
||||
[MSG:TELNET Started 23]
|
||||
|
||||
Grbl 1.3a ['$' for help]
|
||||
; paste with a terminal emulator with a 200 ms delay between lines
|
||||
ok
|
||||
$rst=gcode
|
||||
ok
|
||||
$rst=#
|
||||
ok
|
||||
$#
|
||||
[G54:0.000,0.000,0.000]
|
||||
[G55:0.000,0.000,0.000]
|
||||
[G56:0.000,0.000,0.000]
|
||||
[G57:0.000,0.000,0.000]
|
||||
[G58:0.000,0.000,0.000]
|
||||
[G59:0.000,0.000,0.000]
|
||||
[G28:0.000,0.000,0.000]
|
||||
[G30:0.000,0.000,0.000]
|
||||
[G92:0.000,0.000,0.000]
|
||||
[TLO:0.000]
|
||||
[PRB:0.000,0.000,0.000:0]
|
||||
ok
|
||||
g10 l2 p0 x0 y0 z0
|
||||
ok
|
||||
g10 l2 p1 x0 y0 z0
|
||||
ok
|
||||
g10 l2 p2 x0 y0 z0
|
||||
ok
|
||||
g10 l2 p3 x0 y0 z0
|
||||
ok
|
||||
g10 l2 p4 x0 y0 z0
|
||||
ok
|
||||
g10 l2 p5 x0 y0 z0
|
||||
ok
|
||||
g10 l2 p6 x0 y0 z0
|
||||
ok
|
||||
?
|
||||
<Idle|MPos:0.000,0.000,0.000|FS:0,0|WCO:0.000,0.000,0.000>
|
||||
ok
|
||||
g0 x0 y0 z0
|
||||
ok
|
||||
?
|
||||
<Idle|MPos:0.000,0.000,0.000|FS:0,0|Ov:100,100,100>
|
||||
ok
|
||||
G0
|
||||
ok
|
||||
G0 X1
|
||||
ok
|
||||
G0 I1
|
||||
error:36
|
||||
$G
|
||||
[GC:G0 G54 G17 G21 G90 G94 M5 M9 T0 F0 S0]
|
||||
ok
|
||||
G1
|
||||
error:22
|
||||
G1 Z10
|
||||
error:22
|
||||
$G
|
||||
[GC:G0 G54 G17 G21 G90 G94 M5 M9 T0 F0 S0]
|
||||
ok
|
||||
F1000
|
||||
ok
|
||||
$G
|
||||
[GC:G0 G54 G17 G21 G90 G94 M5 M9 T0 F1000 S0]
|
||||
ok
|
||||
G1 I1
|
||||
error:36
|
||||
G2
|
||||
error:26
|
||||
G2 X0 Y0 I-1 J-1
|
||||
error:33
|
||||
$g
|
||||
[GC:G0 G54 G17 G21 G90 G94 M5 M9 T0 F1000 S0]
|
||||
ok
|
||||
G3
|
||||
error:26
|
||||
G3 X0 Y0 I-1 J-1
|
||||
error:33
|
||||
$g
|
||||
[GC:G0 G54 G17 G21 G90 G94 M5 M9 T0 F1000 S0]
|
||||
ok
|
||||
g4
|
||||
error:28
|
||||
g4 p0
|
||||
ok
|
||||
g4.1
|
||||
error:23
|
||||
g4.2
|
||||
error:23
|
||||
g5
|
||||
error:20
|
||||
g6
|
||||
error:20
|
||||
g7
|
||||
error:20
|
||||
g8
|
||||
error:20
|
||||
g9
|
||||
error:20
|
||||
g10
|
||||
error:26
|
||||
g10 l1
|
||||
error:26
|
||||
g10 l2
|
||||
error:26
|
||||
g10 l2 p0
|
||||
error:26
|
||||
g10 l2 p0 x1 y2 z3
|
||||
ok
|
||||
g10 l2 p2 x2 y3 z4
|
||||
ok
|
||||
g10 l2 p6 x3 y4 z5
|
||||
ok
|
||||
$#
|
||||
[G54:1.000,2.000,3.000]
|
||||
[G55:2.000,3.000,4.000]
|
||||
[G56:0.000,0.000,0.000]
|
||||
[G57:0.000,0.000,0.000]
|
||||
[G58:0.000,0.000,0.000]
|
||||
[G59:3.000,4.000,5.000]
|
||||
[G28:0.000,0.000,0.000]
|
||||
[G30:0.000,0.000,0.000]
|
||||
[G92:0.000,0.000,0.000]
|
||||
[TLO:0.000]
|
||||
[PRB:0.000,0.000,0.000:0]
|
||||
ok
|
||||
g10 l2 p6 x3 y4 z5 r1
|
||||
error:20
|
||||
g10 l2 p7 x5 y4 z3
|
||||
error:29
|
||||
g10 l20 p0 x5 y4 z3
|
||||
ok
|
||||
$#
|
||||
[G54:-4.000,-4.000,-3.000]
|
||||
[G55:2.000,3.000,4.000]
|
||||
[G56:0.000,0.000,0.000]
|
||||
[G57:0.000,0.000,0.000]
|
||||
[G58:0.000,0.000,0.000]
|
||||
[G59:3.000,4.000,5.000]
|
||||
[G28:0.000,0.000,0.000]
|
||||
[G30:0.000,0.000,0.000]
|
||||
[G92:0.000,0.000,0.000]
|
||||
[TLO:0.000]
|
||||
[PRB:0.000,0.000,0.000:0]
|
||||
ok
|
||||
g10 l20 p6 x5 y4 z3
|
||||
ok
|
||||
$#
|
||||
[G54:-4.000,-4.000,-3.000]
|
||||
[G55:2.000,3.000,4.000]
|
||||
[G56:0.000,0.000,0.000]
|
||||
[G57:0.000,0.000,0.000]
|
||||
[G58:0.000,0.000,0.000]
|
||||
[G59:-4.000,-4.000,-3.000]
|
||||
[G28:0.000,0.000,0.000]
|
||||
[G30:0.000,0.000,0.000]
|
||||
[G92:0.000,0.000,0.000]
|
||||
[TLO:0.000]
|
||||
[PRB:0.000,0.000,0.000:0]
|
||||
ok
|
||||
g10 l20 p7 x5 y4 z3
|
||||
error:29
|
||||
g10 l20 p7 x5 y4 z3
|
||||
error:29
|
||||
g11
|
||||
error:20
|
||||
g12
|
||||
error:20
|
||||
g13
|
||||
error:20
|
||||
g13
|
||||
error:20
|
||||
g14
|
||||
error:20
|
||||
g15
|
||||
error:20
|
||||
g16
|
||||
error:20
|
||||
|
||||
ok
|
||||
g17
|
||||
ok
|
||||
$g
|
||||
[GC:G0 G54 G17 G21 G90 G94 M5 M9 T0 F1000 S0]
|
||||
ok
|
||||
g18
|
||||
ok
|
||||
$g
|
||||
[GC:G0 G54 G18 G21 G90 G94 M5 M9 T0 F1000 S0]
|
||||
ok
|
||||
g19
|
||||
ok
|
||||
$g
|
||||
[GC:G0 G54 G19 G21 G90 G94 M5 M9 T0 F1000 S0]
|
||||
ok
|
||||
g17
|
||||
ok
|
||||
|
||||
ok
|
||||
g20
|
||||
ok
|
||||
$g
|
||||
[GC:G0 G54 G17 G20 G90 G94 M5 M9 T0 F1000 S0]
|
||||
ok
|
||||
g21
|
||||
ok
|
||||
$g
|
||||
[GC:G0 G54 G17 G21 G90 G94 M5 M9 T0 F1000 S0]
|
||||
ok
|
||||
|
||||
ok
|
||||
g22
|
||||
error:20
|
||||
g23
|
||||
error:20
|
||||
g24
|
||||
error:20
|
||||
g25
|
||||
error:20
|
||||
g26
|
||||
error:20
|
||||
g27
|
||||
error:20
|
||||
|
||||
ok
|
||||
g28
|
||||
ok
|
||||
g28 x3
|
||||
ok
|
||||
$#
|
||||
error:8
|
||||
g28.1
|
||||
ok
|
||||
g28.1 x3
|
||||
ok
|
||||
g28.2
|
||||
error:20
|
||||
g29
|
||||
error:20
|
||||
g30 y1
|
||||
ok
|
||||
$#
|
||||
error:8
|
||||
g30.1
|
||||
ok
|
||||
g30.1 y2
|
||||
ok
|
||||
g30.2
|
||||
error:20
|
||||
|
||||
ok
|
||||
g31
|
||||
error:20
|
||||
g32
|
||||
error:20
|
||||
g33
|
||||
error:20
|
||||
g34
|
||||
error:20
|
||||
g35
|
||||
error:20
|
||||
g36
|
||||
error:20
|
||||
g37
|
||||
error:20
|
||||
g38
|
||||
[MSG:No probe pin defined]
|
||||
error:20
|
||||
g39
|
||||
error:20
|
||||
|
||||
ok
|
||||
g40
|
||||
ok
|
||||
|
||||
ok
|
||||
g41
|
||||
error:20
|
||||
g42
|
||||
error:20
|
||||
|
||||
ok
|
||||
g43
|
||||
error:20
|
||||
g43.1 x0
|
||||
error:37
|
||||
g43.1 z2
|
||||
ok
|
||||
$#
|
||||
[G54:-4.000,-4.000,-3.000]
|
||||
[G55:2.000,3.000,4.000]
|
||||
[G56:0.000,0.000,0.000]
|
||||
[G57:0.000,0.000,0.000]
|
||||
[G58:0.000,0.000,0.000]
|
||||
[G59:-4.000,-4.000,-3.000]
|
||||
[G28:0.000,0.000,0.000]
|
||||
[G30:-1.000,0.000,0.000]
|
||||
[G92:0.000,0.000,0.000]
|
||||
[TLO:2.000]
|
||||
[PRB:0.000,0.000,0.000:0]
|
||||
ok
|
||||
|
||||
ok
|
||||
g44
|
||||
error:20
|
||||
g45
|
||||
error:20
|
||||
g46
|
||||
error:20
|
||||
g47
|
||||
error:20
|
||||
g48
|
||||
error:20
|
||||
|
||||
ok
|
||||
g49
|
||||
ok
|
||||
$#
|
||||
[G54:-4.000,-4.000,-3.000]
|
||||
[G55:2.000,3.000,4.000]
|
||||
[G56:0.000,0.000,0.000]
|
||||
[G57:0.000,0.000,0.000]
|
||||
[G58:0.000,0.000,0.000]
|
||||
[G59:-4.000,-4.000,-3.000]
|
||||
[G28:0.000,0.000,0.000]
|
||||
[G30:-1.000,0.000,0.000]
|
||||
[G92:0.000,0.000,0.000]
|
||||
[TLO:0.000]
|
||||
[PRB:0.000,0.000,0.000:0]
|
||||
ok
|
||||
g49.1
|
||||
ok
|
||||
|
||||
ok
|
||||
g50
|
||||
error:20
|
||||
g51
|
||||
error:20
|
||||
g52
|
||||
error:20
|
||||
g53
|
||||
ok
|
||||
g53 g0 x1
|
||||
ok
|
||||
g53.1
|
||||
error:23
|
||||
|
||||
ok
|
||||
g54
|
||||
ok
|
||||
$g
|
||||
[GC:G0 G54 G17 G21 G90 G94 M5 M9 T0 F1000 S0]
|
||||
ok
|
||||
g55
|
||||
ok
|
||||
$g
|
||||
[GC:G0 G55 G17 G21 G90 G94 M5 M9 T0 F1000 S0]
|
||||
ok
|
||||
g56
|
||||
ok
|
||||
$g
|
||||
[GC:G0 G56 G17 G21 G90 G94 M5 M9 T0 F1000 S0]
|
||||
ok
|
||||
g57
|
||||
ok
|
||||
$g
|
||||
[GC:G0 G57 G17 G21 G90 G94 M5 M9 T0 F1000 S0]
|
||||
ok
|
||||
g58
|
||||
ok
|
||||
$g
|
||||
[GC:G0 G58 G17 G21 G90 G94 M5 M9 T0 F1000 S0]
|
||||
ok
|
||||
g59 g0 x1
|
||||
ok
|
||||
$g
|
||||
[GC:G0 G59 G17 G21 G90 G94 M5 M9 T0 F1000 S0]
|
||||
ok
|
||||
|
||||
ok
|
||||
g60
|
||||
error:20
|
||||
|
||||
ok
|
||||
g61
|
||||
ok
|
||||
g61.1
|
||||
error:20
|
||||
|
||||
ok
|
||||
g62
|
||||
error:20
|
||||
g63
|
||||
error:20
|
||||
g64
|
||||
error:20
|
||||
g65
|
||||
error:20
|
||||
g66
|
||||
error:20
|
||||
g67
|
||||
error:20
|
||||
g68
|
||||
error:20
|
||||
g69
|
||||
error:20
|
||||
g70
|
||||
error:20
|
||||
g71
|
||||
error:20
|
||||
g72
|
||||
error:20
|
||||
g73
|
||||
error:20
|
||||
g74
|
||||
error:20
|
||||
g75
|
||||
error:20
|
||||
g76
|
||||
error:20
|
||||
g77
|
||||
error:20
|
||||
g78
|
||||
error:20
|
||||
g79
|
||||
error:20
|
||||
|
||||
ok
|
||||
g80
|
||||
ok
|
||||
$g
|
||||
[GC:G80 G59 G17 G21 G90 G94 M5 M9 T0 F1000 S0]
|
||||
ok
|
||||
x1
|
||||
error:31
|
||||
g0 x1
|
||||
ok
|
||||
$g
|
||||
[GC:G0 G59 G17 G21 G90 G94 M5 M9 T0 F1000 S0]
|
||||
ok
|
||||
|
||||
ok
|
||||
g81
|
||||
error:20
|
||||
g82
|
||||
error:20
|
||||
g83
|
||||
error:20
|
||||
g84
|
||||
error:20
|
||||
g85
|
||||
error:20
|
||||
g86
|
||||
error:20
|
||||
g87
|
||||
error:20
|
||||
g88
|
||||
error:20
|
||||
g89
|
||||
error:20
|
||||
|
||||
ok
|
||||
g90
|
||||
ok
|
||||
$g
|
||||
[GC:G0 G59 G17 G21 G90 G94 M5 M9 T0 F1000 S0]
|
||||
ok
|
||||
g90.1
|
||||
error:20
|
||||
g91
|
||||
ok
|
||||
$g
|
||||
[GC:G0 G59 G17 G21 G91 G94 M5 M9 T0 F1000 S0]
|
||||
ok
|
||||
g91.1
|
||||
ok
|
||||
|
||||
ok
|
||||
g92
|
||||
error:26
|
||||
g92 z1
|
||||
ok
|
||||
$#
|
||||
[G54:-4.000,-4.000,-3.000]
|
||||
[G55:2.000,3.000,4.000]
|
||||
[G56:0.000,0.000,0.000]
|
||||
[G57:0.000,0.000,0.000]
|
||||
[G58:0.000,0.000,0.000]
|
||||
[G59:-4.000,-4.000,-3.000]
|
||||
[G28:0.000,0.000,0.000]
|
||||
[G30:-1.000,0.000,0.000]
|
||||
[G92:0.000,0.000,2.000]
|
||||
[TLO:0.000]
|
||||
[PRB:0.000,0.000,0.000:0]
|
||||
ok
|
||||
g92.1
|
||||
ok
|
||||
$#
|
||||
[G54:-4.000,-4.000,-3.000]
|
||||
[G55:2.000,3.000,4.000]
|
||||
[G56:0.000,0.000,0.000]
|
||||
[G57:0.000,0.000,0.000]
|
||||
[G58:0.000,0.000,0.000]
|
||||
[G59:-4.000,-4.000,-3.000]
|
||||
[G28:0.000,0.000,0.000]
|
||||
[G30:-1.000,0.000,0.000]
|
||||
[G92:0.000,0.000,0.000]
|
||||
[TLO:0.000]
|
||||
[PRB:0.000,0.000,0.000:0]
|
||||
ok
|
||||
g92.1 z0
|
||||
ok
|
||||
g92.2
|
||||
error:20
|
||||
|
||||
ok
|
||||
g93
|
||||
ok
|
||||
$g
|
||||
[GC:G0 G59 G17 G21 G91 G93 M5 M9 T0 F0 S0]
|
||||
ok
|
||||
g94
|
||||
ok
|
||||
$g
|
||||
[GC:G0 G59 G17 G21 G91 G94 M5 M9 T0 F0 S0]
|
||||
ok
|
||||
|
||||
ok
|
||||
g95
|
||||
error:20
|
||||
g96
|
||||
error:20
|
||||
g97
|
||||
error:20
|
||||
g98
|
||||
error:20
|
||||
g99
|
||||
error:20
|
||||
|
||||
ok
|
||||
m0
|
||||
?
|
||||
<Hold:0|MPos:-3.000,-2.000,0.000|FS:0,0|WCO:-4.000,-4.000,-3.000>
|
||||
~
|
||||
ok
|
||||
ok
|
||||
ok
|
||||
?
|
||||
<Idle|MPos:-3.000,-2.000,0.000|FS:0,0>
|
||||
ok
|
||||
m1
|
||||
ok
|
||||
m2
|
||||
[MSG:Program End]
|
||||
ok
|
||||
?
|
||||
<Idle|MPos:-3.000,-2.000,0.000|FS:0,0|WCO:-4.000,-4.000,-3.000>
|
||||
ok
|
||||
|
||||
ok
|
||||
m3
|
||||
ok
|
||||
$g
|
||||
[GC:G1 G54 G17 G21 G90 G94 M3 M9 T0 F0 S0]
|
||||
ok
|
||||
m4
|
||||
error:20
|
||||
$g
|
||||
[GC:G1 G54 G17 G21 G90 G94 M3 M9 T0 F0 S0]
|
||||
ok
|
||||
m5
|
||||
ok
|
||||
$g
|
||||
[GC:G1 G54 G17 G21 G90 G94 M5 M9 T0 F0 S0]
|
||||
ok
|
||||
|
||||
ok
|
||||
m6
|
||||
ok
|
||||
t2
|
||||
[MSG:Tool No: 2]
|
||||
ok
|
||||
|
||||
ok
|
||||
m7
|
||||
ok
|
||||
$g
|
||||
[GC:G1 G54 G17 G21 G90 G94 M5 M9 T2 F0 S0]
|
||||
ok
|
||||
m8
|
||||
ok
|
||||
$g
|
||||
[GC:G1 G54 G17 G21 G90 G94 M5 M9 T2 F0 S0]
|
||||
ok
|
||||
m9
|
||||
ok
|
||||
$g
|
||||
[GC:G1 G54 G17 G21 G90 G94 M5 M9 T2 F0 S0]
|
||||
ok
|
||||
|
||||
ok
|
||||
m10
|
||||
error:20
|
||||
m55
|
||||
error:20
|
||||
|
||||
ok
|
||||
m56
|
||||
error:20
|
||||
|
||||
ok
|
||||
m62
|
||||
error:28
|
||||
m62 p0
|
||||
ok
|
||||
m62 p1
|
||||
ok
|
||||
m62 p4
|
||||
ok
|
||||
m62 p5
|
||||
error:39
|
||||
|
||||
ok
|
||||
m63
|
||||
error:28
|
||||
m63 p0
|
||||
ok
|
||||
m63 p1
|
||||
ok
|
||||
m63 p4
|
||||
ok
|
||||
m63 p5
|
||||
error:39
|
||||
|
253
Grbl_Esp32/src/tests/parser.nc
Normal file
253
Grbl_Esp32/src/tests/parser.nc
Normal file
@@ -0,0 +1,253 @@
|
||||
; paste with a terminal emulator with a 200 ms delay between lines
|
||||
$rst=gcode
|
||||
$rst=#
|
||||
$#
|
||||
g10 l2 p0 x0 y0 z0
|
||||
g10 l2 p1 x0 y0 z0
|
||||
g10 l2 p2 x0 y0 z0
|
||||
g10 l2 p3 x0 y0 z0
|
||||
g10 l2 p4 x0 y0 z0
|
||||
g10 l2 p5 x0 y0 z0
|
||||
g10 l2 p6 x0 y0 z0
|
||||
?
|
||||
g0 x0 y0 z0
|
||||
?
|
||||
G0
|
||||
G0 X1
|
||||
G0 I1
|
||||
$G
|
||||
G1
|
||||
G1 Z10
|
||||
$G
|
||||
F1000
|
||||
$G
|
||||
G1 I1
|
||||
G2
|
||||
G2 X0 Y0 I-1 J-1
|
||||
$g
|
||||
G3
|
||||
G3 X0 Y0 I-1 J-1
|
||||
$g
|
||||
g4
|
||||
g4 p0
|
||||
g4.1
|
||||
g4.2
|
||||
g5
|
||||
g6
|
||||
g7
|
||||
g8
|
||||
g9
|
||||
g10
|
||||
g10 l1
|
||||
g10 l2
|
||||
g10 l2 p0
|
||||
g10 l2 p0 x1 y2 z3
|
||||
g10 l2 p2 x2 y3 z4
|
||||
g10 l2 p6 x3 y4 z5
|
||||
$#
|
||||
g10 l2 p6 x3 y4 z5 r1
|
||||
g10 l2 p7 x5 y4 z3
|
||||
g10 l20 p0 x5 y4 z3
|
||||
$#
|
||||
g10 l20 p6 x5 y4 z3
|
||||
$#
|
||||
g10 l20 p7 x5 y4 z3
|
||||
g10 l20 p7 x5 y4 z3
|
||||
g11
|
||||
g12
|
||||
g13
|
||||
g13
|
||||
g14
|
||||
g15
|
||||
g16
|
||||
|
||||
g17
|
||||
$g
|
||||
g18
|
||||
$g
|
||||
g19
|
||||
$g
|
||||
g17
|
||||
|
||||
g20
|
||||
$g
|
||||
g21
|
||||
$g
|
||||
|
||||
g22
|
||||
g23
|
||||
g24
|
||||
g25
|
||||
g26
|
||||
g27
|
||||
|
||||
g28
|
||||
g28 x3
|
||||
$#
|
||||
g28.1
|
||||
g28.1 x3
|
||||
g28.2
|
||||
g29
|
||||
g30 y1
|
||||
$#
|
||||
g30.1
|
||||
g30.1 y2
|
||||
g30.2
|
||||
|
||||
g31
|
||||
g32
|
||||
g33
|
||||
g34
|
||||
g35
|
||||
g36
|
||||
g37
|
||||
g38
|
||||
g39
|
||||
|
||||
g40
|
||||
|
||||
g41
|
||||
g42
|
||||
|
||||
g43
|
||||
g43.1 x0
|
||||
g43.1 z2
|
||||
$#
|
||||
|
||||
g44
|
||||
g45
|
||||
g46
|
||||
g47
|
||||
g48
|
||||
|
||||
g49
|
||||
$#
|
||||
g49.1
|
||||
|
||||
g50
|
||||
g51
|
||||
g52
|
||||
g53
|
||||
g53 g0 x1
|
||||
g53.1
|
||||
|
||||
g54
|
||||
$g
|
||||
g55
|
||||
$g
|
||||
g56
|
||||
$g
|
||||
g57
|
||||
$g
|
||||
g58
|
||||
$g
|
||||
g59 g0 x1
|
||||
$g
|
||||
|
||||
g60
|
||||
|
||||
g61
|
||||
g61.1
|
||||
|
||||
g62
|
||||
g63
|
||||
g64
|
||||
g65
|
||||
g66
|
||||
g67
|
||||
g68
|
||||
g69
|
||||
g70
|
||||
g71
|
||||
g72
|
||||
g73
|
||||
g74
|
||||
g75
|
||||
g76
|
||||
g77
|
||||
g78
|
||||
g79
|
||||
|
||||
g80
|
||||
$g
|
||||
x1
|
||||
g0 x1
|
||||
$g
|
||||
|
||||
g81
|
||||
g82
|
||||
g83
|
||||
g84
|
||||
g85
|
||||
g86
|
||||
g87
|
||||
g88
|
||||
g89
|
||||
|
||||
g90
|
||||
$g
|
||||
g90.1
|
||||
g91
|
||||
$g
|
||||
g91.1
|
||||
|
||||
g92
|
||||
g92 z1
|
||||
$#
|
||||
g92.1
|
||||
$#
|
||||
g92.1 z0
|
||||
g92.2
|
||||
|
||||
g93
|
||||
$g
|
||||
g94
|
||||
$g
|
||||
|
||||
g95
|
||||
g96
|
||||
g97
|
||||
g98
|
||||
g99
|
||||
|
||||
m0
|
||||
?
|
||||
~
|
||||
?
|
||||
m1
|
||||
m2
|
||||
?
|
||||
|
||||
m3
|
||||
$g
|
||||
m4
|
||||
$g
|
||||
m5
|
||||
$g
|
||||
|
||||
m6
|
||||
t2
|
||||
|
||||
m7
|
||||
$g
|
||||
m8
|
||||
$g
|
||||
m9
|
||||
$g
|
||||
|
||||
m10
|
||||
m55
|
||||
|
||||
m56
|
||||
|
||||
m62
|
||||
m62 p0
|
||||
m62 p1
|
||||
m62 p4
|
||||
m62 p5
|
||||
|
||||
m63
|
||||
m63 p0
|
||||
m63 p1
|
||||
m63 p4
|
||||
m63 p5
|
Reference in New Issue
Block a user