mirror of
https://github.com/bdring/Grbl_Esp32.git
synced 2025-08-13 18:14:23 +02:00
@@ -56,6 +56,10 @@ void setup() {
|
||||
#ifdef USE_PEN_SOLENOID
|
||||
solenoid_init();
|
||||
#endif
|
||||
|
||||
#ifdef USE_MACHINE_INIT
|
||||
machine_init(); // user supplied function for special initialization
|
||||
#endif
|
||||
|
||||
// Initialize system state.
|
||||
#ifdef FORCE_INITIALIZATION_ALARM
|
||||
|
324
Grbl_Esp32/atari_1020.cpp
Normal file
324
Grbl_Esp32/atari_1020.cpp
Normal file
@@ -0,0 +1,324 @@
|
||||
/*
|
||||
atari_1020.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/>.
|
||||
|
||||
--------------------------------------------------------------
|
||||
|
||||
This contains all the special features required to control an
|
||||
Atari 1010 Pen Plotter
|
||||
*/
|
||||
#include "grbl.h"
|
||||
|
||||
#ifdef ATARI_1020
|
||||
|
||||
#define HOMING_PHASE_FULL_APPROACH 0 // move to right end
|
||||
#define HOMING_PHASE_CHECK 1 // check reed switch
|
||||
#define HOMING_PHASE_RETRACT 2 // retract
|
||||
#define HOMING_PHASE_SHORT_APPROACH 3 // retract
|
||||
|
||||
static TaskHandle_t solenoidSyncTaskHandle = 0;
|
||||
static TaskHandle_t atariHomingTaskHandle = 0;
|
||||
uint16_t solenoid_pull_count;
|
||||
bool atari_homing = false;
|
||||
uint8_t homing_phase = HOMING_PHASE_FULL_APPROACH;
|
||||
uint8_t current_tool;
|
||||
|
||||
void machine_init()
|
||||
{
|
||||
solenoid_pull_count = 0; // initialize
|
||||
|
||||
grbl_send(CLIENT_SERIAL, "[MSG:Atari 1020 Solenoid]\r\n");
|
||||
|
||||
// setup PWM channel
|
||||
ledcSetup(SOLENOID_CHANNEL_NUM, SOLENOID_PWM_FREQ, SOLENOID_PWM_RES_BITS);
|
||||
ledcAttachPin(SOLENOID_PEN_PIN, SOLENOID_CHANNEL_NUM);
|
||||
|
||||
pinMode(SOLENOID_DIRECTION_PIN, OUTPUT); // this sets the direction of the solenoid current
|
||||
pinMode(REED_SW_PIN, INPUT_PULLUP); // external pullup required
|
||||
|
||||
// setup a task that will calculate solenoid position
|
||||
xTaskCreatePinnedToCore( solenoidSyncTask, // task
|
||||
"solenoidSyncTask", // name for task
|
||||
4096, // size of task stack
|
||||
NULL, // parameters
|
||||
1, // priority
|
||||
&solenoidSyncTaskHandle,
|
||||
0 // core
|
||||
);
|
||||
// setup a task that will do the custom homing sequence
|
||||
xTaskCreatePinnedToCore( atari_home_task, // task
|
||||
"atari_home_task", // name for task
|
||||
4096, // size of task stack
|
||||
NULL, // parameters
|
||||
1, // priority
|
||||
&atariHomingTaskHandle,
|
||||
0 // core
|
||||
);
|
||||
}
|
||||
|
||||
// this task tracks the Z position and sets the solenoid
|
||||
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_TASK_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
|
||||
|
||||
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);
|
||||
}
|
||||
}
|
||||
|
||||
// to do...have this return a true or false. This could be used by the normal homing feature to
|
||||
// continue with regular homing after setup
|
||||
// return true if this completes homing
|
||||
|
||||
bool user_defined_homing() {
|
||||
// create and start a task to do the special homing
|
||||
homing_phase = HOMING_PHASE_FULL_APPROACH;
|
||||
atari_homing = true;
|
||||
return true; // this does it...skip the rest of mc_homing_cycle(...)
|
||||
}
|
||||
|
||||
/*
|
||||
Do a custom homing routine.
|
||||
|
||||
A task is used because it needs to wait until until idle after each move.
|
||||
|
||||
1) Do a full travel move to the right. OK to stall if the pen started closer
|
||||
2) Check for pen 1
|
||||
3) If fail Retract
|
||||
4) move to right end
|
||||
5) Check...
|
||||
....repeat up to 12 times to try to find pen one
|
||||
|
||||
TODO can the retract, move back be 1 phase rather than 2?
|
||||
|
||||
*/
|
||||
void atari_home_task(void *pvParameters) {
|
||||
uint8_t homing_attempt = 0; // how many times have we tried to home
|
||||
TickType_t xLastWakeTime;
|
||||
const TickType_t xHomingTaskFrequency = 100; // in ticks (typically ms) .... need to make sure there is enough time to get out of idle
|
||||
char gcode_line[20];
|
||||
|
||||
while(true) { // this task will only last as long as it is homing
|
||||
|
||||
if (atari_homing) {
|
||||
// must be in idle or alarm state
|
||||
if (sys.state == STATE_IDLE) {
|
||||
switch(homing_phase) {
|
||||
case HOMING_PHASE_FULL_APPROACH: // a full width move to insure it hits left end
|
||||
inputBuffer.push("G90G0Z1\r"); // lift the pen
|
||||
sprintf(gcode_line, "G91G0X%3.2f\r", -ATARI_PAPER_WIDTH + ATARI_HOME_POS - 3.0); // plus a little extra
|
||||
inputBuffer.push(gcode_line);
|
||||
homing_attempt = 1;
|
||||
homing_phase = HOMING_PHASE_CHECK;
|
||||
break;
|
||||
case HOMING_PHASE_CHECK: // check the limits switch
|
||||
if (digitalRead(REED_SW_PIN) == 0) { // see if reed switch is grounded
|
||||
inputBuffer.push("G4P0.1\n"); // dramtic pause
|
||||
|
||||
sys_position[X_AXIS] = ATARI_HOME_POS * settings.steps_per_mm[X_AXIS];
|
||||
sys_position[Y_AXIS] = 0.0;
|
||||
sys_position[Z_AXIS] = 1.0 * settings.steps_per_mm[Y_AXIS];
|
||||
|
||||
gc_sync_position();
|
||||
plan_sync_position();
|
||||
|
||||
sprintf(gcode_line, "G90G0X%3.2f\r", ATARI_PAPER_WIDTH); // alway return to right side to reduce home travel stalls
|
||||
inputBuffer.push(gcode_line);
|
||||
|
||||
current_tool = 1; // local copy for reference...until actual M6 change
|
||||
gc_state.tool = current_tool;
|
||||
atari_homing = false; // done with homing sequence
|
||||
}
|
||||
else {
|
||||
homing_phase = HOMING_PHASE_RETRACT;
|
||||
homing_attempt++;
|
||||
}
|
||||
break;
|
||||
case HOMING_PHASE_RETRACT:
|
||||
sprintf(gcode_line, "G0X%3.2f\r", -ATARI_HOME_POS);
|
||||
inputBuffer.push(gcode_line);
|
||||
sprintf(gcode_line, "G0X%3.2f\r", ATARI_HOME_POS);
|
||||
inputBuffer.push(gcode_line);
|
||||
homing_phase = HOMING_PHASE_CHECK;
|
||||
break;
|
||||
default:
|
||||
grbl_sendf(CLIENT_SERIAL, "[MSG:Homing phase error %d]\r\n", homing_phase);
|
||||
atari_homing = false;; // kills task
|
||||
break;
|
||||
}
|
||||
|
||||
if (homing_attempt > ATARI_HOMING_ATTEMPTS) { // try all positions plus 1
|
||||
grbl_send(CLIENT_SERIAL, "[MSG: Atari homing failed]\r\n");
|
||||
inputBuffer.push("G90\r");
|
||||
atari_homing = false;;
|
||||
}
|
||||
}
|
||||
}
|
||||
vTaskDelayUntil(&xLastWakeTime, xHomingTaskFrequency);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
// calculate and set the PWM value for the servo
|
||||
void calc_solenoid(float penZ)
|
||||
{
|
||||
bool isPenUp;
|
||||
static bool previousPenState = false;
|
||||
uint32_t solenoid_pen_pulse_len; // duty cycle of solenoid
|
||||
|
||||
isPenUp = ( (penZ > 0) || (sys.state == STATE_ALARM) ); // is pen above Z0 or is there an alarm
|
||||
|
||||
// if the state has not change, we only count down to the pull time
|
||||
if (previousPenState == isPenUp) { // if state is unchanged
|
||||
if (solenoid_pull_count > 0) {
|
||||
solenoid_pull_count--;
|
||||
solenoid_pen_pulse_len = SOLENOID_PULSE_LEN_PULL; // stay at full power while counting down
|
||||
}
|
||||
else {
|
||||
solenoid_pen_pulse_len = SOLENOID_PULSE_LEN_HOLD; // pull in delay has expired so lower duty cycle
|
||||
}
|
||||
}
|
||||
else { // pen direction has changed
|
||||
solenoid_pen_pulse_len = SOLENOID_PULSE_LEN_PULL; // go to full power
|
||||
solenoid_pull_count = SOLENOID_PULL_DURATION; // set the time to count down
|
||||
}
|
||||
|
||||
previousPenState = isPenUp; // save the prev state
|
||||
|
||||
digitalWrite(SOLENOID_DIRECTION_PIN, isPenUp);
|
||||
|
||||
// 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;
|
||||
portENTER_CRITICAL(&myMutex);
|
||||
ledcWrite(SOLENOID_CHANNEL_NUM, solenoid_pen_pulse_len);
|
||||
portEXIT_CRITICAL(&myMutex);
|
||||
}
|
||||
|
||||
|
||||
/*
|
||||
A tool (pen) change is done by bumping the carriage against the right edge 3 times per
|
||||
position change. Pen 1-4 is valid range.
|
||||
*/
|
||||
void user_tool_change(uint8_t new_tool) {
|
||||
uint8_t move_count;
|
||||
char gcode_line[20];
|
||||
|
||||
protocol_buffer_synchronize(); // wait for all previous moves to complete
|
||||
|
||||
if ((new_tool < 1) || (new_tool > MAX_PEN_NUMBER)) {
|
||||
grbl_sendf(CLIENT_ALL, "[MSG: Requested Pen#%d is out of 1-4 range]\r\n", new_tool);
|
||||
return;
|
||||
}
|
||||
|
||||
if (new_tool == current_tool)
|
||||
return;
|
||||
|
||||
if (new_tool > current_tool) {
|
||||
move_count = BUMPS_PER_PEN_CHANGE * (new_tool - current_tool);
|
||||
}
|
||||
else {
|
||||
move_count = BUMPS_PER_PEN_CHANGE * ((MAX_PEN_NUMBER - current_tool) + new_tool);
|
||||
}
|
||||
sprintf(gcode_line, "G0Z%3.2f\r", ATARI_TOOL_CHANGE_Z); // go to tool change height
|
||||
inputBuffer.push(gcode_line);
|
||||
for (uint8_t i = 0; i < move_count; i++) {
|
||||
sprintf(gcode_line, "G0X%3.2f\r", ATARI_HOME_POS); //
|
||||
inputBuffer.push(gcode_line);
|
||||
inputBuffer.push("G0X0\r");
|
||||
}
|
||||
|
||||
current_tool = new_tool;
|
||||
|
||||
grbl_sendf(CLIENT_ALL, "[MSG: Change to Pen#%d]\r\n", current_tool);
|
||||
|
||||
}
|
||||
|
||||
// move from current tool to next tool....
|
||||
void atari_next_pen() {
|
||||
if (current_tool < MAX_PEN_NUMBER) {
|
||||
gc_state.tool = current_tool + 1;
|
||||
}
|
||||
else {
|
||||
gc_state.tool = 1;
|
||||
}
|
||||
user_tool_change(gc_state.tool);
|
||||
}
|
||||
|
||||
// Polar coaster has macro buttons, this handles those button pushes.
|
||||
void user_defined_macro(uint8_t index)
|
||||
{
|
||||
char gcode_line[20];
|
||||
|
||||
switch (index) {
|
||||
#ifdef MACRO_BUTTON_0_PIN
|
||||
case CONTROL_PIN_INDEX_MACRO_0:
|
||||
grbl_send(CLIENT_SERIAL, "[MSG: Pen Switch]\r\n");
|
||||
inputBuffer.push("$H\r");
|
||||
break;
|
||||
#endif
|
||||
|
||||
#ifdef MACRO_BUTTON_1_PIN
|
||||
case CONTROL_PIN_INDEX_MACRO_1:
|
||||
grbl_send(CLIENT_SERIAL, "[MSG: Color Switch]\r\n");
|
||||
atari_next_pen();
|
||||
sprintf(gcode_line, "G90G0X%3.2f\r", ATARI_PAPER_WIDTH); // alway return to right side to reduce home travel stalls
|
||||
inputBuffer.push(gcode_line);
|
||||
break;
|
||||
#endif
|
||||
|
||||
#ifdef MACRO_BUTTON_2_PIN
|
||||
case CONTROL_PIN_INDEX_MACRO_2:
|
||||
// feed out some paper and reset the Y 0
|
||||
grbl_send(CLIENT_SERIAL, "[MSG: Paper Switch]\r\n");
|
||||
inputBuffer.push("G0Y-25\r");
|
||||
inputBuffer.push("G4P0.1\r"); // sync...forces wait for planner to clear
|
||||
sys_position[Y_AXIS] = 0.0; // reset the Y position
|
||||
gc_sync_position();
|
||||
plan_sync_position();
|
||||
break;
|
||||
#endif
|
||||
|
||||
default:
|
||||
grbl_sendf(CLIENT_SERIAL, "[MSG: Unknown Switch %d]\r\n", index);
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
void user_m30() {
|
||||
char gcode_line[20];
|
||||
sprintf(gcode_line, "G90G0X%3.2f\r", ATARI_PAPER_WIDTH); //
|
||||
inputBuffer.push(gcode_line);
|
||||
}
|
||||
|
||||
#endif
|
||||
|
63
Grbl_Esp32/atari_1020.h
Normal file
63
Grbl_Esp32/atari_1020.h
Normal file
@@ -0,0 +1,63 @@
|
||||
/*
|
||||
atari_1020.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/>.
|
||||
|
||||
This contains all the special features required to control an
|
||||
Atari 1010 Pen Plotter
|
||||
*/
|
||||
|
||||
#define SOLENOID_PWM_FREQ 5000
|
||||
#define SOLENOID_PWM_RES_BITS 8
|
||||
|
||||
#define SOLENOID_PULSE_LEN_PULL 255
|
||||
#define SOLENOID_PULL_DURATION 50 // in task counts...after this delay power will change to hold level see SOLENOID_TASK_FREQ
|
||||
#define SOLENOID_PULSE_LEN_HOLD 40 // solenoid hold level ... typically a lower value to prevent overheating
|
||||
|
||||
#define SOLENOID_TASK_FREQ 50 // this is milliseconds
|
||||
|
||||
#define MAX_PEN_NUMBER 4
|
||||
#define BUMPS_PER_PEN_CHANGE 3
|
||||
|
||||
|
||||
#define ATARI_HOME_POS -10.0f // this amound to the left of the paper 0
|
||||
#define ATARI_PAPER_WIDTH 100.0f //
|
||||
#define ATARI_HOMING_ATTEMPTS 13
|
||||
|
||||
// tells grbl we have some special functions to call
|
||||
#define USE_MACHINE_INIT
|
||||
#define USE_CUSTOM_HOMING
|
||||
#define USE_TOOL_CHANGE
|
||||
#define ATARI_TOOL_CHANGE_Z 5.0
|
||||
#define USE_M30 // use the user defined end of program
|
||||
|
||||
#ifndef atari_h
|
||||
#define atari_h
|
||||
|
||||
void machine_init();
|
||||
void solenoid_disable();
|
||||
void solenoidSyncTask(void *pvParameters);
|
||||
void calc_solenoid(float penZ);
|
||||
bool user_defined_homing();
|
||||
void atari_home_task(void *pvParameters);
|
||||
void user_tool_change(uint8_t new_tool);
|
||||
void user_defined_macro(uint8_t index);
|
||||
void user_m30();
|
||||
void atari_next_pen();
|
||||
|
||||
#endif
|
@@ -1346,6 +1346,118 @@
|
||||
#define DEFAULT_B_MAX_TRAVEL 250.0 // mm NOTE: Must be a positive value.
|
||||
#define DEFAULT_C_MAX_TRAVEL 100.0 // This is percent in servo mode
|
||||
|
||||
#endif
|
||||
|
||||
#ifdef CPU_MAP_ATARI_1020
|
||||
|
||||
#include "atari_1020.h"
|
||||
|
||||
#define CPU_MAP_NAME "CPU_MAP_ATARI_1020"
|
||||
|
||||
#define ATARI_1020
|
||||
|
||||
#define USE_UNIPOLAR
|
||||
|
||||
#define X_UNIPOLAR
|
||||
#define X_PIN_PHASE_0 GPIO_NUM_13
|
||||
#define X_PIN_PHASE_1 GPIO_NUM_21
|
||||
#define X_PIN_PHASE_2 GPIO_NUM_16
|
||||
#define X_PIN_PHASE_3 GPIO_NUM_22
|
||||
|
||||
#define Y_UNIPOLAR
|
||||
#define Y_PIN_PHASE_0 GPIO_NUM_25
|
||||
#define Y_PIN_PHASE_1 GPIO_NUM_27
|
||||
#define Y_PIN_PHASE_2 GPIO_NUM_26
|
||||
#define Y_PIN_PHASE_3 GPIO_NUM_32
|
||||
|
||||
|
||||
#define SOLENOID_DIRECTION_PIN GPIO_NUM_4
|
||||
#define SOLENOID_PEN_PIN GPIO_NUM_2
|
||||
#define SOLENOID_CHANNEL_NUM 6
|
||||
|
||||
#ifdef HOMING_CYCLE_0
|
||||
#undef HOMING_CYCLE_0
|
||||
#endif
|
||||
#define HOMING_CYCLE_0 (1<<X_AXIS) // this 'bot only homes the X axis
|
||||
#ifdef HOMING_CYCLE_1
|
||||
#undef HOMING_CYCLE_1
|
||||
#endif
|
||||
#ifdef HOMING_CYCLE_2
|
||||
#undef HOMING_CYCLE_2
|
||||
#endif
|
||||
|
||||
#define REED_SW_PIN GPIO_NUM_17
|
||||
#define LIMIT_MASK 0
|
||||
|
||||
|
||||
#ifdef IGNORE_CONTROL_PINS // maybe set in config.h
|
||||
#undef IGNORE_CONTROL_PINS
|
||||
#endif
|
||||
|
||||
|
||||
#ifndef ENABLE_CONTROL_SW_DEBOUNCE
|
||||
#define ENABLE_CONTROL_SW_DEBOUNCE
|
||||
#endif
|
||||
|
||||
#ifdef INVERT_CONTROL_PIN_MASK
|
||||
#undef IGNORE_CONTROL_PINS
|
||||
#endif
|
||||
#define INVERT_CONTROL_PIN_MASK B01110000
|
||||
|
||||
#define MACRO_BUTTON_0_PIN GPIO_NUM_34 // Pen Switch
|
||||
#define MACRO_BUTTON_1_PIN GPIO_NUM_35 // Color Switch
|
||||
#define MACRO_BUTTON_2_PIN GPIO_NUM_36 // Paper Switch
|
||||
|
||||
#ifdef DEFAULTS_GENERIC
|
||||
#undef DEFAULTS_GENERIC // undefine generic then define each default below
|
||||
#endif
|
||||
#define DEFAULT_STEP_PULSE_MICROSECONDS 3
|
||||
#define DEFAULT_STEPPER_IDLE_LOCK_TIME 200 // 200ms
|
||||
|
||||
#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 1
|
||||
#define DEFAULT_HOMING_DIR_MASK 0
|
||||
#define DEFAULT_HOMING_FEED_RATE 3000.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 2.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 10
|
||||
#define DEFAULT_Y_STEPS_PER_MM 10
|
||||
#define DEFAULT_Z_STEPS_PER_MM 100.0 // This is percent in servo mode
|
||||
|
||||
|
||||
#define DEFAULT_X_MAX_RATE 5000.0 // mm/min
|
||||
#define DEFAULT_Y_MAX_RATE 5000.0 // mm/min
|
||||
#define DEFAULT_Z_MAX_RATE 200000.0 // mm/min
|
||||
|
||||
#define DEFAULT_X_ACCELERATION (500.0*60*60) // 10*60*60 mm/min^2 = 10 mm/sec^2
|
||||
#define DEFAULT_Y_ACCELERATION (500.0*60*60) // 10*60*60 mm/min^2 = 10 mm/sec^2
|
||||
#define DEFAULT_Z_ACCELERATION (500.0*60*60)
|
||||
|
||||
#define DEFAULT_X_MAX_TRAVEL 120.0 // mm NOTE: Must be a positive value.
|
||||
#define DEFAULT_Y_MAX_TRAVEL 20000.0 // mm NOTE: Must be a positive value.
|
||||
#define DEFAULT_Z_MAX_TRAVEL 10.0 // This is percent in servo mode
|
||||
|
||||
#endif
|
||||
|
||||
// ================= common to all machines ================================
|
||||
|
@@ -35,7 +35,7 @@ ESPResponseStream::ESPResponseStream(WebServer * webserver){
|
||||
#endif
|
||||
|
||||
ESPResponseStream::ESPResponseStream(){
|
||||
_client = CLIENT_NONE;
|
||||
_client = CLIENT_INPUT;
|
||||
#if defined (ENABLE_HTTP) && defined(ENABLE_WIFI)
|
||||
_header_sent=false;
|
||||
_webserver = NULL;
|
||||
@@ -72,7 +72,7 @@ String ESPResponseStream::formatBytes (uint64_t bytes)
|
||||
}
|
||||
|
||||
void ESPResponseStream::print(const char *data){
|
||||
if (_client == CLIENT_NONE) return;
|
||||
if (_client == CLIENT_INPUT) return;
|
||||
#if defined (ENABLE_HTTP) && defined(ENABLE_WIFI)
|
||||
if (_webserver) {
|
||||
if (!_header_sent) {
|
||||
|
@@ -344,7 +344,11 @@ uint8_t gc_execute_line(char *line, uint8_t client)
|
||||
}
|
||||
break;
|
||||
case 6: // too change
|
||||
grbl_send(CLIENT_ALL, "[MSG:Tool Change]\r\n");
|
||||
word_bit = MODAL_GROUP_M6;
|
||||
gc_block.modal.tool_change = TOOL_CHANGE;
|
||||
#ifdef USE_TOOL_CHANGE
|
||||
//tool_change(gc_state.tool);
|
||||
#endif
|
||||
break;
|
||||
case 7:
|
||||
case 8:
|
||||
@@ -491,7 +495,7 @@ uint8_t gc_execute_line(char *line, uint8_t client)
|
||||
axis_words |= (1<<Z_AXIS);
|
||||
break;
|
||||
default:
|
||||
FAIL(STATUS_GCODE_UNSUPPORTED_COMMAND);
|
||||
FAIL(STATUS_GCODE_UNSUPPORTED_COMMAND);
|
||||
}
|
||||
|
||||
// NOTE: Variable 'word_bit' is always assigned, if the non-command letter is valid.
|
||||
@@ -1215,6 +1219,11 @@ uint8_t gc_execute_line(char *line, uint8_t client)
|
||||
// gc_state.tool = gc_block.values.t;
|
||||
|
||||
// [6. Change tool ]: NOT SUPPORTED
|
||||
if (gc_block.modal.tool_change == TOOL_CHANGE) {
|
||||
#ifdef USE_TOOL_CHANGE
|
||||
user_tool_change(gc_state.tool);
|
||||
#endif
|
||||
}
|
||||
|
||||
// [7. Spindle control ]:
|
||||
if (gc_state.modal.spindle != gc_block.modal.spindle) {
|
||||
@@ -1412,6 +1421,9 @@ uint8_t gc_execute_line(char *line, uint8_t client)
|
||||
coolant_set_state(COOLANT_DISABLE);
|
||||
}
|
||||
report_feedback_message(MESSAGE_PROGRAM_END);
|
||||
#ifdef USE_M30
|
||||
user_m30();
|
||||
#endif
|
||||
}
|
||||
gc_state.modal.program_flow = PROGRAM_FLOW_RUNNING; // Reset program flow.
|
||||
}
|
||||
|
@@ -44,6 +44,7 @@
|
||||
#define MODAL_GROUP_G13 10 // [G61] Control mode
|
||||
|
||||
#define MODAL_GROUP_M4 11 // [M0,M1,M2,M30] Stopping
|
||||
#define MODAL_GROUP_M6 14 // [M6] Tool change
|
||||
#define MODAL_GROUP_M7 12 // [M3,M4,M5] Spindle turning
|
||||
#define MODAL_GROUP_M8 13 // [M7,M8,M9] Coolant control
|
||||
#define MODAL_GROUP_M10 14 // [M62, M63] User Defined http://linuxcnc.org/docs/html/gcode/overview.html#_modal_groups
|
||||
@@ -134,7 +135,7 @@
|
||||
#define TOOL_LENGTH_OFFSET_CANCEL 0 // G49 (Default: Must be zero)
|
||||
#define TOOL_LENGTH_OFFSET_ENABLE_DYNAMIC 1 // G43.1
|
||||
|
||||
|
||||
#define TOOL_CHANGE 1
|
||||
|
||||
// Modal Group G12: Active work coordinate system
|
||||
// N/A: Stores coordinate system value (54-59) to change to.
|
||||
@@ -200,6 +201,7 @@ typedef struct {
|
||||
uint8_t program_flow; // {M0,M1,M2,M30}
|
||||
uint8_t coolant; // {M7,M8,M9}
|
||||
uint8_t spindle; // {M3,M4,M5}
|
||||
uint8_t tool_change; // {M6}
|
||||
uint8_t io_control; // {M62, M63}
|
||||
} gc_modal_t;
|
||||
|
||||
|
@@ -20,7 +20,7 @@
|
||||
|
||||
// Grbl versioning system
|
||||
#define GRBL_VERSION "1.1f"
|
||||
#define GRBL_VERSION_BUILD "20191018"
|
||||
#define GRBL_VERSION_BUILD "20191023"
|
||||
|
||||
//#include <sdkconfig.h>
|
||||
#include <Arduino.h>
|
||||
@@ -89,3 +89,7 @@
|
||||
#include "grbl_trinamic.h"
|
||||
#endif
|
||||
|
||||
#ifdef USE_UNIPOLAR
|
||||
#include "grbl_unipolar.h"
|
||||
#endif
|
||||
|
||||
|
236
Grbl_Esp32/grbl_unipolar.cpp
Normal file
236
Grbl_Esp32/grbl_unipolar.cpp
Normal file
@@ -0,0 +1,236 @@
|
||||
/*
|
||||
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_send(CLIENT_SERIAL, "[MSG:X Unipolar]\r\n");
|
||||
#endif
|
||||
#ifdef Y_UNIPOLAR
|
||||
Y_Unipolar.init();
|
||||
grbl_send(CLIENT_SERIAL, "[MSG:Y Unipolar]\r\n");
|
||||
#endif
|
||||
#ifdef Z_UNIPOLAR
|
||||
Z_Unipolar.init();
|
||||
grbl_send(CLIENT_SERIAL, "[MSG:Z Unipolar]\r\n");
|
||||
#endif
|
||||
}
|
||||
|
||||
void unipolar_step(uint8_t step_mask, uint8_t dir_mask)
|
||||
{
|
||||
#ifdef X_UNIPOLAR
|
||||
X_Unipolar.step(step_mask & (1<<X_AXIS), dir_mask & (1<<X_AXIS));
|
||||
#endif
|
||||
#ifdef Y_UNIPOLAR
|
||||
Y_Unipolar.step(step_mask & (1<<Y_AXIS), dir_mask & (1<<Y_AXIS));
|
||||
#endif
|
||||
#ifdef Z_UNIPOLAR
|
||||
Z_Unipolar.step(step_mask & (1<<Z_AXIS), dir_mask & (1<<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
|
||||
|
||||
//grbl_sendf(CLIENT_SERIAL, "[MSG:Enabled...%d]\r\n", enabled);
|
||||
|
||||
_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
|
54
Grbl_Esp32/grbl_unipolar.h
Normal file
54
Grbl_Esp32/grbl_unipolar.h
Normal file
@@ -0,0 +1,54 @@
|
||||
/*
|
||||
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
|
||||
|
||||
*/
|
||||
#ifndef grbl_unipolar_h
|
||||
#define grbl_unipolar_h
|
||||
|
||||
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;
|
||||
|
||||
};
|
||||
#endif
|
@@ -231,6 +231,12 @@ void mc_dwell(float seconds)
|
||||
// executing the homing cycle. This prevents incorrect buffered plans after homing.
|
||||
void mc_homing_cycle(uint8_t cycle_mask)
|
||||
{
|
||||
#ifdef USE_CUSTOM_HOMING
|
||||
if (user_defined_homing())
|
||||
{
|
||||
return;
|
||||
}
|
||||
#endif
|
||||
|
||||
// This give kinematics a chance to do something before normal homing
|
||||
// if it returns true, the homing is canceled.
|
||||
|
@@ -53,7 +53,7 @@
|
||||
// this is a generic send function that everything should use, so interfaces could be added (Bluetooth, etc)
|
||||
void grbl_send(uint8_t client, const char *text)
|
||||
{
|
||||
if (client == CLIENT_NONE) return;
|
||||
if (client == CLIENT_INPUT) return;
|
||||
#ifdef ENABLE_BLUETOOTH
|
||||
if (SerialBT.hasClient() && ( client == CLIENT_BT || client == CLIENT_ALL ) )
|
||||
{
|
||||
@@ -81,7 +81,7 @@ void grbl_send(uint8_t client, const char *text)
|
||||
// This is a formating version of the grbl_send(CLIENT_ALL,...) function that work like printf
|
||||
void grbl_sendf(uint8_t client, const char *format, ...)
|
||||
{
|
||||
if (client == CLIENT_NONE) return;
|
||||
if (client == CLIENT_INPUT) return;
|
||||
char loc_buf[64];
|
||||
char * temp = loc_buf;
|
||||
va_list arg;
|
||||
|
@@ -99,13 +99,13 @@
|
||||
#define MESSAGE_SLEEP_MODE 11
|
||||
#define MESSAGE_SD_FILE_QUIT 60 // mc_reset was called during an SD job
|
||||
|
||||
#define CLIENT_NONE 0
|
||||
#define CLIENT_SERIAL 1
|
||||
#define CLIENT_SERIAL 1
|
||||
#define CLIENT_BT 2
|
||||
#define CLIENT_WEBUI 3
|
||||
#define CLIENT_TELNET 4
|
||||
#define CLIENT_INPUT 5
|
||||
#define CLIENT_ALL 0xFF
|
||||
#define CLIENT_COUNT 5 // total number of client types regardless if they are used
|
||||
#define CLIENT_COUNT 5 // total number of client types regardless if they are used
|
||||
|
||||
// functions to send data to the user.
|
||||
void grbl_send(uint8_t client, const char *text);
|
||||
|
@@ -89,7 +89,7 @@ void serialCheckTask(void *pvParameters)
|
||||
data = Serial.read();
|
||||
}
|
||||
else if (inputBuffer.available()){
|
||||
client = CLIENT_NONE;
|
||||
client = CLIENT_INPUT;
|
||||
data = inputBuffer.read();
|
||||
}
|
||||
else
|
||||
@@ -228,7 +228,7 @@ void serialCheck()
|
||||
}
|
||||
else if (inputBuffer.available())
|
||||
{
|
||||
client = CLIENT_NONE;
|
||||
client = CLIENT_INPUT;
|
||||
data = inputBuffer.read();
|
||||
}
|
||||
#if defined (ENABLE_BLUETOOTH) || (defined (ENABLE_WIFI) && defined(ENABLE_HTTP) && defined(ENABLE_SERIAL2SOCKET_IN))
|
||||
|
@@ -234,7 +234,11 @@ void IRAM_ATTR onStepperDriverTimer(void *para) // ISR It is time to take a ste
|
||||
#else
|
||||
set_stepper_pins_on(st.step_outbits);
|
||||
step_pulse_off_time = esp_timer_get_time() + (settings.pulse_microseconds); // determine when to turn off pulse
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#ifdef USE_UNIPOLAR
|
||||
unipolar_step(st.step_outbits, st.dir_outbits);
|
||||
#endif
|
||||
|
||||
busy = true;
|
||||
// If there is no step segment, attempt to pop one from the stepper buffer
|
||||
@@ -435,9 +439,9 @@ void stepper_init()
|
||||
set_stepper_disable(true);
|
||||
#endif
|
||||
|
||||
//#ifdef USE_TMC2130
|
||||
// TMC2130_Init();
|
||||
//#endif
|
||||
#ifdef USE_UNIPOLAR
|
||||
unipolar_init();
|
||||
#endif
|
||||
|
||||
#ifdef USE_TRINAMIC
|
||||
Trinamic_Init();
|
||||
@@ -1505,6 +1509,10 @@ void set_stepper_disable(uint8_t isOn) // isOn = true // to disable
|
||||
isOn = !isOn; // Apply pin invert.
|
||||
}
|
||||
|
||||
#ifdef USE_UNIPOLAR
|
||||
unipolar_disable(isOn);
|
||||
#endif
|
||||
|
||||
#ifdef STEPPERS_DISABLE_PIN
|
||||
digitalWrite(STEPPERS_DISABLE_PIN, isOn );
|
||||
#endif
|
||||
|
@@ -22,6 +22,7 @@
|
||||
#include "config.h"
|
||||
|
||||
xQueueHandle control_sw_queue; // used by control switch debouncing
|
||||
bool debouncing = false; // debouncing in process
|
||||
|
||||
void system_ini() // Renamed from system_init() due to conflict with esp32 files
|
||||
{
|
||||
@@ -46,21 +47,25 @@ void system_ini() // Renamed from system_init() due to conflict with esp32 files
|
||||
#endif
|
||||
|
||||
#ifdef MACRO_BUTTON_0_PIN
|
||||
grbl_send(CLIENT_SERIAL, "[MSG:Macro Pin 0]\r\n");
|
||||
pinMode(MACRO_BUTTON_0_PIN, INPUT_PULLUP);
|
||||
attachInterrupt(digitalPinToInterrupt(MACRO_BUTTON_0_PIN), isr_control_inputs, CHANGE);
|
||||
#endif
|
||||
|
||||
#ifdef MACRO_BUTTON_1_PIN
|
||||
grbl_send(CLIENT_SERIAL, "[MSG:Macro Pin 1]\r\n");
|
||||
pinMode(MACRO_BUTTON_1_PIN, INPUT_PULLUP);
|
||||
attachInterrupt(digitalPinToInterrupt(MACRO_BUTTON_1_PIN), isr_control_inputs, CHANGE);
|
||||
#endif
|
||||
|
||||
#ifdef MACRO_BUTTON_2_PIN
|
||||
grbl_send(CLIENT_SERIAL, "[MSG:Macro Pin 2]\r\n");
|
||||
pinMode(MACRO_BUTTON_2_PIN, INPUT_PULLUP);
|
||||
attachInterrupt(digitalPinToInterrupt(MACRO_BUTTON_2_PIN), isr_control_inputs, CHANGE);
|
||||
#endif
|
||||
|
||||
#ifdef MACRO_BUTTON_3_PIN
|
||||
grbl_send(CLIENT_SERIAL, "[MSG:Macro Pin 3]\r\n");
|
||||
pinMode(MACRO_BUTTON_3_PIN, INPUT_PULLUP);
|
||||
attachInterrupt(digitalPinToInterrupt(MACRO_BUTTON_3_PIN), isr_control_inputs, CHANGE);
|
||||
#endif
|
||||
@@ -86,22 +91,24 @@ void system_ini() // Renamed from system_init() due to conflict with esp32 files
|
||||
|
||||
// Setup USER_DIGITAL_PINs controlled by M62 and M63
|
||||
#ifdef USER_DIGITAL_PIN_1
|
||||
pinMode(USER_DIGITAL_PIN_1, OUTPUT);
|
||||
pinMode(USER_DIGITAL_PIN_1, OUTPUT);
|
||||
sys_io_control(1<<1, false); // turn off
|
||||
#endif
|
||||
|
||||
#ifdef USER_DIGITAL_PIN_2
|
||||
pinMode(USER_DIGITAL_PIN_2, OUTPUT);
|
||||
sys_io_control(1<<2, false); // turn off
|
||||
#endif
|
||||
|
||||
#ifdef USER_DIGITAL_PIN_3
|
||||
pinMode(USER_DIGITAL_PIN_3, OUTPUT);
|
||||
sys_io_control(1<<3, false); // turn off
|
||||
#endif
|
||||
|
||||
#ifdef USER_DIGITAL_PIN_4
|
||||
pinMode(USER_DIGITAL_PIN_4, OUTPUT);
|
||||
#endif
|
||||
|
||||
sys_io_control(0xFF, false); // turn them all off
|
||||
sys_io_control(1<<4, false); // turn off
|
||||
#endif
|
||||
}
|
||||
|
||||
#ifdef ENABLE_CONTROL_SW_DEBOUNCE
|
||||
@@ -111,22 +118,26 @@ void controlCheckTask(void *pvParameters)
|
||||
while(true) {
|
||||
int evt;
|
||||
xQueueReceive(control_sw_queue, &evt, portMAX_DELAY); // block until receive queue
|
||||
vTaskDelay( CONTROL_SW_DEBOUNCE_PERIOD / portTICK_PERIOD_MS ); // delay a while
|
||||
vTaskDelay(CONTROL_SW_DEBOUNCE_PERIOD); // delay a while
|
||||
|
||||
uint8_t pin = system_control_get_state();
|
||||
if (pin) {
|
||||
system_exec_control_pin(pin);
|
||||
}
|
||||
debouncing = false;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
void IRAM_ATTR isr_control_inputs()
|
||||
{
|
||||
{
|
||||
#ifdef ENABLE_CONTROL_SW_DEBOUNCE
|
||||
// we will start a task that will recheck the switches after a small delay
|
||||
int evt;
|
||||
xQueueSendFromISR(control_sw_queue, &evt, NULL);
|
||||
if (!debouncing) { // prevent resending until debounce is done
|
||||
debouncing = true;
|
||||
xQueueSendFromISR(control_sw_queue, &evt, NULL);
|
||||
}
|
||||
#else
|
||||
uint8_t pin = system_control_get_state();
|
||||
system_exec_control_pin(pin);
|
||||
@@ -541,17 +552,17 @@ void system_exec_control_pin(uint8_t pin) {
|
||||
bit_true(sys_rt_exec_state, EXEC_SAFETY_DOOR);
|
||||
}
|
||||
#ifdef MACRO_BUTTON_0_PIN
|
||||
else if (pin == 96) {
|
||||
else if (bit_istrue(pin,CONTROL_PIN_INDEX_MACRO_0)) {
|
||||
user_defined_macro(CONTROL_PIN_INDEX_MACRO_0); // function must be implemented by user
|
||||
}
|
||||
#endif
|
||||
#ifdef MACRO_BUTTON_1_PIN
|
||||
else if (pin == 80) {
|
||||
else if (bit_istrue(pin,CONTROL_PIN_INDEX_MACRO_1)) {
|
||||
user_defined_macro(CONTROL_PIN_INDEX_MACRO_1); // function must be implemented by user
|
||||
}
|
||||
#endif
|
||||
#ifdef MACRO_BUTTON_2_PIN
|
||||
else if (pin == 48) {
|
||||
else if (bit_istrue(pin,CONTROL_PIN_INDEX_MACRO_2)) {
|
||||
user_defined_macro(CONTROL_PIN_INDEX_MACRO_2); // function must be implemented by user
|
||||
}
|
||||
#endif
|
||||
|
Reference in New Issue
Block a user