mirror of
https://github.com/bdring/Grbl_Esp32.git
synced 2025-09-02 10:53:01 +02:00
Removed PWM for now. Should do this different anyways.
Added debug mode to pin class. Uncomment "PIN_DEBUG" in Pin.h for debug mode, which should dump a lot of info to your serial.
This commit is contained in:
@@ -5,6 +5,9 @@
|
||||
#include "Pins/VoidPinDetail.h"
|
||||
#include "Pins/GPIOPinDetail.h"
|
||||
#include "Pins/I2SPinDetail.h"
|
||||
#ifdef PIN_DEBUG
|
||||
#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.
|
||||
@@ -70,6 +73,10 @@ bool Pin::parse(String str, Pins::PinDetail*& pinImplementation, int& pinNumber)
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef PIN_DEBUG
|
||||
pinImplementation = new Pins::DebugPinDetail(pinImplementation);
|
||||
#endif
|
||||
|
||||
return pinImplementation;
|
||||
}
|
||||
|
||||
|
@@ -9,6 +9,8 @@
|
||||
#include <cstdint>
|
||||
#include <cstring>
|
||||
|
||||
// #define PIN_DEBUG // Pin debugging. WILL spam you with a lot of data!
|
||||
|
||||
// Forward declarations:
|
||||
class String;
|
||||
|
||||
@@ -86,30 +88,6 @@ public:
|
||||
inline void on() const { write(1); }
|
||||
inline void off() const { write(0); }
|
||||
|
||||
// PWM
|
||||
|
||||
inline bool initPWM(uint32_t frequency, uint32_t maxDuty) const {
|
||||
auto detail = Pins::PinLookup::_instance.GetPin(_index);
|
||||
return detail->initPWM(frequency, maxDuty);
|
||||
}
|
||||
|
||||
// Returns actual frequency which might not be exactly the same as requested(nearest supported value)
|
||||
inline uint32_t getPWMFrequency() const {
|
||||
auto detail = Pins::PinLookup::_instance.GetPin(_index);
|
||||
return detail->getPWMFrequency();
|
||||
}
|
||||
|
||||
// Returns actual maxDuty which might not be exactly the same as requested(nearest supported value)
|
||||
inline uint32_t getPWMMaxDuty() const {
|
||||
auto detail = Pins::PinLookup::_instance.GetPin(_index);
|
||||
return detail->getPWMMaxDuty();
|
||||
}
|
||||
|
||||
inline void setPWMDuty(uint32_t duty) const {
|
||||
auto detail = Pins::PinLookup::_instance.GetPin(_index);
|
||||
return detail->setPWMDuty(duty);
|
||||
}
|
||||
|
||||
// ISR handlers. Map methods on 'this' types.
|
||||
|
||||
template <typename ThisType, void (ThisType::*Callback)()>
|
||||
|
@@ -847,6 +847,8 @@ PinSetting* ServoPins[MAX_N_AXIS][2];
|
||||
PinSetting* StepStickMS3[MAX_N_AXIS][2];
|
||||
PinSetting* PhasePins[4][MAX_N_AXIS][2];
|
||||
|
||||
#include "Pin.h"
|
||||
|
||||
// Initialize the pin settings
|
||||
void make_pin_settings() {
|
||||
CoolantFloodPin = new PinSetting("Pins/CoolantFlood", COOLANT_FLOOD_PIN_DEFAULT);
|
||||
|
87
Grbl_Esp32/src/Pins/DebugPinDetail.cpp
Normal file
87
Grbl_Esp32/src/Pins/DebugPinDetail.cpp
Normal file
@@ -0,0 +1,87 @@
|
||||
#include "DebugPinDetail.h"
|
||||
|
||||
#include "../Grbl.h" // for printf
|
||||
#include <Arduino.h> // for timer
|
||||
|
||||
namespace Pins {
|
||||
// I/O:
|
||||
void DebugPinDetail::write(int high) {
|
||||
grbl_msg_sendf(CLIENT_ALL, MsgLevel::Info, "Writing pin %s = %d", toString().c_str(), high);
|
||||
_implementation->write(high);
|
||||
}
|
||||
|
||||
int DebugPinDetail::read() {
|
||||
auto result = _implementation->read();
|
||||
grbl_msg_sendf(CLIENT_ALL, MsgLevel::Info, "Reading pin %s = %d", toString().c_str(), result);
|
||||
return result;
|
||||
}
|
||||
void DebugPinDetail::setAttr(PinAttributes value) {
|
||||
char buf[10];
|
||||
int n = 0;
|
||||
if (value.has(PinAttributes::Input)) {
|
||||
buf[n++] = 'I';
|
||||
}
|
||||
if (value.has(PinAttributes::Output)) {
|
||||
buf[n++] = 'O';
|
||||
}
|
||||
if (value.has(PinAttributes::PullUp)) {
|
||||
buf[n++] = 'U';
|
||||
}
|
||||
if (value.has(PinAttributes::PullDown)) {
|
||||
buf[n++] = 'D';
|
||||
}
|
||||
if (value.has(PinAttributes::ISR)) {
|
||||
buf[n++] = 'E';
|
||||
}
|
||||
if (value.has(PinAttributes::Exclusive)) {
|
||||
buf[n++] = 'X';
|
||||
}
|
||||
if (value.has(PinAttributes::InitialHigh)) {
|
||||
buf[n++] = '+';
|
||||
}
|
||||
buf[n++] = 0;
|
||||
|
||||
if (shouldEvent()) {
|
||||
grbl_msg_sendf(CLIENT_ALL, MsgLevel::Info, "Setting pin attr %s = %s", toString().c_str(), buf);
|
||||
}
|
||||
_implementation->setAttr(value);
|
||||
}
|
||||
|
||||
void DebugPinDetail::CallbackHandler::handle(void* arg) {
|
||||
auto handler = static_cast<CallbackHandler*>(arg);
|
||||
if (handler->_myPin->shouldEvent()) {
|
||||
grbl_msg_sendf(CLIENT_ALL, MsgLevel::Info, "Received ISR on pin %s", handler->_myPin->toString().c_str());
|
||||
}
|
||||
handler->callback(handler->argument);
|
||||
}
|
||||
|
||||
// ISR's:
|
||||
void DebugPinDetail::attachInterrupt(void (*callback)(void*), void* arg, int mode) {
|
||||
_isrHandler._myPin = this;
|
||||
_isrHandler.argument = arg;
|
||||
_isrHandler.callback = callback;
|
||||
|
||||
if (shouldEvent()) {
|
||||
grbl_msg_sendf(CLIENT_ALL, MsgLevel::Info, "Attaching interrupt to pin %s, mode %d", toString().c_str(), mode);
|
||||
}
|
||||
_implementation->attachInterrupt(_isrHandler.handle, &_isrHandler, mode);
|
||||
}
|
||||
void DebugPinDetail::detachInterrupt() { _implementation->detachInterrupt(); }
|
||||
|
||||
bool DebugPinDetail::shouldEvent() {
|
||||
// This method basically ensures we don't flood users:
|
||||
auto time = millis();
|
||||
|
||||
if (_lastEvent + 1000 > time) {
|
||||
_lastEvent = time;
|
||||
_eventCount = 1;
|
||||
return true;
|
||||
} else if (_eventCount < 20) {
|
||||
_lastEvent = time;
|
||||
++_eventCount;
|
||||
return true;
|
||||
} else {
|
||||
return false;
|
||||
}
|
||||
}
|
||||
}
|
43
Grbl_Esp32/src/Pins/DebugPinDetail.h
Normal file
43
Grbl_Esp32/src/Pins/DebugPinDetail.h
Normal file
@@ -0,0 +1,43 @@
|
||||
#pragma once
|
||||
|
||||
#include "PinDetail.h"
|
||||
|
||||
namespace Pins {
|
||||
class DebugPinDetail : public PinDetail {
|
||||
PinDetail* _implementation;
|
||||
|
||||
int _lastEvent;
|
||||
int _eventCount;
|
||||
|
||||
struct CallbackHandler {
|
||||
void (*callback)(void* arg);
|
||||
void* argument;
|
||||
DebugPinDetail* _myPin;
|
||||
|
||||
static void handle(void* arg);
|
||||
} _isrHandler;
|
||||
|
||||
friend void CallbackHandler::handle(void* arg);
|
||||
|
||||
bool shouldEvent();
|
||||
|
||||
public:
|
||||
DebugPinDetail(PinDetail* implementation) : _implementation(implementation), _lastEvent(0), _eventCount(0) {}
|
||||
|
||||
PinCapabilities capabilities() const override { return _implementation->capabilities(); }
|
||||
|
||||
// I/O:
|
||||
void write(int high) override;
|
||||
int read() override;
|
||||
void setAttr(PinAttributes value) override;
|
||||
|
||||
// ISR's:
|
||||
void attachInterrupt(void (*callback)(void*), void* arg, int mode) override;
|
||||
void detachInterrupt() override;
|
||||
|
||||
String toString() const override { return _implementation->toString(); }
|
||||
|
||||
~DebugPinDetail() override {}
|
||||
};
|
||||
|
||||
}
|
@@ -156,27 +156,5 @@ namespace Pins {
|
||||
::detachInterrupt(_index);
|
||||
}
|
||||
|
||||
bool GPIOPinDetail::initPWM(uint32_t frequency, uint32_t maxDuty) {
|
||||
// TODO FIXME: Implement
|
||||
throw "Notimplemented";
|
||||
}
|
||||
|
||||
// Returns actual frequency which might not be exactly the same as requested(nearest supported value)
|
||||
uint32_t GPIOPinDetail::getPWMFrequency() {
|
||||
// TODO FIXME: Implement
|
||||
throw "Notimplemented";
|
||||
}
|
||||
|
||||
// Returns actual maxDuty which might not be exactly the same as requested(nearest supported value)
|
||||
uint32_t GPIOPinDetail::getPWMMaxDuty() {
|
||||
// TODO FIXME: Implement
|
||||
throw "Notimplemented";
|
||||
}
|
||||
|
||||
void GPIOPinDetail::setPWMDuty(uint32_t duty) {
|
||||
// TODO FIXME: Implement
|
||||
throw "Notimplemented";
|
||||
}
|
||||
|
||||
String GPIOPinDetail::toString() const { return String("GPIO.") + int(_index); }
|
||||
}
|
||||
|
@@ -25,12 +25,6 @@ namespace Pins {
|
||||
void attachInterrupt(void (*callback)(void*), void* arg, int mode) override;
|
||||
void detachInterrupt() override;
|
||||
|
||||
// PWM
|
||||
bool initPWM(uint32_t frequency, uint32_t maxDuty) override;
|
||||
uint32_t getPWMFrequency() override;
|
||||
uint32_t getPWMMaxDuty() override;
|
||||
void setPWMDuty(uint32_t duty) override;
|
||||
|
||||
String toString() const override;
|
||||
|
||||
~GPIOPinDetail() override {}
|
||||
|
@@ -7,9 +7,4 @@ namespace Pins {
|
||||
Assert(false, "Interrupts are not supported by this pin.");
|
||||
}
|
||||
void PinDetail::detachInterrupt() { Assert(false, "Interrupts are not supported by this pin."); }
|
||||
|
||||
bool PinDetail::initPWM(uint32_t frequency, uint32_t maxDuty) { Assert(false, "PWM is not supported by this pin."); }
|
||||
uint32_t PinDetail::getPWMFrequency() { Assert(false, "PWM is not supported by this pin."); }
|
||||
uint32_t PinDetail::getPWMMaxDuty() { Assert(false, "PWM is not supported by this pin."); }
|
||||
void PinDetail::setPWMDuty(uint32_t duty) { Assert(false, "PWM is not supported by this pin."); }
|
||||
}
|
||||
|
@@ -29,18 +29,6 @@ namespace Pins {
|
||||
virtual void attachInterrupt(void (*callback)(void*), void* arg, int mode);
|
||||
virtual void detachInterrupt();
|
||||
|
||||
// PWM
|
||||
// Returns true if successful Deassign if frequency == 0 ?
|
||||
virtual bool initPWM(uint32_t frequency, uint32_t maxDuty);
|
||||
|
||||
// Returns actual frequency which might not be exactly the same as requested(nearest supported value)
|
||||
virtual uint32_t getPWMFrequency();
|
||||
|
||||
// Returns actual maxDuty which might not be exactly the same as requested(nearest supported value)
|
||||
virtual uint32_t getPWMMaxDuty();
|
||||
|
||||
virtual void setPWMDuty(uint32_t duty);
|
||||
|
||||
virtual String toString() const = 0;
|
||||
|
||||
virtual ~PinDetail() {}
|
||||
|
@@ -9,22 +9,6 @@ namespace Pins {
|
||||
int VoidPinDetail::read() { return 0; }
|
||||
void VoidPinDetail::setAttr(PinAttributes value) {}
|
||||
|
||||
bool VoidPinDetail::initPWM(uint32_t frequency, uint32_t maxDuty) {
|
||||
// We just set frequency and maxDuty to ensure we at least return values
|
||||
// for getPWMFreq / getPWMMaxDuty that make sense.
|
||||
_frequency = frequency;
|
||||
_maxDuty = maxDuty;
|
||||
return false;
|
||||
}
|
||||
|
||||
// Returns actual frequency which might not be exactly the same as requested(nearest supported value)
|
||||
uint32_t VoidPinDetail::getPWMFrequency() { return _frequency; }
|
||||
|
||||
// Returns actual maxDuty which might not be exactly the same as requested(nearest supported value)
|
||||
uint32_t VoidPinDetail::getPWMMaxDuty() { return _maxDuty; }
|
||||
|
||||
void VoidPinDetail::setPWMDuty(uint32_t duty) {}
|
||||
|
||||
String VoidPinDetail::toString() const { return "UNDEFINED_PIN"; }
|
||||
|
||||
}
|
||||
|
@@ -18,12 +18,6 @@ namespace Pins {
|
||||
int read() override;
|
||||
void setAttr(PinAttributes value) override;
|
||||
|
||||
// PWM
|
||||
bool initPWM(uint32_t frequency, uint32_t maxDuty) override;
|
||||
uint32_t getPWMFrequency() override;
|
||||
uint32_t getPWMMaxDuty() override;
|
||||
void setPWMDuty(uint32_t duty) override;
|
||||
|
||||
String toString() const override;
|
||||
|
||||
~VoidPinDetail() override {}
|
||||
|
@@ -449,6 +449,9 @@ void PinSetting::load() {
|
||||
size_t len = 0;
|
||||
esp_err_t err = nvs_get_str(_handle, _keyName, NULL, &len);
|
||||
if (err) {
|
||||
#ifdef PIN_DEBUG
|
||||
grbl_msg_sendf(CLIENT_ALL, MsgLevel::Info, "Initializing pin %s with: %s", _keyName, _defaultValue);
|
||||
#endif
|
||||
_storedValue = _defaultValue;
|
||||
_currentValue = Pin::create(_defaultValue);
|
||||
return;
|
||||
@@ -456,10 +459,17 @@ void PinSetting::load() {
|
||||
char buf[len];
|
||||
err = nvs_get_str(_handle, _keyName, buf, &len);
|
||||
if (err) {
|
||||
#ifdef PIN_DEBUG
|
||||
grbl_msg_sendf(CLIENT_ALL, MsgLevel::Info, "Initializing pin %s with: %s", _keyName, _defaultValue);
|
||||
#endif
|
||||
_storedValue = _defaultValue;
|
||||
_currentValue = Pin::create(_defaultValue);
|
||||
return;
|
||||
}
|
||||
|
||||
#ifdef PIN_DEBUG
|
||||
grbl_msg_sendf(CLIENT_ALL, MsgLevel::Info, "Initializing pin %s with: %s", _keyName, _storedValue);
|
||||
#endif
|
||||
_storedValue = String(buf);
|
||||
_currentValue = Pin::create(_storedValue);
|
||||
}
|
||||
|
Reference in New Issue
Block a user