1
0
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:
Stefan de Bruijn
2020-10-28 08:48:52 +01:00
parent 5f1cad9dac
commit 463c92babf
4 changed files with 62 additions and 52 deletions

View File

@@ -22,6 +22,7 @@
#include <WiFi.h>
void grbl_init() {
try {
#ifdef USE_I2S_OUT
i2s_out_init(); // The I2S out must be initialized before it can access the expanded GPIO port
#endif
@@ -31,7 +32,8 @@ void grbl_init() {
WiFi.enableAP(false);
WiFi.mode(WIFI_OFF);
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(
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
#ifdef MACHINE_NAME
@@ -73,6 +75,13 @@ void grbl_init() {
WebUI::bt_config.begin();
#endif
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() {
@@ -118,7 +127,10 @@ void run_once() {
protocol_main_loop();
} catch (const AssertionFailed& ex) {
// 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);
}
}
}

View File

@@ -36,10 +36,10 @@ namespace PinUsers {
uart_config_t uart_config = { 0 };
int bufferSize = 128;
for (auto opt : options) {
// if (opt.is("baud")) { baudRate = opt.valueInt(); }
// if (opt.is("mode")) { mode = opt.valueString(); /* 8N1 etc */ }
// if (opt.is("bufsize")) { mode = opt.valueString(); /* 128 etc */ }
// if (opt.is("protocol")) { protocol= opt.valueString(); /* RS485 etc */ }
// if (opt.is("baud")) { uart_config.baud_rate = opt.iValue(); }
// if (opt.is("mode")) { mode = opt.value(); /* 8N1 etc */ }
// if (opt.is("bufsize")) { mode = opt.iValue(); /* 128 etc */ }
// if (opt.is("protocol")) { protocol= opt.value(); /* RS485 etc */ }
// etc...
}
for (auto opt : userOptions) {
@@ -99,11 +99,9 @@ namespace PinUsers {
Pins::PinOptionsParser userConfigParser(userConfig.begin(), userConfig.end());
// 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);
}
else {
} else {
Assert(false, "Pin is not supported for UART.");
}
}

View File

@@ -161,12 +161,12 @@ namespace Pins {
}
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);
}
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);
}

View File

@@ -23,9 +23,9 @@
// GPIO FUNCTIONS
#define INPUT 0x01
#define OUTPUT 0x02
// #define PULLUP 0x04
#define PULLUP 0x04
#define INPUT_PULLUP 0x05
// #define PULLDOWN 0x08
#define PULLDOWN 0x08
#define INPUT_PULLDOWN 0x09
// #define OPEN_DRAIN 0x10
// #define OUTPUT_OPEN_DRAIN 0x12