mirror of
https://github.com/bdring/Grbl_Esp32.git
synced 2025-08-25 07:20:52 +02:00
Merge remote-tracking branch 'Grbl_Esp32_JH/master' into Devt
This commit is contained in:
2
.gitignore
vendored
2
.gitignore
vendored
@@ -19,4 +19,4 @@ __vm/
|
|||||||
*.vcxproj
|
*.vcxproj
|
||||||
*.vcxproj.filters
|
*.vcxproj.filters
|
||||||
*.suo
|
*.suo
|
||||||
Grbl_Esp32.ino.cpp
|
Grbl_Esp32/Grbl_Esp32.ino.cpp
|
||||||
|
365
Grbl_Esp32/Custom/4axis_xyza.cpp
Normal file
365
Grbl_Esp32/Custom/4axis_xyza.cpp
Normal file
@@ -0,0 +1,365 @@
|
|||||||
|
/*
|
||||||
|
custom_code_template.cpp (4 axis machine)
|
||||||
|
Part of Grbl_ESP32
|
||||||
|
|
||||||
|
copyright (c) 2020 Jens Hauser. This file was intended for use on the ESP32
|
||||||
|
CPU. Do not use this with Grbl for atMega328P
|
||||||
|
|
||||||
|
|
||||||
|
//TODO describe this
|
||||||
|
Tool change function called by G code "T[1..n] M06". Not triggered by G38.2 or ESP3D probe function :-)
|
||||||
|
first Z probe before tool change. Only executed once, because then we<77>ll know the initial Z height.
|
||||||
|
// second Z probe after tool change. Now we can compare
|
||||||
|
|
||||||
|
//TODO parameterise this
|
||||||
|
//TODO correct ifdef/ifndef debugging messages or info messages
|
||||||
|
|
||||||
|
//vTaskDelay (0.5 / portTICK_RATE_MS); // 0.5 Sec.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#define DEBOUNCE_TIME_MACRO_1 300 //ms
|
||||||
|
|
||||||
|
#include <stdint.h>
|
||||||
|
#include "src/Grbl.h"
|
||||||
|
#include "Machines/4axis_xyza.h"
|
||||||
|
|
||||||
|
uint32_t earlier = 0;
|
||||||
|
|
||||||
|
/*
|
||||||
|
options. user_defined_macro() is called with the button number to
|
||||||
|
perform whatever actions you choose.
|
||||||
|
*/
|
||||||
|
#if defined(MACRO_BUTTON_0_PIN) || defined(MACRO_BUTTON_1_PIN) || defined(MACRO_BUTTON_2_PIN)
|
||||||
|
void user_defined_macro(uint8_t index) {
|
||||||
|
uint32_t later, msPassedBy = 0;
|
||||||
|
|
||||||
|
later = millis();
|
||||||
|
msPassedBy = later - earlier;
|
||||||
|
|
||||||
|
if (msPassedBy >= DEBOUNCE_TIME_MACRO_1) {
|
||||||
|
switch (index) {
|
||||||
|
|
||||||
|
case 0: // Macro button 1 (Hold/Cycle switch)
|
||||||
|
switch (sys.state) {
|
||||||
|
case State::Hold:
|
||||||
|
grbl_sendf(CLIENT_ALL, "Macro button #%d pressed. New state \"Cyle start\"\r\n", index + 1);
|
||||||
|
sys_rt_exec_state.bit.cycleStart = true;
|
||||||
|
break;
|
||||||
|
|
||||||
|
case State::Cycle:
|
||||||
|
grbl_sendf(CLIENT_ALL, "Macro button #%d pressed. New state \"Hold\"\r\n", index + 1);
|
||||||
|
sys_rt_exec_state.bit.feedHold = true;
|
||||||
|
break;
|
||||||
|
|
||||||
|
default:
|
||||||
|
grbl_sendf(CLIENT_ALL, "Macro button #%d pressed. Works only in states \"Cycle\" or \"Hold\"\r\n", index + 1);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
|
||||||
|
case 1: // Macro button 2 (Homing)
|
||||||
|
if (sys.state == State::Idle) {
|
||||||
|
grbl_sendf(CLIENT_ALL, "Macro button #%d pressed. Homing, Y tool change position\r\n", index + 1);
|
||||||
|
|
||||||
|
grbl_sendf(CLIENT_ALL, "$H\r\n");
|
||||||
|
WebUI::inputBuffer.push("$H\r\n"); // Homing all axis
|
||||||
|
|
||||||
|
grbl_sendf(CLIENT_ALL, "G53 G0 Z-5\r\n");
|
||||||
|
WebUI::inputBuffer.push("G53 G0 Z-5\r\n"); // Move Z axis up (should already be there, just to be sure)
|
||||||
|
|
||||||
|
grbl_sendf(CLIENT_ALL, "G53 G0 X-5 Y-210 F1000\r\n");
|
||||||
|
WebUI::inputBuffer.push("G53 G0 X-5 Y-210 F1000\r\n"); // Move Y axis to the middle for tool change
|
||||||
|
} else {
|
||||||
|
grbl_sendf(CLIENT_ALL, "Macro button #%d pressed. Works only in state \"Idle\"\r\n", index + 1);
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
|
||||||
|
case 2: // Macro button 3 (Z Probe)
|
||||||
|
if (sys.state == State::Idle) {
|
||||||
|
grbl_sendf(CLIENT_ALL, "Macro button #%d pressed. Z probe\r\n", index + 1);
|
||||||
|
|
||||||
|
// use datum plane XY, mm unit of measure, relative addresing mode
|
||||||
|
grbl_sendf(CLIENT_ALL, "G17 G21 G91\r\n");
|
||||||
|
WebUI::inputBuffer.push("G17 G21 G91\r\n");
|
||||||
|
|
||||||
|
// Go 25mm deeper to hopefully hit alu plate
|
||||||
|
grbl_sendf(CLIENT_ALL, "G38.2 Z-25.0 F50\r\n");
|
||||||
|
WebUI::inputBuffer.push("G38.2 Z-25.0 F50\r\n");
|
||||||
|
|
||||||
|
// Plate thickness 20mm, so adjust Z G54 WCS height. NO X/Y WCS changes!!!
|
||||||
|
grbl_sendf(CLIENT_ALL, "G10 L20 P0 Z+20\r\n");
|
||||||
|
WebUI::inputBuffer.push("G10 L20 P0 Z+20\r\n"); // Set G54, only Z axis, on workpiece level, 20mm below alu plate
|
||||||
|
|
||||||
|
//Move up
|
||||||
|
grbl_sendf(CLIENT_ALL, "G53 G0 Z-5 F200\r\n");
|
||||||
|
WebUI::inputBuffer.push("G53 G0 Z-5 F200\r\n"); // Z up
|
||||||
|
} else {
|
||||||
|
grbl_sendf(CLIENT_ALL, "Macro button #%d pressed. Works only in state \"Idle\"\r\n", index + 1);
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
|
||||||
|
default:
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
|
earlier = later;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/*
|
||||||
|
VARIABLES
|
||||||
|
*/
|
||||||
|
|
||||||
|
/*
|
||||||
|
uint8_t AmountOfToolChanges; // Each new tool increases this by 1. Before first tool, it<69>s 0.
|
||||||
|
uint8_t currenttoolNo, newtoolNo;
|
||||||
|
float firstZPos, newZPos, Zdiff;
|
||||||
|
static TaskHandle_t zProbeSyncTaskHandle = NULL;
|
||||||
|
|
||||||
|
// Finite state machine and sequence of steps
|
||||||
|
uint8_t tc_state; // tool change (tc) state machine
|
||||||
|
#define TOOLCHANGE_IDLE 0 // initial state. tool change switched off. set during machine_init()
|
||||||
|
#define TOOLCHANGE_INIT 1 // do some reporting at first. initialize G code for this procedure
|
||||||
|
#define TOOLCHANGE_START 2 // decide, if first or further tool changes and set next status appropriately
|
||||||
|
#define TOOLCHANGE_ZPROBE_1a 3 // Z probe #1. Send order to press the Z probe button
|
||||||
|
#define TOOLCHANGE_ZPROBE_1b 4 // Z probe #1. After button press
|
||||||
|
#define TOOLCHANGE_MANUAL 5 // Go to tool change position
|
||||||
|
#define TOOLCHANGE_ZPROBE_2 6 // Z probe #2. Send order to press the Z probe button
|
||||||
|
#define TOOLCHANGE_FINISH 99 // tool change finish. do some reporting, clean up, etc.
|
||||||
|
|
||||||
|
// declare functions
|
||||||
|
float getLastZProbePos();
|
||||||
|
|
||||||
|
#ifdef USE_MACHINE_INIT
|
||||||
|
|
||||||
|
machine_init() is called when Grbl_ESP32 first starts. You can use it to do any
|
||||||
|
special things your machine needs at startup.
|
||||||
|
|
||||||
|
Prerequisite: add "#define USE_MACHINE_INIT" to your machine.h file
|
||||||
|
|
||||||
|
void machine_init()
|
||||||
|
{
|
||||||
|
// We start with 0 tool changes
|
||||||
|
AmountOfToolChanges=0;
|
||||||
|
|
||||||
|
// unknown at the beginning, maybe there is no special tool loaded. But this will change, if the next tool is loaded
|
||||||
|
currenttoolNo = 0;
|
||||||
|
|
||||||
|
// Initialize state machine
|
||||||
|
tc_state=TOOLCHANGE_IDLE;
|
||||||
|
|
||||||
|
// TODO this task runs permanently. Alternative?
|
||||||
|
xTaskCreatePinnedToCore(zProbeSyncTask, // task
|
||||||
|
"zProbeSyncTask", // name for task
|
||||||
|
4096, // size of task stack
|
||||||
|
NULL, // parameters
|
||||||
|
1, // priority
|
||||||
|
&zProbeSyncTaskHandle, // handle
|
||||||
|
0 // core
|
||||||
|
);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// state machine
|
||||||
|
|
||||||
|
void zProbeSyncTask(void* pvParameters)
|
||||||
|
{
|
||||||
|
TickType_t xLastWakeTime;
|
||||||
|
|
||||||
|
const TickType_t xProbeFrequency = 100; // in ticks
|
||||||
|
xLastWakeTime = xTaskGetTickCount(); // Initialise the xLastWakeTime variable with the current time.
|
||||||
|
|
||||||
|
//protocol_buffer_synchronize(); // wait for all previous moves to complete
|
||||||
|
|
||||||
|
for ( ;; )
|
||||||
|
{
|
||||||
|
switch ( tc_state )
|
||||||
|
{
|
||||||
|
|
||||||
|
case TOOLCHANGE_INIT:
|
||||||
|
// TODO set AmountOfToolChanges to 0 after job finish
|
||||||
|
// Set amount of tool changes
|
||||||
|
AmountOfToolChanges++;
|
||||||
|
|
||||||
|
#ifdef DEBUG
|
||||||
|
grbl_sendf (CLIENT_ALL, "zProbeSyncTask. TOOLCHANGE_INIT. State=%d\r", tc_state);
|
||||||
|
grbl_sendf (CLIENT_ALL, "This is the %d. tool change in this job\r", AmountOfToolChanges);
|
||||||
|
grbl_sendf (CLIENT_ALL, "Old tool is #%d (0 means unknown), new tool is #%d\r", currenttoolNo, newtoolNo);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Switch off spindle
|
||||||
|
inputBuffer.push("M05\r");
|
||||||
|
|
||||||
|
tc_state = TOOLCHANGE_START;
|
||||||
|
break;
|
||||||
|
|
||||||
|
case TOOLCHANGE_START:
|
||||||
|
#ifdef DEBUG
|
||||||
|
grbl_sendf (CLIENT_ALL, "zProbeSyncTask. TOOLCHANGE_START. State=%d\r", tc_state);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Measure firstZPos only once. Then adjust G43.2 by comparing firstZPos and newZPos.
|
||||||
|
if (AmountOfToolChanges == 1) // first time
|
||||||
|
tc_state = TOOLCHANGE_ZPROBE_1a; // measure before manual tool change
|
||||||
|
else
|
||||||
|
tc_state = TOOLCHANGE_MANUAL; // measure after manual tool change
|
||||||
|
break;
|
||||||
|
|
||||||
|
// First Z Probe
|
||||||
|
case TOOLCHANGE_ZPROBE_1a:
|
||||||
|
#ifdef DEBUG
|
||||||
|
grbl_sendf (CLIENT_ALL, "zProbeSyncTask. TOOLCHANGE_ZPROBE_1a. State=%d\r", tc_state);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Place spindle directly above button in X/Y and at high Z
|
||||||
|
inputBuffer.push("G53 G0 Z-5\r");
|
||||||
|
inputBuffer.push("G53 G0 X-29 Y-410\r");
|
||||||
|
|
||||||
|
// Z probe
|
||||||
|
inputBuffer.push("G91 G38.2 Z-100 F500\r");
|
||||||
|
|
||||||
|
tc_state = TOOLCHANGE_ZPROBE_1b;
|
||||||
|
break;
|
||||||
|
|
||||||
|
case TOOLCHANGE_ZPROBE_1b: // wait for button press
|
||||||
|
#ifdef DEBUG
|
||||||
|
grbl_sendf (CLIENT_ALL, "zProbeSyncTask. TOOLCHANGE_ZPROBE_1b. State=%d\r", tc_state);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// wait until we hit Z probe button
|
||||||
|
// TODO Error handling. What happens in case the button is not pressed?
|
||||||
|
if ( probe_get_state() )
|
||||||
|
{
|
||||||
|
#ifndef DEBUG
|
||||||
|
grbl_sendf(CLIENT_ALL, "zProbeSyncTask. TOOLCHANGE_ZPROBE_1b. State=%d\r", tc_state);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
if (AmountOfToolChanges == 1)
|
||||||
|
firstZPos = getLastZProbePos(); // save Z pos for comparison later
|
||||||
|
|
||||||
|
// hit the probe
|
||||||
|
grbl_sendf(CLIENT_ALL, "Button pressed first time. Z probe pos=%4.3f\r", firstZPos);
|
||||||
|
|
||||||
|
inputBuffer.push("G53 G0 Z-5\r");
|
||||||
|
|
||||||
|
tc_state = TOOLCHANGE_MANUAL;
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
|
||||||
|
// go to manual tool change position
|
||||||
|
case TOOLCHANGE_MANUAL:
|
||||||
|
#ifdef DEBUG
|
||||||
|
grbl_sendf (CLIENT_ALL, "zProbeSyncTask. TOOLCHANGE_MANUAL. State=%d\r", tc_state);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
if ( !probe_get_state() ) // button released now
|
||||||
|
{
|
||||||
|
// Go to tool change position
|
||||||
|
inputBuffer.push("G53 G0 X-5 Y-210\r");
|
||||||
|
|
||||||
|
// Hold
|
||||||
|
inputBuffer.push("M0\r");
|
||||||
|
|
||||||
|
// Place spindle directly above button in X/Y and a few mm above Z
|
||||||
|
inputBuffer.push("G53 G0 Z-5\r");
|
||||||
|
inputBuffer.push("G53 G0 X-29 Y-410\r");
|
||||||
|
|
||||||
|
// Z probe, max. 50mm to press button, quick
|
||||||
|
inputBuffer.push("G91 G38.2 Z-100 F500\r");
|
||||||
|
|
||||||
|
tc_state = TOOLCHANGE_ZPROBE_2;
|
||||||
|
}
|
||||||
|
|
||||||
|
break;
|
||||||
|
|
||||||
|
case TOOLCHANGE_ZPROBE_2: // wait for button press
|
||||||
|
#ifdef DEBUG
|
||||||
|
// grbl_sendf (CLIENT_ALL, "zProbeSyncTask. TOOLCHANGE_ZPROBE_2. State=%d\r", tc_state);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// TODO Error handling. What happens in case the button is not pressed?
|
||||||
|
if ( probe_get_state() )
|
||||||
|
{
|
||||||
|
newZPos = getLastZProbePos(); // save Z pos for later comparison to firstZPos
|
||||||
|
|
||||||
|
// hit the probe
|
||||||
|
#ifdef DEBUG
|
||||||
|
grbl_sendf (CLIENT_ALL, "Button pressed second time. new Z probe pos=%4.3f\r", newZPos);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// calculate and send out G43.1 adjustment
|
||||||
|
char gcode_line[20];
|
||||||
|
sprintf(gcode_line, "G43.1 Z%4.3f\r", newZPos-firstZPos);
|
||||||
|
inputBuffer.push(gcode_line);
|
||||||
|
grbl_sendf (CLIENT_ALL, gcode_line);
|
||||||
|
|
||||||
|
// go up
|
||||||
|
inputBuffer.push("G53 G0 Z-5\r");
|
||||||
|
|
||||||
|
tc_state = TOOLCHANGE_FINISH;
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
|
||||||
|
// That<61>s it
|
||||||
|
case TOOLCHANGE_FINISH:
|
||||||
|
#ifdef DEBUG
|
||||||
|
grbl_sendf (CLIENT_ALL, "zProbeSyncTask. TOOLCHANGE_FINISH. State=%d\r", tc_state);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// button released, we lift up
|
||||||
|
if (! probe_get_state() )
|
||||||
|
{
|
||||||
|
//vTaskDelay (1 / portTICK_RATE_MS); // 1 sec.
|
||||||
|
|
||||||
|
grbl_send (CLIENT_ALL, "Tool change procedure finished.\r");
|
||||||
|
grbl_send (CLIENT_ALL, "Go to current WCS origin after hold.\r");
|
||||||
|
|
||||||
|
// go to current WCS origin. This could be G54, but also another one
|
||||||
|
inputBuffer.push("G0 X0 Y0\r");
|
||||||
|
inputBuffer.push("G0 Z0\r");
|
||||||
|
}
|
||||||
|
|
||||||
|
tc_state = TOOLCHANGE_IDLE;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
|
vTaskDelayUntil(&xLastWakeTime, xProbeFrequency);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
#ifdef USE_TOOL_CHANGE
|
||||||
|
//
|
||||||
|
// user_tool_change() is called when tool change gcode is received,
|
||||||
|
// to perform appropriate actions for your machine.
|
||||||
|
|
||||||
|
// Prerequisite: add "#define USE_TOOL_CHANGE" to your machine.h file
|
||||||
|
void user_tool_change(uint8_t new_tool)
|
||||||
|
{
|
||||||
|
// let<65>s start with the state machine
|
||||||
|
|
||||||
|
newtoolNo = new_tool;
|
||||||
|
tc_state = TOOLCHANGE_INIT;
|
||||||
|
|
||||||
|
//TODO
|
||||||
|
// Nach Aufruf dieser Function wird gleich wieder zurc<72>gkegeben in die aufrufende Function.
|
||||||
|
// Ziel: Erst return, wenn wirklich beendet (RTOS!)
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// return last Z probe machine position
|
||||||
|
float getLastZProbePos()
|
||||||
|
{
|
||||||
|
int32_t lastZPosition[N_AXIS]; // copy of current location
|
||||||
|
float m_pos[N_AXIS]; // machine position in mm
|
||||||
|
char output[200];
|
||||||
|
|
||||||
|
memcpy(lastZPosition, sys_probe_position, sizeof(sys_probe_position)); // get current position in step
|
||||||
|
system_convert_array_steps_to_mpos(m_pos, lastZPosition); // convert to millimeters
|
||||||
|
|
||||||
|
return m_pos[Z_AXIS];
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
*/
|
177
Grbl_Esp32/Custom/4axis_xyza.txt
Normal file
177
Grbl_Esp32/Custom/4axis_xyza.txt
Normal file
@@ -0,0 +1,177 @@
|
|||||||
|
Working GRBL_Esp32 parameters
|
||||||
|
|
||||||
|
(1) $S parameters
|
||||||
|
$Sta/SSID=Home
|
||||||
|
$Sta/Password=******
|
||||||
|
$Sta/IPMode=Static
|
||||||
|
$Sta/IP=192.168.2.30
|
||||||
|
$Sta/Gateway=192.168.2.2
|
||||||
|
$Sta/Netmask=255.255.255.0
|
||||||
|
$AP/SSID=GRBL_ESP
|
||||||
|
$AP/Password=******
|
||||||
|
$AP/IP=192.168.0.1
|
||||||
|
$AP/Channel=1
|
||||||
|
$System/Hostname=grblesp
|
||||||
|
$Http/Enable=ON
|
||||||
|
$Http/Port=80
|
||||||
|
$Telnet/Enable=ON
|
||||||
|
$Telnet/Port=23
|
||||||
|
$Radio/Mode=STA
|
||||||
|
$Notification/Type=NONE
|
||||||
|
$Notification/T1=
|
||||||
|
$Notification/T2=
|
||||||
|
$Notification/TS=
|
||||||
|
$Message/Level=Info
|
||||||
|
$User/Macro0=
|
||||||
|
$User/Macro1=
|
||||||
|
$User/Macro2=
|
||||||
|
$User/Macro3=
|
||||||
|
$Homing/Cycle0=Z
|
||||||
|
$Homing/Cycle1=XY
|
||||||
|
$Homing/Cycle2=
|
||||||
|
$Homing/Cycle3=
|
||||||
|
$Homing/Cycle4=
|
||||||
|
$Homing/Cycle5=
|
||||||
|
$Report/StallGuard=
|
||||||
|
$Stepper/Pulse=10
|
||||||
|
$Stepper/IdleTime=250
|
||||||
|
$Stepper/StepInvert=
|
||||||
|
$Stepper/DirInvert=Y
|
||||||
|
$Stepper/EnableInvert=On
|
||||||
|
$Limits/Invert=Off
|
||||||
|
$Probe/Invert=On
|
||||||
|
$Report/Status=1
|
||||||
|
$GCode/JunctionDeviation=0.010
|
||||||
|
$GCode/ArcTolerance=0.002
|
||||||
|
$Report/Inches=Off
|
||||||
|
$Firmware/Build=
|
||||||
|
$Limits/Soft=On
|
||||||
|
$Limits/Hard=On
|
||||||
|
$Homing/Enable=On
|
||||||
|
$Homing/DirInvert=Y
|
||||||
|
$Homing/Squared=
|
||||||
|
$Homing/Feed=200.000
|
||||||
|
$Homing/Seek=3000.000
|
||||||
|
$Homing/Debounce=250.000
|
||||||
|
$Homing/Pulloff=5.000
|
||||||
|
$GCode/MaxS=1000.000
|
||||||
|
$GCode/MinS=0.000
|
||||||
|
$Laser/FullPower=1000
|
||||||
|
$GCode/LaserMode=Off
|
||||||
|
$GCode/Line1=
|
||||||
|
$GCode/Line0=
|
||||||
|
$Spindle/Enable/Invert=Off
|
||||||
|
$Spindle/Enable/OffWithSpeed=Off
|
||||||
|
$Spindle/Delay/SpinDown=0.000
|
||||||
|
$Spindle/Delay/SpinUp=0.000
|
||||||
|
$Spindle/PWM/Invert=Off
|
||||||
|
$Spindle/PWM/Frequency=5000.000
|
||||||
|
$Spindle/PWM/Off=0.000
|
||||||
|
$Spindle/PWM/Min=0.000
|
||||||
|
$Spindle/PWM/Max=100.000
|
||||||
|
$Spindle/Type=RELAY
|
||||||
|
$X/StepsPerMm=160.000
|
||||||
|
$Y/StepsPerMm=160.000
|
||||||
|
$Z/StepsPerMm=160.000
|
||||||
|
$A/StepsPerMm=160.000
|
||||||
|
$B/StepsPerMm=100.000
|
||||||
|
$C/StepsPerMm=100.000
|
||||||
|
$X/MaxRate=4000.000
|
||||||
|
$Y/MaxRate=4000.000
|
||||||
|
$Z/MaxRate=1500.000
|
||||||
|
$A/MaxRate=1000.000
|
||||||
|
$B/MaxRate=1000.000
|
||||||
|
$C/MaxRate=1000.000
|
||||||
|
$X/Acceleration=100.000
|
||||||
|
$Y/Acceleration=100.000
|
||||||
|
$Z/Acceleration=100.000
|
||||||
|
$A/Acceleration=200.000
|
||||||
|
$B/Acceleration=200.000
|
||||||
|
$C/Acceleration=200.000
|
||||||
|
$X/Home/Mpos=0.000
|
||||||
|
$Y/Home/Mpos=-420.000
|
||||||
|
$Z/Home/Mpos=0.000
|
||||||
|
$A/Home/Mpos=0.000
|
||||||
|
$B/Home/Mpos=0.000
|
||||||
|
$C/Home/Mpos=0.000
|
||||||
|
$X/MaxTravel=1000.000
|
||||||
|
$Y/MaxTravel=425.000
|
||||||
|
$Z/MaxTravel=120.000
|
||||||
|
$A/MaxTravel=300.000
|
||||||
|
$B/MaxTravel=300.000
|
||||||
|
$C/MaxTravel=300.000
|
||||||
|
$X/Current/Run=0.250
|
||||||
|
$Y/Current/Run=0.250
|
||||||
|
$Z/Current/Run=0.250
|
||||||
|
$A/Current/Run=0.250
|
||||||
|
$B/Current/Run=0.250
|
||||||
|
$C/Current/Run=0.250
|
||||||
|
$X/Current/Hold=0.125
|
||||||
|
$Y/Current/Hold=0.125
|
||||||
|
$Z/Current/Hold=0.125
|
||||||
|
$A/Current/Hold=0.125
|
||||||
|
$B/Current/Hold=0.125
|
||||||
|
$C/Current/Hold=0.125
|
||||||
|
$X/Microsteps=16
|
||||||
|
$Y/Microsteps=16
|
||||||
|
$Z/Microsteps=16
|
||||||
|
$A/Microsteps=16
|
||||||
|
$B/Microsteps=16
|
||||||
|
$C/Microsteps=16
|
||||||
|
$X/StallGuard=16
|
||||||
|
$Y/StallGuard=16
|
||||||
|
$Z/StallGuard=16
|
||||||
|
$A/StallGuard=16
|
||||||
|
$B/StallGuard=16
|
||||||
|
$C/StallGuard=16
|
||||||
|
$Errors/Verbose=Off
|
||||||
|
|
||||||
|
(2) $$ parameters
|
||||||
|
$0=10
|
||||||
|
$1=250
|
||||||
|
$2=0
|
||||||
|
$3=2
|
||||||
|
$4=1
|
||||||
|
$5=0
|
||||||
|
$6=1
|
||||||
|
$10=1
|
||||||
|
$11=0.010
|
||||||
|
$12=0.002
|
||||||
|
$13=0
|
||||||
|
$20=1
|
||||||
|
$21=1
|
||||||
|
$22=1
|
||||||
|
$23=2
|
||||||
|
$24=200.000
|
||||||
|
$25=3000.000
|
||||||
|
$26=250.000
|
||||||
|
$27=5.000
|
||||||
|
$30=1000.000
|
||||||
|
$31=0.000
|
||||||
|
$32=0
|
||||||
|
$N1=
|
||||||
|
$N0=
|
||||||
|
$100=160.000
|
||||||
|
$101=160.000
|
||||||
|
$102=160.000
|
||||||
|
$103=160.000
|
||||||
|
$104=100.000
|
||||||
|
$105=100.000
|
||||||
|
$110=4000.000
|
||||||
|
$111=4000.000
|
||||||
|
$112=1500.000
|
||||||
|
$113=1000.000
|
||||||
|
$114=1000.000
|
||||||
|
$115=1000.000
|
||||||
|
$120=100.000
|
||||||
|
$121=100.000
|
||||||
|
$122=100.000
|
||||||
|
$123=200.000
|
||||||
|
$124=200.000
|
||||||
|
$125=200.000
|
||||||
|
$130=1000.000
|
||||||
|
$131=425.000
|
||||||
|
$132=120.000
|
||||||
|
$133=300.000
|
||||||
|
$134=300.000
|
||||||
|
$135=300.000
|
96
Grbl_Esp32/Machines/4axis_xyza.h
Normal file
96
Grbl_Esp32/Machines/4axis_xyza.h
Normal file
@@ -0,0 +1,96 @@
|
|||||||
|
#pragma once
|
||||||
|
/*
|
||||||
|
* 4 Achsen CNC Fraese von Jens
|
||||||
|
* Infos zur Benutzung einer Spindel mit Relais https://github.com/bdring/Grbl_Esp32/wiki/Spindle-Types
|
||||||
|
*/
|
||||||
|
|
||||||
|
#define MACHINE_NAME "MACHINE_ESP32 Jens XYZA"
|
||||||
|
|
||||||
|
#define CUSTOM_CODE_FILENAME "Custom/4axis_xyza.cpp"
|
||||||
|
|
||||||
|
#ifdef N_AXIS
|
||||||
|
#undef N_AXIS
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/*
|
||||||
|
* Moechte ich mit 3 oder 4 Achsen arbeiten?
|
||||||
|
* Beides ist eingerichtet.
|
||||||
|
*/
|
||||||
|
// ######################################
|
||||||
|
#define N_AXIS 3
|
||||||
|
// #######################################
|
||||||
|
|
||||||
|
/*
|
||||||
|
* Spindeltyp definieren
|
||||||
|
* Das 1. Relais
|
||||||
|
*/
|
||||||
|
#define SPINDLE_TYPE SpindleType::RELAY
|
||||||
|
#define SPINDLE_OUTPUT_PIN GPIO_NUM_32
|
||||||
|
|
||||||
|
// Das 2. Relais
|
||||||
|
#define COOLANT_FLOOD_PIN GPIO_NUM_2
|
||||||
|
|
||||||
|
/*
|
||||||
|
* Zuordnung Schrittmotoren
|
||||||
|
* Analog zu den Pins des Boards. Am Besten in KICAD ablesen.
|
||||||
|
* Hier wird Version "Fräse 2.6" genutzt
|
||||||
|
*/
|
||||||
|
#define STEPPERS_DISABLE_PIN GPIO_NUM_13 //ok
|
||||||
|
|
||||||
|
#define X_STEP_PIN GPIO_NUM_12
|
||||||
|
#define X_DIRECTION_PIN GPIO_NUM_14
|
||||||
|
#define X_LIMIT_PIN GPIO_NUM_17
|
||||||
|
|
||||||
|
#define Y_STEP_PIN GPIO_NUM_26
|
||||||
|
#define Y_DIRECTION_PIN GPIO_NUM_15
|
||||||
|
#define Y_LIMIT_PIN GPIO_NUM_4
|
||||||
|
|
||||||
|
#define Z_STEP_PIN GPIO_NUM_27
|
||||||
|
#define Z_DIRECTION_PIN GPIO_NUM_33
|
||||||
|
#define Z_LIMIT_PIN GPIO_NUM_16
|
||||||
|
|
||||||
|
// Falls die 4. Achse genutzt wird
|
||||||
|
#if (N_AXIS == 4)
|
||||||
|
#define A_STEP_PIN GPIO_NUM_25
|
||||||
|
#define A_DIRECTION_PIN GPIO_NUM_22
|
||||||
|
#define A_LIMIT_PIN GPIO_NUM_21
|
||||||
|
|
||||||
|
/* Zuordnung Endschalter
|
||||||
|
* The 1 bits in LIMIT_MASK set the axes that have limit switches
|
||||||
|
* X, Y, Z, A do, the LIMIT_MASK value would be B1111
|
||||||
|
*/
|
||||||
|
#define LIMIT_MASK B1111
|
||||||
|
#else
|
||||||
|
// bei 3 Achsen
|
||||||
|
#define LIMIT_MASK B111
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/*
|
||||||
|
* Control pins
|
||||||
|
*/
|
||||||
|
#define PROBE_PIN GPIO_NUM_35 //ok
|
||||||
|
//#define CONTROL_SAFETY_DOOR_PIN GPIO_NUM_36 // needs external pullup
|
||||||
|
//#define CONTROL_RESET_PIN GPIO_NUM_34 // needs external pullup
|
||||||
|
//#define CONTROL_FEED_HOLD_PIN GPIO_NUM_36 // needs external pullup
|
||||||
|
//#define CONTROL_CYCLE_START_PIN GPIO_NUM_39 // needs external pullup
|
||||||
|
|
||||||
|
#define MACRO_BUTTON_0_PIN GPIO_NUM_36
|
||||||
|
#define MACRO_BUTTON_1_PIN GPIO_NUM_39
|
||||||
|
#define MACRO_BUTTON_2_PIN GPIO_NUM_34
|
||||||
|
|
||||||
|
/* Normally Grbl_ESP32 ignores tool changes.
|
||||||
|
* It just tracks the current tool number.
|
||||||
|
* If you put #define USE_TOOL_CHANGE in you header file,
|
||||||
|
* it will call a function void user_tool_change(uint8_t new_tool) when it sees the M6 gcode command.
|
||||||
|
*/
|
||||||
|
|
||||||
|
//#define USE_MACHINE_INIT
|
||||||
|
//#define USE_TOOL_CHANGE
|
||||||
|
|
||||||
|
|
||||||
|
// wrap prototypes
|
||||||
|
#ifndef FourAxis_xyxz_h
|
||||||
|
#define FourAxis_xyxz_h
|
||||||
|
|
||||||
|
void user_defined_macro(uint8_t index);
|
||||||
|
#endif
|
@@ -54,7 +54,7 @@ Some features should not be changed. See notes below.
|
|||||||
// The mask order is ...
|
// The mask order is ...
|
||||||
// Macro3 | Macro2 | Macro 1| Macr0 |Cycle Start | Feed Hold | Reset | Safety Door
|
// Macro3 | Macro2 | Macro 1| Macr0 |Cycle Start | Feed Hold | Reset | Safety Door
|
||||||
// For example B1101 will invert the function of the Reset pin.
|
// For example B1101 will invert the function of the Reset pin.
|
||||||
#define INVERT_CONTROL_PIN_MASK B00001111
|
#define INVERT_CONTROL_PIN_MASK B01111111
|
||||||
|
|
||||||
// #define ENABLE_CONTROL_SW_DEBOUNCE // Default disabled. Uncomment to enable.
|
// #define ENABLE_CONTROL_SW_DEBOUNCE // Default disabled. Uncomment to enable.
|
||||||
#define CONTROL_SW_DEBOUNCE_PERIOD 32 // in milliseconds default 32 microseconds
|
#define CONTROL_SW_DEBOUNCE_PERIOD 32 // in milliseconds default 32 microseconds
|
||||||
@@ -93,10 +93,10 @@ const int MAX_N_AXIS = 6;
|
|||||||
#define BAUD_RATE 115200
|
#define BAUD_RATE 115200
|
||||||
|
|
||||||
//Connect to your local AP with these credentials
|
//Connect to your local AP with these credentials
|
||||||
//#define CONNECT_TO_SSID "your SSID"
|
#define CONNECT_TO_SSID "Home"
|
||||||
//#define SSID_PASSWORD "your SSID password"
|
#define SSID_PASSWORD "12345678"
|
||||||
//CONFIGURE_EYECATCH_BEGIN (DO NOT MODIFY THIS LINE)
|
//CONFIGURE_EYECATCH_BEGIN (DO NOT MODIFY THIS LINE)
|
||||||
#define ENABLE_BLUETOOTH // enable bluetooth
|
// #define ENABLE_BLUETOOTH // enable bluetooth
|
||||||
|
|
||||||
#define ENABLE_SD_CARD // enable use of SD Card to run jobs
|
#define ENABLE_SD_CARD // enable use of SD Card to run jobs
|
||||||
|
|
||||||
@@ -202,7 +202,7 @@ enum class Cmd : uint8_t {
|
|||||||
// If homing is enabled, homing init lock sets Grbl into an alarm state upon power up. This forces
|
// If homing is enabled, homing init lock sets Grbl into an alarm state upon power up. This forces
|
||||||
// the user to perform the homing cycle (or override the locks) before doing anything else. This is
|
// the user to perform the homing cycle (or override the locks) before doing anything else. This is
|
||||||
// mainly a safety feature to remind the user to home, since position is unknown to Grbl.
|
// mainly a safety feature to remind the user to home, since position is unknown to Grbl.
|
||||||
#define HOMING_INIT_LOCK // Comment to disable
|
//#define HOMING_INIT_LOCK // Comment to disable
|
||||||
|
|
||||||
// Number of homing cycles performed after when the machine initially jogs to limit switches.
|
// 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
|
// This help in preventing overshoot and should improve repeatability. This value should be one or
|
||||||
@@ -496,8 +496,8 @@ const int DWELL_TIME_STEP = 50; // Integer (1-255) (milliseconds)
|
|||||||
// A simple software debouncing feature for hard limit switches. When enabled, the limit
|
// A simple software debouncing feature for hard limit switches. When enabled, the limit
|
||||||
// switch interrupt unblock a waiting task which will recheck the limit switch pins after
|
// switch interrupt unblock a waiting task which will recheck the limit switch pins after
|
||||||
// a short delay. Default disabled
|
// a short delay. Default disabled
|
||||||
//#define ENABLE_SOFTWARE_DEBOUNCE // Default disabled. Uncomment to enable.
|
#define ENABLE_SOFTWARE_DEBOUNCE // Default disabled. Uncomment to enable.
|
||||||
const int DEBOUNCE_PERIOD = 32; // in milliseconds default 32 microseconds
|
#define DEBOUNCE_PERIOD 32 // in milliseconds default 32 microseconds
|
||||||
|
|
||||||
// Configures the position after a probing cycle during Grbl's check mode. Disabled sets
|
// Configures the position after a probing cycle during Grbl's check mode. Disabled sets
|
||||||
// the position to the probe target, when enabled sets the position to the start position.
|
// the position to the probe target, when enabled sets the position to the start position.
|
||||||
|
@@ -8,7 +8,8 @@
|
|||||||
// !!! For initial testing, start with test_drive.h which disables
|
// !!! For initial testing, start with test_drive.h which disables
|
||||||
// all I/O pins
|
// all I/O pins
|
||||||
// #include "Machines/atari_1020.h"
|
// #include "Machines/atari_1020.h"
|
||||||
# include "Machines/test_drive.h"
|
//#include "Machines/test_drive.h"
|
||||||
|
#include "Machines/4axis_xyza.h"
|
||||||
|
|
||||||
// !!! For actual use, change the line above to select a board
|
// !!! For actual use, change the line above to select a board
|
||||||
// from Machines/, for example:
|
// from Machines/, for example:
|
||||||
|
@@ -53,6 +53,9 @@ src_filter =
|
|||||||
+<*.h> +<*.s> +<*.S> +<*.cpp> +<*.c> +<*.ino> +<src/>
|
+<*.h> +<*.s> +<*.S> +<*.cpp> +<*.c> +<*.ino> +<src/>
|
||||||
-<.git/> -<data/> -<test/> -<tests/>
|
-<.git/> -<data/> -<test/> -<tests/>
|
||||||
|
|
||||||
|
upload_protocol = espota
|
||||||
|
upload_port = 192.168.2.30
|
||||||
|
|
||||||
[env:release]
|
[env:release]
|
||||||
|
|
||||||
[env:debug]
|
[env:debug]
|
||||||
|
Reference in New Issue
Block a user