mirror of
https://github.com/bdring/Grbl_Esp32.git
synced 2025-09-01 18:32:37 +02:00
@@ -192,14 +192,20 @@
|
||||
|
||||
#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 Y_STEP_PIN GPIO_NUM_14
|
||||
#define X_DIRECTION_PIN GPIO_NUM_26
|
||||
#define Y_DIRECTION_PIN GPIO_NUM_25
|
||||
#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
|
||||
|
||||
@@ -232,7 +238,24 @@
|
||||
|
||||
#define SPINDLE_PWM_RANGE (SPINDLE_PWM_MAX_VALUE-SPINDLE_PWM_MIN_VALUE)
|
||||
|
||||
#define SERVO_PEN_PIN GPIO_NUM_27
|
||||
#define USING_SERVO // uncommewnt to use this feature
|
||||
#define USING_SOLENOID // uncommewnt 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
|
||||
|
||||
|
||||
|
||||
#ifdef DEFAULTS_GENERIC
|
||||
#undef DEFAULTS_GENERIC // undefine generic then define each default below
|
||||
|
@@ -20,7 +20,7 @@
|
||||
|
||||
// Grbl versioning system
|
||||
#define GRBL_VERSION "1.1f"
|
||||
#define GRBL_VERSION_BUILD "20190626"
|
||||
#define GRBL_VERSION_BUILD "20190708"
|
||||
|
||||
//#include <sdkconfig.h>
|
||||
#include <Arduino.h>
|
||||
|
@@ -26,6 +26,8 @@
|
||||
|
||||
#ifdef USE_SERVO_AXES
|
||||
|
||||
static TaskHandle_t servosSyncTaskHandle = 0;
|
||||
|
||||
#ifdef SERVO_X_PIN
|
||||
ServoAxis X_Servo_Axis(X_AXIS, SERVO_X_PIN, SERVO_X_CHANNEL_NUM);
|
||||
#endif
|
||||
@@ -38,18 +40,22 @@
|
||||
|
||||
void init_servos()
|
||||
{
|
||||
grbl_send(CLIENT_SERIAL, "[MSG: Init Servos]\r\n");
|
||||
#ifdef SERVO_X_PIN
|
||||
grbl_send(CLIENT_SERIAL, "[MSG: Init X Servo]\r\n");
|
||||
X_Servo_Axis.init();
|
||||
Y_Servo_Axis.set_range(SERVO_X_RANGE_MIN, SERVO_X_RANGE_MAX);
|
||||
X_Servo_Axis.set_range(SERVO_X_RANGE_MIN, SERVO_X_RANGE_MAX);
|
||||
X_Servo_Axis.set_homing_type(SERVO_HOMING_OFF);
|
||||
X_Servo_Axis.set_disable_on_alarm(true);
|
||||
X_Servo_Axis.set_disable_on_alarm(false);
|
||||
X_Servo_Axis.set_disable_with_steppers(false);
|
||||
#endif
|
||||
#ifdef SERVO_Y_PIN
|
||||
grbl_send(CLIENT_SERIAL, "[MSG: Init Y Servo]\r\n");
|
||||
Y_Servo_Axis.init();
|
||||
Y_Servo_Axis.set_range(SERVO_Y_RANGE_MIN, SERVO_Y_RANGE_MAX);
|
||||
#endif
|
||||
#ifdef SERVO_Z_PIN
|
||||
grbl_send(CLIENT_SERIAL, "[MSG: Init Z Servo]\r\n");
|
||||
Z_Servo_Axis.init();
|
||||
Z_Servo_Axis.set_range(SERVO_Z_RANGE_MIN, SERVO_Z_RANGE_MAX);
|
||||
Z_Servo_Axis.set_homing_type(SERVO_HOMING_TARGET);
|
||||
@@ -73,14 +79,13 @@ void servosSyncTask(void *pvParameters)
|
||||
{
|
||||
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);
|
||||
xLastWakeTime = xTaskGetTickCount(); // Initialise the xLastWakeTime variable with the current time.
|
||||
while(true) { // don't ever return from this or the task dies
|
||||
#ifdef SERVO_X_PIN
|
||||
X_Servo_Axis.set_location();
|
||||
|
||||
X_Servo_Axis.set_location();
|
||||
#endif
|
||||
#ifdef SERVO_Y_PIN
|
||||
Y_Servo_Axis.set_location();
|
||||
@@ -88,6 +93,7 @@ void servosSyncTask(void *pvParameters)
|
||||
#ifdef SERVO_Z_PIN
|
||||
Z_Servo_Axis.set_location();
|
||||
#endif
|
||||
vTaskDelayUntil(&xLastWakeTime, xServoFrequency);
|
||||
}
|
||||
}
|
||||
|
||||
@@ -104,7 +110,7 @@ void ServoAxis::init()
|
||||
{
|
||||
ledcSetup(_channel_num, _pwm_freq, _pwm_resolution_bits);
|
||||
ledcAttachPin(_pin_num, _channel_num);
|
||||
disable();
|
||||
disable();
|
||||
}
|
||||
/*
|
||||
void ServoAxis::set_location()
|
||||
@@ -139,7 +145,7 @@ void ServoAxis::set_location()
|
||||
}
|
||||
|
||||
// get the calibration values
|
||||
if (_cal_is_valid(false)) { // if calibration settings are OK then apply them
|
||||
if (_cal_is_valid()) { // if calibration settings are OK then apply them
|
||||
min_pulse_cal = (settings.steps_per_mm[_axis] / 100.0);
|
||||
max_pulse_cal = (settings.max_travel[_axis] / -100.0);
|
||||
if (bit_istrue(settings.dir_invert_mask,bit(_axis))) { // the offset needs to be backwards
|
||||
@@ -182,7 +188,7 @@ void ServoAxis::set_location()
|
||||
float servo_pulse_min, servo_pulse_max;
|
||||
float min_pulse_cal, max_pulse_cal; // calibration values in percent 110% = 1.1
|
||||
uint32_t servo_pulse_len;
|
||||
float servo_pos, mpos, offset, wpos;
|
||||
float servo_pos, mpos, offset;
|
||||
|
||||
// skip location if we are in alarm mode
|
||||
if (_disable_on_alarm && (sys.state == STATE_ALARM)) {
|
||||
@@ -213,7 +219,7 @@ void ServoAxis::set_location()
|
||||
}
|
||||
|
||||
// get the calibration values
|
||||
if (_cal_is_valid(false)) { // if calibration settings are OK then apply them
|
||||
if (_cal_is_valid()) { // if calibration settings are OK then apply them
|
||||
min_pulse_cal = (settings.steps_per_mm[_axis] / 100.0);
|
||||
max_pulse_cal = (settings.max_travel[_axis] / -100.0);
|
||||
if (bit_istrue(settings.dir_invert_mask,bit(_axis))) { // the offset needs to be backwards
|
||||
@@ -263,12 +269,13 @@ void ServoAxis::disable()
|
||||
|
||||
// checks to see if calibration values are in an acceptable range
|
||||
// vebose = true if you want an error sent to serial port
|
||||
bool ServoAxis::_cal_is_valid(bool verbose)
|
||||
bool ServoAxis::_cal_is_valid()
|
||||
{
|
||||
bool settingsOK = true;
|
||||
static bool showError = true; // this will be used to show error only once
|
||||
|
||||
if ( (settings.steps_per_mm[_axis] < SERVO_CAL_MIN) || (settings.steps_per_mm[_axis] > SERVO_CAL_MAX) ) {
|
||||
if (verbose) {
|
||||
if (showError) {
|
||||
grbl_sendf(CLIENT_SERIAL, "[MSG:Servo cal ($10%d) Error: %4.4f s/b between %.2f and %.2f]\r\n", _axis, settings.steps_per_mm[_axis], SERVO_CAL_MIN, SERVO_CAL_MAX);
|
||||
}
|
||||
settingsOK = false;
|
||||
@@ -276,11 +283,13 @@ bool ServoAxis::_cal_is_valid(bool verbose)
|
||||
|
||||
// Note: Max travel is set positive via $$, but stored as a negative number
|
||||
if ( (settings.max_travel[_axis] < -SERVO_CAL_MAX) || (settings.max_travel[_axis] > -SERVO_CAL_MIN) ) {
|
||||
if (verbose) {
|
||||
if (showError) {
|
||||
grbl_sendf(CLIENT_SERIAL, "[MSG:Servo cal ($13%d) Error: %4.4f s/b between %.2f and %.2f]\r\n", _axis, -settings.max_travel[_axis], SERVO_CAL_MIN, SERVO_CAL_MAX);
|
||||
}
|
||||
settingsOK = false;
|
||||
}
|
||||
|
||||
showError = false; // to show error once
|
||||
return settingsOK;
|
||||
}
|
||||
|
||||
|
@@ -85,8 +85,6 @@
|
||||
#define SERVO_HOMING_OFF 0 // servo is off during homing
|
||||
#define SERVO_HOMING_TARGET 1 // servo is send to a location during homing
|
||||
|
||||
static TaskHandle_t servosSyncTaskHandle = 0;
|
||||
|
||||
extern float my_location;
|
||||
|
||||
void init_servos();
|
||||
@@ -126,9 +124,7 @@ class ServoAxis{
|
||||
|
||||
bool _validate_cal_settings();
|
||||
void _write_pwm(uint32_t duty);
|
||||
bool _cal_is_valid(bool verbose); // checks to see if calibration values are in acceptable range
|
||||
|
||||
|
||||
bool _cal_is_valid(); // checks to see if calibration values are in acceptable range
|
||||
};
|
||||
|
||||
#endif
|
||||
|
@@ -104,10 +104,8 @@ void servoSyncTask(void *pvParameters)
|
||||
float mpos_z, wpos_z;
|
||||
float z_offset;
|
||||
|
||||
xLastWakeTime = xTaskGetTickCount(); // Initialise the xLastWakeTime variable with the current time.
|
||||
while(true) { // don't ever return from this or the task dies
|
||||
|
||||
vTaskDelayUntil(&xLastWakeTime, xServoFrequency);
|
||||
|
||||
if (sys.state != STATE_ALARM) { // don't move until alarm is cleared...typically homing
|
||||
if (!servo_pen_enable ) {
|
||||
servo_delay_counter++;
|
||||
@@ -120,6 +118,7 @@ void servoSyncTask(void *pvParameters)
|
||||
calc_pen_servo(wpos_z); // calculate kinematics and move the servos
|
||||
}
|
||||
}
|
||||
vTaskDelayUntil(&xLastWakeTime, xServoFrequency);
|
||||
}
|
||||
}
|
||||
|
||||
@@ -169,9 +168,9 @@ void calc_pen_servo(float penZ)
|
||||
// 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);
|
||||
portENTER_CRITICAL(&myMutex);
|
||||
ledcWrite(SERVO_PEN_CHANNEL_NUM, servo_pen_pulse_len);
|
||||
taskEXIT_CRITICAL(&myMutex);
|
||||
portEXIT_CRITICAL(&myMutex);
|
||||
}
|
||||
|
||||
#endif
|
||||
|
@@ -68,11 +68,9 @@ void solenoidSyncTask(void *pvParameters)
|
||||
TickType_t xLastWakeTime;
|
||||
const TickType_t xSolenoidFrequency = SOLENOID_TIMER_INT_FREQ; // in ticks (typically ms)
|
||||
uint16_t solenoid_delay_counter = 0;
|
||||
|
||||
|
||||
xLastWakeTime = xTaskGetTickCount(); // Initialise the xLastWakeTime variable with the current time.
|
||||
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);
|
||||
@@ -82,6 +80,7 @@ void solenoidSyncTask(void *pvParameters)
|
||||
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
|
||||
}
|
||||
vTaskDelayUntil(&xLastWakeTime, xSolenoidFrequency);
|
||||
}
|
||||
}
|
||||
|
||||
@@ -115,9 +114,9 @@ void calc_solenoid(float penZ)
|
||||
// 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);
|
||||
portENTER_CRITICAL(&myMutex);
|
||||
ledcWrite(SOLENOID_CHANNEL_NUM, solenoid_pen_pulse_len);
|
||||
portEXIT_CRITICAL(&myMutex);
|
||||
}
|
||||
|
||||
#endif
|
||||
|
@@ -32,8 +32,6 @@
|
||||
|
||||
*/
|
||||
|
||||
#define SOLENOID_PEN_PIN GPIO_NUM_16
|
||||
#define SOLENOID_CHANNEL_NUM 6
|
||||
#define SOLENOID_PWM_FREQ 5000
|
||||
#define SOLENOID_PWM_RES_BITS 8
|
||||
|
||||
|
@@ -5,15 +5,20 @@ data_dir=Grbl_Esp32/data
|
||||
|
||||
[common_env_data]
|
||||
lib_deps_builtin =
|
||||
EEPROM
|
||||
ArduinoOTA
|
||||
BluetoothSerial
|
||||
WiFi
|
||||
DNSServer
|
||||
EEPROM
|
||||
ESPmDNS
|
||||
FS
|
||||
Preferences
|
||||
SD
|
||||
SPI
|
||||
Preferences
|
||||
SPIFFS
|
||||
Update
|
||||
WebServer
|
||||
WiFi
|
||||
WiFiClientSecure
|
||||
|
||||
[env:nodemcu-32s]
|
||||
platform = espressif32
|
||||
@@ -21,3 +26,4 @@ board = nodemcu-32s
|
||||
framework = arduino
|
||||
upload_speed = 512000
|
||||
board_build.partitions = min_spiffs.csv
|
||||
monitor_speed = 115200
|
||||
|
Reference in New Issue
Block a user