mirror of
https://github.com/bdring/Grbl_Esp32.git
synced 2025-09-01 18:32:37 +02:00
Handle macros in protocol real time handler
This commit is contained in:
@@ -87,3 +87,6 @@ PWM:
|
|||||||
spindown_ms: 1000
|
spindown_ms: 1000
|
||||||
speeds: 0=0% 1000=100%
|
speeds: 0=0% 1000=100%
|
||||||
tool: 0
|
tool: 0
|
||||||
|
|
||||||
|
macros:
|
||||||
|
n0: G0 X0
|
||||||
|
@@ -3,9 +3,6 @@
|
|||||||
#include "Report.h" // addPinReport
|
#include "Report.h" // addPinReport
|
||||||
#include <Arduino.h> // IRAM_ATTR
|
#include <Arduino.h> // IRAM_ATTR
|
||||||
|
|
||||||
// XXX we need to dispatch the user defined macros somehow
|
|
||||||
// user_defined_macro(N)
|
|
||||||
|
|
||||||
void IRAM_ATTR ControlPin::handleISR() {
|
void IRAM_ATTR ControlPin::handleISR() {
|
||||||
bool pinState = _pin.read();
|
bool pinState = _pin.read();
|
||||||
_value = pinState;
|
_value = pinState;
|
||||||
|
@@ -48,8 +48,6 @@ bool limitsCheckTravel(float* target); // weak in Limits.cpp; true if out of ra
|
|||||||
void inverse_kinematics(float* position); // used to return a converted value
|
void inverse_kinematics(float* position); // used to return a converted value
|
||||||
void forward_kinematics(float* position);
|
void forward_kinematics(float* position);
|
||||||
|
|
||||||
void user_defined_macro(uint8_t index);
|
|
||||||
|
|
||||||
void user_m30();
|
void user_m30();
|
||||||
|
|
||||||
void user_tool_change(uint8_t new_tool);
|
void user_tool_change(uint8_t new_tool);
|
||||||
|
@@ -19,6 +19,7 @@
|
|||||||
*/
|
*/
|
||||||
|
|
||||||
#include "../Configuration/Configurable.h"
|
#include "../Configuration/Configurable.h"
|
||||||
|
#include "../WebUI/InputBuffer.h" // WebUI::inputBuffer
|
||||||
|
|
||||||
namespace Machine {
|
namespace Machine {
|
||||||
class Macros : public Configuration::Configurable {
|
class Macros : public Configuration::Configurable {
|
||||||
@@ -33,8 +34,36 @@ namespace Machine {
|
|||||||
public:
|
public:
|
||||||
Macros() = default;
|
Macros() = default;
|
||||||
|
|
||||||
String macro(size_t index) { return index < n_macros ? _macro[index] : ""; }
|
void run_macro(size_t index) {
|
||||||
String startup_line(size_t index) { return index < n_startup_lines ? _startup_line[index] : ""; }
|
if (index >= n_macros) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
String macro = _macro[index];
|
||||||
|
if (macro == "") {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
// & is a proxy for newlines in macros, because you cannot
|
||||||
|
// enter a newline directly in a config file string value.
|
||||||
|
macro.replace('&', '\n');
|
||||||
|
macro += "\n";
|
||||||
|
|
||||||
|
WebUI::inputBuffer.push(macro.c_str());
|
||||||
|
}
|
||||||
|
|
||||||
|
String startup_line(size_t index) {
|
||||||
|
if (index >= n_startup_lines) {
|
||||||
|
return "";
|
||||||
|
}
|
||||||
|
String s = _startup_line[index];
|
||||||
|
if (s == "") {
|
||||||
|
return s;
|
||||||
|
}
|
||||||
|
// & is a proxy for newlines in startup lines, because you cannot
|
||||||
|
// enter a newline directly in a config file string value.
|
||||||
|
s.replace('&', '\n');
|
||||||
|
return s + "\n";
|
||||||
|
}
|
||||||
|
|
||||||
// Configuration helpers:
|
// Configuration helpers:
|
||||||
|
|
||||||
|
@@ -684,10 +684,14 @@ Error system_execute_line(char* line, uint8_t client, WebUI::AuthenticationLevel
|
|||||||
|
|
||||||
void system_execute_startup() {
|
void system_execute_startup() {
|
||||||
Error status_code;
|
Error status_code;
|
||||||
char gcline[256];
|
|
||||||
for (int i = 0; i < config->_macros->n_startup_lines; i++) {
|
for (int i = 0; i < config->_macros->n_startup_lines; i++) {
|
||||||
strncpy(gcline, config->_macros->startup_line(i).c_str(), 255);
|
String str = config->_macros->startup_line(i);
|
||||||
if (*gcline) {
|
const char* s = str.c_str();
|
||||||
|
if (s && strlen(s)) {
|
||||||
|
// We have to copy this to a mutable array because
|
||||||
|
// gc_execute_line modifies the line while parsing.
|
||||||
|
char gcline[256];
|
||||||
|
strncpy(gcline, s, 255);
|
||||||
status_code = gc_execute_line(gcline, CLIENT_SERIAL);
|
status_code = gc_execute_line(gcline, CLIENT_SERIAL);
|
||||||
report_execute_startup_message(gcline, status_code, CLIENT_SERIAL);
|
report_execute_startup_message(gcline, status_code, CLIENT_SERIAL);
|
||||||
}
|
}
|
||||||
|
@@ -646,6 +646,16 @@ static void protocol_execute_overrides() {
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void protocol_do_macro(int macro_num) {
|
||||||
|
// must be in Idle
|
||||||
|
if (sys.state != State::Idle) {
|
||||||
|
info_serial("Macro button only permitted in idle");
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
config->_macros->run_macro(macro_num);
|
||||||
|
}
|
||||||
|
|
||||||
void protocol_exec_rt_system() {
|
void protocol_exec_rt_system() {
|
||||||
protocol_do_alarm(); // If there is a hard or soft limit, this will block until rtReset is set
|
protocol_do_alarm(); // If there is a hard or soft limit, this will block until rtReset is set
|
||||||
|
|
||||||
@@ -687,6 +697,23 @@ void protocol_exec_rt_system() {
|
|||||||
protocol_do_cycle_stop();
|
protocol_do_cycle_stop();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
if (rtButtonMacro0) {
|
||||||
|
protocol_do_macro(0);
|
||||||
|
rtButtonMacro0 = false;
|
||||||
|
}
|
||||||
|
if (rtButtonMacro1) {
|
||||||
|
protocol_do_macro(1);
|
||||||
|
rtButtonMacro1 = false;
|
||||||
|
}
|
||||||
|
if (rtButtonMacro2) {
|
||||||
|
protocol_do_macro(2);
|
||||||
|
rtButtonMacro0 = false;
|
||||||
|
}
|
||||||
|
if (rtButtonMacro3) {
|
||||||
|
protocol_do_macro(3);
|
||||||
|
rtButtonMacro3 = false;
|
||||||
|
}
|
||||||
|
|
||||||
protocol_execute_overrides();
|
protocol_execute_overrides();
|
||||||
|
|
||||||
#ifdef DEBUG_PROTOCOL
|
#ifdef DEBUG_PROTOCOL
|
||||||
|
@@ -26,7 +26,6 @@
|
|||||||
#include "UserOutput.h"
|
#include "UserOutput.h"
|
||||||
#include "SettingsDefinitions.h"
|
#include "SettingsDefinitions.h"
|
||||||
#include "Machine/MachineConfig.h"
|
#include "Machine/MachineConfig.h"
|
||||||
#include "WebUI/InputBuffer.h" // WebUI::inputBuffer
|
|
||||||
|
|
||||||
#include <atomic>
|
#include <atomic>
|
||||||
#include <cstring> // memset
|
#include <cstring> // memset
|
||||||
@@ -181,28 +180,6 @@ uint8_t sys_calc_pwm_precision(uint32_t freq) {
|
|||||||
return precision - 1;
|
return precision - 1;
|
||||||
}
|
}
|
||||||
|
|
||||||
void __attribute__((weak)) user_defined_macro(uint8_t index) {
|
|
||||||
// must be in Idle
|
|
||||||
if (sys.state != State::Idle) {
|
|
||||||
info_serial("Macro button only permitted in idle");
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
|
|
||||||
String user_macro = config->_macros->macro(index);
|
|
||||||
|
|
||||||
if (user_macro == "") {
|
|
||||||
info_serial("User/Macro%d empty", index);
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
|
|
||||||
char line[255];
|
|
||||||
|
|
||||||
user_macro.replace('&', '\n');
|
|
||||||
user_macro.toCharArray(line, 255, 0);
|
|
||||||
strcat(line, "\r");
|
|
||||||
WebUI::inputBuffer.push(line);
|
|
||||||
}
|
|
||||||
|
|
||||||
std::map<State, const char*> StateName = {
|
std::map<State, const char*> StateName = {
|
||||||
{ State::Idle, "Idle" },
|
{ State::Idle, "Idle" },
|
||||||
{ State::Alarm, "Alarm" },
|
{ State::Alarm, "Alarm" },
|
||||||
|
Reference in New Issue
Block a user