mirror of
https://github.com/bdring/Grbl_Esp32.git
synced 2025-08-30 17:49:56 +02:00
Exclusive pins
This commit is contained in:
@@ -27,14 +27,14 @@
|
||||
|
||||
#ifdef ESP32
|
||||
# include "Grbl.h" // serial output
|
||||
# define pin_error(...) info_serial(__VA_ARGS__)
|
||||
# define pin_error(...) error_serial(__VA_ARGS__)
|
||||
#else
|
||||
# define pin_error(...) \
|
||||
{}
|
||||
#endif
|
||||
|
||||
#if defined PIN_DEBUG
|
||||
# define pin_debug(...) pin_error(__VA_ARGS__)
|
||||
# define pin_debug(...) debug_serial(__VA_ARGS__)
|
||||
#else
|
||||
# define pin_debug(...) \
|
||||
{}
|
||||
@@ -129,7 +129,7 @@ bool Pin::parse(StringRange tmp, Pins::PinDetail*& pinImplementation) {
|
||||
pinImplementation = new Pins::VoidPinDetail();
|
||||
return true;
|
||||
}
|
||||
pin_error("Unknown prefix: \"%s\"\r\n", prefix.c_str());
|
||||
pin_error("ERR: Unknown prefix: \"%s\"\r\n", prefix.c_str());
|
||||
return false;
|
||||
}
|
||||
|
||||
@@ -148,7 +148,7 @@ Pin Pin::create(const StringRange& str) {
|
||||
|
||||
return Pin(pinImplementation);
|
||||
} catch (const AssertionFailed& ex) { // We shouldn't get here under normal circumstances.
|
||||
pin_error("Setting up pin [%s] failed. Details: %s\r\n", str.str().c_str(), ex.what());
|
||||
pin_error("ERR: Setting up pin [%s] failed. Details: %s", str.str().c_str(), ex.what());
|
||||
(void)ex; // Get rid of compiler warning
|
||||
|
||||
return Pin(new Pins::ErrorPinDetail(str.str()));
|
||||
|
@@ -27,6 +27,8 @@ extern "C" int __digitalRead(uint8_t pin);
|
||||
extern "C" void __digitalWrite(uint8_t pin, uint8_t val);
|
||||
|
||||
namespace Pins {
|
||||
std::vector<bool> GPIOPinDetail::_claimed(nGPIOPins, false);
|
||||
|
||||
PinCapabilities GPIOPinDetail::GetDefaultCapabilities(uint8_t index) {
|
||||
// See https://randomnerdtutorials.com/esp32-pinout-reference-gpios/ for an overview:
|
||||
switch (index) {
|
||||
@@ -103,6 +105,7 @@ namespace Pins {
|
||||
// WILL get into trouble.
|
||||
|
||||
Assert(_capabilities != PinCapabilities::None, "Bad GPIO number");
|
||||
Assert(!_claimed[index], "Pin is already used.");
|
||||
|
||||
// User defined pin capabilities
|
||||
for (auto opt : options) {
|
||||
@@ -118,6 +121,7 @@ namespace Pins {
|
||||
Assert(false, "Bad GPIO option passed to pin %d: %s", int(index), opt());
|
||||
}
|
||||
}
|
||||
_claimed[index] = true;
|
||||
|
||||
// readWriteMask is xor'ed with the value to invert it if active low
|
||||
_readWriteMask = _attributes.has(PinAttributes::ActiveLow);
|
||||
|
@@ -28,6 +28,9 @@ namespace Pins {
|
||||
|
||||
static PinCapabilities GetDefaultCapabilities(uint8_t index);
|
||||
|
||||
static const int nGPIOPins = 40;
|
||||
static std::vector<bool> _claimed;
|
||||
|
||||
public:
|
||||
GPIOPinDetail(uint8_t index, PinOptionsParser options);
|
||||
|
||||
@@ -45,7 +48,7 @@ namespace Pins {
|
||||
|
||||
String toString() override;
|
||||
|
||||
~GPIOPinDetail() override {}
|
||||
~GPIOPinDetail() override { _claimed[_index] = false; }
|
||||
};
|
||||
|
||||
}
|
||||
|
@@ -25,9 +25,12 @@
|
||||
extern "C" void __digitalWrite(uint8_t pin, uint8_t val);
|
||||
|
||||
namespace Pins {
|
||||
std::vector<bool> I2SOPinDetail::_claimed(nI2SOPins, false);
|
||||
|
||||
I2SOPinDetail::I2SOPinDetail(uint8_t index, const PinOptionsParser& options) :
|
||||
PinDetail(index), _capabilities(PinCapabilities::Output | PinCapabilities::I2S), _attributes(Pins::PinAttributes::Undefined),
|
||||
_readWriteMask(0) {
|
||||
Assert(!_claimed[index], "Pin is already used.");
|
||||
// User defined pin capabilities
|
||||
for (auto opt : options) {
|
||||
if (opt.is("low")) {
|
||||
@@ -38,6 +41,7 @@ namespace Pins {
|
||||
Assert(false, "Unsupported I2SO option '%s'", opt());
|
||||
}
|
||||
}
|
||||
_claimed[index] = true;
|
||||
|
||||
// readWriteMask is xor'ed with the value to invert it if active low
|
||||
_readWriteMask = _attributes.has(PinAttributes::ActiveLow);
|
||||
|
@@ -27,6 +27,9 @@ namespace Pins {
|
||||
PinAttributes _attributes;
|
||||
int _readWriteMask;
|
||||
|
||||
static const int nI2SOPins = 32;
|
||||
static std::vector<bool> _claimed;
|
||||
|
||||
public:
|
||||
I2SOPinDetail(uint8_t index, const PinOptionsParser& options);
|
||||
|
||||
@@ -40,7 +43,7 @@ namespace Pins {
|
||||
|
||||
String toString() override;
|
||||
|
||||
~I2SOPinDetail() override {}
|
||||
~I2SOPinDetail() override { _claimed[_index] = false; }
|
||||
};
|
||||
}
|
||||
|
||||
|
@@ -25,6 +25,7 @@
|
||||
#include <WString.h>
|
||||
#include <cstdint>
|
||||
#include <cstring>
|
||||
#include <vector>
|
||||
|
||||
namespace Pins {
|
||||
|
||||
|
Reference in New Issue
Block a user