mirror of
https://github.com/bdring/Grbl_Esp32.git
synced 2025-09-03 03:13:25 +02:00
Various Pin fixes
Undefined pin name is the empty string Fixed PinOptions iterator so option parsing works Added $P and $PC commands to show pins Renamed pin settings to conform to the plan Pin options should set attributes, not capabilities. Capabilities are immutable properties of a hardware pin, while attributes tell how we want to use it. Active state (high or low) is a (usage) attribute, not a capability Check GPIO pin number Added throw to GPIO constructor so errors can be reported ... but That is not the right way; we need a separate check function that can be used both by the constructor and the settings checker, because the constructor may have side effects that should not happen during checking.
This commit is contained in:
@@ -59,12 +59,6 @@ Some features should not be changed. See notes below.
|
||||
|
||||
#define USE_RMT_STEPS
|
||||
|
||||
// Define some 'pin' things that will error if used in the program. The *only* thing that should
|
||||
// use pins is the PinSettingsDefinitions.cpp file
|
||||
#ifndef UNDEFINED_PIN
|
||||
# define UNDEFINED_PIN static_assert(false, "Don't use me!");
|
||||
#endif
|
||||
|
||||
// Include the file that loads the machine-specific config file.
|
||||
// machine.h must be edited to choose the desired file.
|
||||
#include "Machine.h"
|
||||
|
@@ -79,4 +79,5 @@ std::map<Error, const char*> ErrorCodes = {
|
||||
{ Error::NvsSetFailed, "Failed to store setting" },
|
||||
{ Error::NvsGetStatsFailed, "Failed to get setting status" },
|
||||
{ Error::AuthenticationFailed, "Authentication failed!" },
|
||||
{ Error::BadPinSpecification, "Bad Pin Specification" },
|
||||
};
|
||||
|
@@ -83,6 +83,7 @@ enum class Error : uint8_t {
|
||||
NvsGetStatsFailed = 101,
|
||||
AuthenticationFailed = 110,
|
||||
Eol = 111,
|
||||
BadPinSpecification = 150,
|
||||
};
|
||||
|
||||
extern std::map<Error, const char*> ErrorCodes;
|
||||
|
@@ -25,6 +25,8 @@
|
||||
// #define false 0
|
||||
// #define true 1
|
||||
|
||||
#define UNDEFINED_PIN ""
|
||||
|
||||
const double SOME_LARGE_VALUE = 1.0E+38;
|
||||
|
||||
// Axis array index values. Must start with 0 and be continuous.
|
||||
|
@@ -1,4 +1,5 @@
|
||||
#include "Pin.h"
|
||||
#include "Grbl.h"
|
||||
|
||||
// Pins:
|
||||
#include "Pins/PinOptionsParser.h"
|
||||
@@ -6,13 +7,18 @@
|
||||
#include "Pins/GPIOPinDetail.h"
|
||||
#include "Pins/I2SPinDetail.h"
|
||||
#ifdef PIN_DEBUG
|
||||
#include "Pins/DebugPinDetail.h"
|
||||
# include "Pins/DebugPinDetail.h"
|
||||
#endif
|
||||
|
||||
bool Pin::parse(String str, Pins::PinDetail*& pinImplementation, int& pinNumber) {
|
||||
// Initialize pinImplementation first! Callers might want to delete it, and we don't want a random pointer.
|
||||
pinImplementation = nullptr;
|
||||
|
||||
if (str == "") {
|
||||
pinImplementation = new Pins::VoidPinDetail();
|
||||
return pinImplementation;
|
||||
}
|
||||
|
||||
// Parse the definition: [GPIO].[pinNumber]:[attributes]
|
||||
auto nameStart = str.begin();
|
||||
auto idx = nameStart;
|
||||
@@ -25,7 +31,7 @@ bool Pin::parse(String str, Pins::PinDetail*& pinImplementation, int& pinNumber)
|
||||
++idx;
|
||||
}
|
||||
|
||||
if (prefix != "undef") {
|
||||
if (prefix != "") {
|
||||
if (idx == str.end()) {
|
||||
// Incorrect pin definition.
|
||||
return false;
|
||||
@@ -57,26 +63,28 @@ bool Pin::parse(String str, Pins::PinDetail*& pinImplementation, int& pinNumber)
|
||||
// into 'nul' tokens. We then pass the number of 'nul' tokens, and the first char*
|
||||
// which is pretty easy to parse.
|
||||
|
||||
// Build this pin:
|
||||
|
||||
// Build an options parser:
|
||||
Pins::PinOptionsParser parser(options.begin(), options.end());
|
||||
|
||||
if (prefix == "gpio") {
|
||||
pinImplementation = new Pins::GPIOPinDetail(uint8_t(pinNumber), parser);
|
||||
} else if (prefix == "undef") {
|
||||
pinImplementation = new Pins::VoidPinDetail(parser);
|
||||
}
|
||||
// Build this pin:
|
||||
|
||||
try {
|
||||
if (prefix == "gpio") {
|
||||
pinImplementation = new Pins::GPIOPinDetail(uint8_t(pinNumber), parser);
|
||||
} else if (prefix == "i2s") {
|
||||
#ifdef ESP_32
|
||||
else if (prefix == "i2s") {
|
||||
pinImplementation = new Pins::I2SPinDetail(uint8_t(pinNumber), parser);
|
||||
}
|
||||
pinImplementation = new Pins::I2SPinDetail(uint8_t(pinNumber), parser);
|
||||
#endif
|
||||
|
||||
} else {
|
||||
#ifdef PIN_DEBUG
|
||||
pinImplementation = new Pins::DebugPinDetail(pinImplementation);
|
||||
pinImplementation = new Pins::DebugPinDetail(pinImplementation);
|
||||
#endif
|
||||
|
||||
}
|
||||
} catch (const std::exception& e) {
|
||||
grbl_sendf(CLIENT_SERIAL, "%s\r\n", e.what());
|
||||
pinImplementation = new Pins::VoidPinDetail();
|
||||
return false;
|
||||
}
|
||||
return pinImplementation;
|
||||
}
|
||||
|
||||
|
File diff suppressed because it is too large
Load Diff
@@ -1,4 +1,5 @@
|
||||
#include <Arduino.h>
|
||||
#include <stdexcept>
|
||||
|
||||
#include "GPIOPinDetail.h"
|
||||
#include "../Assert.h"
|
||||
@@ -71,27 +72,34 @@ namespace Pins {
|
||||
break;
|
||||
|
||||
default: // Not mapped to actual GPIO pins
|
||||
return PinCapabilities::Native;
|
||||
return PinCapabilities::None;
|
||||
}
|
||||
}
|
||||
|
||||
GPIOPinDetail::GPIOPinDetail(uint8_t index, PinOptionsParser options) :
|
||||
_index(index), _capabilities(GetDefaultCapabilities(index)), _attributes(Pins::PinAttributes::Undefined), _readWriteMask(0) {
|
||||
if (_capabilities == PinCapabilities::None) {
|
||||
throw std::runtime_error("Bad GPIO number");
|
||||
}
|
||||
// User defined pin capabilities
|
||||
for (auto opt : options) {
|
||||
if (opt.is("pu")) {
|
||||
_capabilities = _capabilities | PinCapabilities::PullUp;
|
||||
_attributes = _attributes | PinAttributes::PullUp;
|
||||
} else if (opt.is("pd")) {
|
||||
_capabilities = _capabilities | PinCapabilities::PullDown;
|
||||
_attributes = _attributes | PinAttributes::PullDown;
|
||||
} else if (opt.is("low")) {
|
||||
_capabilities = _capabilities | PinCapabilities::ActiveLow;
|
||||
_attributes = _attributes | PinAttributes::ActiveLow;
|
||||
} else if (opt.is("high")) {
|
||||
// Default: Active HIGH.
|
||||
} else {
|
||||
throw std::runtime_error("Bad GPIO option");
|
||||
}
|
||||
}
|
||||
|
||||
// XXX This should not be done when the constructor is called for
|
||||
// validating a setting.
|
||||
// Update the R/W mask for ActiveLow setting
|
||||
if (_capabilities.has(PinCapabilities::ActiveLow)) {
|
||||
if (_attributes.has(PinAttributes::ActiveLow)) {
|
||||
__pinMode(_index, OUTPUT);
|
||||
__digitalWrite(_index, HIGH);
|
||||
_readWriteMask = HIGH;
|
||||
|
@@ -13,18 +13,18 @@ namespace Pins {
|
||||
// User defined pin capabilities
|
||||
for (auto opt : options) {
|
||||
if (opt.is("pu")) {
|
||||
_capabilities = _capabilities | PinCapabilities::PullUp;
|
||||
_attributes = _attributes | PinAttributes::PullUp;
|
||||
} else if (opt.is("pd")) {
|
||||
_capabilities = _capabilities | PinCapabilities::PullDown;
|
||||
_attributes = _attributes | PinAttributes::PullDown;
|
||||
} else if (opt.is("low")) {
|
||||
_capabilities = _capabilities | PinCapabilities::ActiveLow;
|
||||
_attributes = _attributes | PinAttributes::ActiveLow;
|
||||
} else if (opt.is("high")) {
|
||||
// Default: Active HIGH.
|
||||
}
|
||||
}
|
||||
|
||||
// Update the R/W mask for ActiveLow setting
|
||||
if (_capabilities.ActiveLow) {
|
||||
if (_attributes.ActiveLow) {
|
||||
__digitalWrite(_index, HIGH);
|
||||
_readWriteMask = 1;
|
||||
} else {
|
||||
|
@@ -16,6 +16,7 @@ namespace Pins {
|
||||
PinAttributes PinAttributes::PullDown(1 << (__LINE__ - START_LINE));
|
||||
PinAttributes PinAttributes::ISR(1 << (__LINE__ - START_LINE)); // ^ These are capabilities mapped
|
||||
const int capabilityMask = (1 << (__LINE__ - START_LINE)) - 1; // -------- Mask capabilities till here
|
||||
PinAttributes PinAttributes::ActiveLow(1 << (__LINE__ - START_LINE));
|
||||
PinAttributes PinAttributes::Exclusive(1 << (__LINE__ - START_LINE)); // \/ These are attributes
|
||||
PinAttributes PinAttributes::InitialHigh(1 << (__LINE__ - START_LINE)); // \/ These are attributes
|
||||
|
||||
|
@@ -33,6 +33,7 @@ namespace Pins {
|
||||
static PinAttributes PullDown;
|
||||
static PinAttributes ISR;
|
||||
|
||||
static PinAttributes ActiveLow;
|
||||
static PinAttributes Exclusive;
|
||||
static PinAttributes InitialHigh;
|
||||
|
||||
|
@@ -17,7 +17,6 @@ namespace Pins {
|
||||
PinCapabilities PinCapabilities::PullUp(1 << (__LINE__ - START_LINE)); // NOTE: Mapped in PinAttributes!
|
||||
PinCapabilities PinCapabilities::PullDown(1 << (__LINE__ - START_LINE)); // NOTE: Mapped in PinAttributes!
|
||||
PinCapabilities PinCapabilities::ISR(1 << (__LINE__ - START_LINE)); // NOTE: Mapped in PinAttributes!
|
||||
PinCapabilities PinCapabilities::ActiveLow(1 << (__LINE__ - START_LINE));
|
||||
PinCapabilities PinCapabilities::Native(1 << (__LINE__ - START_LINE));
|
||||
PinCapabilities PinCapabilities::PWM(1 << (__LINE__ - START_LINE));
|
||||
PinCapabilities PinCapabilities::UART(1 << (__LINE__ - START_LINE));
|
||||
|
@@ -30,7 +30,6 @@ namespace Pins {
|
||||
static PinCapabilities PullDown; // NOTE: Mapped in PinAttributes!
|
||||
static PinCapabilities ISR; // NOTE: Mapped in PinAttributes!
|
||||
|
||||
static PinCapabilities ActiveLow;
|
||||
static PinCapabilities Native;
|
||||
static PinCapabilities ADC;
|
||||
static PinCapabilities DAC;
|
||||
|
@@ -9,7 +9,7 @@
|
||||
#include <cstring>
|
||||
|
||||
namespace Pins {
|
||||
// Implementation details of pins.
|
||||
// Implementation details of pins.
|
||||
class PinDetail {
|
||||
public:
|
||||
PinDetail() = default;
|
||||
|
@@ -48,7 +48,8 @@ namespace Pins {
|
||||
}
|
||||
|
||||
PinDetail* GetPin(uint8_t index) const {
|
||||
Assert(_pins[index] != nullptr, "Pin is not defined. Cannot use this pin.");
|
||||
// This assertion causes message spewing making debugging impossible
|
||||
// Assert(_pins[index] != nullptr, "Pin is not defined. Cannot use this pin.");
|
||||
return _pins[index];
|
||||
}
|
||||
|
||||
|
@@ -3,20 +3,19 @@
|
||||
#include <cstring>
|
||||
|
||||
namespace Pins {
|
||||
PinOption::PinOption(char* start, const char* end) : _start(start) {}
|
||||
PinOption::PinOption(char* start, const char* end) : _start(start), _end(end) {}
|
||||
|
||||
bool PinOption::is(const char* option) const { return !::strcmp(option, _start); }
|
||||
|
||||
PinOption PinOption ::operator++() const {
|
||||
if (_start == _end) {
|
||||
return *this;
|
||||
PinOption PinOption ::operator++() {
|
||||
if (_start != _end) {
|
||||
auto newStart = _start + ::strlen(_start); // to the \0
|
||||
if (newStart != _end) { // and 1 past it if we're not at the end
|
||||
++newStart;
|
||||
}
|
||||
_start = newStart;
|
||||
}
|
||||
|
||||
auto newStart = _start + ::strlen(_start); // to the \0
|
||||
if (newStart != _end) { // and 1 past it if we're not at the end
|
||||
++newStart;
|
||||
}
|
||||
return PinOption(newStart, _end);
|
||||
return *this;
|
||||
}
|
||||
|
||||
PinOptionsParser::PinOptionsParser(char* buffer, char* bufferEnd) : _buffer(buffer), _bufferEnd(bufferEnd) {
|
||||
|
@@ -35,7 +35,7 @@ namespace Pins {
|
||||
// Iterator support:
|
||||
inline PinOption const* operator->() const { return this; }
|
||||
inline PinOption operator*() const { return *this; }
|
||||
PinOption operator++() const;
|
||||
PinOption operator++() ;
|
||||
|
||||
bool operator==(const PinOption& o) const { return _start == o._start; }
|
||||
bool operator!=(const PinOption& o) const { return _start != o._start; }
|
||||
|
@@ -1,7 +1,8 @@
|
||||
#include "VoidPinDetail.h"
|
||||
|
||||
namespace Pins {
|
||||
VoidPinDetail::VoidPinDetail(const PinOptionsParser& options) : _frequency(0), _maxDuty(0) {}
|
||||
VoidPinDetail::VoidPinDetail() : _frequency(0), _maxDuty(0) {}
|
||||
VoidPinDetail::VoidPinDetail(const PinOptionsParser& options) : VoidPinDetail() {}
|
||||
|
||||
PinCapabilities VoidPinDetail::capabilities() const { return PinCapabilities::None; } // Should we?
|
||||
|
||||
@@ -9,6 +10,6 @@ namespace Pins {
|
||||
int VoidPinDetail::read() { return 0; }
|
||||
void VoidPinDetail::setAttr(PinAttributes value) {}
|
||||
|
||||
String VoidPinDetail::toString() const { return "UNDEFINED_PIN"; }
|
||||
String VoidPinDetail::toString() const { return ""; }
|
||||
|
||||
}
|
||||
|
@@ -9,6 +9,7 @@ namespace Pins {
|
||||
uint32_t _maxDuty;
|
||||
|
||||
public:
|
||||
VoidPinDetail();
|
||||
VoidPinDetail(const PinOptionsParser& options);
|
||||
|
||||
PinCapabilities capabilities() const override;
|
||||
|
@@ -150,7 +150,9 @@ Error list_grbl_names(const char* value, WebUI::AuthenticationLevel auth_level,
|
||||
Error list_settings(const char* value, WebUI::AuthenticationLevel auth_level, WebUI::ESPResponseStream* out) {
|
||||
for (Setting* s = Setting::List; s; s = s->next()) {
|
||||
const char* displayValue = auth_failed(s, value, auth_level) ? "<Authentication required>" : s->getStringValue();
|
||||
show_setting(s->getName(), displayValue, NULL, out);
|
||||
if (s->getType() != PIN) {
|
||||
show_setting(s->getName(), displayValue, NULL, out);
|
||||
}
|
||||
}
|
||||
return Error::Ok;
|
||||
}
|
||||
@@ -158,12 +160,32 @@ Error list_changed_settings(const char* value, WebUI::AuthenticationLevel auth_l
|
||||
for (Setting* s = Setting::List; s; s = s->next()) {
|
||||
const char* value = s->getStringValue();
|
||||
if (!auth_failed(s, value, auth_level) && strcmp(value, s->getDefaultString())) {
|
||||
show_setting(s->getName(), value, NULL, out);
|
||||
if (s->getType() != PIN) {
|
||||
show_setting(s->getName(), value, NULL, out);
|
||||
}
|
||||
}
|
||||
}
|
||||
grbl_sendf(out->client(), "(Passwords not shown)\r\n");
|
||||
return Error::Ok;
|
||||
}
|
||||
Error list_pins(const char* value, WebUI::AuthenticationLevel auth_level, WebUI::ESPResponseStream* out) {
|
||||
for (Setting* s = Setting::List; s; s = s->next()) {
|
||||
const char* displayValue = auth_failed(s, value, auth_level) ? "<Authentication required>" : s->getStringValue();
|
||||
if (s->getType() == PIN) {
|
||||
show_setting(s->getName(), displayValue, NULL, out);
|
||||
}
|
||||
}
|
||||
return Error::Ok;
|
||||
}
|
||||
Error list_changed_pins(const char* value, WebUI::AuthenticationLevel auth_level, WebUI::ESPResponseStream* out) {
|
||||
for (Setting* s = Setting::List; s; s = s->next()) {
|
||||
const char* value = s->getStringValue();
|
||||
if (s->getType() == PIN && strcmp(value, UNDEFINED_PIN)) {
|
||||
show_setting(s->getName(), value, NULL, out);
|
||||
}
|
||||
}
|
||||
return Error::Ok;
|
||||
}
|
||||
Error list_commands(const char* value, WebUI::AuthenticationLevel auth_level, WebUI::ESPResponseStream* out) {
|
||||
for (Command* cp = Command::List; cp; cp = cp->next()) {
|
||||
const char* name = cp->getName();
|
||||
@@ -285,15 +307,15 @@ Error report_startup_lines(const char* value, WebUI::AuthenticationLevel auth_le
|
||||
|
||||
std::map<const char*, uint8_t, cmp_str> restoreCommands = {
|
||||
#ifdef ENABLE_RESTORE_DEFAULT_SETTINGS
|
||||
{ "$", SettingsRestore::Defaults }, { "settings", SettingsRestore::Defaults },
|
||||
{ "$", SettingsRestore::Defaults }, { "settings", SettingsRestore::Defaults },
|
||||
#endif
|
||||
#ifdef ENABLE_RESTORE_CLEAR_PARAMETERS
|
||||
{ "#", SettingsRestore::Parameters }, { "gcode", SettingsRestore::Parameters },
|
||||
{ "#", SettingsRestore::Parameters }, { "gcode", SettingsRestore::Parameters },
|
||||
#endif
|
||||
#ifdef ENABLE_RESTORE_WIPE_ALL
|
||||
{ "*", SettingsRestore::All }, { "all", SettingsRestore::All },
|
||||
{ "*", SettingsRestore::All }, { "all", SettingsRestore::All },
|
||||
#endif
|
||||
{ "@", SettingsRestore::Wifi }, { "wifi", SettingsRestore::Wifi },
|
||||
{ "@", SettingsRestore::Wifi }, { "wifi", SettingsRestore::Wifi },
|
||||
};
|
||||
Error restore_settings(const char* value, WebUI::AuthenticationLevel auth_level, WebUI::ESPResponseStream* out) {
|
||||
if (!value) {
|
||||
@@ -381,7 +403,9 @@ void make_grbl_commands() {
|
||||
new GrblCommand("+", "ExtendedSettings/List", report_extended_settings, notCycleOrHold);
|
||||
new GrblCommand("L", "GrblNames/List", list_grbl_names, notCycleOrHold);
|
||||
new GrblCommand("S", "Settings/List", list_settings, notCycleOrHold);
|
||||
new GrblCommand("SC","Settings/ListChanged", list_changed_settings, notCycleOrHold);
|
||||
new GrblCommand("SC", "Settings/ListChanged", list_changed_settings, notCycleOrHold);
|
||||
new GrblCommand("P", "Pins/List", list_pins, notCycleOrHold);
|
||||
new GrblCommand("PC", "Pins/ListChanged", list_changed_pins, notCycleOrHold);
|
||||
new GrblCommand("CMD", "Commands/List", list_commands, notCycleOrHold);
|
||||
new GrblCommand("E", "ErrorCodes/List", listErrorCodes, anyState);
|
||||
new GrblCommand("G", "GCode/Modes", report_gcode, anyState);
|
||||
|
@@ -441,7 +441,7 @@ void StringSetting::addWebui(WebUI::JSONencoder* j) {
|
||||
}
|
||||
|
||||
PinSetting::PinSetting(const char* description, const char* name, const char* defVal, bool (*checker)(char*)) :
|
||||
Setting(description, WEBSET, WA, NULL, name, checker), _currentValue(Pin::UNDEFINED) {
|
||||
Setting(description, PIN, WA, NULL, name, checker), _currentValue(Pin::UNDEFINED) {
|
||||
_defaultValue = defVal;
|
||||
};
|
||||
|
||||
@@ -480,7 +480,7 @@ void PinSetting::setDefault() {
|
||||
|
||||
Error PinSetting::setStringValue(char* s) {
|
||||
if (!Pin::validate(s)) {
|
||||
return Error::BadNumberFormat;
|
||||
return Error::BadPinSpecification;
|
||||
}
|
||||
|
||||
Error err = check(s);
|
||||
@@ -506,7 +506,7 @@ const char* PinSetting::getStringValue() {
|
||||
return _storedValue.c_str();
|
||||
}
|
||||
const char* PinSetting::getDefaultString() {
|
||||
return "undef";
|
||||
return "";
|
||||
}
|
||||
|
||||
void PinSetting::addWebui(WebUI::JSONencoder* j) {
|
||||
|
@@ -43,6 +43,7 @@ typedef enum : uint8_t {
|
||||
GRBL = 1, // Classic GRBL settings like $100
|
||||
EXTENDED, // Settings added by early versions of Grbl_Esp32
|
||||
WEBSET, // Settings for ESP3D_WebUI, stored in NVS
|
||||
PIN, // Pin settings
|
||||
GRBLCMD, // Non-persistent GRBL commands like $H
|
||||
WEBCMD, // ESP3D_WebUI commands that are not directly settings
|
||||
} type_t;
|
||||
|
@@ -25,6 +25,6 @@ namespace Pins {
|
||||
AssertThrow(unassigned.detachInterrupt());
|
||||
|
||||
Assert(unassigned.capabilities() == Pin::Capabilities::None);
|
||||
Assert(unassigned.name().equals("UNDEFINED_PIN"));
|
||||
Assert(unassigned.name().equals(UNDEFINED_PIN));
|
||||
}
|
||||
}
|
||||
|
Reference in New Issue
Block a user