diff --git a/Grbl_Esp32/src/Grbl.cpp b/Grbl_Esp32/src/Grbl.cpp index fcb808ba..769bd434 100644 --- a/Grbl_Esp32/src/Grbl.cpp +++ b/Grbl_Esp32/src/Grbl.cpp @@ -77,10 +77,11 @@ void grbl_init() { 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); - } + + // Should grbl_sendf always work? Serial is initialized first, so after line 34 it should. + grbl_msg_sendf(CLIENT_ALL, MsgLevel::Error, "Critical error in run_once: %s", ex.stackTrace.c_str()); + sleep(10000); + throw; } } @@ -127,10 +128,9 @@ void run_once() { protocol_main_loop(); } 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); - } + grbl_msg_sendf(CLIENT_ALL, MsgLevel::Error, "Critical error in run_once: %s", ex.stackTrace.c_str()); + sleep(10000); + throw; } } diff --git a/Grbl_Esp32/src/Limits.cpp b/Grbl_Esp32/src/Limits.cpp index 37065c42..85592b08 100644 --- a/Grbl_Esp32/src/Limits.cpp +++ b/Grbl_Esp32/src/Limits.cpp @@ -309,10 +309,11 @@ uint8_t limit_mask = 0; void limits_init() { limit_mask = 0; - Pin::Attr mode = Pin::Attr::Input | Pin::Attr::PullUp; + Pin::Attr mode = Pin::Attr::Input | Pin::Attr::PullUp | Pin::Attr::ISR; #ifdef DISABLE_LIMIT_PIN_PULL_UP - mode = Pin::Attr::Input; + mode = Pin::Attr::Input | Pin::Attr::ISR; #endif + auto n_axis = number_axis->get(); for (int axis = 0; axis < n_axis; axis++) { for (int gang_index = 0; gang_index < 2; gang_index++) { diff --git a/Grbl_Esp32/src/PinSettingsDefinitions.cpp b/Grbl_Esp32/src/PinSettingsDefinitions.cpp index 6da4f48b..b60d887a 100644 --- a/Grbl_Esp32/src/PinSettingsDefinitions.cpp +++ b/Grbl_Esp32/src/PinSettingsDefinitions.cpp @@ -177,7 +177,6 @@ const char* USER_ANALOG_PIN_2_DEFAULT = USER_ANALOG_PIN_2; #endif const char* USER_ANALOG_PIN_3_DEFAULT = USER_ANALOG_PIN_3; - #ifndef SPINDLE_OUTPUT_PIN # define SPINDLE_OUTPUT_PIN UNDEFINED_PIN #endif @@ -866,9 +865,9 @@ void make_pin_settings() { MacroButton3Pin = new PinSetting("Macro/3/Pin", MACRO_BUTTON_3_PIN_DEFAULT); // XXX Move to Dynamixel class - DynamixelTXDPin = new PinSetting("Dynamixel/TXD/Pin", DYNAMIXEL_TXD_DEFAULT); - DynamixelRXDPin = new PinSetting("Dynamixel/RXD/Pin", DYNAMIXEL_RXD_DEFAULT); - DynamixelRTSPin = new PinSetting("Dynamixel/RTS/Pin", DYNAMIXEL_RTS_DEFAULT); + DynamixelTXDPin = new PinSetting("Dynamixel/TXD/Pin", DYNAMIXEL_TXD_DEFAULT); + DynamixelRXDPin = new PinSetting("Dynamixel/RXD/Pin", DYNAMIXEL_RXD_DEFAULT); + DynamixelRTSPin = new PinSetting("Dynamixel/RTS/Pin", DYNAMIXEL_RTS_DEFAULT); // User pins: UserDigitalPin[0] = new PinSetting("UserDigital/0/Pin", USER_DIGITAL_PIN_0_DEFAULT); @@ -887,9 +886,9 @@ void make_pin_settings() { SpindleForwardPin = new PinSetting("Spindle/Forward/Pin", SPINDLE_FORWARD_PIN_DEFAULT); SpindleReversePin = new PinSetting("Spindle/Reverse/Pin", SPINDLE_REVERSE_PIN_DEFAULT); // XXX Move to VFD class - VFDRS485TXDPin = new PinSetting("Spindle/VFD/TxD/Pin", VFD_RS485_TXD_PIN_DEFAULT); // VFD_RS485_TXD_PIN - VFDRS485RXDPin = new PinSetting("Spindle/VFD/RxD/Pin", VFD_RS485_RXD_PIN_DEFAULT); // VFD_RS485_RXD_PIN - VFDRS485RTSPin = new PinSetting("Spindle/VFD/RTS/Pin", VFD_RS485_RTS_PIN_DEFAULT); // VFD_RS485_RTS_PIN + VFDRS485TXDPin = new PinSetting("Spindle/VFD/TxD/Pin", VFD_RS485_TXD_PIN_DEFAULT); // VFD_RS485_TXD_PIN + VFDRS485RXDPin = new PinSetting("Spindle/VFD/RxD/Pin", VFD_RS485_RXD_PIN_DEFAULT); // VFD_RS485_RXD_PIN + VFDRS485RTSPin = new PinSetting("Spindle/VFD/RTS/Pin", VFD_RS485_RTS_PIN_DEFAULT); // VFD_RS485_RTS_PIN // Axis: LimitPins[X_AXIS][0] = new PinSetting("X/Limit/Pin", X_LIMIT_PIN_DEFAULT); diff --git a/Grbl_Esp32/src/Pins/GPIOPinDetail.cpp b/Grbl_Esp32/src/Pins/GPIOPinDetail.cpp index 04605f0c..e7563e41 100644 --- a/Grbl_Esp32/src/Pins/GPIOPinDetail.cpp +++ b/Grbl_Esp32/src/Pins/GPIOPinDetail.cpp @@ -143,6 +143,12 @@ namespace Pins { pinModeValue |= OUTPUT; } + // TODO FIXME: For now, I added PU capabilities to 'value' as well. This *should* be removed once the + // code that uses #define's to decide this is gone. + if (value.has(PinAttributes::PullUp)) { + pinModeValue |= PULLUP; + } + // PU/PD should be specified by the user. Code has nothing to do with them: if (_attributes.has(PinAttributes::PullUp)) { pinModeValue |= PULLUP; @@ -161,12 +167,14 @@ namespace Pins { } void GPIOPinDetail::attachInterrupt(void (*callback)(void*), void* arg, int mode) { - Assert(_capabilities.has(PinCapabilities::ISR), "Pin has no ISR capability defined. Cannot bind ISR."); + Assert(_attributes.has(PinAttributes::ISR), + "Pin has no ISR attribute, which means 'setAttr' was not set, or the pin doesn't support ISR's. Cannot bind ISR."); ::attachInterruptArg(_index, callback, arg, mode); } void GPIOPinDetail::detachInterrupt() { - Assert(_capabilities.has(PinCapabilities::ISR), "Pin has no ISR capability defined. Cannot unbind ISR."); + Assert(_attributes.has(PinAttributes::ISR), + "Pin has no ISR attribute, which means 'setAttr' was not set, or the pin doesn't support ISR's. Cannot unbind ISR."); ::detachInterrupt(_index); } diff --git a/Grbl_Esp32/src/System.cpp b/Grbl_Esp32/src/System.cpp index fed1a0b2..f9695b3e 100644 --- a/Grbl_Esp32/src/System.cpp +++ b/Grbl_Esp32/src/System.cpp @@ -48,42 +48,42 @@ void system_ini() { // Renamed from system_init() due to conflict with esp32 fi // setup control inputs if (ControlSafetyDoorPin->get() != Pin::UNDEFINED) { - ControlSafetyDoorPin->get().setAttr(Pin::Attr::Input | Pin::Attr::PullUp); + ControlSafetyDoorPin->get().setAttr(Pin::Attr::Input | Pin::Attr::PullUp | Pin::Attr::ISR); ControlSafetyDoorPin->get().attachInterrupt(isr_control_inputs, CHANGE); } if (ControlResetPin->get() != Pin::UNDEFINED) { - ControlResetPin->get().setAttr(Pin::Attr::Input | Pin::Attr::PullUp); + ControlResetPin->get().setAttr(Pin::Attr::Input | Pin::Attr::PullUp | Pin::Attr::ISR); ControlResetPin->get().attachInterrupt(isr_control_inputs, CHANGE); } if (ControlFeedHoldPin->get() != Pin::UNDEFINED) { - ControlFeedHoldPin->get().setAttr(Pin::Attr::Input | Pin::Attr::PullUp); + ControlFeedHoldPin->get().setAttr(Pin::Attr::Input | Pin::Attr::PullUp | Pin::Attr::ISR); ControlFeedHoldPin->get().attachInterrupt(isr_control_inputs, CHANGE); } if (ControlCycleStartPin->get() != Pin::UNDEFINED) { - ControlCycleStartPin->get().setAttr(Pin::Attr::Input | Pin::Attr::PullUp); + ControlCycleStartPin->get().setAttr(Pin::Attr::Input | Pin::Attr::PullUp | Pin::Attr::ISR); ControlCycleStartPin->get().attachInterrupt(isr_control_inputs, CHANGE); } if (MacroButton0Pin->get() != Pin::UNDEFINED) { - MacroButton0Pin->get().setAttr(Pin::Attr::Input | Pin::Attr::PullUp); + MacroButton0Pin->get().setAttr(Pin::Attr::Input | Pin::Attr::PullUp | Pin::Attr::ISR); MacroButton0Pin->get().attachInterrupt(isr_control_inputs, CHANGE); } if (MacroButton1Pin->get() != Pin::UNDEFINED) { - MacroButton1Pin->get().setAttr(Pin::Attr::Input | Pin::Attr::PullUp); + MacroButton1Pin->get().setAttr(Pin::Attr::Input | Pin::Attr::PullUp | Pin::Attr::ISR); MacroButton1Pin->get().attachInterrupt(isr_control_inputs, CHANGE); } if (MacroButton2Pin->get() != Pin::UNDEFINED) { - MacroButton2Pin->get().setAttr(Pin::Attr::Input | Pin::Attr::PullUp); + MacroButton2Pin->get().setAttr(Pin::Attr::Input | Pin::Attr::PullUp | Pin::Attr::ISR); MacroButton2Pin->get().attachInterrupt(isr_control_inputs, CHANGE); } if (MacroButton3Pin->get() != Pin::UNDEFINED) { - MacroButton3Pin->get().setAttr(Pin::Attr::Input | Pin::Attr::PullUp); + MacroButton3Pin->get().setAttr(Pin::Attr::Input | Pin::Attr::PullUp | Pin::Attr::ISR); MacroButton3Pin->get().attachInterrupt(isr_control_inputs, CHANGE); }