mirror of
https://github.com/bdring/Grbl_Esp32.git
synced 2025-08-27 08:14:31 +02:00
Added ways to free up more I/O pins
- Any step or direction pin can be commented out if you don't plan to use it - Spindle pin can now be commented out
This commit is contained in:
@@ -38,23 +38,29 @@
|
|||||||
|
|
||||||
// This is the CPU Map for the ESP32 CNC Controller R2
|
// This is the CPU Map for the ESP32 CNC Controller R2
|
||||||
|
|
||||||
|
|
||||||
|
// 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.
|
||||||
#define X_STEP_PIN GPIO_NUM_12
|
#define X_STEP_PIN GPIO_NUM_12
|
||||||
#define Y_STEP_PIN GPIO_NUM_14
|
#define Y_STEP_PIN GPIO_NUM_14
|
||||||
#define Z_STEP_PIN GPIO_NUM_27
|
#define Z_STEP_PIN GPIO_NUM_27
|
||||||
#define STEP_MASK B111 // don't change
|
#define STEP_MASK B111 // don't change
|
||||||
|
|
||||||
#define X_STEP_BIT 0
|
#define X_STEP_BIT 0 // don't change
|
||||||
#define Y_STEP_BIT 1
|
#define Y_STEP_BIT 1 // don't change
|
||||||
#define Z_STEP_BIT 2
|
#define Z_STEP_BIT 2 // don't change
|
||||||
|
|
||||||
#define X_DIRECTION_BIT 0
|
#define X_DIRECTION_BIT 0 // don't change
|
||||||
#define Y_DIRECTION_BIT 1
|
#define Y_DIRECTION_BIT 1 // don't change
|
||||||
#define Z_DIRECTION_BIT 2
|
#define Z_DIRECTION_BIT 2 // don't change
|
||||||
|
|
||||||
#define X_DIRECTION_PIN GPIO_NUM_26
|
#define X_DIRECTION_PIN GPIO_NUM_26
|
||||||
#define Y_DIRECTION_PIN GPIO_NUM_25
|
#define Y_DIRECTION_PIN GPIO_NUM_25
|
||||||
#define Z_DIRECTION_PIN GPIO_NUM_33
|
#define Z_DIRECTION_PIN GPIO_NUM_33
|
||||||
|
|
||||||
|
// OK to comment out to use pin for other features
|
||||||
#define STEPPERS_DISABLE_PIN GPIO_NUM_13
|
#define STEPPERS_DISABLE_PIN GPIO_NUM_13
|
||||||
|
|
||||||
|
|
||||||
@@ -62,8 +68,10 @@
|
|||||||
// *** Comment it out to use the pin for other features
|
// *** Comment it out to use the pin for other features
|
||||||
#define COOLANT_FLOOD_PIN GPIO_NUM_16
|
#define COOLANT_FLOOD_PIN GPIO_NUM_16
|
||||||
//#define COOLANT_MIST_PIN GPIO_NUM_21
|
//#define COOLANT_MIST_PIN GPIO_NUM_21
|
||||||
|
|
||||||
#define SPINDLE_PWM_PIN GPIO_NUM_17
|
// 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
|
||||||
#define SPINDLE_PWM_CHANNEL 0
|
#define SPINDLE_PWM_CHANNEL 0
|
||||||
#define SPINDLE_PWM_BASE_FREQ 5000 // Hz
|
#define SPINDLE_PWM_BASE_FREQ 5000 // Hz
|
||||||
#define SPINDLE_PWM_BIT_PRECISION 8
|
#define SPINDLE_PWM_BIT_PRECISION 8
|
||||||
@@ -76,9 +84,9 @@
|
|||||||
//#define SPINDLE_ENABLE_PIN GPIO_NUM_16
|
//#define SPINDLE_ENABLE_PIN GPIO_NUM_16
|
||||||
//#define SPINDLE_DIR_PIN GPIO_NUM_16
|
//#define SPINDLE_DIR_PIN GPIO_NUM_16
|
||||||
|
|
||||||
#define X_LIMIT_BIT 0
|
#define X_LIMIT_BIT 0 // don't change
|
||||||
#define Y_LIMIT_BIT 1
|
#define Y_LIMIT_BIT 1 // don't change
|
||||||
#define Z_LIMIT_BIT 2
|
#define Z_LIMIT_BIT 2 // don't change
|
||||||
|
|
||||||
#define X_LIMIT_PIN GPIO_NUM_2
|
#define X_LIMIT_PIN GPIO_NUM_2
|
||||||
#define Y_LIMIT_PIN GPIO_NUM_4
|
#define Y_LIMIT_PIN GPIO_NUM_4
|
||||||
|
@@ -331,9 +331,7 @@ uint8_t get_step_pin_mask(uint8_t axis_idx)
|
|||||||
|
|
||||||
// Returns direction pin mask according to Grbl internal axis indexing.
|
// Returns direction pin mask according to Grbl internal axis indexing.
|
||||||
uint8_t get_direction_pin_mask(uint8_t axis_idx)
|
uint8_t get_direction_pin_mask(uint8_t axis_idx)
|
||||||
{
|
{
|
||||||
if ( axis_idx == X_AXIS ) { return((1<<X_DIRECTION_BIT)); }
|
return(1<<axis_idx);
|
||||||
if ( axis_idx == Y_AXIS ) { return((1<<Y_DIRECTION_BIT)); }
|
|
||||||
return((1<<Z_DIRECTION_BIT));
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@@ -32,23 +32,31 @@ void spindle_init()
|
|||||||
pinMode(SPINDLE_DIR_PIN, OUTPUT);
|
pinMode(SPINDLE_DIR_PIN, OUTPUT);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#ifdef SPINDLE_PWM_PIN
|
||||||
// use the LED control feature to setup PWM https://esp-idf.readthedocs.io/en/v1.0/api/ledc.html
|
// use the LED control feature to setup PWM https://esp-idf.readthedocs.io/en/v1.0/api/ledc.html
|
||||||
ledcSetup(SPINDLE_PWM_CHANNEL, SPINDLE_PWM_BASE_FREQ, SPINDLE_PWM_BIT_PRECISION); // setup the channel
|
ledcSetup(SPINDLE_PWM_CHANNEL, SPINDLE_PWM_BASE_FREQ, SPINDLE_PWM_BIT_PRECISION); // setup the channel
|
||||||
ledcAttachPin(SPINDLE_PWM_PIN, SPINDLE_PWM_CHANNEL); // attach the PWM to the pin
|
ledcAttachPin(SPINDLE_PWM_PIN, SPINDLE_PWM_CHANNEL); // attach the PWM to the pin
|
||||||
|
#endif
|
||||||
|
|
||||||
// Start with spindle off off
|
// Start with spindle off off
|
||||||
spindle_stop();
|
spindle_stop();
|
||||||
}
|
}
|
||||||
|
|
||||||
void spindle_stop()
|
void spindle_stop()
|
||||||
{
|
{
|
||||||
spindle_set_enable(false);
|
spindle_set_enable(false);
|
||||||
grbl_analogWrite(SPINDLE_PWM_CHANNEL, 0);
|
#ifdef SPINDLE_PWM_PIN
|
||||||
|
grbl_analogWrite(SPINDLE_PWM_CHANNEL, 0);
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
uint8_t spindle_get_state() // returns SPINDLE_STATE_DISABLE, SPINDLE_STATE_CW or SPINDLE_STATE_CCW
|
uint8_t spindle_get_state() // returns SPINDLE_STATE_DISABLE, SPINDLE_STATE_CW or SPINDLE_STATE_CCW
|
||||||
{
|
{
|
||||||
// TODO Update this when direction and enable pin are added
|
// TODO Update this when direction and enable pin are added
|
||||||
|
#ifndef SPINDLE_PWM_PIN
|
||||||
|
return(SPINDLE_STATE_DISABLE);
|
||||||
|
#endif
|
||||||
|
|
||||||
if (ledcRead(SPINDLE_PWM_CHANNEL) == 0) // Check the PWM value
|
if (ledcRead(SPINDLE_PWM_CHANNEL) == 0) // Check the PWM value
|
||||||
return(SPINDLE_STATE_DISABLE);
|
return(SPINDLE_STATE_DISABLE);
|
||||||
else
|
else
|
||||||
@@ -66,6 +74,10 @@ uint8_t spindle_get_state() // returns SPINDLE_STATE_DISABLE, SPINDLE_STATE_CW
|
|||||||
|
|
||||||
void spindle_set_speed(uint8_t pwm_value)
|
void spindle_set_speed(uint8_t pwm_value)
|
||||||
{
|
{
|
||||||
|
#ifndef SPINDLE_PWM_PIN
|
||||||
|
return;
|
||||||
|
#endif
|
||||||
|
|
||||||
#ifndef SPINDLE_ENABLE_OFF_WITH_ZERO_SPEED
|
#ifndef SPINDLE_ENABLE_OFF_WITH_ZERO_SPEED
|
||||||
spindle_set_enable(true);
|
spindle_set_enable(true);
|
||||||
#else
|
#else
|
||||||
|
@@ -341,17 +341,31 @@ void stepper_init()
|
|||||||
{
|
{
|
||||||
|
|
||||||
// make the direction pins outputs
|
// make the direction pins outputs
|
||||||
pinMode(X_DIRECTION_PIN, OUTPUT);
|
#ifdef X_DIRECTION_PIN
|
||||||
pinMode(Y_DIRECTION_PIN, OUTPUT);
|
pinMode(X_DIRECTION_PIN, OUTPUT);
|
||||||
pinMode(Z_DIRECTION_PIN, OUTPUT);
|
#endif
|
||||||
|
#ifdef Y_DIRECTION_PIN
|
||||||
|
pinMode(Y_DIRECTION_PIN, OUTPUT);
|
||||||
|
#endif
|
||||||
|
#ifdef Z_DIRECTION_PIN
|
||||||
|
pinMode(Z_DIRECTION_PIN, OUTPUT);
|
||||||
|
#endif
|
||||||
|
|
||||||
// make the step pins outputs
|
// make the step pins outputs
|
||||||
pinMode(X_STEP_PIN, OUTPUT);
|
#ifdef X_STEP_PIN
|
||||||
pinMode(Y_STEP_PIN, OUTPUT);
|
pinMode(X_STEP_PIN, OUTPUT);
|
||||||
pinMode(Z_STEP_PIN, OUTPUT);
|
#endif
|
||||||
|
#ifdef Y_STEP_PIN
|
||||||
|
pinMode(Y_STEP_PIN, OUTPUT);
|
||||||
|
#endif
|
||||||
|
#ifdef Z_STEP_PIN
|
||||||
|
pinMode(Z_STEP_PIN, OUTPUT);
|
||||||
|
#endif
|
||||||
|
|
||||||
// make the stepper disable pin an output
|
// make the stepper disable pin an output
|
||||||
pinMode(STEPPERS_DISABLE_PIN, OUTPUT);
|
#ifdef STEPPERS_DISABLE_PIN
|
||||||
|
pinMode(STEPPERS_DISABLE_PIN, OUTPUT);
|
||||||
|
#endif
|
||||||
|
|
||||||
// setup stepper timer interrupt
|
// setup stepper timer interrupt
|
||||||
|
|
||||||
@@ -444,17 +458,30 @@ void st_reset()
|
|||||||
void set_direction_pins_on(uint8_t onMask)
|
void set_direction_pins_on(uint8_t onMask)
|
||||||
{
|
{
|
||||||
// inverts are applied in step generation
|
// inverts are applied in step generation
|
||||||
digitalWrite(X_DIRECTION_PIN, (onMask & (1<<X_AXIS)));
|
#ifdef X_DIRECTION_PIN
|
||||||
digitalWrite(Y_DIRECTION_PIN, (onMask & (1<<Y_AXIS)));
|
digitalWrite(X_DIRECTION_PIN, (onMask & (1<<X_AXIS)));
|
||||||
digitalWrite(Z_DIRECTION_PIN, (onMask & (1<<Z_AXIS)));
|
#endif
|
||||||
|
#ifdef Y_DIRECTION_PIN
|
||||||
|
digitalWrite(Y_DIRECTION_PIN, (onMask & (1<<Y_AXIS)));
|
||||||
|
#endif
|
||||||
|
#ifdef Z_DIRECTION_PIN
|
||||||
|
digitalWrite(Z_DIRECTION_PIN, (onMask & (1<<Z_AXIS)));
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
void set_stepper_pins_on(uint8_t onMask)
|
void set_stepper_pins_on(uint8_t onMask)
|
||||||
{
|
{
|
||||||
onMask ^= settings.step_invert_mask; // invert pins as required by invert mask
|
onMask ^= settings.step_invert_mask; // invert pins as required by invert mask
|
||||||
digitalWrite(X_STEP_PIN, (onMask & (1<<X_AXIS)));
|
|
||||||
digitalWrite(Y_STEP_PIN, (onMask & (1<<Y_AXIS)));
|
#ifdef X_STEP_PIN
|
||||||
digitalWrite(Z_STEP_PIN, (onMask & (1<<Z_AXIS)));
|
digitalWrite(X_STEP_PIN, (onMask & (1<<X_AXIS)));
|
||||||
|
#endif
|
||||||
|
#ifdef Y_STEP_PIN
|
||||||
|
digitalWrite(Y_STEP_PIN, (onMask & (1<<Y_AXIS)));
|
||||||
|
#endif
|
||||||
|
#ifdef Z_STEP_PIN
|
||||||
|
digitalWrite(Z_STEP_PIN, (onMask & (1<<Z_AXIS)));
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
@@ -1027,7 +1054,10 @@ void IRAM_ATTR Stepper_Timer_Stop()
|
|||||||
void set_stepper_disable(uint8_t isOn) // isOn = true // to disable
|
void set_stepper_disable(uint8_t isOn) // isOn = true // to disable
|
||||||
{
|
{
|
||||||
if (bit_istrue(settings.flags,BITFLAG_INVERT_ST_ENABLE)) { isOn = !isOn; } // Apply pin invert.
|
if (bit_istrue(settings.flags,BITFLAG_INVERT_ST_ENABLE)) { isOn = !isOn; } // Apply pin invert.
|
||||||
digitalWrite(STEPPERS_DISABLE_PIN, isOn );
|
|
||||||
|
#ifdef STEPPERS_DISABLE_PIN
|
||||||
|
digitalWrite(STEPPERS_DISABLE_PIN, isOn );
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
Reference in New Issue
Block a user