1
0
mirror of https://github.com/bdring/Grbl_Esp32.git synced 2025-08-31 10:01:48 +02:00
* Handles Tranimic drivers errors better

- If an unsupported driver is specified, it will give a message and not crash.

* Cleaned up unused files

Got rid of old unipolar files
Got rid of servo axis feature - it is a motor class now
Got rid of solenoid pen feature - never really used and it should be a motor class if it is.

* Fix ENABLE_AUTHENTICATION (#569)

* Fixed authentication code.

* Removed another const cast

Co-authored-by: Stefan de Bruijn <stefan@nubilosoft.com>

* Fix step leakage with inverted steps (#570)

* Fix step leakage with inverted steps

* Update build date for merge

Co-authored-by: Bart Dring <bdring@buildlog.net>

Co-authored-by: Stefan de Bruijn <atlaste@users.noreply.github.com>
Co-authored-by: Stefan de Bruijn <stefan@nubilosoft.com>
Co-authored-by: Mitch Bradley <wmb@firmworks.com>
Co-authored-by: Bart Dring <bdring@buildlog.net>
This commit is contained in:
bdring
2020-09-01 16:53:53 -05:00
committed by GitHub
parent f4f7b948a5
commit fbf1732efa
20 changed files with 129 additions and 1019 deletions

View File

@@ -45,12 +45,7 @@ void grbl_init() {
#ifdef USE_PEN_SERVO
servo_init();
#endif
#ifdef USE_SERVO_AXES
init_servos();
#endif
#ifdef USE_PEN_SOLENOID
solenoid_init();
#endif
#ifdef USE_MACHINE_INIT
machine_init(); // user supplied function for special initialization
#endif

View File

@@ -23,7 +23,7 @@
// Grbl versioning system
#define GRBL_VERSION "1.3a"
#define GRBL_VERSION_BUILD "20200823"
#define GRBL_VERSION_BUILD "20200828"
//#include <sdkconfig.h>
#include <Arduino.h>
@@ -85,12 +85,6 @@
# endif
#endif
#include "SolenoidPen.h"
#ifdef USE_SERVO_AXES
# include "ServoAxis.h"
#endif
#ifdef USE_I2S_OUT
# include "I2SOut.h"
#endif

View File

@@ -0,0 +1,83 @@
#pragma once
// clang-format off
/*
3_pack_v1.h
Covers all V1 versions V1p0, V1p1, etc
Part of Grbl_ESP32
Pin assignments for the ESP32 I2S 6-axis board
2020 - Bart Dring
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 "3 Pack Controller V1"
#define USE_STEPSTICK // makes sure MS1,2,3 !reset and !sleep are set
#define X_STEPPER_MS3 GPIO_NUM_4 // X_CS (works for all drivers on this board)
#define X_STEP_PIN GPIO_NUM_32
#define X_DIRECTION_PIN GPIO_NUM_27
#define Y_STEP_PIN GPIO_NUM_33
#define Y_DIRECTION_PIN GPIO_NUM_26
#define Z_STEP_PIN GPIO_NUM_25
#define Z_DIRECTION_PIN GPIO_NUM_17
#define STEPPERS_DISABLE_PIN GPIO_NUM_16
/* Socket #1 ref
#1 GPIO_NUM_36 // Input Only (X_LIMIT_PIN)
#2 GPIO_NUM_39 // Input Only (Y_LIMIT_PIN)
#4 GPIO_NUM_34 // Input Only (Z_LIMIT_PIN)
#4 GPIO_NUM_35 // Input Only
*/
/* Socket #2 ref
#1 GPIO_NUM_2
#2 GPIO_NUM_21
#4 GPIO_NUM_22
#4 N/C
*/
/* Socket #3 ref
#1 GPIO_NUM_14
#2 GPIO_NUM_13
#4 GPIO_NUM_15
#4 GPIO_NUM_12
*/
// Socket #1
#define X_LIMIT_PIN GPIO_NUM_36
#define Y_LIMIT_PIN GPIO_NUM_39
#define Z_LIMIT_PIN GPIO_NUM_34
#define PROBE_PIN GPIO_NUM_35
/*
// Socket #3 5V Output
#define SPINDLE_TYPE SPINDLE_TYPE_LASER
#define SPINDLE_OUTPUT_PIN GPIO_NUM_14 // labeled SpinPWM
#define SPINDLE_ENABLE_PIN GPIO_NUM_13 // labeled SpinEnbl
#define COOLANT_MIST_PIN GPIO_NUM_15
#define COOLANT_FLOOD_PIN GPIO_NUM_12
*/
// Socket #3 5V Output
#define USER_DIGITAL_PIN_1 GPIO_NUM_14
#define USER_DIGITAL_PIN_2 GPIO_NUM_13
#define USER_DIGITAL_PIN_3 GPIO_NUM_15
#define USER_DIGITAL_PIN_4 GPIO_NUM_12

View File

@@ -132,14 +132,10 @@
// === Servos
// To use a servo motor on an axis, do not define step and direction
// pins for that axis, but instead include a block like this:
//#define USE_SERVO_AXES
//#define SERVO_Z_PIN GPIO_NUM_15 // It cannot be used when JTAG debugging
//#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
// === Homing cycles
// The default homing order is Z first (HOMING_CYCLE_0),

View File

@@ -52,20 +52,13 @@
// C is a servo
// servos
#define USE_SERVO_AXES
#define SERVO_Z_PIN GPIO_NUM_22
#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
#define SERVO_C_PIN GPIO_NUM_2
#define SERVO_C_RANGE_MIN 0.0
#define SERVO_C_RANGE_MAX 5.0
#define SERVO_C_HOMING_TYPE SERVO_HOMING_TARGET // during homing it will instantly move to a target value
#define SERVO_C_HOME_POS SERVO_C_RANGE_MAX // move to max during homing
#define SERVO_C_MPOS false // will not use mpos, uses work coordinates
// limit switches
#define X_LIMIT_PIN GPIO_NUM_21

View File

@@ -52,7 +52,6 @@
#define Y_LIMIT_PIN GPIO_NUM_4
#define USING_SERVO // uncomment to use this feature
//#define USING_SOLENOID // uncomment to use this feature
#ifdef USING_SERVO
#define Z_SERVO_PIN GPIO_NUM_27
@@ -60,11 +59,6 @@
#define Z_SERVO_RANGE_MAX 10.0
#endif
#ifdef USING_SOLENOID
#define USE_PEN_SOLENOID
#define SOLENOID_PEN_PIN GPIO_NUM_16
#endif
#define SPINDLE_TYPE SPINDLE_TYPE_NONE
// defaults

View File

@@ -130,14 +130,10 @@
// === Servos
// To use a servo motor on an axis, do not define step and direction
// pins for that axis, but instead include a block like this:
// #define USE_SERVO_AXES
// #define SERVO_Z_PIN GPIO_NUM_22
// #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
// === Homing cycles
// The default homing order is Z first (HOMING_CYCLE_0),

View File

@@ -57,22 +57,10 @@
#define STEPPERS_DISABLE_PIN GPIO_NUM_13
// Define one of these 2 options for spindle or servo
#define USE_SERVO_AXES
//#define USE_SPINDLE
#ifdef USE_SERVO_AXES
#define SPINDLE_TYPE SPINDLE_TYPE_NONE
#define Z_SERVO_PIN GPIO_NUM_27 // comment this out if PWM spindle/laser control.
#define Z_SERVO_RANGE_MIN 0.0
#define Z_SERVO_RANGE_MAX 5.0
#else
#define SPINDLE_TYPE SPINDLE_TYPE_PWM
#define SPINDLE_OUTPUT_PIN GPIO_NUM_27
#endif
#define Z_SERVO_PIN GPIO_NUM_27 // comment this out if PWM spindle/laser control.
#define Z_SERVO_RANGE_MIN 0.0
#define Z_SERVO_RANGE_MAX 5.0
// #define X_LIMIT_PIN See version section at beginning of file
#define Y_LIMIT_PIN GPIO_NUM_4

View File

@@ -52,10 +52,11 @@ namespace Motors {
motor_class_id_t type_id;
uint8_t is_active = false;
uint8_t has_errors = false;
protected:
uint8_t axis_index; // X_AXIS, etc
uint8_t dual_axis_index; // 0 = primary 1=ganged
uint8_t axis_index; // X_AXIS, etc
uint8_t dual_axis_index; // 0 = primary 1=ganged
bool _showError;
bool _use_mpos = true;

View File

@@ -220,8 +220,9 @@ void init_motors() {
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Using StepStick Mode");
uint8_t ms3_pins[MAX_N_AXIS][2] = { { X_STEPPER_MS3, X2_STEPPER_MS3 }, { Y_STEPPER_MS3, Y2_STEPPER_MS3 }, { Z_STEPPER_MS3, Z2_STEPPER_MS3 },
{ A_STEPPER_MS3, A2_STEPPER_MS3 }, { B_STEPPER_MS3, B2_STEPPER_MS3 }, { C_STEPPER_MS3, C2_STEPPER_MS3 } };
uint8_t ms3_pins[MAX_N_AXIS][2] = { { X_STEPPER_MS3, X2_STEPPER_MS3 }, { Y_STEPPER_MS3, Y2_STEPPER_MS3 },
{ Z_STEPPER_MS3, Z2_STEPPER_MS3 }, { A_STEPPER_MS3, A2_STEPPER_MS3 },
{ B_STEPPER_MS3, B2_STEPPER_MS3 }, { C_STEPPER_MS3, C2_STEPPER_MS3 } };
for (int axis = 0; axis < N_AXIS; axis++) {
for (int gang_index = 0; gang_index < 2; gang_index++) {
@@ -333,8 +334,9 @@ void motors_set_disable(bool disable) {
// now loop through all the motors to see if they can individually diable
for (uint8_t gang_index = 0; gang_index < MAX_GANGED; gang_index++) {
for (uint8_t axis = X_AXIS; axis < N_AXIS; axis++)
for (uint8_t axis = X_AXIS; axis < N_AXIS; axis++) {
myMotor[axis][gang_index]->set_disable(disable);
}
}
}

View File

@@ -44,16 +44,17 @@ namespace Motors {
_homing_mode = TRINAMIC_HOMING_MODE;
_homing_mask = 0; // no axes homing
set_axis_name();
if (_driver_part_number == 2130)
tmcstepper = new TMC2130Stepper(cs_pin, _r_sense, spi_index);
else if (_driver_part_number == 5160)
tmcstepper = new TMC5160Stepper(cs_pin, _r_sense, spi_index);
else {
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Trinamic unsupported p/n:%d", _driver_part_number);
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "%s Axis Unsupported Trinamic part number TMC%d", _axis_name, _driver_part_number);
has_errors = true; // as opposed to NullMotors, this is a real motor
return;
}
set_axis_name();
}
init_step_dir_pins(); // from StandardStepper
@@ -70,6 +71,9 @@ namespace Motors {
}
void TrinamicDriver::init() {
if (has_errors)
return;
SPI.begin(); // this will get called for each motor, but does not seem to hurt anything
tmcstepper->begin();
@@ -78,7 +82,7 @@ namespace Motors {
set_mode(false);
_homing_mask = 0;
is_active = true; // as opposed to NullMotors, this is a real motor
}
/*
@@ -98,6 +102,8 @@ namespace Motors {
}
bool TrinamicDriver::test() {
if (has_errors)
return false;
switch (tmcstepper->test_connection()) {
case 1:
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "%s Trinamic driver test failed. Check connection", _axis_name);
@@ -148,6 +154,8 @@ namespace Motors {
float hold (as a percentage of run)
*/
void TrinamicDriver::read_settings() {
if (has_errors)
return;
uint16_t run_i_ma = (uint16_t)(axis_settings[axis_index]->run_current->get() * 1000.0);
float hold_i_percent;
@@ -175,6 +183,8 @@ namespace Motors {
Coolstep mode, so it will need to switch to Coolstep when homing
*/
void TrinamicDriver::set_mode(bool isHoming) {
if (has_errors)
return;
if (isHoming)
_mode = TRINAMIC_HOMING_MODE;
else
@@ -216,6 +226,8 @@ namespace Motors {
This is the stallguard tuning info. It is call debug, so it could be generic across all classes.
*/
void TrinamicDriver::debug_message() {
if (has_errors)
return;
uint32_t tstep = tmcstepper->TSTEP();
if (tstep == 0xFFFFF || tstep < 1) // if axis is not moving return
@@ -247,7 +259,8 @@ namespace Motors {
// this can use the enable feature over SPI. The dedicated pin must be in the enable mode,
// but that can be hardwired that way.
void TrinamicDriver::set_disable(bool disable) {
//grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "%s Axis disable %d", _axis_name, disable);
if (has_errors)
return;
digitalWrite(disable_pin, disable);

View File

@@ -1,382 +0,0 @@
/*
ServoAxis.cpp
Part of Grbl_ESP32
copyright (c) 2018 - Bart Dring. This file was intended 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/>.
See ServoAxis.h for more details
*/
#include "Grbl.h"
#include "ServoAxis.h"
#ifdef USE_SERVO_AXES
static TaskHandle_t servosSyncTaskHandle = 0;
# ifdef SERVO_X_PIN
ServoAxis X_Servo_Axis(X_AXIS, SERVO_X_PIN);
# endif
# ifdef SERVO_Y_PIN
ServoAxis Y_Servo_Axis(Y_AXIS, SERVO_Y_PIN);
# endif
# ifdef SERVO_Z_PIN
ServoAxis Z_Servo_Axis(Z_AXIS, SERVO_Z_PIN);
# endif
# ifdef SERVO_A_PIN
ServoAxis A_Servo_Axis(A_AXIS, SERVO_A_PIN);
# endif
# ifdef SERVO_B_PIN
ServoAxis B_Servo_Axis(B_AXIS, SERVO_B_PIN);
# endif
# ifdef SERVO_C_PIN
ServoAxis C_Servo_Axis(C_AXIS, SERVO_C_PIN);
# endif
void init_servos() {
// ======================== X Axis ===========================
# ifdef SERVO_X_PIN
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "X Servo range %4.3f to %4.3f", SERVO_X_RANGE_MIN, SERVO_X_RANGE_MAX);
X_Servo_Axis.init();
X_Servo_Axis.set_range(SERVO_X_RANGE_MIN, SERVO_X_RANGE_MAX);
# ifdef SERVO_X_HOMING_TYPE
X_Servo_Axis.set_homing_type(SERVO_X_HOMING_TYPE);
# endif
# ifdef SERVO_X_HOME_POS
X_Servo_Axis.set_homing_position(SERVO_X_HOME_POS);
# endif
# ifdef SERVO_X_MPOS // value should be true or false
X_Servo_Axis.set_use_mpos(SERVO_X_MPOS);
# endif
# ifdef SERVO_X_DISABLE_ON_ALARM
set_disable_on_alarm(SERVO_X_DISABLE_ON_ALARM);
# endif
# ifdef SERVO_X_DISABLE_WITH_STEPPERS
set_disable_with_steppers(SERVO_X_DISABLE_WITH_STEPPERS);
# endif
# endif
// ======================== Y Axis ===========================
# ifdef SERVO_Y_PIN
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Y Servo range %4.3f to %4.3f", SERVO_Y_RANGE_MIN, SERVO_Y_RANGE_MAX);
Y_Servo_Axis.init();
Y_Servo_Axis.set_range(SERVO_Y_RANGE_MIN, SERVO_Y_RANGE_MAX);
# ifdef SERVO_Y_HOMING_TYPE
Y_Servo_Axis.set_homing_type(SERVO_Y_HOMING_TYPE);
# endif
# ifdef SERVO_Y_HOME_POS
Y_Servo_Axis.set_homing_position(SERVO_Y_HOME_POS);
# endif
# ifdef SERVO_Y_MPOS // value should be true or false
Y_Servo_Axis.set_use_mpos(SERVO_Y_MPOS);
# endif
# ifdef SERVO_Y_DISABLE_ON_ALARM
set_disable_on_alarm(SERVO_Y_DISABLE_ON_ALARM);
# endif
# ifdef SERVO_Y_DISABLE_WITH_STEPPERS
set_disable_with_steppers(SERVO_Y_DISABLE_WITH_STEPPERS);
# endif
# endif
// ======================== Z Axis ===========================
# ifdef SERVO_Z_PIN
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Z Servo range %4.3f to %4.3f", SERVO_Z_RANGE_MIN, SERVO_Z_RANGE_MAX);
Z_Servo_Axis.init();
Z_Servo_Axis.set_range(SERVO_Z_RANGE_MIN, SERVO_Z_RANGE_MAX);
# ifdef SERVO_Z_HOMING_TYPE
Z_Servo_Axis.set_homing_type(SERVO_Z_HOMING_TYPE);
# endif
# ifdef SERVO_Z_HOME_POS
Z_Servo_Axis.set_homing_position(SERVO_Z_HOME_POS);
# endif
# ifdef SERVO_Z_MPOS // value should be true or false
Z_Servo_Axis.set_use_mpos(SERVO_Z_MPOS);
# endif
# ifdef SERVO_Z_DISABLE_ON_ALARM
set_disable_on_alarm(SERVO_Z_DISABLE_ON_ALARM);
# endif
# ifdef SERVO_Z_DISABLE_WITH_STEPPERS
set_disable_with_steppers(SERVO_Z_DISABLE_WITH_STEPPERS);
# endif
# endif
// ======================== A Axis ===========================
# ifdef SERVO_A_PIN
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "A Servo range %4.3f to %4.3f", SERVO_A_RANGE_MIN, SERVO_A_RANGE_MAX);
A_Servo_Axis.init();
A_Servo_Axis.set_range(SERVO_A_RANGE_MIN, SERVO_A_RANGE_MAX);
# ifdef SERVO_A_HOMING_TYPE
A_Servo_Axis.set_homing_type(SERVO_A_HOMING_TYPE);
# endif
# ifdef SERVO_A_HOME_POS
A_Servo_Axis.set_homing_position(SERVO_A_HOME_POS);
# endif
# ifdef SERVO_A_MPOS // value should be true or false
A_Servo_Axis.set_use_mpos(SERVO_A_MPOS);
# endif
# ifdef SERVO_A_DISABLE_ON_ALARM
set_disable_on_alarm(SERVO_A_DISABLE_ON_ALARM);
# endif
# ifdef SERVO_A_DISABLE_WITH_STEPPERS
set_disable_with_steppers(SERVO_A_DISABLE_WITH_STEPPERS);
# endif
# endif
// ======================== B Axis ===========================
# ifdef SERVO_B_PIN
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "B Servo range %4.3f to %4.3f", SERVO_B_RANGE_MIN, SERVO_B_RANGE_MAX);
B_Servo_Axis.init();
B_Servo_Axis.set_range(SERVO_B_RANGE_MIN, SERVO_B_RANGE_MAX);
# ifdef SERVO_B_HOMING_TYPE
B_Servo_Axis.set_homing_type(SERVO_B_HOMING_TYPE);
# endif
# ifdef SERVO_B_HOME_POS
B_Servo_Axis.set_homing_position(SERVO_B_HOME_POS);
# endif
# ifdef SERVO_B_MPOS // value should be true or false
B_Servo_Axis.set_use_mpos(SERVO_B_MPOS);
# endif
# ifdef SERVO_B_DISABLE_ON_ALARM
set_disable_on_alarm(SERVO_B_DISABLE_ON_ALARM);
# endif
# ifdef SERVO_B_DISABLE_WITH_STEPPERS
set_disable_with_steppers(SERVO_B_DISABLE_WITH_STEPPERS);
# endif
# endif
// ======================== C Axis ===========================
# ifdef SERVO_C_PIN
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "C Servo range %4.3f to %4.3f", SERVO_C_RANGE_MIN, SERVO_C_RANGE_MAX);
C_Servo_Axis.init();
C_Servo_Axis.set_range(SERVO_C_RANGE_MIN, SERVO_C_RANGE_MAX);
# ifdef SERVO_C_HOMING_TYPE
C_Servo_Axis.set_homing_type(SERVO_C_HOMING_TYPE);
# endif
# ifdef SERVO_C_HOME_POS
C_Servo_Axis.set_homing_position(SERVO_C_HOME_POS);
# endif
# ifdef SERVO_C_MPOS // value should be true or false
C_Servo_Axis.set_use_mpos(SERVO_C_MPOS);
# endif
# ifdef SERVO_C_DISABLE_ON_ALARM
set_disable_on_alarm(SERVO_C_DISABLE_ON_ALARM);
# endif
# ifdef SERVO_C_DISABLE_WITH_STEPPERS
set_disable_with_steppers(SERVO_C_DISABLE_WITH_STEPPERS);
# endif
# endif
// setup a task that will calculate the determine and set the servo positions
xTaskCreatePinnedToCore(servosSyncTask, // task
"servosSyncTask", // name for task
4096, // size of task stack
NULL, // parameters
1, // priority
&servosSyncTaskHandle,
0 // core
);
}
// this is the task
void servosSyncTask(void* pvParameters) {
TickType_t xLastWakeTime;
const TickType_t xServoFrequency = SERVO_TIMER_INT_FREQ; // in ticks (typically ms)
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();
# endif
# ifdef SERVO_Y_PIN
Y_Servo_Axis.set_location();
# endif
# ifdef SERVO_Z_PIN
Z_Servo_Axis.set_location();
# endif
# ifdef SERVO_A_PIN
A_Servo_Axis.set_location();
# endif
# ifdef SERVO_B_PIN
B_Servo_Axis.set_location();
# endif
# ifdef SERVO_C_PIN
C_Servo_Axis.set_location();
# endif
vTaskDelayUntil(&xLastWakeTime, xServoFrequency);
}
}
// =============================== Class Stuff ================================= //
ServoAxis::ServoAxis(uint8_t axis, uint8_t pin_num) { // constructor
_axis = axis;
_pin_num = pin_num;
_channel_num = sys_get_next_PWM_chan_num();
_showError = true; // this will be used to show calibration error only once
_use_mpos = true; // default is to use the machine position rather than work position
}
void ServoAxis::init() {
_cal_is_valid();
ledcSetup(_channel_num, _pwm_freq, _pwm_resolution_bits);
ledcAttachPin(_pin_num, _channel_num);
disable();
}
void ServoAxis::set_location() {
// These are the pulse lengths for the minimum and maximum positions
// Note: Some machines will have the physical max/min inverted with pulse length max/min due to invert setting $3=...
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;
// skip location if we are in alarm mode
if (_disable_on_alarm && (sys.state == STATE_ALARM)) {
disable();
return;
}
// track the disable status of the steppers if desired.
if (_disable_with_steppers && get_stepper_disable()) {
disable();
return;
}
if ((_homing_type == SERVO_HOMING_TARGET) && (sys.state == STATE_HOMING)) {
servo_pos = _homing_position; // go to servos home position
} else {
mpos = system_convert_axis_steps_to_mpos(sys_position, _axis); // get the axis machine position in mm
if (_use_mpos)
servo_pos = mpos;
else {
offset = gc_state.coord_system[_axis] + gc_state.coord_offset[_axis]; // get the current axis work offset
servo_pos = mpos - offset; // determine the current work position
}
}
// 1. Get the pulse ranges of the servos
// 2. Invert if selected in the settings
// 3. Get the calibration values from the settings
// 4. Adjust the calibration offset direction of the cal based on the direction
// 5. Apply the calibrarion
servo_pulse_min = SERVO_MIN_PULSE;
servo_pulse_max = SERVO_MAX_PULSE;
if (bit_istrue(dir_invert_mask->get(), bit(_axis))) // this allows the user to change the direction via settings
swap(servo_pulse_min, servo_pulse_max);
// get the calibration values
if (_cal_is_valid()) { // if calibration settings are OK then apply them
// apply a calibration
// the cals apply differently if the direction is reverse (i.e. longer pulse is lower position)
if (bit_isfalse(dir_invert_mask->get(), bit(_axis))) { // normal direction
min_pulse_cal = 2.0 - (axis_settings[_axis]->steps_per_mm->get() / 100.0);
max_pulse_cal = (axis_settings[_axis]->max_travel->get() / 100.0);
} else { // inverted direction
min_pulse_cal = (axis_settings[_axis]->steps_per_mm->get() / 100.0);
max_pulse_cal = 2.0 - (axis_settings[_axis]->max_travel->get() / -100.0);
}
} else { // settings are not valid so don't apply any calibration
min_pulse_cal = 1.0;
max_pulse_cal = 1.0;
}
// apply the calibrations
servo_pulse_min *= min_pulse_cal;
servo_pulse_max *= max_pulse_cal;
// determine the pulse length
servo_pulse_len = (uint32_t)mapConstrain(servo_pos, _position_min, _position_max, servo_pulse_min, servo_pulse_max);
_write_pwm(servo_pulse_len);
}
void ServoAxis::_write_pwm(uint32_t duty) {
if (ledcRead(_channel_num) != duty) // only write if it is changing
ledcWrite(_channel_num, duty);
}
// sets the PWM to zero. This allows most servos to be manually moved
void ServoAxis::disable() {
_write_pwm(0);
}
// 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 settingsOK = true;
if ((axis_settings[_axis]->steps_per_mm->get() < SERVO_CAL_MIN) || (axis_settings[_axis]->steps_per_mm->get() > SERVO_CAL_MAX)) {
if (_showError) {
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Servo calibration ($10%d) value error. Reset to 100", _axis);
char reset_val[] = "100";
axis_settings[_axis]->steps_per_mm->setStringValue(reset_val);
}
settingsOK = false;
}
// Note: Max travel is set positive via $$, but stored as a negative number
auto travel = -axis_settings[_axis]->max_travel->get();
if ((travel < -SERVO_CAL_MAX) || travel > -SERVO_CAL_MIN) {
if (_showError) {
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Servo calibration ($13%d) value error. Reset to 100", _axis);
char reset_val[] = "-100"; // stored as a negative
axis_settings[_axis]->max_travel->setStringValue(reset_val);
}
settingsOK = false;
}
_showError = false; // to show error once
return settingsOK;
}
/*
Use this to set the max and min position in mm of the servo
This is used when mapping pulse length to the position
*/
void ServoAxis::set_range(float min, float max) {
if (min < max) {
_position_min = min;
_position_max = max;
} else
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Error setting range. Min not smaller than max");
}
/*
Sets the mode the servo will be in during homing
See servo_axis.h for SERVO_HOMING_xxxxx types
*/
void ServoAxis::set_homing_type(uint8_t homing_type) {
if (homing_type <= SERVO_HOMING_TARGET)
_homing_type = homing_type;
}
/*
Use this to set the homing position the servo will be commanded to go if
the current homing mode is SERVO_HOMING_TARGET
*/
void ServoAxis::set_homing_position(float homing_position) {
_homing_position = homing_position;
}
/*
Use this to set the disable on alarm feature. If true, then hobby servo PWM
will be disable in Grbl alarm mode (like before homing). Typical hobby servo
can be moved by hand in this mode
*/
void ServoAxis::set_disable_on_alarm(bool disable_on_alarm) {
_disable_on_alarm = disable_on_alarm;
}
void ServoAxis::set_disable_with_steppers(bool disable_with_steppers) {
_disable_with_steppers = disable_with_steppers;
}
/*
If true, servo position will alway be calculated in machine position
Offsets will not be applied
*/
void ServoAxis::set_use_mpos(bool use_mpos) {
_use_mpos = use_mpos;
}
#endif

View File

@@ -1,101 +0,0 @@
#pragma once
/*
ServoAxis.h
Part of Grbl_ESP32
copyright (c) 2019 - Bart Dring. This file was intended 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/>.
Servo Axis Class
The Servo axis feature allows you to use a hobby servo on any axis.
This is done using a repeating RTOS task. Grbl continues to calculate
the position of the axis in real time. The task looks at the current position of
the axis and calculates the required PWM value to go to that location. You define the travel
of the servo in millimeters.
Grbl still uses the acceleration and speed values you have in the settings, so it
will coordinate servo axes with stepper motor axes. This assumes these values are within the
capabilities of the servo
Usage
1. In config.h un-comment #define USE_SERVO_AXES
2. In the machine definition file in Machines/, define servo pins and PWM channels like this ....
#define SERVO_Y_PIN GPIO_NUM_14
undefine any step and direction pins associated with that axis
3. In servo_axis.cpp init_servos() function, configure servos like this ....
X_Servo_Axis.set_range(0.0, 20.0); // millimeter
X_Servo_Axis.set_homing_type(SERVO_HOMING_OFF);
X_Servo_Axis.set_disable_on_alarm(true);
The positions can be calibrated using the settings. $10x (resolution) settings adjust the minimum
position and $13x (max travel) settings adjust the maximum position. If the servo is traveling
backwards from what you want, you can use the $3 direction setting to compensate.
*/
#include "Motors/RcServoSettings.h"
#define SERVO_HOMING_OFF 0 // servo is off during homing
#define SERVO_HOMING_TARGET 1 // servo is send to a location during homing
extern float my_location;
void init_servos();
void servosSyncTask(void* pvParameters);
class ServoAxis {
public:
ServoAxis(uint8_t axis, uint8_t pin_num); // constructor
void init();
void set_location();
void disable(); // sets PWM to 0% duty cycle. Most servos can be manually moved in this state
void set_range(float min, float max);
void set_homing_type(uint8_t homing_type);
void set_homing_position(float homing_position);
void set_disable_on_alarm(bool disable_on_alarm);
void set_disable_with_steppers(bool disable_with_steppers);
void set_use_mpos(bool use_mpos);
private:
int _axis; // these should be assign in constructor using Grbl X_AXIS type values
int _pin_num; // The GPIO pin being used
int _channel_num; // The PWM channel
bool _showError;
uint32_t _pwm_freq = SERVO_PULSE_FREQ;
uint32_t _pwm_resolution_bits = SERVO_PULSE_RES_BITS;
float _pulse_min = SERVO_MIN_PULSE; // in pwm counts
float _pulse_max = SERVO_MAX_PULSE; // in pwm counts
float _position_min = SERVO_POSITION_MIN_DEFAULT; // position in millimeters
float _position_max = SERVO_POSITION_MAX_DEFAULT; // position in millimeters
uint8_t _homing_type = SERVO_HOMING_OFF;
float _homing_position = SERVO_POSITION_MAX_DEFAULT;
bool _disable_on_alarm = true;
bool _disable_with_steppers = false;
bool _use_mpos = true;
bool _validate_cal_settings();
void _write_pwm(uint32_t duty);
bool _cal_is_valid(); // checks to see if calibration values are in acceptable range
};

View File

@@ -1,107 +0,0 @@
/*
SolenoidPen.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
int8_t solenoid_pwm_chan_num;
static TaskHandle_t solenoidSyncTaskHandle = 0;
// 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
solenoid_pwm_chan_num = sys_get_next_PWM_chan_num();
ledcSetup(solenoid_pwm_chan_num, SOLENOID_PWM_FREQ, SOLENOID_PWM_RES_BITS);
ledcAttachPin(SOLENOID_PEN_PIN, solenoid_pwm_chan_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_pwm_chan_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;
xLastWakeTime = xTaskGetTickCount(); // Initialise the xLastWakeTime variable with the current time.
while (true) { // don't ever return from this or the task dies
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
}
vTaskDelayUntil(&xLastWakeTime, xSolenoidFrequency);
}
}
// 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_pwm_chan_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;
portENTER_CRITICAL(&myMutex);
ledcWrite(solenoid_pwm_chan_num, solenoid_pen_pulse_len);
portEXIT_CRITICAL(&myMutex);
}
#endif

View File

@@ -1,68 +0,0 @@
#pragma once
/*
SolenoidPen.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.
There are two power levels, the initial pull up strength, then the hold strength
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.
*/
#ifndef SOLENOID_PWM_FREQ
# define SOLENOID_PWM_FREQ 5000
#endif
#ifndef SOLENOID_PWM_RES_BITS
# define SOLENOID_PWM_RES_BITS 8
#endif
#ifndef SOLENOID_TURNON_DELAY
# define SOLENOID_TURNON_DELAY (SOLENOID_TIMER_INT_FREQ / 2)
#endif
#ifndef SOLENOID_PULSE_LEN_UP
# define SOLENOID_PULSE_LEN_UP 255
#endif
#ifndef SOLENOID_HOLD_DELAY
# define SOLENOID_HOLD_DELAY (SOLENOID_TIMER_INT_FREQ / 2) // in task counts...after this delay power will change to hold level
#endif
#ifndef SOLENOID_PULSE_LEN_HOLD
# define SOLENOID_PULSE_LEN_HOLD 80 // solenoid hold level ... typically a lower value to prevent overheating
#endif
#ifndef SOLENOID_TIMER_INT_FREQ
# define SOLENOID_TIMER_INT_FREQ 50
#endif
void solenoid_init();
void solenoid_disable();
void solenoidSyncTask(void* pvParameters);
void calc_solenoid(float penZ);

View File

@@ -98,10 +98,6 @@ static volatile uint8_t segment_buffer_tail;
static uint8_t segment_buffer_head;
static uint8_t segment_next_head;
// Step and direction port invert masks.
static uint8_t step_port_invert_mask;
static uint8_t dir_port_invert_mask;
// Used to avoid ISR nesting of the "Stepper Driver Interrupt". Should never occur though.
static volatile uint8_t busy;
@@ -420,7 +416,6 @@ static void stepper_pulse_func() {
// Generate pulse (at least one pulse)
// The pulse resolution is limited by I2S_OUT_USEC_PER_PULSE
//
st.step_outbits ^= step_port_invert_mask; // Apply step port invert mask
i2s_out_push_sample(pulse_microseconds->get() / I2S_OUT_USEC_PER_PULSE);
set_stepper_pins_on(0); // turn all off
return;
@@ -429,7 +424,6 @@ static void stepper_pulse_func() {
#ifdef USE_RMT_STEPS
return;
#else
st.step_outbits ^= step_port_invert_mask; // Apply step port invert mask
// wait for step pulse time to complete...some of it should have expired during code above
while (esp_timer_get_time() - step_pulse_start_time < pulse_microseconds->get()) {
NOP(); // spin here until time to turn off step
@@ -476,8 +470,6 @@ void st_wake_up() {
// Enable stepper drivers.
motors_set_disable(false);
stepper_idle = false;
// Initialize stepper output bits to ensure first ISR call does not step.
st.step_outbits = step_port_invert_mask;
// Initialize step pulse timing from settings. Here to ensure updating after re-writing.
#ifdef STEP_PULSE_DELAY
// Step pulse delay handling is not require with ESP32...the RMT function does it.
@@ -510,8 +502,8 @@ void st_reset() {
segment_buffer_head = 0; // empty = tail
segment_next_head = 1;
busy = false;
st_generate_step_dir_invert_masks();
st.dir_outbits = dir_port_invert_mask; // Initialize direction bits to default.
st.step_outbits = 0;
st.dir_outbits = dir_invert_mask->get(); // Initialize direction bits to default.
// TODO do we need to turn step pins off?
}
@@ -716,6 +708,7 @@ void st_go_idle() {
motors_set_disable(false);
set_stepper_pins_on(0);
st.step_outbits = 0;
}
// Called by planner_recalculate() when the executing block is updated by the new plan.
@@ -760,22 +753,6 @@ void st_parking_restore_buffer() {
}
#endif
// Generates the step and direction port invert masks used in the Stepper Interrupt Driver.
void st_generate_step_dir_invert_masks() {
/*
uint8_t idx;
step_port_invert_mask = 0;
dir_port_invert_mask = 0;
for (idx=0; idx<N_AXIS; idx++) {
if (bit_istrue(step_invert_mask->get(),bit(idx))) { step_port_invert_mask |= get_step_pin_mask(idx); }
if (bit_istrue(dir_invert_mask->get(),bit(idx))) { dir_port_invert_mask |= get_direction_pin_mask(idx); }
}
*/
// simpler with ESP32, but let's do it here for easier change management
step_port_invert_mask = step_invert_mask->get();
dir_port_invert_mask = dir_invert_mask->get();
}
// Increments the step segment buffer block data ring buffer.
static uint8_t st_next_block_index(uint8_t block_index) {
block_index++;

View File

@@ -97,9 +97,6 @@ void st_wake_up();
// Immediately disables steppers
void st_go_idle();
// Generate the step and direction port invert masks.
void st_generate_step_dir_invert_masks();
// Reset the stepper subsystem variables
void st_reset();

View File

@@ -592,8 +592,8 @@ namespace WebUI {
String sadminPassword = admin_password->get();
String suserPassword = user_password->get();
if (!((sUser == DEFAULT_ADMIN_LOGIN && sPassword == sadminPassword) ||
(sUser == DEFAULT_USER_LOGIN && sPassword == suserPassword)) {
if (!(sUser == DEFAULT_ADMIN_LOGIN && sPassword == sadminPassword) ||
(sUser == DEFAULT_USER_LOGIN && sPassword == suserPassword)) {
msg_alert_error = true;
smsg = "Error: Incorrect password";
code = 401;
@@ -607,13 +607,19 @@ namespace WebUI {
//change password
if (_webserver->hasArg("PASSWORD") && _webserver->hasArg("USER") && _webserver->hasArg("NEWPASSWORD") &&
(msg_alert_error == false)) {
String newpassword = _webserver->arg("NEWPASSWORD");
if (COMMANDS::isLocalPasswordValid((char*)newpassword.c_str())) {
char pwdbuf[MAX_LOCAL_PASSWORD_LENGTH + 1];
newpassword.toCharArray(pwdbuf, MAX_LOCAL_PASSWORD_LENGTH + 1);
if (COMMANDS::isLocalPasswordValid(pwdbuf)) {
err_t err;
if (sUser == DEFAULT_ADMIN_LOGIN) {
err = admin_password->setStringValue(newpassword);
err = admin_password->setStringValue(pwdbuf);
} else {
err = user_password->setStringValue(newpassword);
err = user_password->setStringValue(pwdbuf);
}
if (err) {
msg_alert_error = true;

View File

@@ -1,214 +0,0 @@
/*
unipolar.cpp
Part of Grbl_ESP32
copyright (c) 2019 - Bart Dring. This file was intended 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/>.
Unipolar Class
This class allows you to control a unipolar motor. Unipolar motors have 5 wires. One
is typically tied to a voltage, while the other 4 are switched to ground in a
sequence
To take a step simply call the step(step, direction) function.
*/
#include "grbl.h"
#ifdef USE_UNIPOLAR
// assign the I/O pins used for each coil of the motors
#ifdef X_UNIPOLAR
Unipolar X_Unipolar(X_PIN_PHASE_0, X_PIN_PHASE_1, X_PIN_PHASE_2, X_PIN_PHASE_3, true);
#endif
#ifdef Y_UNIPOLAR
Unipolar Y_Unipolar(Y_PIN_PHASE_0, Y_PIN_PHASE_1, Y_PIN_PHASE_2, Y_PIN_PHASE_3, true);
#endif
#ifdef Z_UNIPOLAR
Unipolar Z_Unipolar(Z_PIN_PHASE_0, Z_PIN_PHASE_1, Z_PIN_PHASE_2, Z_PIN_PHASE_3, true);
#endif
void unipolar_init() {
#ifdef X_UNIPOLAR
X_Unipolar.init();
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "X unipolar");
#endif
#ifdef Y_UNIPOLAR
Y_Unipolar.init();
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Y unipolar");
#endif
#ifdef Z_UNIPOLAR
Z_Unipolar.init();
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Z unipolar");
#endif
}
void unipolar_step(uint8_t step_mask, uint8_t dir_mask) {
#ifdef X_UNIPOLAR
X_Unipolar.step(step_mask & bit(X_AXIS), dir_mask & bit(X_AXIS));
#endif
#ifdef Y_UNIPOLAR
Y_Unipolar.step(step_mask & bit(Y_AXIS), dir_mask & bit(Y_AXIS));
#endif
#ifdef Z_UNIPOLAR
Z_Unipolar.step(step_mask & bit(Z_AXIS), dir_mask & bit(ZX_AXIS));
#endif
}
void unipolar_disable(bool disable) {
#ifdef X_UNIPOLAR
X_Unipolar.set_enabled(!disable);
#endif
#ifdef Y_UNIPOLAR
Y_Unipolar.set_enabled(!disable);
#endif
#ifdef Z_UNIPOLAR
Z_Unipolar.set_enabled(!disable);
#endif
}
Unipolar::Unipolar(uint8_t pin_phase0, uint8_t pin_phase1, uint8_t pin_phase2, uint8_t pin_phase3, bool half_step) { // constructor
_pin_phase0 = pin_phase0;
_pin_phase1 = pin_phase1;
_pin_phase2 = pin_phase2;
_pin_phase3 = pin_phase3;
_half_step = half_step;
}
void Unipolar::init() {
pinMode(_pin_phase0, OUTPUT);
pinMode(_pin_phase1, OUTPUT);
pinMode(_pin_phase2, OUTPUT);
pinMode(_pin_phase3, OUTPUT);
_current_phase = 0;
set_enabled(false);
}
void Unipolar::set_enabled(bool enabled) {
if (enabled == _enabled)
return; // no change
_enabled = enabled;
if (!enabled) {
digitalWrite(_pin_phase0, 0);
digitalWrite(_pin_phase1, 0);
digitalWrite(_pin_phase2, 0);
digitalWrite(_pin_phase3, 0);
}
}
/*
To take a step set step to true and set the driection
step is included so that st.step_outbits can be used to determine if a
step is required on this axis
*/
void Unipolar::step(bool step, bool dir_forward) {
uint8_t _phase[8] = {0, 0, 0, 0, 0, 0, 0, 0}; // temporary phase values...all start as off
uint8_t phase_max;
if (_half_step)
phase_max = 7;
else
phase_max = 3;
if (!step)
return; // a step is not required on this interrupt
if (!_enabled)
return; // don't do anything, phase is not changed or lost
if (dir_forward) { // count up
if (_current_phase == phase_max)
_current_phase = 0;
else
_current_phase++;
} else { // count down
if (_current_phase == 0)
_current_phase = phase_max;
else
_current_phase--;
}
/*
8 Step : A AB B BC C CD D DA
4 Step : AB BC CD DA (Usual application)
Step IN4 IN3 IN2 IN1
A 0 0 0 1
AB 0 0 1 1
B 0 0 1 0
BC 0 1 1 0
C 0 1 0 0
CD 1 1 0 0
D 1 0 0 0
DA 1 0 0 1
*/
if (_half_step) {
switch (_current_phase) {
case 0:
_phase[0] = 1;
break;
case 1:
_phase[0] = 1;
_phase[1] = 1;
break;
case 2:
_phase[1] = 1;
break;
case 3:
_phase[1] = 1;
_phase[2] = 1;
break;
case 4:
_phase[2] = 1;
break;
case 5:
_phase[2] = 1;
_phase[3] = 1;
break;
case 6:
_phase[3] = 1;
break;
case 7:
_phase[3] = 1;
_phase[0] = 1;
break;
}
} else {
switch (_current_phase) {
case 0:
_phase[0] = 1;
_phase[1] = 1;
break;
case 1:
_phase[1] = 1;
_phase[2] = 1;
break;
case 2:
_phase[2] = 1;
_phase[3] = 1;
break;
case 3:
_phase[3] = 1;
_phase[0] = 1;
break;
}
}
digitalWrite(_pin_phase0, _phase[0]);
digitalWrite(_pin_phase1, _phase[1]);
digitalWrite(_pin_phase2, _phase[2]);
digitalWrite(_pin_phase3, _phase[3]);
}
#endif

View File

@@ -1,53 +0,0 @@
#pragma once
/*
grbl_unipolar.h
Part of Grbl_ESP32
copyright (c) 2019 - Bart Dring. This file was intended 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/>.
Unipolar Class
This class allows you to control a unipolar motor. Unipolar motors have 5 wires. One
is typically tied to a voltage, while the other 4 are switched to ground in a
sequence
To take a step simply call the step(direction) function. It will take
*/
void unipolar_init();
void unipolar_step(uint8_t step_mask, uint8_t dir_mask);
void unipolar_disable(bool enable);
class Unipolar {
public:
Unipolar(uint8_t pin_phase0, uint8_t pin_phase1, uint8_t pin_phase2, uint8_t pin_phase3, bool half_step); // constructor
void set_enabled(bool enabled);
void step(bool step, bool dir_forward);
void init();
private:
uint8_t _current_phase = 0;
bool _enabled = false;
bool _half_step = true; // default is half step, full step
uint8_t _pin_phase0;
uint8_t _pin_phase1;
uint8_t _pin_phase2;
uint8_t _pin_phase3;
};