mirror of
https://github.com/bdring/Grbl_Esp32.git
synced 2025-09-03 03:13:25 +02:00
Fixed a few bugs. Build-all runs now.
This commit is contained in:
@@ -15,7 +15,7 @@
|
|||||||
TODO
|
TODO
|
||||||
Make sure public/private/protected is cleaned up.
|
Make sure public/private/protected is cleaned up.
|
||||||
Only a few Unipolar axes have been setup in init()
|
Only a few Unipolar axes have been setup in init()
|
||||||
Get rid of Z_SERVO, just reply on ServoPins[Z_AXIS][0]->get()
|
Get rid of Z_SERVO, just reply on ServoPins[Z_AXIS][0]
|
||||||
Deal with custom machine ... machine_trinamic_setup();
|
Deal with custom machine ... machine_trinamic_setup();
|
||||||
Class is ready to deal with non SPI pins, but they have not been needed yet.
|
Class is ready to deal with non SPI pins, but they have not been needed yet.
|
||||||
It would be nice in the config message though
|
It would be nice in the config message though
|
||||||
@@ -473,7 +473,7 @@ uint8_t motors_set_homing_mode(uint8_t homing_mask, bool isHoming) {
|
|||||||
|
|
||||||
void motors_step(uint8_t step_mask, uint8_t dir_mask) {
|
void motors_step(uint8_t step_mask, uint8_t dir_mask) {
|
||||||
auto n_axis = number_axis->get();
|
auto n_axis = number_axis->get();
|
||||||
//grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "motors_DirectionPins[set_AXIS][0]->get()s:0x%02X", onMask);
|
//grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "motors_set_direction_pins:0x%02X", onMask);
|
||||||
|
|
||||||
// Set the direction pins, but optimize for the common
|
// Set the direction pins, but optimize for the common
|
||||||
// situation where the direction bits haven't changed.
|
// situation where the direction bits haven't changed.
|
||||||
|
@@ -25,7 +25,7 @@
|
|||||||
|
|
||||||
// Override default function and insert a short delay
|
// Override default function and insert a short delay
|
||||||
void TMC2130Stepper::switchCSpin(bool state) {
|
void TMC2130Stepper::switchCSpin(bool state) {
|
||||||
_pinCS.write(state);
|
digitalWrite(_pinCS, state);
|
||||||
i2s_out_delay();
|
i2s_out_delay();
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
@@ -64,7 +64,7 @@ bool Pin::parse(String str, Pins::PinDetail*& pinImplementation, int& pinNumber)
|
|||||||
} else if (prefix == "undef") {
|
} else if (prefix == "undef") {
|
||||||
pinImplementation = new Pins::VoidPinDetail(parser);
|
pinImplementation = new Pins::VoidPinDetail(parser);
|
||||||
}
|
}
|
||||||
#ifdef USE_I2S_OUT
|
#ifdef ESP_32
|
||||||
else if (prefix == "i2s") {
|
else if (prefix == "i2s") {
|
||||||
pinImplementation = new Pins::I2SPinDetail(uint8_t(pinNumber), parser);
|
pinImplementation = new Pins::I2SPinDetail(uint8_t(pinNumber), parser);
|
||||||
}
|
}
|
||||||
|
@@ -138,6 +138,47 @@ const char* DYNAMIXEL_RXD_DEFAULT = DYNAMIXEL_RXD;
|
|||||||
#endif
|
#endif
|
||||||
const char* DYNAMIXEL_RTS_DEFAULT = DYNAMIXEL_RTS;
|
const char* DYNAMIXEL_RTS_DEFAULT = DYNAMIXEL_RTS;
|
||||||
|
|
||||||
|
#ifndef USER_DIGITAL_PIN_0
|
||||||
|
# define USER_DIGITAL_PIN_0 UNDEFINED_PIN
|
||||||
|
#endif
|
||||||
|
const char* USER_DIGITAL_PIN_0_DEFAULT = USER_DIGITAL_PIN_0;
|
||||||
|
|
||||||
|
#ifndef USER_DIGITAL_PIN_1
|
||||||
|
# define USER_DIGITAL_PIN_1 UNDEFINED_PIN
|
||||||
|
#endif
|
||||||
|
const char* USER_DIGITAL_PIN_1_DEFAULT = USER_DIGITAL_PIN_1;
|
||||||
|
|
||||||
|
#ifndef USER_DIGITAL_PIN_2
|
||||||
|
# define USER_DIGITAL_PIN_2 UNDEFINED_PIN
|
||||||
|
#endif
|
||||||
|
const char* USER_DIGITAL_PIN_2_DEFAULT = USER_DIGITAL_PIN_2;
|
||||||
|
|
||||||
|
#ifndef USER_DIGITAL_PIN_3
|
||||||
|
# define USER_DIGITAL_PIN_3 UNDEFINED_PIN
|
||||||
|
#endif
|
||||||
|
const char* USER_DIGITAL_PIN_3_DEFAULT = USER_DIGITAL_PIN_3;
|
||||||
|
|
||||||
|
#ifndef USER_ANALOG_PIN_0
|
||||||
|
# define USER_ANALOG_PIN_0 UNDEFINED_PIN
|
||||||
|
#endif
|
||||||
|
const char* USER_ANALOG_PIN_0_DEFAULT = USER_ANALOG_PIN_0;
|
||||||
|
|
||||||
|
#ifndef USER_ANALOG_PIN_1
|
||||||
|
# define USER_ANALOG_PIN_1 UNDEFINED_PIN
|
||||||
|
#endif
|
||||||
|
const char* USER_ANALOG_PIN_1_DEFAULT = USER_ANALOG_PIN_1;
|
||||||
|
|
||||||
|
#ifndef USER_ANALOG_PIN_2
|
||||||
|
# define USER_ANALOG_PIN_2 UNDEFINED_PIN
|
||||||
|
#endif
|
||||||
|
const char* USER_ANALOG_PIN_2_DEFAULT = USER_ANALOG_PIN_2;
|
||||||
|
|
||||||
|
#ifndef USER_ANALOG_PIN_3
|
||||||
|
# define USER_ANALOG_PIN_3 UNDEFINED_PIN
|
||||||
|
#endif
|
||||||
|
const char* USER_ANALOG_PIN_3_DEFAULT = USER_ANALOG_PIN_3;
|
||||||
|
|
||||||
|
|
||||||
#ifndef SPINDLE_OUTPUT_PIN
|
#ifndef SPINDLE_OUTPUT_PIN
|
||||||
# define SPINDLE_OUTPUT_PIN "undef"
|
# define SPINDLE_OUTPUT_PIN "undef"
|
||||||
#endif
|
#endif
|
||||||
@@ -827,25 +868,25 @@ void make_pin_settings() {
|
|||||||
DynamixelRTSPin = new PinSetting("Pins/DynamixelRTS", DYNAMIXEL_RTS_DEFAULT);
|
DynamixelRTSPin = new PinSetting("Pins/DynamixelRTS", DYNAMIXEL_RTS_DEFAULT);
|
||||||
|
|
||||||
// User pins:
|
// User pins:
|
||||||
UserDigitalPin[0] = new PinSetting("Pins/UserDigital/0", USER_DIGITAL_PIN_0);
|
UserDigitalPin[0] = new PinSetting("Pins/UserDigital/0", USER_DIGITAL_PIN_0_DEFAULT);
|
||||||
UserAnalogPin[0] = new PinSetting("Pins/UserAnalog/0", USER_ANALOG_PIN_0);
|
UserAnalogPin[0] = new PinSetting("Pins/UserAnalog/0", USER_ANALOG_PIN_0_DEFAULT);
|
||||||
UserDigitalPin[1] = new PinSetting("Pins/UserDigital/1", USER_DIGITAL_PIN_1);
|
UserDigitalPin[1] = new PinSetting("Pins/UserDigital/1", USER_DIGITAL_PIN_1_DEFAULT);
|
||||||
UserAnalogPin[1] = new PinSetting("Pins/UserAnalog/1", USER_ANALOG_PIN_1);
|
UserAnalogPin[1] = new PinSetting("Pins/UserAnalog/1", USER_ANALOG_PIN_1_DEFAULT);
|
||||||
UserDigitalPin[2] = new PinSetting("Pins/UserDigital/2", USER_DIGITAL_PIN_2);
|
UserDigitalPin[2] = new PinSetting("Pins/UserDigital/2", USER_DIGITAL_PIN_2_DEFAULT);
|
||||||
UserAnalogPin[2] = new PinSetting("Pins/UserAnalog/2", USER_ANALOG_PIN_2);
|
UserAnalogPin[2] = new PinSetting("Pins/UserAnalog/2", USER_ANALOG_PIN_2_DEFAULT);
|
||||||
UserDigitalPin[3] = new PinSetting("Pins/UserDigital/3", USER_DIGITAL_PIN_3);
|
UserDigitalPin[3] = new PinSetting("Pins/UserDigital/3", USER_DIGITAL_PIN_3_DEFAULT);
|
||||||
UserAnalogPin[3] = new PinSetting("Pins/UserAnalog/3", USER_ANALOG_PIN_3);
|
UserAnalogPin[3] = new PinSetting("Pins/UserAnalog/3", USER_ANALOG_PIN_3_DEFAULT);
|
||||||
|
|
||||||
// Spindes:
|
// Spindes:
|
||||||
|
|
||||||
SpindleOutputPin = new PinSetting("Pins/Spindle/Output", SPINDLE_OUTPUT_PIN);
|
SpindleOutputPin = new PinSetting("Pins/Spindle/Output", SPINDLE_OUTPUT_PIN_DEFAULT);
|
||||||
SpindleEnablePin = new PinSetting("Pins/Spindle/Enable", SPINDLE_ENABLE_PIN);
|
SpindleEnablePin = new PinSetting("Pins/Spindle/Enable", SPINDLE_ENABLE_PIN_DEFAULT);
|
||||||
SpindleDirectionPin = new PinSetting("Pins/Spindle/Direction", SPINDLE_DIRECTION_PIN);
|
SpindleDirectionPin = new PinSetting("Pins/Spindle/Direction", SPINDLE_DIRECTION_PIN_DEFAULT);
|
||||||
SpindleForwardPin = new PinSetting("Pins/Spindle/Forward", SPINDLE_FORWARD_PIN);
|
SpindleForwardPin = new PinSetting("Pins/Spindle/Forward", SPINDLE_FORWARD_PIN_DEFAULT);
|
||||||
SpindleReversePin = new PinSetting("Pins/Spindle/Reverse", SPINDLE_REVERSE_PIN);
|
SpindleReversePin = new PinSetting("Pins/Spindle/Reverse", SPINDLE_REVERSE_PIN_DEFAULT);
|
||||||
VFDRS485TXDPin = new PinSetting("Pins/Spindle/RS485TXD", VFD_RS485_TXD_PIN); // VFD_RS485_TXD_PIN
|
VFDRS485TXDPin = new PinSetting("Pins/Spindle/RS485TXD", VFD_RS485_TXD_PIN_DEFAULT); // VFD_RS485_TXD_PIN
|
||||||
VFDRS485RXDPin = new PinSetting("Pins/Spindle/RS485RXD", VFD_RS485_RXD_PIN); // VFD_RS485_RXD_PIN
|
VFDRS485RXDPin = new PinSetting("Pins/Spindle/RS485RXD", VFD_RS485_RXD_PIN_DEFAULT); // VFD_RS485_RXD_PIN
|
||||||
VFDRS485RTSPin = new PinSetting("Pins/Spindle/RS485RTS", VFD_RS485_RTS_PIN); // VFD_RS485_RTS_PIN
|
VFDRS485RTSPin = new PinSetting("Pins/Spindle/RS485RTS", VFD_RS485_RTS_PIN_DEFAULT); // VFD_RS485_RTS_PIN
|
||||||
|
|
||||||
// Axis:
|
// Axis:
|
||||||
LimitPins[X_AXIS][0] = new PinSetting("Pins/X/Limit", X_LIMIT_PIN_DEFAULT);
|
LimitPins[X_AXIS][0] = new PinSetting("Pins/X/Limit", X_LIMIT_PIN_DEFAULT);
|
||||||
|
@@ -13,13 +13,15 @@ namespace Pins {
|
|||||||
switch (index) {
|
switch (index) {
|
||||||
case 0: // Outputs PWM signal at boot
|
case 0: // Outputs PWM signal at boot
|
||||||
return PinCapabilities::Native | PinCapabilities::Input | PinCapabilities::Output | PinCapabilities::PullUp |
|
return PinCapabilities::Native | PinCapabilities::Input | PinCapabilities::Output | PinCapabilities::PullUp |
|
||||||
PinCapabilities::PullDown | PinCapabilities::ADC | PinCapabilities::PWM | PinCapabilities::ISR;
|
PinCapabilities::PullDown | PinCapabilities::ADC | PinCapabilities::PWM | PinCapabilities::ISR |
|
||||||
|
PinCapabilities::UART;
|
||||||
|
|
||||||
case 1: // TX pin of Serial0. Note that Serial0 also runs through the Pins framework!
|
case 1: // TX pin of Serial0. Note that Serial0 also runs through the Pins framework!
|
||||||
return PinCapabilities::Native | PinCapabilities::Output | PinCapabilities::Input;
|
return PinCapabilities::Native | PinCapabilities::Output | PinCapabilities::Input | PinCapabilities::UART;
|
||||||
|
|
||||||
case 3: // RX pin of Serial0. Note that Serial0 also runs through the Pins framework!
|
case 3: // RX pin of Serial0. Note that Serial0 also runs through the Pins framework!
|
||||||
return PinCapabilities::Native | PinCapabilities::Output | PinCapabilities::Input | PinCapabilities::ISR;
|
return PinCapabilities::Native | PinCapabilities::Output | PinCapabilities::Input | PinCapabilities::ISR |
|
||||||
|
PinCapabilities::UART;
|
||||||
|
|
||||||
case 5:
|
case 5:
|
||||||
case 16:
|
case 16:
|
||||||
@@ -31,7 +33,7 @@ namespace Pins {
|
|||||||
case 23:
|
case 23:
|
||||||
case 29:
|
case 29:
|
||||||
return PinCapabilities::Native | PinCapabilities::Input | PinCapabilities::Output | PinCapabilities::PullUp |
|
return PinCapabilities::Native | PinCapabilities::Input | PinCapabilities::Output | PinCapabilities::PullUp |
|
||||||
PinCapabilities::PullDown | PinCapabilities::PWM | PinCapabilities::ISR;
|
PinCapabilities::PullDown | PinCapabilities::PWM | PinCapabilities::ISR | PinCapabilities::UART;
|
||||||
|
|
||||||
case 2: // Normal pins
|
case 2: // Normal pins
|
||||||
case 4:
|
case 4:
|
||||||
@@ -43,12 +45,14 @@ namespace Pins {
|
|||||||
case 32:
|
case 32:
|
||||||
case 33:
|
case 33:
|
||||||
return PinCapabilities::Native | PinCapabilities::Input | PinCapabilities::Output | PinCapabilities::PullUp |
|
return PinCapabilities::Native | PinCapabilities::Input | PinCapabilities::Output | PinCapabilities::PullUp |
|
||||||
PinCapabilities::PullDown | PinCapabilities::ADC | PinCapabilities::PWM | PinCapabilities::ISR;
|
PinCapabilities::PullDown | PinCapabilities::ADC | PinCapabilities::PWM | PinCapabilities::ISR |
|
||||||
|
PinCapabilities::UART;
|
||||||
|
|
||||||
case 25:
|
case 25:
|
||||||
case 26:
|
case 26:
|
||||||
return PinCapabilities::Native | PinCapabilities::Input | PinCapabilities::Output | PinCapabilities::PullUp |
|
return PinCapabilities::Native | PinCapabilities::Input | PinCapabilities::Output | PinCapabilities::PullUp |
|
||||||
PinCapabilities::PullDown | PinCapabilities::ADC | PinCapabilities::DAC | PinCapabilities::PWM | PinCapabilities::ISR;
|
PinCapabilities::PullDown | PinCapabilities::ADC | PinCapabilities::DAC | PinCapabilities::PWM |
|
||||||
|
PinCapabilities::ISR | PinCapabilities::UART;
|
||||||
|
|
||||||
case 6: // SPI flash integrated
|
case 6: // SPI flash integrated
|
||||||
case 7:
|
case 7:
|
||||||
@@ -57,13 +61,13 @@ namespace Pins {
|
|||||||
case 10:
|
case 10:
|
||||||
case 11:
|
case 11:
|
||||||
return PinCapabilities::Native | PinCapabilities::Input | PinCapabilities::Output | PinCapabilities::PWM |
|
return PinCapabilities::Native | PinCapabilities::Input | PinCapabilities::Output | PinCapabilities::PWM |
|
||||||
PinCapabilities::ISR;
|
PinCapabilities::ISR | PinCapabilities::UART;
|
||||||
|
|
||||||
case 34: // Input only pins
|
case 34: // Input only pins
|
||||||
case 35:
|
case 35:
|
||||||
case 36:
|
case 36:
|
||||||
case 39:
|
case 39:
|
||||||
return PinCapabilities::Native | PinCapabilities::Input | PinCapabilities::ADC | PinCapabilities::ISR;
|
return PinCapabilities::Native | PinCapabilities::Input | PinCapabilities::ADC | PinCapabilities::ISR | PinCapabilities::UART;
|
||||||
break;
|
break;
|
||||||
|
|
||||||
default: // Not mapped to actual GPIO pins
|
default: // Not mapped to actual GPIO pins
|
||||||
|
@@ -7,7 +7,7 @@ namespace Pins {
|
|||||||
uint8_t _index;
|
uint8_t _index;
|
||||||
PinCapabilities _capabilities;
|
PinCapabilities _capabilities;
|
||||||
PinAttributes _attributes;
|
PinAttributes _attributes;
|
||||||
int _readWriteMask;
|
int _readWriteMask;
|
||||||
|
|
||||||
static PinCapabilities GetDefaultCapabilities(uint8_t index);
|
static PinCapabilities GetDefaultCapabilities(uint8_t index);
|
||||||
|
|
||||||
|
@@ -2,11 +2,14 @@
|
|||||||
# include "I2SPinDetail.h"
|
# include "I2SPinDetail.h"
|
||||||
|
|
||||||
# include "../I2SOut.h"
|
# include "../I2SOut.h"
|
||||||
|
# include "../Assert.h"
|
||||||
|
|
||||||
# ifdef USE_I2S_OUT
|
extern "C" void __digitalWrite(uint8_t pin, uint8_t val);
|
||||||
|
|
||||||
namespace Pins {
|
namespace Pins {
|
||||||
I2SPinDetail::I2SPinDetail(uint8_t index, const PinOptionsParser& options) : _index(index) {
|
I2SPinDetail::I2SPinDetail(uint8_t index, const PinOptionsParser& options) :
|
||||||
|
_index(index), _capabilities(PinCapabilities::Output | PinCapabilities::I2S), _attributes(Pins::PinAttributes::Undefined),
|
||||||
|
_readWriteMask(0) {
|
||||||
// User defined pin capabilities
|
// User defined pin capabilities
|
||||||
for (auto opt : options) {
|
for (auto opt : options) {
|
||||||
if (opt.is("pu")) {
|
if (opt.is("pu")) {
|
||||||
@@ -53,8 +56,7 @@ namespace Pins {
|
|||||||
// just check for conflicts above...
|
// just check for conflicts above...
|
||||||
}
|
}
|
||||||
|
|
||||||
String I2SPinDetail::toString() { return String("I2S_") + int(_index); }
|
String I2SPinDetail::toString() const { return String("I2S_") + int(_index); }
|
||||||
}
|
}
|
||||||
|
|
||||||
# endif
|
|
||||||
#endif
|
#endif
|
||||||
|
@@ -1,15 +1,14 @@
|
|||||||
#pragma once
|
#pragma once
|
||||||
#ifdef ESP32
|
#ifdef ESP32
|
||||||
|
|
||||||
#include "PinDetail.h"
|
# include "PinDetail.h"
|
||||||
|
|
||||||
#ifdef USE_I2S_OUT
|
|
||||||
|
|
||||||
namespace Pins {
|
namespace Pins {
|
||||||
class I2SPinDetail : public PinDetail {
|
class I2SPinDetail : public PinDetail {
|
||||||
uint8_t _index;
|
uint8_t _index;
|
||||||
PinCapabilities _capabilities;
|
PinCapabilities _capabilities;
|
||||||
PinAttributes _attributes;
|
PinAttributes _attributes;
|
||||||
|
int _readWriteMask;
|
||||||
|
|
||||||
public:
|
public:
|
||||||
I2SPinDetail(uint8_t index, const PinOptionsParser& options);
|
I2SPinDetail(uint8_t index, const PinOptionsParser& options);
|
||||||
@@ -21,11 +20,10 @@ namespace Pins {
|
|||||||
int read() override;
|
int read() override;
|
||||||
void setAttr(PinAttributes value) override;
|
void setAttr(PinAttributes value) override;
|
||||||
|
|
||||||
String toString() override;
|
String toString() const override;
|
||||||
|
|
||||||
~I2SPinDetail() override {}
|
~I2SPinDetail() override {}
|
||||||
};
|
};
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
#endif
|
|
||||||
|
@@ -104,7 +104,7 @@ namespace Spindles {
|
|||||||
if (_gpio_ok) {
|
if (_gpio_ok) {
|
||||||
auto outputNative = _output_pin.getNative(Pin::Capabilities::DAC);
|
auto outputNative = _output_pin.getNative(Pin::Capabilities::DAC);
|
||||||
|
|
||||||
dacWrite(outputNative, (uint8_t)duty);
|
dacWrite(outputNative, static_cast<uint8_t>(duty));
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@@ -51,42 +51,42 @@ void system_ini() { // Renamed from system_init() due to conflict with esp32 fi
|
|||||||
ControlSafetyDoorPin->get().setAttr(Pin::Attr::Input | Pin::Attr::PullUp);
|
ControlSafetyDoorPin->get().setAttr(Pin::Attr::Input | Pin::Attr::PullUp);
|
||||||
ControlSafetyDoorPin->get().attachInterrupt(isr_control_inputs, CHANGE);
|
ControlSafetyDoorPin->get().attachInterrupt(isr_control_inputs, CHANGE);
|
||||||
}
|
}
|
||||||
#ifdef CONTROL_SAFETY_DOOR_PIN
|
|
||||||
pinMode(CONTROL_SAFETY_DOOR_PIN, INPUT_PULLUP);
|
if (ControlResetPin->get() != Pin::UNDEFINED) {
|
||||||
attachInterrupt(digitalPinToInterrupt(CONTROL_SAFETY_DOOR_PIN), isr_control_inputs, CHANGE);
|
ControlResetPin->get().setAttr(Pin::Attr::Input | Pin::Attr::PullUp);
|
||||||
#endif
|
ControlResetPin->get().attachInterrupt(isr_control_inputs, CHANGE);
|
||||||
#ifdef CONTROL_RESET_PIN
|
}
|
||||||
pinMode(CONTROL_RESET_PIN, INPUT_PULLUP);
|
|
||||||
attachInterrupt(digitalPinToInterrupt(CONTROL_RESET_PIN), isr_control_inputs, CHANGE);
|
if (ControlFeedHoldPin->get() != Pin::UNDEFINED) {
|
||||||
#endif
|
ControlFeedHoldPin->get().setAttr(Pin::Attr::Input | Pin::Attr::PullUp);
|
||||||
#ifdef CONTROL_FEED_HOLD_PIN
|
ControlFeedHoldPin->get().attachInterrupt(isr_control_inputs, CHANGE);
|
||||||
pinMode(CONTROL_FEED_HOLD_PIN, INPUT_PULLUP);
|
}
|
||||||
attachInterrupt(digitalPinToInterrupt(CONTROL_FEED_HOLD_PIN), isr_control_inputs, CHANGE);
|
|
||||||
#endif
|
if (ControlCycleStartPin->get() != Pin::UNDEFINED) {
|
||||||
#ifdef CONTROL_CYCLE_START_PIN
|
ControlCycleStartPin->get().setAttr(Pin::Attr::Input | Pin::Attr::PullUp);
|
||||||
pinMode(CONTROL_CYCLE_START_PIN, INPUT_PULLUP);
|
ControlCycleStartPin->get().attachInterrupt(isr_control_inputs, CHANGE);
|
||||||
attachInterrupt(digitalPinToInterrupt(CONTROL_CYCLE_START_PIN), isr_control_inputs, CHANGE);
|
}
|
||||||
#endif
|
|
||||||
#ifdef MACRO_BUTTON_0_PIN
|
if (MacroButton0Pin->get() != Pin::UNDEFINED) {
|
||||||
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Macro Pin 0");
|
MacroButton0Pin->get().setAttr(Pin::Attr::Input | Pin::Attr::PullUp);
|
||||||
pinMode(MACRO_BUTTON_0_PIN, INPUT_PULLUP);
|
MacroButton0Pin->get().attachInterrupt(isr_control_inputs, CHANGE);
|
||||||
attachInterrupt(digitalPinToInterrupt(MACRO_BUTTON_0_PIN), isr_control_inputs, CHANGE);
|
}
|
||||||
#endif
|
|
||||||
#ifdef MACRO_BUTTON_1_PIN
|
if (MacroButton1Pin->get() != Pin::UNDEFINED) {
|
||||||
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Macro Pin 1");
|
MacroButton1Pin->get().setAttr(Pin::Attr::Input | Pin::Attr::PullUp);
|
||||||
pinMode(MACRO_BUTTON_1_PIN, INPUT_PULLUP);
|
MacroButton1Pin->get().attachInterrupt(isr_control_inputs, CHANGE);
|
||||||
attachInterrupt(digitalPinToInterrupt(MACRO_BUTTON_1_PIN), isr_control_inputs, CHANGE);
|
}
|
||||||
#endif
|
|
||||||
#ifdef MACRO_BUTTON_2_PIN
|
if (MacroButton2Pin->get() != Pin::UNDEFINED) {
|
||||||
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Macro Pin 2");
|
MacroButton2Pin->get().setAttr(Pin::Attr::Input | Pin::Attr::PullUp);
|
||||||
pinMode(MACRO_BUTTON_2_PIN, INPUT_PULLUP);
|
MacroButton2Pin->get().attachInterrupt(isr_control_inputs, CHANGE);
|
||||||
attachInterrupt(digitalPinToInterrupt(MACRO_BUTTON_2_PIN), isr_control_inputs, CHANGE);
|
}
|
||||||
#endif
|
|
||||||
#ifdef MACRO_BUTTON_3_PIN
|
if (MacroButton3Pin->get() != Pin::UNDEFINED) {
|
||||||
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Macro Pin 3");
|
MacroButton3Pin->get().setAttr(Pin::Attr::Input | Pin::Attr::PullUp);
|
||||||
pinMode(MACRO_BUTTON_3_PIN, INPUT_PULLUP);
|
MacroButton3Pin->get().attachInterrupt(isr_control_inputs, CHANGE);
|
||||||
attachInterrupt(digitalPinToInterrupt(MACRO_BUTTON_3_PIN), isr_control_inputs, CHANGE);
|
}
|
||||||
#endif
|
|
||||||
#ifdef ENABLE_CONTROL_SW_DEBOUNCE
|
#ifdef ENABLE_CONTROL_SW_DEBOUNCE
|
||||||
// setup task used for debouncing
|
// setup task used for debouncing
|
||||||
control_sw_queue = xQueueCreate(10, sizeof(int));
|
control_sw_queue = xQueueCreate(10, sizeof(int));
|
||||||
|
Reference in New Issue
Block a user