mirror of
https://github.com/bdring/Grbl_Esp32.git
synced 2025-09-03 03:13:25 +02:00
Changed ISR attachment a bit. It should trigger on PinCapabilities, not PinAttributes
This commit is contained in:
@@ -22,57 +22,66 @@
|
|||||||
#include <WiFi.h>
|
#include <WiFi.h>
|
||||||
|
|
||||||
void grbl_init() {
|
void grbl_init() {
|
||||||
|
try {
|
||||||
#ifdef USE_I2S_OUT
|
#ifdef USE_I2S_OUT
|
||||||
i2s_out_init(); // The I2S out must be initialized before it can access the expanded GPIO port
|
i2s_out_init(); // The I2S out must be initialized before it can access the expanded GPIO port
|
||||||
#endif
|
#endif
|
||||||
WiFi.persistent(false);
|
WiFi.persistent(false);
|
||||||
WiFi.disconnect(true);
|
WiFi.disconnect(true);
|
||||||
WiFi.enableSTA(false);
|
WiFi.enableSTA(false);
|
||||||
WiFi.enableAP(false);
|
WiFi.enableAP(false);
|
||||||
WiFi.mode(WIFI_OFF);
|
WiFi.mode(WIFI_OFF);
|
||||||
serial_init(); // Setup serial baud rate and interrupts
|
serial_init(); // Setup serial baud rate and interrupts
|
||||||
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Grbl_ESP32 Ver %s Date %s", GRBL_VERSION, GRBL_VERSION_BUILD); // print grbl_esp32 verion info
|
grbl_msg_sendf(
|
||||||
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Compiled with ESP32 SDK:%s", ESP.getSdkVersion()); // print the SDK version
|
CLIENT_SERIAL, MsgLevel::Info, "Grbl_ESP32 Ver %s Date %s", GRBL_VERSION, GRBL_VERSION_BUILD); // print grbl_esp32 verion info
|
||||||
|
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Compiled with ESP32 SDK:%s", ESP.getSdkVersion()); // print the SDK version
|
||||||
// show the map name at startup
|
// show the map name at startup
|
||||||
#ifdef MACHINE_NAME
|
#ifdef MACHINE_NAME
|
||||||
report_machine_type(CLIENT_SERIAL);
|
report_machine_type(CLIENT_SERIAL);
|
||||||
#endif
|
#endif
|
||||||
settings_init(); // Load Grbl settings from non-volatile storage
|
settings_init(); // Load Grbl settings from non-volatile storage
|
||||||
stepper_init(); // Configure stepper pins and interrupt timers
|
stepper_init(); // Configure stepper pins and interrupt timers
|
||||||
init_motors();
|
init_motors();
|
||||||
system_ini(); // Configure pinout pins and pin-change interrupt (Renamed due to conflict with esp32 files)
|
system_ini(); // Configure pinout pins and pin-change interrupt (Renamed due to conflict with esp32 files)
|
||||||
memset(sys_position, 0, sizeof(sys_position)); // Clear machine position.
|
memset(sys_position, 0, sizeof(sys_position)); // Clear machine position.
|
||||||
|
|
||||||
#ifdef USE_MACHINE_INIT
|
#ifdef USE_MACHINE_INIT
|
||||||
machine_init(); // user supplied function for special initialization
|
machine_init(); // user supplied function for special initialization
|
||||||
#endif
|
#endif
|
||||||
// Initialize system state.
|
// Initialize system state.
|
||||||
#ifdef FORCE_INITIALIZATION_ALARM
|
#ifdef FORCE_INITIALIZATION_ALARM
|
||||||
// Force Grbl into an ALARM state upon a power-cycle or hard reset.
|
// Force Grbl into an ALARM state upon a power-cycle or hard reset.
|
||||||
sys.state = State::Alarm;
|
|
||||||
#else
|
|
||||||
sys.state = State::Idle;
|
|
||||||
#endif
|
|
||||||
// Check for power-up and set system alarm if homing is enabled to force homing cycle
|
|
||||||
// by setting Grbl's alarm state. Alarm locks out all g-code commands, including the
|
|
||||||
// startup scripts, but allows access to settings and internal commands. Only a homing
|
|
||||||
// cycle '$H' or kill alarm locks '$X' will disable the alarm.
|
|
||||||
// NOTE: The startup script will run after successful completion of the homing cycle, but
|
|
||||||
// not after disabling the alarm locks. Prevents motion startup blocks from crashing into
|
|
||||||
// things uncontrollably. Very bad.
|
|
||||||
#ifdef HOMING_INIT_LOCK
|
|
||||||
if (homing_enable->get()) {
|
|
||||||
sys.state = State::Alarm;
|
sys.state = State::Alarm;
|
||||||
}
|
#else
|
||||||
|
sys.state = State::Idle;
|
||||||
#endif
|
#endif
|
||||||
Spindles::Spindle::select();
|
// Check for power-up and set system alarm if homing is enabled to force homing cycle
|
||||||
|
// by setting Grbl's alarm state. Alarm locks out all g-code commands, including the
|
||||||
|
// startup scripts, but allows access to settings and internal commands. Only a homing
|
||||||
|
// cycle '$H' or kill alarm locks '$X' will disable the alarm.
|
||||||
|
// NOTE: The startup script will run after successful completion of the homing cycle, but
|
||||||
|
// not after disabling the alarm locks. Prevents motion startup blocks from crashing into
|
||||||
|
// things uncontrollably. Very bad.
|
||||||
|
#ifdef HOMING_INIT_LOCK
|
||||||
|
if (homing_enable->get()) {
|
||||||
|
sys.state = State::Alarm;
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
Spindles::Spindle::select();
|
||||||
#ifdef ENABLE_WIFI
|
#ifdef ENABLE_WIFI
|
||||||
WebUI::wifi_config.begin();
|
WebUI::wifi_config.begin();
|
||||||
#endif
|
#endif
|
||||||
#ifdef ENABLE_BLUETOOTH
|
#ifdef ENABLE_BLUETOOTH
|
||||||
WebUI::bt_config.begin();
|
WebUI::bt_config.begin();
|
||||||
#endif
|
#endif
|
||||||
WebUI::inputBuffer.begin();
|
WebUI::inputBuffer.begin();
|
||||||
|
} catch (const AssertionFailed& ex) {
|
||||||
|
// This means something is terribly broken:
|
||||||
|
grbl_sendf(CLIENT_ALL, "Critical error in run_once: %s", ex.stackTrace.c_str());
|
||||||
|
while (true) {
|
||||||
|
sleep(1000);
|
||||||
|
}
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
static void reset_variables() {
|
static void reset_variables() {
|
||||||
@@ -118,7 +127,10 @@ void run_once() {
|
|||||||
protocol_main_loop();
|
protocol_main_loop();
|
||||||
} catch (const AssertionFailed& ex) {
|
} catch (const AssertionFailed& ex) {
|
||||||
// This means something is terribly broken:
|
// This means something is terribly broken:
|
||||||
grbl_sendf(CLIENT_ALL, "Critical error: %s", ex.stackTrace.c_str());
|
grbl_sendf(CLIENT_ALL, "Critical error in run_once: %s", ex.stackTrace.c_str());
|
||||||
|
while (true) {
|
||||||
|
sleep(1000);
|
||||||
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@@ -34,12 +34,12 @@ namespace PinUsers {
|
|||||||
|
|
||||||
// Iterate options:
|
// Iterate options:
|
||||||
uart_config_t uart_config = { 0 };
|
uart_config_t uart_config = { 0 };
|
||||||
int bufferSize = 128;
|
int bufferSize = 128;
|
||||||
for (auto opt : options) {
|
for (auto opt : options) {
|
||||||
// if (opt.is("baud")) { baudRate = opt.valueInt(); }
|
// if (opt.is("baud")) { uart_config.baud_rate = opt.iValue(); }
|
||||||
// if (opt.is("mode")) { mode = opt.valueString(); /* 8N1 etc */ }
|
// if (opt.is("mode")) { mode = opt.value(); /* 8N1 etc */ }
|
||||||
// if (opt.is("bufsize")) { mode = opt.valueString(); /* 128 etc */ }
|
// if (opt.is("bufsize")) { mode = opt.iValue(); /* 128 etc */ }
|
||||||
// if (opt.is("protocol")) { protocol= opt.valueString(); /* RS485 etc */ }
|
// if (opt.is("protocol")) { protocol= opt.value(); /* RS485 etc */ }
|
||||||
// etc...
|
// etc...
|
||||||
}
|
}
|
||||||
for (auto opt : userOptions) {
|
for (auto opt : userOptions) {
|
||||||
@@ -94,16 +94,14 @@ namespace PinUsers {
|
|||||||
}
|
}
|
||||||
};
|
};
|
||||||
|
|
||||||
Uart::Uart(Pin tx, Pin rx, Pin rts, String config, String userConfig) {
|
Uart::Uart(Pin tx, Pin rx, Pin rts, String config, String userConfig) {
|
||||||
Pins::PinOptionsParser configParser(config.begin(), config.end());
|
Pins::PinOptionsParser configParser(config.begin(), config.end());
|
||||||
Pins::PinOptionsParser userConfigParser(userConfig.begin(), userConfig.end());
|
Pins::PinOptionsParser userConfigParser(userConfig.begin(), userConfig.end());
|
||||||
|
|
||||||
// Decide on the RX pin what to do:
|
// Decide on the RX pin what to do:
|
||||||
if (rx.capabilities().has(Pin::Capabilities::Native))
|
if (rx.capabilities().has(Pin::Capabilities::Native)) {
|
||||||
{
|
|
||||||
this->_detail = new NativeUart(tx, rx, rts, configParser, userConfigParser);
|
this->_detail = new NativeUart(tx, rx, rts, configParser, userConfigParser);
|
||||||
}
|
} else {
|
||||||
else {
|
|
||||||
Assert(false, "Pin is not supported for UART.");
|
Assert(false, "Pin is not supported for UART.");
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@@ -161,12 +161,12 @@ namespace Pins {
|
|||||||
}
|
}
|
||||||
|
|
||||||
void GPIOPinDetail::attachInterrupt(void (*callback)(void*), void* arg, int mode) {
|
void GPIOPinDetail::attachInterrupt(void (*callback)(void*), void* arg, int mode) {
|
||||||
Assert(_attributes.has(PinAttributes::ISR), "Pin has no ISR attribute defined. Cannot bind ISR.");
|
Assert(_capabilities.has(PinCapabilities::ISR), "Pin has no ISR capability defined. Cannot bind ISR.");
|
||||||
::attachInterruptArg(_index, callback, arg, mode);
|
::attachInterruptArg(_index, callback, arg, mode);
|
||||||
}
|
}
|
||||||
|
|
||||||
void GPIOPinDetail::detachInterrupt() {
|
void GPIOPinDetail::detachInterrupt() {
|
||||||
Assert(_attributes.has(PinAttributes::ISR), "Pin has no ISR attribute defined. Cannot unbind ISR.");
|
Assert(_capabilities.has(PinCapabilities::ISR), "Pin has no ISR capability defined. Cannot unbind ISR.");
|
||||||
::detachInterrupt(_index);
|
::detachInterrupt(_index);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@@ -23,9 +23,9 @@
|
|||||||
// GPIO FUNCTIONS
|
// GPIO FUNCTIONS
|
||||||
#define INPUT 0x01
|
#define INPUT 0x01
|
||||||
#define OUTPUT 0x02
|
#define OUTPUT 0x02
|
||||||
// #define PULLUP 0x04
|
#define PULLUP 0x04
|
||||||
#define INPUT_PULLUP 0x05
|
#define INPUT_PULLUP 0x05
|
||||||
// #define PULLDOWN 0x08
|
#define PULLDOWN 0x08
|
||||||
#define INPUT_PULLDOWN 0x09
|
#define INPUT_PULLDOWN 0x09
|
||||||
// #define OPEN_DRAIN 0x10
|
// #define OPEN_DRAIN 0x10
|
||||||
// #define OUTPUT_OPEN_DRAIN 0x12
|
// #define OUTPUT_OPEN_DRAIN 0x12
|
||||||
|
Reference in New Issue
Block a user