1
0
mirror of https://github.com/bdring/Grbl_Esp32.git synced 2025-09-03 03:13:25 +02:00

Added optional pen and solenoid control of Z axis

- Added Servo features
- Added Solenoid Features
- Added cpu_maps for pen/laser controler and midtbot
This commit is contained in:
bdring
2018-11-29 21:17:18 -06:00
parent 6980402a15
commit 82fdb29a18
9 changed files with 644 additions and 9 deletions

View File

@@ -58,10 +58,15 @@ void setup() {
}
#endif
memset(sys_position,0,sizeof(sys_position)); // Clear machine position.
#ifdef USE_PEN_SERVO
servo_init();
#endif
#ifdef USE_PEN_SOLENOID
solenoid_init();
#endif
// Initialize system state.
#ifdef FORCE_INITIALIZATION_ALARM

View File

@@ -47,7 +47,6 @@ Some features should not be changed. See notes below.
// If doing so, simply comment out these two defines and see instructions below.
#define DEFAULTS_GENERIC
#define CPU_MAP_ESP32 // currently not required
#define VERBOSE_HELP // adds addition help info, but could confuse some senders
// Serial baud rate
#define BAUD_RATE 115200
@@ -223,6 +222,13 @@ Some features should not be changed. See notes below.
// have the same steps per mm internally.
// #define COREXY // Default disabled. Uncomment to enable.
// Enable using a servo for the Z axis on a pen type machine.
// You typically should not define a pin for the Z axis in cpu_map.h
// You should configure your servo PWM pin and settings in servo_pen.h
//#define USE_PEN_SERVO
// Enable using a solenoid for the Z axis on a pen type machine
//#define USE_PEN_SOLENOID
// Inverts pin logic of the control command pins based on a mask. This essentially means you can use
// normally-closed switches on the specified pins, rather than the default normally-open switches.
// NOTE: The top option will mask and invert all control pins. The bottom option is an example of

View File

@@ -19,7 +19,7 @@
*/
#ifndef cpu_map_h
#define cpu_map_h
//#define cpu_map_h
/*
Not all pins can can work for all functions.
@@ -36,6 +36,7 @@
*/
#ifdef CPU_MAP_ESP32
// This is the CPU Map for the ESP32 CNC Controller R2
// It is OK to comment out any step and direction pins. This
@@ -71,9 +72,11 @@
#define SPINDLE_PWM_BIT_PRECISION 12 // be sure to match this with SPINDLE_PWM_MAX_VALUE
#define SPINDLE_PWM_OFF_VALUE 0
#define SPINDLE_PWM_MAX_VALUE 4096 // (2^SPINDLE_PWM_BIT_PRECISION)
#ifndef SPINDLE_PWM_MIN_VALUE
#define SPINDLE_PWM_MIN_VALUE 1 // Must be greater than zero.
#endif
#ifndef SPINDLE_PWM_MIN_VALUE
#define SPINDLE_PWM_MIN_VALUE 1 // Must be greater than zero.
#endif
#define SPINDLE_PWM_RANGE (SPINDLE_PWM_MAX_VALUE-SPINDLE_PWM_MIN_VALUE)
// if these spindle function pins are defined, they will be activated in the code
@@ -92,7 +95,113 @@
#define CONTROL_FEED_HOLD_PIN GPIO_NUM_36 // needs external pullup
#define CONTROL_CYCLE_START_PIN GPIO_NUM_39 // needs external pullup
// These are some ESP32 CPU Settings that the program needs, but are generally not changed
#endif
#ifdef CPU_MAP_PEN_LASER // The Buildlog.net pen laser controller V1
#define X_STEP_PIN GPIO_NUM_12
#define Y_STEP_PIN GPIO_NUM_14
#define X_DIRECTION_PIN GPIO_NUM_26
#define Y_DIRECTION_PIN GPIO_NUM_25
#define STEPPERS_DISABLE_PIN GPIO_NUM_13
#define X_LIMIT_PIN GPIO_NUM_2
#define Y_LIMIT_PIN GPIO_NUM_4
// ignored via config.h
#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
// 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
// PWM Generator is based on 80,000,000 Hz counter
// Therefor the freq determines the resolution
// 80,000,000 / freq = max resolution
// For 5000 that is 80,000,000 / 5000 = 16000
// round down to nearest bit count for SPINDLE_PWM_MAX_VALUE = 13bits (8192)
#define SPINDLE_PWM_BASE_FREQ 5000 // Hz
#define SPINDLE_PWM_BIT_PRECISION 12 // be sure to match this with SPINDLE_PWM_MAX_VALUE
#define SPINDLE_PWM_OFF_VALUE 0
#define SPINDLE_PWM_MAX_VALUE 4096 // (2^SPINDLE_PWM_BIT_PRECISION)
#ifndef SPINDLE_PWM_MIN_VALUE
#define SPINDLE_PWM_MIN_VALUE 1 // Must be greater than zero.
#endif
#define SPINDLE_PWM_RANGE (SPINDLE_PWM_MAX_VALUE-SPINDLE_PWM_MIN_VALUE)
// see servo_pen.h for servo i/o mapping
#endif
#ifdef CPU_MAP_MIDTBOT // Buildlog.net midtbot
#define X_STEP_PIN GPIO_NUM_12
#define Y_STEP_PIN GPIO_NUM_14
#define X_DIRECTION_PIN GPIO_NUM_26
#define Y_DIRECTION_PIN GPIO_NUM_25
#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
#ifndef USE_PEN_SERVO // maybe set in config.h
#define USE_PEN_SERVO
#endif
#ifndef IGNORE_CONTROL_PINS // maybe set in config.h
#define IGNORE_CONTROL_PINS
#endif
#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
// 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
// PWM Generator is based on 80,000,000 Hz counter
// Therefor the freq determines the resolution
// 80,000,000 / freq = max resolution
// For 5000 that is 80,000,000 / 5000 = 16000
// round down to nearest bit count for SPINDLE_PWM_MAX_VALUE = 13bits (8192)
#define SPINDLE_PWM_BASE_FREQ 5000 // Hz
#define SPINDLE_PWM_BIT_PRECISION 12 // be sure to match this with SPINDLE_PWM_MAX_VALUE
#define SPINDLE_PWM_OFF_VALUE 0
#define SPINDLE_PWM_MAX_VALUE 4096 // (2^SPINDLE_PWM_BIT_PRECISION)
#ifndef SPINDLE_PWM_MIN_VALUE
#define SPINDLE_PWM_MIN_VALUE 1 // Must be greater than zero.
#endif
// redefine some stuff from config.h
#define HOMING_CYCLE_0 (1<<X_AXIS)
#define HOMING_CYCLE_1 (1<<Y_AXIS)
#ifdef HOMING_CYCLE_2
#undef HOMING_CYCLE_2
#endif
#define SPINDLE_PWM_RANGE (SPINDLE_PWM_MAX_VALUE-SPINDLE_PWM_MIN_VALUE)
#define SERVO_PEN_PIN GPIO_NUM_27
#endif
// ================= common to all machines ================================
// These are some ESP32 CPU Settings that the program needs, but are generally not changed
#define F_TIMERS 80000000 // a reference to the speed of ESP32 timers
#define F_STEPPER_TIMER 20000000 // frequency of step pulse timer
#define STEPPER_OFF_TIMER_PRESCALE 8 // gives a frequency of 10MHz
@@ -125,4 +234,5 @@
// =======================================================================
#endif

View File

@@ -82,6 +82,102 @@
#endif
#ifdef DEFAULTS_PEN_LASER
// Grbl generic default settings. Should work across different machines.
#define DEFAULT_STEP_PULSE_MICROSECONDS 3
#define DEFAULT_STEPPER_IDLE_LOCK_TIME 250 // msec (0-254, 255 keeps steppers enabled)
#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 0 // boolean
#define DEFAULT_INVERT_PROBE_PIN 0 // boolean
#define DEFAULT_STATUS_REPORT_MASK 2 // MPos enabled
#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 // false
#define DEFAULT_HOMING_DIR_MASK 3 // move positive dir Z, negative X,Y
#define DEFAULT_HOMING_FEED_RATE 200.0 // mm/min
#define DEFAULT_HOMING_SEEK_RATE 2000.0 // mm/min
#define DEFAULT_HOMING_DEBOUNCE_DELAY 250 // msec (0-65k)
#define DEFAULT_HOMING_PULLOFF 1.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.0
#define DEFAULT_Y_STEPS_PER_MM 80.0
#define DEFAULT_Z_STEPS_PER_MM 80.0
#define DEFAULT_X_MAX_RATE 12000.0 // mm/min
#define DEFAULT_Y_MAX_RATE 12000.0 // mm/min
#define DEFAULT_Z_MAX_RATE 5000.0 // mm/min
#define DEFAULT_X_ACCELERATION (200.0*60*60) // 10*60*60 mm/min^2 = 10 mm/sec^2
#define DEFAULT_Y_ACCELERATION (200.0*60*60) // 10*60*60 mm/min^2 = 10 mm/sec^2
#define DEFAULT_Z_ACCELERATION (50.0*60*60) // 10*60*60 mm/min^2 = 10 mm/sec^2
#define DEFAULT_X_MAX_TRAVEL 100.0 // mm NOTE: Must be a positive value.
#define DEFAULT_Y_MAX_TRAVEL 100.0 // mm NOTE: Must be a positive value.
#define DEFAULT_Z_MAX_TRAVEL 10.0 // mm NOTE: Must be a positive value.
#endif
#ifdef DEFAULTS_MIDTBOT
// Grbl generic default settings. Should work across different machines.
#define DEFAULT_STEP_PULSE_MICROSECONDS 3
#define DEFAULT_STEPPER_IDLE_LOCK_TIME 250 // msec (0-254, 255 keeps steppers enabled)
#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 0 // boolean
#define DEFAULT_INVERT_PROBE_PIN 0 // boolean
#define DEFAULT_STATUS_REPORT_MASK 2 // MPos enabled
#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 1 // false
#define DEFAULT_HOMING_DIR_MASK 3 // move positive dir Z, negative X,Y
#define DEFAULT_HOMING_FEED_RATE 200.0 // mm/min
#define DEFAULT_HOMING_SEEK_RATE 3000.0 // mm/min
#define DEFAULT_HOMING_DEBOUNCE_DELAY 250 // msec (0-65k)
#define DEFAULT_HOMING_PULLOFF 1.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 400.0
#define DEFAULT_Y_STEPS_PER_MM 200.0
#define DEFAULT_Z_STEPS_PER_MM 100.0 // DEFAULT CAL VALUE !!
#define DEFAULT_X_MAX_RATE 12000.0 // mm/min
#define DEFAULT_Y_MAX_RATE 12000.0 // mm/min
#define DEFAULT_Z_MAX_RATE 12000.0 // mm/min
#define DEFAULT_X_ACCELERATION (800.0*60*60) // 10*60*60 mm/min^2 = 10 mm/sec^2
#define DEFAULT_Y_ACCELERATION (800.0*60*60) // 10*60*60 mm/min^2 = 10 mm/sec^2
#define DEFAULT_Z_ACCELERATION (100.0*60*60) // 10*60*60 mm/min^2 = 10 mm/sec^2
#define DEFAULT_X_MAX_TRAVEL 90.0 // mm NOTE: Must be a positive value.
#define DEFAULT_Y_MAX_TRAVEL 90.0 // mm NOTE: Must be a positive value.
#define DEFAULT_Z_MAX_TRAVEL 100.0 // DEFAULT CAL VALUE !!
#endif
#endif

View File

@@ -73,3 +73,6 @@
#include "telnet_server.h"
#endif
#endif
#include "servo_pen.h"
#include "solenoid_pen.h"

157
Grbl_Esp32/servo_pen.cpp Normal file
View File

@@ -0,0 +1,157 @@
/*
servo_pen.cpp
Part of Grbl_ESP32
copyright (c) 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 <http://www.gnu.org/licenses/>.
*/
#include "grbl.h"
#ifdef USE_PEN_SERVO
// used to delay turn on
bool servo_pen_enable = false;
void servo_init()
{
grbl_send(CLIENT_SERIAL, "[MSG:Servo Pen Mode]\r\n"); // startup message
//validate_servo_settings(true); // display any calibration errors
// Debug stuff
grbl_sendf(CLIENT_SERIAL, "[MSG:Servo max,min pulse times %.4f sec,%.4f sec]\r\n", SERVO_MAX_PULSE_SEC, SERVO_MIN_PULSE_SEC);
grbl_sendf(CLIENT_SERIAL, "[MSG:Servo max,min pulse counts %d,%d]\r\n", SERVO_MAX_PULSE, SERVO_MIN_PULSE);
validate_servo_settings(true); // will print errors
// debug stuff
servo_pen_enable = false; // start delay has not completed yet.
// setup PWM channel
ledcSetup(SERVO_PEN_CHANNEL_NUM, SERVO_PULSE_FREQ, SERVO_PULSE_RES_BITS);
ledcAttachPin(SERVO_PEN_PIN, SERVO_PEN_CHANNEL_NUM);
servo_disable(); // start it it off
// setup a task that will calculate the determine and set the servo position
xTaskCreatePinnedToCore( servoSyncTask, // task
"servoSyncTask", // name for task
4096, // size of task stack
NULL, // parameters
1, // priority
&servoSyncTaskHandle,
0 // core
);
}
// turn off the PWM (0 duty) to prevent servo jitter when not in use.
void servo_disable()
{
ledcWrite(SERVO_PEN_CHANNEL_NUM, 0);
}
// Grbl settings are used to calibrate the servo positions
// They work on a percentage, so a value of 100 (100%) applies no calibration
// Values outside a reasonable range can cause errors, so this function checks
// that they are within a reasonable range
bool validate_servo_settings(bool verbose) // make sure the settings are reasonable..otherwise reset the settings to default
{
bool settingsOK = true;
if ( (settings.steps_per_mm[Z_AXIS] < SERVO_CAL_MIN) || (settings.steps_per_mm[Z_AXIS] > SERVO_CAL_MAX) ) {
if (verbose) {
grbl_sendf(CLIENT_SERIAL, "[MSG:Servo cal ($102) Error: %4.4f s/b between %.2f and %.2f]\r\n", settings.steps_per_mm[Z_AXIS], SERVO_CAL_MIN, SERVO_CAL_MAX);
}
settingsOK = false;
}
// Note: Max travel is set positive via $$, but stored as a negative number
if ( (settings.max_travel[Z_AXIS] < -SERVO_CAL_MAX) || (settings.max_travel[Z_AXIS] > -SERVO_CAL_MIN) ) {
if (verbose) {
grbl_sendf(CLIENT_SERIAL, "[MSG:Servo cal ($132) Error: %4.4f s/b between %.2f and %.2f]\r\n", -settings.max_travel[Z_AXIS], SERVO_CAL_MIN, SERVO_CAL_MAX);
}
settingsOK = false;
}
return settingsOK;
}
// this is the task
void servoSyncTask(void *pvParameters)
{
int32_t current_position[N_AXIS]; // copy of current location
float m_pos[N_AXIS]; // machine position in mm
TickType_t xLastWakeTime;
const TickType_t xServoFrequency = SERVO_TIMER_INT_FREQ; // in ticks (typically ms)
uint16_t servo_delay_counter = 0;
while(true) { // don't ever return from this or the task dies
vTaskDelayUntil(&xLastWakeTime, xServoFrequency);
if (!servo_pen_enable) {
servo_delay_counter++;
servo_pen_enable = (servo_delay_counter > SERVO_TURNON_DELAY);
} else {
if(!stepper_idle) {
memcpy(current_position,sys_position,sizeof(sys_position)); // get current position in step
system_convert_array_steps_to_mpos(m_pos,current_position); // convert to millimeters
calc_pen_servo(m_pos[Z_AXIS]); // calculate kinematics and move the servos
} else {
servo_disable();
}
}
}
}
// calculate and set the PWM value for the servo
void calc_pen_servo(float penZ)
{
uint32_t servo_pen_pulse_len;
float servo_pen_pulse_min, servo_pen_pulse_max;
if (!servo_pen_enable) { // only proceed if startup delay as expired
return;
}
if (validate_servo_settings(false)) { // if calibration settings are OK then apply them
// Apply a calibration to the minimum position
servo_pen_pulse_min = SERVO_MIN_PULSE * (settings.steps_per_mm[Z_AXIS] / 100.0);
// Apply a calibration to the maximum position
servo_pen_pulse_max = SERVO_MAX_PULSE * (settings.max_travel[Z_AXIS] / -100.0);
} else { // use the defaults
servo_pen_pulse_min = SERVO_MIN_PULSE;
servo_pen_pulse_max = SERVO_MAX_PULSE;
}
// determine the pulse length
servo_pen_pulse_len = mapConstrain(penZ, SERVO_PEN_RANGE_MIN_MM, SERVO_PEN_RANGE_MAX_MM, servo_pen_pulse_min, servo_pen_pulse_max );
// TODO only update it if it has changed
// update the PWM value
// ledcWrite appears to have issues with interrupts, so make this a critical section
portMUX_TYPE myMutex = portMUX_INITIALIZER_UNLOCKED;
taskENTER_CRITICAL(&myMutex);
ledcWrite(SERVO_PEN_CHANNEL_NUM, servo_pen_pulse_len);
taskEXIT_CRITICAL(&myMutex);
}
#endif

80
Grbl_Esp32/servo_pen.h Normal file
View File

@@ -0,0 +1,80 @@
/*
servo.h
Part of Grbl_ESP32
copyright (c) 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 <http://www.gnu.org/licenses/>.
To use this, uncomment #define USE_PEN_SERVO in config.h
That should be the only change you need at the top level
Everything occurs as a low priority task that syncs the servo with the
current machine position.
TODO Make it reversible (turn opposite way)
*/
// ==== Begin: Things you are likely to change ====================
//#define SERVO_PEN_PIN GPIO_NUM_27 // FYI...you can disable the Z stepper pins (step & dir)
// the pulse lengths for the min and max travel .. (Note: Servo brands vary)
// If the servo goes backward from what you want, flip the values
// Note: this is not necessarily the servos limits (just the travel you want)
#define SERVO_MIN_PULSE_SEC 0.0012 // min pulse in seconds
#define SERVO_MAX_PULSE_SEC 0.002 // max pulse in seconds
// Pulse repeat rate (PWM Frequency)
#define SERVO_PULSE_FREQ 50 // 50Hz ...This is a standard analog servo value. Digital ones can repeat faster
// the range of the servo is constrained
// values above or below these will be limited to the min or max
#define SERVO_PEN_RANGE_MIN_MM 0.0 // the minimum z position in mm
#define SERVO_PEN_RANGE_MAX_MM 5.0 // the minimum z position in mm
// ==== End: Things you are likely to change =======================
// Begin: Advanced settings
#define SERVO_TIMER_NUM 1
#define SERVO_TIMER_INT_FREQ 20 // Hz This is the task frequency
#define SERVO_PEN_CHANNEL_NUM 5
#define SERVO_PULSE_RES_BITS 16 // bits of resolution of PWM (16 is max)
#define SERVO_PULSE_RES_COUNT 65535 // see above TODO...do the math here 2^SERVO_PULSE_RES_BITS
// A way to reduce the turn on current
#define SERVO_TURNON_DELAY 25 // Wait this many task counts to turn on servo
#define SERVO_TIME_PER_BIT ((1.0 / (float)SERVO_PULSE_FREQ) / ((float)SERVO_PULSE_RES_COUNT) ) // seconds
#define SERVO_MIN_PULSE (uint16_t)(SERVO_MIN_PULSE_SEC / SERVO_TIME_PER_BIT) // in timer counts
#define SERVO_MAX_PULSE (uint16_t)(SERVO_MAX_PULSE_SEC / SERVO_TIME_PER_BIT) // in timer counts
#define SERVO_CAL_MIN 20.0 // Percent: the minimum allowable calibration value
#define SERVO_CAL_MAX 180.0 // Percent: the maximum allowable calibration value
#ifndef servo_h
#define servo_h
static TaskHandle_t servoSyncTaskHandle = 0;
void servo_init();
void servo_disable();
bool validate_servo_settings(bool verbose);
void servoSyncTask(void *pvParameters);
void calc_pen_servo(float penZ);
#endif

125
Grbl_Esp32/solenoid_pen.cpp Normal file
View File

@@ -0,0 +1,125 @@
/*
solenoid_pen.cpp
Part of Grbl_ESP32
copyright (c) 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 <http://www.gnu.org/licenses/>.
*/
#include "grbl.h"
#ifdef USE_PEN_SOLENOID
// used to delay turn on
bool solenoid_pen_enable;
uint16_t solenoide_hold_count;
void solenoid_init()
{
grbl_send(CLIENT_SERIAL, "[MSG:Solenoid Mode]\r\n"); // startup message
//validate_servo_settings(true); // display any calibration errors
solenoid_pen_enable = false; // start delay has not completed yet.
solenoide_hold_count = 0; // initialize
// setup PWM channel
ledcSetup(SOLENOID_CHANNEL_NUM, SOLENOID_PWM_FREQ, SOLENOID_PWM_RES_BITS);
ledcAttachPin(SOLENOID_PEN_PIN, SOLENOID_CHANNEL_NUM);
solenoid_disable(); // start it it off
// setup a task that will calculate the determine and set the servo position
xTaskCreatePinnedToCore( solenoidSyncTask, // task
"solenoidSyncTask", // name for task
4096, // size of task stack
NULL, // parameters
1, // priority
&solenoidSyncTaskHandle,
0 // core
);
}
// turn off the PWM (0 duty)
void solenoid_disable()
{
ledcWrite(SOLENOID_CHANNEL_NUM, 0);
}
// this is the task
void solenoidSyncTask(void *pvParameters)
{
int32_t current_position[N_AXIS]; // copy of current location
float m_pos[N_AXIS]; // machine position in mm
TickType_t xLastWakeTime;
const TickType_t xSolenoidFrequency = SOLENOID_TIMER_INT_FREQ; // in ticks (typically ms)
uint16_t solenoid_delay_counter = 0;
while(true) { // don't ever return from this or the task dies
vTaskDelayUntil(&xLastWakeTime, xSolenoidFrequency);
if (!solenoid_pen_enable) {
solenoid_delay_counter++;
solenoid_pen_enable = (solenoid_delay_counter > SOLENOID_TURNON_DELAY);
}
else {
memcpy(current_position,sys_position,sizeof(sys_position)); // get current position in step
system_convert_array_steps_to_mpos(m_pos,current_position); // convert to millimeters
calc_solenoid(m_pos[Z_AXIS]); // calculate kinematics and move the servos
}
}
}
// calculate and set the PWM value for the servo
void calc_solenoid(float penZ)
{
uint32_t solenoid_pen_pulse_len;
if (!solenoid_pen_enable) // only proceed if startup delay as expired
return;
if (penZ < 0 && (sys.state != STATE_ALARM)) { // alarm also makes it go up
solenoide_hold_count = 0; // reset this count
solenoid_pen_pulse_len = 0; //
}
else {
if (solenoide_hold_count < SOLENOID_PULSE_LEN_HOLD) {
solenoid_pen_pulse_len = SOLENOID_PULSE_LEN_UP;
solenoide_hold_count++;
}
else {
solenoid_pen_pulse_len = SOLENOID_PULSE_LEN_HOLD;
}
}
// skip setting value if it is unchanged
if (ledcRead(SOLENOID_CHANNEL_NUM) == solenoid_pen_pulse_len)
return;
// update the PWM value
// ledcWrite appears to have issues with interrupts, so make this a critical section
portMUX_TYPE myMutex = portMUX_INITIALIZER_UNLOCKED;
taskENTER_CRITICAL(&myMutex);
ledcWrite(SOLENOID_CHANNEL_NUM, solenoid_pen_pulse_len);
taskEXIT_CRITICAL(&myMutex);
}
#endif

53
Grbl_Esp32/solenoid_pen.h Normal file
View File

@@ -0,0 +1,53 @@
/*
solenoid_pen.h
Part of Grbl_ESP32
copyright (c) 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 <http://www.gnu.org/licenses/>.
Usage notes:
This is designed to use a solenoid to lift a pen.
When the current Z location is below zero the pen is down
If the Z goes to zero or above the pen goes up.
Note: There is a still a virtual Z axis that has a finite speed.
If your gcode is commanding long travels in Z, there will be delays
between solenoid states as the Z "travels" to the location that will
change the state.
*/
#define SOLENOID_PEN_PIN GPIO_NUM_16
#define SOLENOID_CHANNEL_NUM 6
#define SOLENOID_PWM_FREQ 5000
#define SOLENOID_PWM_RES_BITS 8
#define SOLENOID_TURNON_DELAY (SOLENOID_TIMER_INT_FREQ/2)
#define SOLENOID_PULSE_LEN_UP 255
#define SOLENOID_PULSE_LEN_HOLD 80 // a lower value to prevent overheating
#define SOLENOID_HOLD_DELAY (SOLENOID_TIMER_INT_FREQ/2) // in task counts
#define SOLENOID_TIMER_INT_FREQ 50
#ifndef solenoid_h
#define solenoid_h
static TaskHandle_t solenoidSyncTaskHandle = 0;
void solenoid_init();
void solenoid_disable();
void solenoidSyncTask(void *pvParameters);
void calc_solenoid(float penZ);
#endif