/*
cpu_map.h - Header for system level commands and real-time processes
Part of Grbl
Copyright (c) 2014-2016 Sungeun K. Jeon for Gnea Research LLC
2018 - Bart Dring This file was modified for use on the ESP32
CPU. Do not use this with Grbl for atMega328P
Grbl 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. If not, see .
*/
#ifndef cpu_map_h
//#define cpu_map_h
/*
Not all pins can can work for all functions.
Check features like pull-ups, pwm, etc before
re-assigning numbers
(gpio34-39) are inputs only and don't have software pullup/down functions
You MUST use external pull-ups or noise WILL cause problems.
Unlike the AVR version certain pins are not forced into the same port.
Therefore, bit masks are not use the same way and typically should not be
changed. They are just preserved right now to make it easy to stay in sync
with AVR grbl
*/
//Set your pin definition
//let -1 to use default board pin
#define GRBL_SPI_SS -1
#define GRBL_SPI_MOSI -1
#define GRBL_SPI_MISO -1
#define GRBL_SPI_SCK -1
//Set your frequency
#define GRBL_SPI_FREQ 4000000
#ifdef CPU_MAP_TEST_DRIVE
/*
This is just a demo CPU_MAP for test driving. It creates a basic 3 axis machine, but
no actual i/o is used. It will appear that axes are moving, but they are virtual
This can be uploaded to an unattached ESP32 or attached to unknown hardware. There is no risk
pins trying to output signals into a short, etc that could dmamge the ESP32
Assuming no changes have been made to the config.h file it is also a way to get he basic program
running so OTA (over the air) firmware loading can be done.
*/
#define CPU_MAP_NAME "CPU_MAP_DEFAULT - Demo Only No I/O!"
#define CONTROL_FEED_HOLD_PIN GPIO_NUM_21 // Uno A1
#define LIMIT_MASK 0 // no limit pins
#endif
#ifdef CPU_MAP_ESP32
// This is the CPU Map for the ESP32 Development Controller
// https://github.com/bdring/Grbl_ESP32_Development_Controller
// https://www.tindie.com/products/33366583/grbl_esp32-cnc-development-board-v35/
// Select the version (uncomment one of them)
#define CPU_MAP_V3p5 // version 3.5 and earlier
//#define CPU_MAP_V4 // version 4 or higher (in developement)
#define USE_RMT_STEPS
// It is OK to comment out any step and direction pins. This
// won't affect operation except that there will be no output
// form the pins. Grbl will virtually move the axis. This could
// be handy if you are using a servo, etc. for another axis.
#if (defined CPU_MAP_V4)
#define CPU_MAP_NAME "CPU_MAP_ESP32_V4"
#define X_DIRECTION_PIN GPIO_NUM_14
#define Y_STEP_PIN GPIO_NUM_26
#define Y_DIRECTION_PIN GPIO_NUM_15
//#define COOLANT_FLOOD_PIN GPIO_NUM_25
#define SPINDLE_PWM_PIN GPIO_NUM_2
#define X_LIMIT_PIN GPIO_NUM_17
#define Z_LIMIT_PIN GPIO_NUM_16
#elif (defined CPU_MAP_V3p5)
#define CPU_MAP_NAME "CPU_MAP_ESP32_V3.5"
#define X_DIRECTION_PIN GPIO_NUM_26
#define Y_STEP_PIN GPIO_NUM_14
#define Y_DIRECTION_PIN GPIO_NUM_25
//#define COOLANT_FLOOD_PIN GPIO_NUM_16
#define SPINDLE_PWM_PIN GPIO_NUM_17
#define X_LIMIT_PIN GPIO_NUM_13 // CRA4
#define Z_LIMIT_PIN GPIO_NUM_15
#endif
#define X_STEP_PIN GPIO_NUM_12
#define X_RMT_CHANNEL 0
// #define Y_STEP_PIN (see versions above)
#define Y_RMT_CHANNEL 1
#define Z_STEP_PIN GPIO_NUM_27
#define Z_DIRECTION_PIN GPIO_NUM_33
#define Z_RMT_CHANNEL 2
// OK to comment out to use pin for other features
#define STEPPERS_DISABLE_PIN GPIO_NUM_2 // CRA4
//#define COOLANT_MIST_PIN GPIO_NUM_21
#define USER_DIGITAL_PIN_1 GPIO_NUM_21
#define USER_DIGITAL_PIN_2 GPIO_NUM_25
#define SPINDLE_PWM_CHANNEL 0
#define SPINDLE_PWM_BIT_PRECISION 8
#define SPINDLE_ENABLE_PIN GPIO_NUM_22
// see versions for X and Z
#define Y_LIMIT_PIN GPIO_NUM_4
#define LIMIT_MASK B111
#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
#endif
#ifdef CPU_MAP_ESPDUINO_32
// !!!! Experimental Untested !!!!!
// This is a CPU MAP 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.
#define CPU_MAP_NAME "CPU_MAP_ESPDUINO_32"
#define USE_RMT_STEPS
#define X_STEP_PIN GPIO_NUM_26 // Uno D2
#define X_DIRECTION_PIN GPIO_NUM_16 // Uno D5
#define X_RMT_CHANNEL 0
#define Y_STEP_PIN GPIO_NUM_25 // Uno D3
#define Y_DIRECTION_PIN GPIO_NUM_27 // Uno D6
#define Y_RMT_CHANNEL 1
#define Z_STEP_PIN GPIO_NUM_17 // Uno D4
#define Z_DIRECTION_PIN GPIO_NUM_14 // Uno D7
#define Z_RMT_CHANNEL 2
// OK to comment out to use pin for other features
#define STEPPERS_DISABLE_PIN GPIO_NUM_12 // Uno D8
#define SPINDLE_PWM_PIN GPIO_NUM_19 // Uno D11
#define SPINDLE_PWM_CHANNEL 0
#define SPINDLE_PWM_BIT_PRECISION 8 // be sure to match this with SPINDLE_PWM_MAX_VALUE
#define SPINDLE_DIR_PIN GPIO_NUM_18 // Uno D13
#define COOLANT_FLOOD_PIN GPIO_NUM_34 // Uno A3
#define COOLANT_MIST_PIN GPIO_NUM_36// Uno A4
#define X_LIMIT_PIN GPIO_NUM_13 // Uno D9
#define Y_LIMIT_PIN GPIO_NUM_5 // Uno D10
#define Z_LIMIT_PIN GPIO_NUM_19 // Uno D12
#define LIMIT_MASK B111
#define PROBE_PIN GPIO_NUM_39 // Uno A5
// comment out #define IGNORE_CONTROL_PINS in config.h to use control pins
#define CONTROL_RESET_PIN GPIO_NUM_2 // Uno A0
#define CONTROL_FEED_HOLD_PIN GPIO_NUM_4 // Uno A1
#define CONTROL_CYCLE_START_PIN GPIO_NUM_35 // Uno A2 ... ESP32 needs external pullup
#endif
#ifdef CPU_MAP_ESP32_ESC_SPINDLE
// This is an example of using a Brushless DC Hobby motor as
// a spindle motor
// See this wiki page for more info
// https://github.com/bdring/Grbl_Esp32/wiki/BESC-Spindle-Feature
#define CPU_MAP_NAME "CPU_MAP_ESP32_ESC_SPINDLE"
#define USE_RMT_STEPS
#define X_STEP_PIN GPIO_NUM_12
#define X_DIRECTION_PIN GPIO_NUM_14
#define X_RMT_CHANNEL 0
#define Y_STEP_PIN GPIO_NUM_26
#define Y_DIRECTION_PIN GPIO_NUM_15// #define Y_STEP_PIN (see versions above)
#define Y_RMT_CHANNEL 1
#define Z_STEP_PIN GPIO_NUM_27
#define Z_DIRECTION_PIN GPIO_NUM_33
#define Z_RMT_CHANNEL 2
// OK to comment out to use pin for other features
#define STEPPERS_DISABLE_PIN GPIO_NUM_13
#define SPINDLE_PWM_PIN GPIO_NUM_2
#define SPINDLE_ENABLE_PIN GPIO_NUM_22
#define SPINDLE_PWM_CHANNEL 0
// Begin RC ESC Based Spindle Information ======================
#define SPINDLE_PWM_BIT_PRECISION 16 // 16 bit recommended for ESC (don't change)
/*
Important ESC Settings
$33=50 // Hz this is the typical good frequency for an ESC
Determine the typical min and max pulse length of your ESC
min_pulse is typically 1ms (0.001 sec) or less
max_pulse is typically 2ms (0.002 sec) or more
determine PWM_period. It is (1/freq) if freq = 50...period = 0.02
determine pulse length for min_pulse and max_pulse in percent.
(pulse / PWM_period)
min_pulse = (0.001 / 0.02) = 0.035 = 3.5% so ... $33 and $34 = 3.5
max_pulse = (0.002 / .02) = 0.1 = 10% so ... $36=10
*/
// End RC ESC Based Spindle #defines ===========================
#define X_LIMIT_PIN GPIO_NUM_17
#define Y_LIMIT_PIN GPIO_NUM_4
#define Z_LIMIT_PIN GPIO_NUM_16
#define LIMIT_MASK B111
#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
#endif
#ifdef CPU_MAP_PEN_LASER // The Buildlog.net pen laser controller V1 & V2
// For pen mode be sure to uncomment #define USE_PEN_SERVO in config.h
// For solenoid mode be sure to uncomment #define USE_PEN_SERVO in config.h
// For laser mode, you do not need to change anything
// Note: You can use all 3 modes at the same time if you want
#define CPU_MAP_NAME "CPU_MAP_PEN_LASER"
#define USE_RMT_STEPS
// Pick a board version
//#define PEN_LASER_V1
#define PEN_LASER_V2
#define X_STEP_PIN GPIO_NUM_12
#define X_DIRECTION_PIN GPIO_NUM_26
#define X_RMT_CHANNEL 0
#define Y_STEP_PIN GPIO_NUM_14
#define Y_DIRECTION_PIN GPIO_NUM_25
#define Y_RMT_CHANNEL 1
#define STEPPERS_DISABLE_PIN GPIO_NUM_13
#ifdef PEN_LASER_V1
#define X_LIMIT_PIN GPIO_NUM_2
#endif
#ifdef PEN_LASER_V2
#define X_LIMIT_PIN GPIO_NUM_15
#endif
#define Y_LIMIT_PIN GPIO_NUM_4
#define LIMIT_MASK B11
// If SPINDLE_PWM_PIN is commented out, this frees up the pin, but Grbl will still
// use a virtual spindle. Do not comment out the other parameters for the spindle.
#define SPINDLE_PWM_PIN GPIO_NUM_17 // Laser PWM
#define SPINDLE_PWM_CHANNEL 0
#define SPINDLE_PWM_BIT_PRECISION 8 // be sure to match this with SPINDLE_PWM_MAX_VALUE
#define USING_SERVO // uncomment to use this feature
//#define USING_SOLENOID // uncomment to use this feature
#ifdef USING_SERVO
#define USE_SERVO_AXES
#define SERVO_Z_PIN GPIO_NUM_27
#define SERVO_Z_CHANNEL_NUM 3
#define SERVO_Z_RANGE_MIN 0
#define SERVO_Z_RANGE_MAX 10
#endif
#ifdef USING_SOLENOID
#define USE_PEN_SOLENOID
#define SOLENOID_PEN_PIN GPIO_NUM_16
#define SOLENOID_CHANNEL_NUM 6
#endif
// defaults
#define DEFAULT_STEP_PULSE_MICROSECONDS 3
#define DEFAULT_STEPPER_IDLE_LOCK_TIME 250 // stay on
#define DEFAULT_STEPPING_INVERT_MASK 0 // uint8_t
#define DEFAULT_DIRECTION_INVERT_MASK 0 // uint8_t
#define DEFAULT_INVERT_ST_ENABLE 0 // boolean
#define DEFAULT_INVERT_LIMIT_PINS 1 // boolean
#define DEFAULT_INVERT_PROBE_PIN 0 // boolean
#define DEFAULT_STATUS_REPORT_MASK 1
#define DEFAULT_JUNCTION_DEVIATION 0.01 // mm
#define DEFAULT_ARC_TOLERANCE 0.002 // mm
#define DEFAULT_REPORT_INCHES 0 // false
#define DEFAULT_SOFT_LIMIT_ENABLE 0 // false
#define DEFAULT_HARD_LIMIT_ENABLE 0 // false
#define DEFAULT_HOMING_ENABLE 0
#define DEFAULT_HOMING_DIR_MASK 0 // move positive dir Z, negative X,Y
#define DEFAULT_HOMING_FEED_RATE 200.0 // mm/min
#define DEFAULT_HOMING_SEEK_RATE 1000.0 // mm/min
#define DEFAULT_HOMING_DEBOUNCE_DELAY 250 // msec (0-65k)
#define DEFAULT_HOMING_PULLOFF 3.0 // mm
#define DEFAULT_SPINDLE_RPM_MAX 1000.0 // rpm
#define DEFAULT_SPINDLE_RPM_MIN 0.0 // rpm
#define DEFAULT_LASER_MODE 0 // false
#define DEFAULT_X_STEPS_PER_MM 80
#define DEFAULT_Y_STEPS_PER_MM 80
#define DEFAULT_Z_STEPS_PER_MM 100.0 // This is percent in servo mode...used for calibration
#define DEFAULT_X_MAX_RATE 5000.0 // mm/min
#define DEFAULT_Y_MAX_RATE 5000.0 // mm/min
#define DEFAULT_Z_MAX_RATE 5000.0 // mm/min
#define DEFAULT_X_ACCELERATION (50.0*60*60) // 10*60*60 mm/min^2 = 10 mm/sec^2
#define DEFAULT_Y_ACCELERATION (50.0*60*60) // 10*60*60 mm/min^2 = 10 mm/sec^2
#define DEFAULT_Z_ACCELERATION (50.0*60*60)
#define DEFAULT_X_MAX_TRAVEL 300.0 // mm NOTE: Must be a positive value.
#define DEFAULT_Y_MAX_TRAVEL 300.0 // mm NOTE: Must be a positive value.
#define DEFAULT_Z_MAX_TRAVEL 100.0 // This is percent in servo mode...used for calibration
#endif
#ifdef CPU_MAP_MIDTBOT // Buildlog.net midtbot
#define CPU_MAP_NAME "CPU_MAP_MIDTBOT"
#define USE_RMT_STEPS
#define X_STEP_PIN GPIO_NUM_12
#define Y_STEP_PIN GPIO_NUM_14
#define X_RMT_CHANNEL 0
#define X_DIRECTION_PIN GPIO_NUM_26
#define Y_DIRECTION_PIN GPIO_NUM_25
#define Y_RMT_CHANNEL 1
#ifndef COREXY // maybe set in config.h
#define COREXY
#endif
#define STEPPERS_DISABLE_PIN GPIO_NUM_13
#define X_LIMIT_PIN GPIO_NUM_2
#define Y_LIMIT_PIN GPIO_NUM_4
#define LIMIT_MASK B11
#ifndef USE_SERVO_AXES // maybe set in config.h
#define USE_SERVO_AXES
#endif
#define SERVO_Z_PIN GPIO_NUM_27
#define SERVO_Z_CHANNEL_NUM 5
#define SERVO_Z_RANGE_MIN 0.0
#define SERVO_Z_RANGE_MAX 5.0
#define SERVO_Z_HOMING_TYPE SERVO_HOMING_TARGET // during homing it will instantly move to a target value
#define SERVO_Z_HOME_POS SERVO_Z_RANGE_MAX // move to max during homing
#define SERVO_Z_MPOS false // will not use mpos, uses work coordinates
#ifndef IGNORE_CONTROL_PINS // maybe set in config.h
#define IGNORE_CONTROL_PINS
#endif
// redefine some stuff from config.h
#ifdef HOMING_CYCLE_0
#undef HOMING_CYCLE_0
#endif
#define HOMING_CYCLE_0 (1<