mirror of
https://github.com/bdring/Grbl_Esp32.git
synced 2025-08-29 01:00:00 +02:00
Machine Definition Cleanup (#658)
- Removed machine definitions to speed up testing. - Moved 6 pack CS/MS3 pins with other axis pins to help them stay in sync with the aixs letters
This commit is contained in:
@@ -1,57 +0,0 @@
|
||||
#pragma once
|
||||
// clang-format off
|
||||
|
||||
/*
|
||||
3axis_v3.h
|
||||
Part of Grbl_ESP32
|
||||
|
||||
Pin assignments for the ESP32 Development Controller, v3.5.
|
||||
https://github.com/bdring/Grbl_ESP32_Development_Controller
|
||||
https://www.tindie.com/products/33366583/grbl_esp32-cnc-development-board-v35/
|
||||
|
||||
2018 - Bart Dring
|
||||
2020 - Mitch Bradley
|
||||
|
||||
Grbl_ESP32 is free software: you can redistribute it and/or modify
|
||||
it under the terms of the GNU General Public License as published by
|
||||
the Free Software Foundation, either version 3 of the License, or
|
||||
(at your option) any later version.
|
||||
|
||||
Grbl is distributed in the hope that it will be useful,
|
||||
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
GNU General Public License for more details.
|
||||
|
||||
You should have received a copy of the GNU General Public License
|
||||
along with Grbl_ESP32. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#define MACHINE_NAME "ESP32_V3.5"
|
||||
|
||||
#define X_STEP_PIN GPIO_NUM_12
|
||||
#define X_DIRECTION_PIN GPIO_NUM_26
|
||||
#define Y_STEP_PIN GPIO_NUM_14
|
||||
#define Y_DIRECTION_PIN GPIO_NUM_25
|
||||
#define Z_STEP_PIN GPIO_NUM_27
|
||||
#define Z_DIRECTION_PIN GPIO_NUM_33
|
||||
|
||||
#define X_LIMIT_PIN GPIO_NUM_2 // labeled X Limit
|
||||
#define Y_LIMIT_PIN GPIO_NUM_4 // labeled Y Limit
|
||||
#define Z_LIMIT_PIN GPIO_NUM_15 // labeled Z Limit
|
||||
|
||||
// OK to comment out to use pin for other features
|
||||
#define STEPPERS_DISABLE_PIN GPIO_NUM_13
|
||||
|
||||
#define SPINDLE_TYPE SpindleType::PWM
|
||||
#define SPINDLE_OUTPUT_PIN GPIO_NUM_17 // labeled SpinPWM
|
||||
|
||||
#define SPINDLE_ENABLE_PIN GPIO_NUM_22 // labeled SpinEnbl
|
||||
|
||||
#define COOLANT_MIST_PIN GPIO_NUM_21 // labeled Mist
|
||||
#define COOLANT_FLOOD_PIN GPIO_NUM_16 // labeled Flood
|
||||
#define PROBE_PIN GPIO_NUM_32 // labeled Probe
|
||||
|
||||
#define CONTROL_SAFETY_DOOR_PIN GPIO_NUM_35 // labeled Door, needs external pullup
|
||||
#define CONTROL_RESET_PIN GPIO_NUM_34 // labeled Reset, needs external pullup
|
||||
#define CONTROL_FEED_HOLD_PIN GPIO_NUM_36 // labeled Hold, needs external pullup
|
||||
#define CONTROL_CYCLE_START_PIN GPIO_NUM_39 // labeled Start, needs external pullup
|
@@ -1,59 +0,0 @@
|
||||
#pragma once
|
||||
// clang-format off
|
||||
|
||||
/*
|
||||
3axis_xyx.h
|
||||
Part of Grbl_ESP32
|
||||
|
||||
Pin assignments for the ESP32 Development Controller
|
||||
used to drive a dual motor gantry where the drivers
|
||||
labeled X, Y and Z drive the machine axes X, Y and X.
|
||||
https://github.com/bdring/Grbl_ESP32_Development_Controller
|
||||
https://www.tindie.com/products/33366583/grbl_esp32-cnc-development-board-v35/
|
||||
|
||||
2020 - Mitch Bradley
|
||||
|
||||
Grbl_ESP32 is free software: you can redistribute it and/or modify
|
||||
it under the terms of the GNU General Public License as published by
|
||||
the Free Software Foundation, either version 3 of the License, or
|
||||
(at your option) any later version.
|
||||
|
||||
Grbl is distributed in the hope that it will be useful,
|
||||
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
GNU General Public License for more details.
|
||||
|
||||
You should have received a copy of the GNU General Public License
|
||||
along with Grbl_ESP32. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#define MACHINE_NAME "ESP32_V4_XYX"
|
||||
#define X_STEP_PIN GPIO_NUM_26 /* labeled Y */
|
||||
#define X_DIRECTION_PIN GPIO_NUM_15 /* labeled Y */
|
||||
#define Y_STEP_PIN GPIO_NUM_12 /* labeled X */
|
||||
#define Y_DIRECTION_PIN GPIO_NUM_14 /* labeled X */
|
||||
#define Y2_STEP_PIN GPIO_NUM_27 /* labeled Z */
|
||||
#define Y2_DIRECTION_PIN GPIO_NUM_33 /* labeled Z */
|
||||
|
||||
#define SPINDLE_TYPE SpindleType::PWM
|
||||
#define SPINDLE_OUTPUT_PIN GPIO_NUM_2
|
||||
#define SPINDLE_ENABLE_PIN GPIO_NUM_22
|
||||
|
||||
#define X_LIMIT_PIN GPIO_NUM_17
|
||||
#define Y_LIMIT_PIN GPIO_NUM_4
|
||||
// #define Z_LIMIT_PIN GPIO_NUM_16
|
||||
|
||||
#define STEPPERS_DISABLE_PIN GPIO_NUM_13
|
||||
|
||||
#define COOLANT_MIST_PIN GPIO_NUM_21
|
||||
#define COOLANT_FLOOD_PIN GPIO_NUM_25
|
||||
|
||||
|
||||
|
||||
// see versions for X and Z
|
||||
#define PROBE_PIN GPIO_NUM_32
|
||||
|
||||
#define CONTROL_SAFETY_DOOR_PIN GPIO_NUM_35 // 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
|
@@ -39,37 +39,35 @@
|
||||
#define I2S_OUT_WS GPIO_NUM_17
|
||||
#define I2S_OUT_DATA GPIO_NUM_21
|
||||
|
||||
#define X_STEPPER_MS3 I2SO(3) // Labeled X_CS
|
||||
#define Y_STEPPER_MS3 I2SO(6) // Y_CS
|
||||
#define Z_STEPPER_MS3 I2SO(11) // Z_CS
|
||||
#define X2_STEPPER_MS3 I2SO(14) // A_CS
|
||||
#define Y2_STEPPER_MS3 I2SO(19) // B_CS
|
||||
|
||||
// Motor Socket #1
|
||||
#define X_DISABLE_PIN I2SO(0)
|
||||
#define X_DIRECTION_PIN I2SO(1)
|
||||
#define X_STEP_PIN I2SO(2)
|
||||
#define X_STEPPER_MS3 I2SO(3)
|
||||
|
||||
// Motor Socket #2
|
||||
#define Y_DIRECTION_PIN I2SO(4)
|
||||
#define Y_STEP_PIN I2SO(5)
|
||||
#define Y_STEPPER_MS3 I2SO(6)
|
||||
#define Y_DISABLE_PIN I2SO(7)
|
||||
|
||||
// Motor Socket #3
|
||||
#define Y2_DISABLE_PIN I2SO(8)
|
||||
#define Y2_DIRECTION_PIN I2SO(9)
|
||||
#define Y2_STEP_PIN I2SO(10)
|
||||
#define Y2_STEPPER_MS3 I2SO(11)
|
||||
|
||||
// Motor Socket #4
|
||||
#define Z_DIRECTION_PIN I2SO(12)
|
||||
#define Z_STEP_PIN I2SO(13)
|
||||
#define Z_STEPPER_MS3 I2SO(14)
|
||||
#define Z_DISABLE_PIN I2SO(15)
|
||||
|
||||
// Motor Socket #5
|
||||
#define Z2_DISABLE_PIN I2SO(16)
|
||||
#define Z2_DIRECTION_PIN I2SO(17)
|
||||
#define Z2_STEP_PIN I2SO(18)
|
||||
|
||||
#define Z2_STEPPER_MS3 I2SO(19)
|
||||
|
||||
/*
|
||||
Socket I/O reference
|
||||
@@ -112,8 +110,8 @@ Socket #5
|
||||
// https://github.com/bdring/6-Pack_CNC_Controller/wiki/4x-Switch-Input-module
|
||||
#define X_LIMIT_PIN GPIO_NUM_33
|
||||
#define Y_LIMIT_PIN GPIO_NUM_32
|
||||
#define Y2_LIMIT_PIN GPIO_NUM_35
|
||||
#define Z_LIMIT_PIN GPIO_NUM_34
|
||||
#define Y2_LIMIT_PIN GPIO_NUM_35
|
||||
#define Z_LIMIT_PIN GPIO_NUM_34
|
||||
|
||||
// 4x Input Module in Socket #2
|
||||
// https://github.com/bdring/6-Pack_CNC_Controller/wiki/4x-Switch-Input-module
|
||||
|
@@ -39,36 +39,35 @@
|
||||
#define I2S_OUT_WS GPIO_NUM_17
|
||||
#define I2S_OUT_DATA GPIO_NUM_21
|
||||
|
||||
#define X_STEPPER_MS3 I2SO(3) // Labeled X_CS
|
||||
#define Y_STEPPER_MS3 I2SO(6) // Y_CS
|
||||
#define Z_STEPPER_MS3 I2SO(11) // Z_CS
|
||||
#define X2_STEPPER_MS3 I2SO(14) // A_CS
|
||||
#define Y2_STEPPER_MS3 I2SO(19) // B_CS
|
||||
|
||||
// Motor Socket #1
|
||||
#define X_DISABLE_PIN I2SO(0)
|
||||
#define X_DIRECTION_PIN I2SO(1)
|
||||
#define X_STEP_PIN I2SO(2)
|
||||
#define X_STEPPER_MS3 I2SO(3)
|
||||
|
||||
// Motor Socket #2
|
||||
#define Y_DIRECTION_PIN I2SO(4)
|
||||
#define Y_STEP_PIN I2SO(5)
|
||||
#define Y_STEPPER_MS3 I2SO(6)
|
||||
#define Y_DISABLE_PIN I2SO(7)
|
||||
|
||||
// Motor Socket #3
|
||||
#define Z_DISABLE_PIN I2SO(8)
|
||||
#define Z_DIRECTION_PIN I2SO(9)
|
||||
#define Z_STEP_PIN I2SO(10)
|
||||
#define Z_STEPPER_MS3 I2SO(11)
|
||||
|
||||
// Motor Socket #4
|
||||
#define X2_DIRECTION_PIN I2SO(12)
|
||||
#define X2_STEP_PIN I2SO(13)
|
||||
#define X2_STEPPER_MS3 I2SO(14)
|
||||
#define X2_DISABLE_PIN I2SO(15)
|
||||
|
||||
// Motor Socket #5
|
||||
#define Y2_DISABLE_PIN I2SO(16)
|
||||
#define Y2_DIRECTION_PIN I2SO(17)
|
||||
#define Y2_STEP_PIN I2SO(18)
|
||||
#define Y2_STEPPER_MS3 I2SO(19)
|
||||
|
||||
|
||||
/*
|
||||
|
@@ -41,24 +41,24 @@
|
||||
#define I2S_OUT_WS GPIO_NUM_17
|
||||
#define I2S_OUT_DATA GPIO_NUM_21
|
||||
|
||||
#define X_STEPPER_MS3 I2SO(3) // X_CS
|
||||
#define Y_STEPPER_MS3 I2SO(6) // Y_CS
|
||||
#define Z_STEPPER_MS3 I2SO(11) // Z_CS
|
||||
|
||||
// Motor Socket #1
|
||||
#define X_DISABLE_PIN I2SO(0)
|
||||
#define X_DIRECTION_PIN I2SO(1)
|
||||
#define X_STEP_PIN I2SO(2)
|
||||
#define X_STEPPER_MS3 I2SO(3)
|
||||
|
||||
// Motor Socket #2
|
||||
#define Y_DIRECTION_PIN I2SO(4)
|
||||
#define Y_STEP_PIN I2SO(5)
|
||||
#define Y_STEPPER_MS3 I2SO(6)
|
||||
#define Y_DISABLE_PIN I2SO(7)
|
||||
|
||||
// Motor Socket #3
|
||||
#define Z_DISABLE_PIN I2SO(8)
|
||||
#define Z_DIRECTION_PIN I2SO(9)
|
||||
#define Z_STEP_PIN I2SO(10)
|
||||
#define Z_STEPPER_MS3 I2SO(11)
|
||||
|
||||
/*
|
||||
Socket I/O reference
|
||||
|
@@ -40,41 +40,40 @@
|
||||
#define I2S_OUT_DATA GPIO_NUM_21
|
||||
|
||||
|
||||
#define X_STEPPER_MS3 I2SO(3) // X_CS
|
||||
#define Y_STEPPER_MS3 I2SO(6) // Y_CS
|
||||
#define Z_STEPPER_MS3 I2SO(11) // Z_CS
|
||||
#define A_STEPPER_MS3 I2SO(14) // A_CS
|
||||
#define B_STEPPER_MS3 I2SO(19) // B_CS
|
||||
#define C_STEPPER_MS3 I2SO(22) // C_CS
|
||||
|
||||
// Motor Socket #1
|
||||
#define X_DISABLE_PIN I2SO(0)
|
||||
#define X_DIRECTION_PIN I2SO(1)
|
||||
#define X_STEP_PIN I2SO(2)
|
||||
#define X_STEPPER_MS3 I2SO(3)
|
||||
|
||||
// Motor Socket #2
|
||||
#define Y_DIRECTION_PIN I2SO(4)
|
||||
#define Y_STEP_PIN I2SO(5)
|
||||
#define Y_STEPPER_MS3 I2SO(6)
|
||||
#define Y_DISABLE_PIN I2SO(7)
|
||||
|
||||
// Motor Socket #3
|
||||
#define Z_DISABLE_PIN I2SO(8)
|
||||
#define Z_DIRECTION_PIN I2SO(9)
|
||||
#define Z_STEP_PIN I2SO(10)
|
||||
#define Z_STEPPER_MS3 I2SO(11)
|
||||
|
||||
// Motor Socket #4
|
||||
#define A_DIRECTION_PIN I2SO(12)
|
||||
#define A_STEP_PIN I2SO(13)
|
||||
#define A_STEPPER_MS3 I2SO(14)
|
||||
#define A_DISABLE_PIN I2SO(15)
|
||||
|
||||
// Motor Socket #5
|
||||
#define B_DISABLE_PIN I2SO(16)
|
||||
#define B_DIRECTION_PIN I2SO(17)
|
||||
#define B_STEP_PIN I2SO(18)
|
||||
#define B_STEPPER_MS3 I2SO(19)
|
||||
|
||||
// Motor Socket #5
|
||||
#define C_DIRECTION_PIN I2SO(20)
|
||||
#define C_STEP_PIN I2SO(21)
|
||||
#define C_STEPPER_MS3 I2SO(22)
|
||||
#define C_DISABLE_PIN I2SO(23)
|
||||
|
||||
|
||||
|
@@ -1,61 +0,0 @@
|
||||
#pragma once
|
||||
// clang-format off
|
||||
|
||||
/*
|
||||
espduino.h
|
||||
Part of Grbl_ESP32
|
||||
|
||||
Pin assignments for ESPDUINO-32 Boards and Protoneer V3 boards
|
||||
Note: Probe pin is mapped, but will require a 10k external pullup to 3.3V to work.
|
||||
|
||||
Rebooting...See this issue https://github.com/bdring/Grbl_Esp32/issues/314
|
||||
!!!! Experimental Untested !!!!!
|
||||
|
||||
2019 - Bart Dring
|
||||
2020 - Mitch Bradley
|
||||
|
||||
Grbl_ESP32 is free software: you can redistribute it and/or modify
|
||||
it under the terms of the GNU General Public License as published by
|
||||
the Free Software Foundation, either version 3 of the License, or
|
||||
(at your option) any later version.
|
||||
|
||||
Grbl is distributed in the hope that it will be useful,
|
||||
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
GNU General Public License for more details.
|
||||
|
||||
You should have received a copy of the GNU General Public License
|
||||
along with Grbl_ESP32. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#define MACHINE_NAME "ESPDUINO_32"
|
||||
|
||||
#define X_STEP_PIN GPIO_NUM_26
|
||||
#define X_DIRECTION_PIN GPIO_NUM_16
|
||||
|
||||
#define Y_STEP_PIN GPIO_NUM_25
|
||||
#define Y_DIRECTION_PIN GPIO_NUM_27
|
||||
|
||||
#define Z_STEP_PIN GPIO_NUM_17
|
||||
#define Z_DIRECTION_PIN GPIO_NUM_14
|
||||
|
||||
// OK to comment out to use pin for other features
|
||||
#define STEPPERS_DISABLE_PIN GPIO_NUM_12
|
||||
|
||||
#define SPINDLE_TYPE SpindleType::PWM
|
||||
#define SPINDLE_OUTPUT_PIN GPIO_NUM_19
|
||||
|
||||
#define SPINDLE_DIR_PIN GPIO_NUM_18
|
||||
|
||||
#define COOLANT_FLOOD_PIN GPIO_NUM_34
|
||||
#define COOLANT_MIST_PIN GPIO_NUM_36
|
||||
|
||||
#define X_LIMIT_PIN GPIO_NUM_13
|
||||
#define Y_LIMIT_PIN GPIO_NUM_5
|
||||
#define Z_LIMIT_PIN GPIO_NUM_19
|
||||
|
||||
#define PROBE_PIN GPIO_NUM_39
|
||||
|
||||
#define CONTROL_RESET_PIN GPIO_NUM_2
|
||||
#define CONTROL_FEED_HOLD_PIN GPIO_NUM_4
|
||||
#define CONTROL_CYCLE_START_PIN GPIO_NUM_35 // ESP32 needs external pullup
|
@@ -1,95 +0,0 @@
|
||||
#pragma once
|
||||
// clang-format off
|
||||
|
||||
/*
|
||||
spi_daisy_4axis_xyyz.h
|
||||
Part of Grbl_ESP32
|
||||
|
||||
Pin assignments for a 3-axis with Y ganged using Triaminic drivers
|
||||
in daisy-chained SPI mode.
|
||||
https://github.com/bdring/4_Axis_SPI_CNC
|
||||
|
||||
2019 - Bart Dring
|
||||
2020 - Mitch Bradley
|
||||
|
||||
Grbl_ESP32 is free software: you can redistribute it and/or modify
|
||||
it under the terms of the GNU General Public License as published by
|
||||
the Free Software Foundation, either version 3 of the License, or
|
||||
(at your option) any later version.
|
||||
|
||||
Grbl is distributed in the hope that it will be useful,
|
||||
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
GNU General Public License for more details.
|
||||
|
||||
You should have received a copy of the GNU General Public License
|
||||
along with Grbl_ESP32. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#define MACHINE_NAME "SPI_DAISY_4X_xyyz"
|
||||
|
||||
#ifdef N_AXIS
|
||||
#undef N_AXIS
|
||||
#endif
|
||||
#define N_AXIS 3 // can be 3 or 4. (if 3 install bypass jumper next to the A driver)
|
||||
|
||||
#define TRINAMIC_DAISY_CHAIN
|
||||
|
||||
#define TRINAMIC_RUN_MODE TrinamicMode :: CoolStep
|
||||
#define TRINAMIC_HOMING_MODE TrinamicMode :: CoolStep
|
||||
|
||||
// Use SPI enable instead of the enable pin
|
||||
// The hardware enable pin is tied to ground
|
||||
#define USE_TRINAMIC_ENABLE
|
||||
|
||||
#define DEFAULT_HOMING_SQUARED_AXES bit(Y_AXIS)
|
||||
|
||||
// Y motor connects to the 1st driver
|
||||
#define X_TRINAMIC_DRIVER 2130 // Which Driver Type?
|
||||
#define X_RSENSE TMC2130_RSENSE_DEFAULT
|
||||
#define X_STEP_PIN GPIO_NUM_12
|
||||
#define X_DIRECTION_PIN GPIO_NUM_14
|
||||
#define X_CS_PIN GPIO_NUM_17 // Daisy Chain, all share same CS pin
|
||||
|
||||
// Y motor connects to the 2nd driver
|
||||
#define Y_TRINAMIC_DRIVER 2130 // Which Driver Type?
|
||||
#define Y_RSENSE TMC2130_RSENSE_DEFAULT
|
||||
#define Y_STEP_PIN GPIO_NUM_27
|
||||
#define Y_DIRECTION_PIN GPIO_NUM_26
|
||||
#define Y_CS_PIN X_CS_PIN // Daisy Chain, all share same CS pin
|
||||
|
||||
// Y2 motor connects to the 2nd driver
|
||||
#define Y2_TRINAMIC_DRIVER 2130 // Which Driver Type?
|
||||
#define Y2_RSENSE TMC2130_RSENSE_DEFAULT
|
||||
#define Y2_STEP_PIN GPIO_NUM_15 // Z on schem
|
||||
#define Y2_DIRECTION_PIN GPIO_NUM_2 // Z on schem
|
||||
#define Y2_CS_PIN X_CS_PIN // Daisy Chain, all share same CS pin
|
||||
|
||||
// Z Axis motor connects to the 4th driver
|
||||
#define Z_TRINAMIC_DRIVER 2130 // Which Driver Type?
|
||||
#define Z_RSENSE TMC2130_RSENSE_DEFAULT
|
||||
#define Z_STEP_PIN GPIO_NUM_33 // A on schem
|
||||
#define Z_DIRECTION_PIN GPIO_NUM_32 // A on schem
|
||||
#define Z_CS_PIN X_CS_PIN // Daisy Chain, all share same CS pin
|
||||
|
||||
// Mist is a 3.3V output
|
||||
// Turn on with M7 and off with M9
|
||||
#define COOLANT_MIST_PIN GPIO_NUM_21
|
||||
|
||||
#define SPINDLE_TYPE SpindleType::PWM
|
||||
#define SPINDLE_OUTPUT_PIN GPIO_NUM_25
|
||||
#define SPINDLE_ENABLE_PIN GPIO_NUM_4
|
||||
|
||||
// Relay operation
|
||||
// Install Jumper near relay
|
||||
// For spindle Use max RPM of 1
|
||||
// For PWM remove jumper and set MAX RPM to something higher ($30 setting)
|
||||
// Interlock jumper along top edge needs to be installed for both versions
|
||||
#define DEFAULT_SPINDLE_RPM_MAX 1 // Should be 1 for relay operation
|
||||
|
||||
#define PROBE_PIN GPIO_NUM_22
|
||||
|
||||
#define X_LIMIT_PIN GPIO_NUM_36
|
||||
#define Y_LIMIT_PIN GPIO_NUM_39
|
||||
#define Z_LIMIT_PIN GPIO_NUM_34
|
||||
|
@@ -1,155 +0,0 @@
|
||||
#pragma once
|
||||
// clang-format off
|
||||
|
||||
/*
|
||||
tapster_pro_stepstick.h
|
||||
|
||||
2020 - Bart Dring, Jason Huggins (Tapster Robotics)
|
||||
|
||||
Grbl_ESP32 is free software: you can redistribute it and/or modify
|
||||
it under the terms of the GNU General Public License as published by
|
||||
the Free Software Foundation, either version 3 of the License, or
|
||||
(at your option) any later version.
|
||||
Grbl is distributed in the hope that it will be useful,
|
||||
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
GNU General Public License for more details.
|
||||
You should have received a copy of the GNU General Public License
|
||||
along with Grbl_ESP32. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#define MACHINE_NAME "Tapster Pro Delta (StepStick)"
|
||||
|
||||
#define CUSTOM_CODE_FILENAME "Custom/parallel_delta.cpp"
|
||||
/*
|
||||
// enable these special machine functions to be called from the main program
|
||||
#define USE_KINEMATICS // there are kinematic equations for this machine
|
||||
#define FWD_KINEMATICS_REPORTING // report in cartesian
|
||||
#define USE_RMT_STEPS // Use the RMT periferal to generate step pulses
|
||||
#define USE_TRINAMIC // some Trinamic motors are used on this machine
|
||||
#define USE_MACHINE_TRINAMIC_INIT // there is a machine specific setup for the drivers
|
||||
#define USE_MACHINE_INIT // There is some custom initialization for this machine
|
||||
|
||||
#define SEGMENT_LENGTH 0.5 // segment length in mm
|
||||
#define KIN_ANGLE_CALC_OK 0
|
||||
#define KIN_ANGLE_ERROR -1
|
||||
|
||||
#define MAX_NEGATIVE_ANGLE -36 // in degrees how far can the arms go up?
|
||||
|
||||
#define HOMING_CURRENT_REDUCTION 1.0
|
||||
|
||||
*/
|
||||
|
||||
#define N_AXIS 3
|
||||
|
||||
#define USE_KINEMATICS // there are kinematic equations for this machine
|
||||
#define USE_FWD_KINEMATICS // report in cartesian
|
||||
#define USE_MACHINE_INIT // There is some custom initialization for this machine
|
||||
|
||||
// ================== Delta Geometry ===========================
|
||||
|
||||
#define RADIUS_FIXED 100.0f // radius of the fixed side (length of motor cranks)
|
||||
#define RADIUS_EFF 220.0f // radius of end effector side (length of linkages)
|
||||
#define LENGTH_FIXED_SIDE 294.449f // sized of fixed side triangel
|
||||
#define LENGTH_EFF_SIDE 86.6025f // size of end effector side triangle
|
||||
#define KINEMATIC_SEGMENT_LENGTH 1.0f // segment length in mm
|
||||
#define MAX_NEGATIVE_ANGLE -0.75f //
|
||||
#define MAX_POSITIVE_ANGLE (M_PI / 2.0) //
|
||||
|
||||
|
||||
// ================== Config ======================
|
||||
|
||||
// Set $Homing/Cycle0=XYZ
|
||||
|
||||
// === Special Features
|
||||
|
||||
// I2S (steppers & other output-only pins)
|
||||
#define USE_I2S_OUT
|
||||
#define USE_I2S_STEPS
|
||||
//#define DEFAULT_STEPPER ST_I2S_STATIC
|
||||
// === Default settings
|
||||
#define DEFAULT_STEP_PULSE_MICROSECONDS I2S_OUT_USEC_PER_PULSE
|
||||
|
||||
#define USE_STEPSTICK // makes sure MS1,2,3 !reset and !sleep are set
|
||||
|
||||
#define I2S_OUT_BCK GPIO_NUM_22
|
||||
#define I2S_OUT_WS GPIO_NUM_17
|
||||
#define I2S_OUT_DATA GPIO_NUM_21
|
||||
|
||||
// ================== CPU MAP ======================
|
||||
|
||||
#define X_STEPPER_MS3 I2SO(3) // X_CS
|
||||
#define Y_STEPPER_MS3 I2SO(6) // Y_CS
|
||||
#define Z_STEPPER_MS3 I2SO(11) // Z_CS
|
||||
|
||||
#define STEPPER_RESET GPIO_NUM_19
|
||||
|
||||
// Motor Socket #1
|
||||
#define X_DISABLE_PIN I2SO(0)
|
||||
#define X_DIRECTION_PIN I2SO(1)
|
||||
#define X_STEP_PIN I2SO(2)
|
||||
|
||||
// Motor Socket #2
|
||||
#define Y_DIRECTION_PIN I2SO(4)
|
||||
#define Y_STEP_PIN I2SO(5)
|
||||
#define Y_DISABLE_PIN I2SO(7)
|
||||
|
||||
// Motor Socket #3
|
||||
#define Z_DISABLE_PIN I2SO(8)
|
||||
#define Z_DIRECTION_PIN I2SO(9)
|
||||
#define Z_STEP_PIN I2SO(10)
|
||||
|
||||
// CNC I/O Modules
|
||||
|
||||
#define X_LIMIT_PIN GPIO_NUM_33
|
||||
#define Y_LIMIT_PIN GPIO_NUM_32
|
||||
#define Z_LIMIT_PIN GPIO_NUM_35
|
||||
|
||||
// ================= defaults ===========================
|
||||
|
||||
#define DEFAULT_STEPPER_IDLE_LOCK_TIME 255 // keep them on, the trinamics will reduce power at idle
|
||||
|
||||
#define DEFAULT_X_MICROSTEPS 32
|
||||
#define DEFAULT_Y_MICROSTEPS DEFAULT_X_MICROSTEPS
|
||||
#define DEFAULT_Z_MICROSTEPS DEFAULT_X_MICROSTEPS
|
||||
|
||||
// some math to figure out microsteps per unit // units could bedegrees or radians
|
||||
#define UNITS_PER_REV (2.0 * M_PI) // 360.0 degrees or 6.2831853 radians
|
||||
#define STEPS_PER_REV 400.0
|
||||
#define REDUCTION_RATIO (60.0 / 16.0) // the pulleys on arm and motor
|
||||
#define MICROSTEPS_PER_REV (STEPS_PER_REV * (float)DEFAULT_X_MICROSTEPS * REDUCTION_RATIO)
|
||||
|
||||
#define DEFAULT_X_STEPS_PER_MM (MICROSTEPS_PER_REV / UNITS_PER_REV)
|
||||
#define DEFAULT_Y_STEPS_PER_MM DEFAULT_X_STEPS_PER_MM
|
||||
#define DEFAULT_Z_STEPS_PER_MM DEFAULT_X_STEPS_PER_MM
|
||||
|
||||
#define DEFAULT_X_MAX_RATE 100.0 // mm/min
|
||||
#define DEFAULT_Y_MAX_RATE DEFAULT_X_MAX_RATE
|
||||
#define DEFAULT_Z_MAX_RATE DEFAULT_X_MAX_RATE
|
||||
|
||||
#define DEFAULT_X_ACCELERATION 20.0
|
||||
#define DEFAULT_Y_ACCELERATION DEFAULT_X_ACCELERATION
|
||||
#define DEFAULT_Z_ACCELERATION DEFAULT_X_ACCELERATION
|
||||
|
||||
// homing
|
||||
#define DEFAULT_HOMING_FEED_RATE 25
|
||||
#define DEFAULT_HOMING_SEEK_RATE 100
|
||||
#define DEFAULT_HOMING_DIR_MASK (bit(X_AXIS) | bit(Y_AXIS) | bit(Z_AXIS)) // all axes home negative
|
||||
#define DEFAULT_HOMING_ENABLE 1
|
||||
#define DEFAULT_INVERT_LIMIT_PINS 0
|
||||
|
||||
// The machine homes up and above center. MPos is the axis angle in radians
|
||||
// at the homing posiiton
|
||||
|
||||
#define DEFAULT_X_HOMING_MPOS -0.75 // neagtive because above horizontal
|
||||
#define DEFAULT_Y_HOMING_MPOS -0.75
|
||||
#define DEFAULT_Z_HOMING_MPOS -0.75
|
||||
|
||||
// the total travel is straight down from horizontal (pi/2) + the up travel
|
||||
#define DEFAULT_X_MAX_TRAVEL ((M_PI / 2.0) - DEFAULT_X_HOMING_MPOS)
|
||||
#define DEFAULT_Y_MAX_TRAVEL DEFAULT_X_MAX_TRAVEL
|
||||
#define DEFAULT_Z_MAX_TRAVEL DEFAULT_X_MAX_TRAVEL
|
||||
|
||||
#define DEFAULT_HOMING_PULLOFF -DEFAULT_X_HOMING_MPOS
|
||||
|
||||
#define SPINDLE_TYPE SpindleType::NONE
|
Reference in New Issue
Block a user