mirror of
https://github.com/bdring/Grbl_Esp32.git
synced 2025-09-02 10:53:01 +02:00
Tested probe pin.
This commit is contained in:
@@ -46,32 +46,60 @@
|
|||||||
#undef DEFAULT_HOMING_CYCLE_1
|
#undef DEFAULT_HOMING_CYCLE_1
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#define SPINDLE_TYPE SpindleType::NONE
|
|
||||||
|
|
||||||
#ifdef USE_RMT_STEPS
|
#ifdef USE_RMT_STEPS
|
||||||
#undef USE_RMT_STEPS // Suppress unused variable warning
|
#undef USE_RMT_STEPS // Suppress unused variable warning
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
||||||
// Output devices :
|
// Output devices:
|
||||||
// - I2S
|
// - I2S
|
||||||
// x CoolantControl
|
|
||||||
// - StandardStepper
|
|
||||||
#define X_STEP_PIN "gpio.2"
|
|
||||||
#define X_DIRECTION_PIN "gpio.4"
|
|
||||||
#define X_DISABLE_PIN "gpio.16"
|
|
||||||
|
|
||||||
// - Unipolar
|
// x CoolantControl
|
||||||
// - 10V
|
|
||||||
|
// #define COOLANT_MIST_PIN "gpio.2" // labeled Mist
|
||||||
|
// #define COOLANT_FLOOD_PIN "gpio.4" // labeled Flood
|
||||||
|
|
||||||
|
// x StandardStepper
|
||||||
|
|
||||||
|
// #define X_STEP_PIN "gpio.2"
|
||||||
|
// #define X_DIRECTION_PIN "gpio.4"
|
||||||
|
// #define X_DISABLE_PIN "gpio.16"
|
||||||
|
|
||||||
|
// x Unipolar
|
||||||
|
|
||||||
|
// #define X_UNIPOLAR
|
||||||
|
// #define X_PIN_PHASE_0 "gpio.2"
|
||||||
|
// #define X_PIN_PHASE_1 "gpio.4"
|
||||||
|
// #define X_PIN_PHASE_2 "gpio.16"
|
||||||
|
// #define X_PIN_PHASE_3 "gpio.15"
|
||||||
|
|
||||||
|
// Spindles:
|
||||||
|
|
||||||
|
#define SPINDLE_TYPE SpindleType::NONE
|
||||||
|
|
||||||
|
// #define SPINDLE_OUTPUT_PIN "gpio.15"
|
||||||
|
// #define SPINDLE_ENABLE_PIN "gpio.2"
|
||||||
|
// #define SPINDLE_DIRECTION_PIN "gpio.4"
|
||||||
|
// #define SPINDLE_FORWARD_PIN "gpio.16"
|
||||||
|
// #define SPINDLE_REVERSE_PIN "gpio.17"
|
||||||
|
|
||||||
|
// x 10V
|
||||||
|
// #define SPINDLE_TYPE SpindleType::_10V
|
||||||
|
|
||||||
|
// x PWM
|
||||||
|
// #define SPINDLE_TYPE SpindleType::PWM
|
||||||
|
|
||||||
|
// x Relay
|
||||||
|
// #define SPINDLE_TYPE SpindleType::RELAY
|
||||||
|
|
||||||
// - BESC
|
// - BESC
|
||||||
// - DAC
|
// - DAC
|
||||||
// - Laser
|
|
||||||
// - PWM
|
|
||||||
// - Relay
|
|
||||||
// - Stepper
|
|
||||||
//
|
//
|
||||||
// Input devices :
|
// Input devices :
|
||||||
// -Probe
|
// x Probe
|
||||||
|
// #define PROBE_PIN "gpio.18:pu" // labeled Probe
|
||||||
|
|
||||||
// - User Analog / Digital pins
|
// - User Analog / Digital pins
|
||||||
// - Limits
|
// - Limits
|
||||||
// - System : ControlSafetyDoor
|
// - System : ControlSafetyDoor
|
||||||
|
@@ -1,15 +1,31 @@
|
|||||||
#include "DebugPinDetail.h"
|
#include "DebugPinDetail.h"
|
||||||
|
|
||||||
#include "../Grbl.h" // for printf
|
#include "../Grbl.h" // for printf
|
||||||
#include <Arduino.h> // for timer
|
#include <Arduino.h> // for timer
|
||||||
|
#include <HardwareSerial.h> // HW serial
|
||||||
|
#include <cstdio> // vsnprintf
|
||||||
|
|
||||||
namespace Pins {
|
namespace Pins {
|
||||||
|
inline void WriteSerial(const char* format, ...) {
|
||||||
|
char buf[50];
|
||||||
|
va_list arg;
|
||||||
|
va_list copy;
|
||||||
|
va_start(arg, format);
|
||||||
|
va_copy(copy, arg);
|
||||||
|
size_t len = vsnprintf(buf, 50, format, arg);
|
||||||
|
va_end(copy);
|
||||||
|
Serial.print("[MSG: ");
|
||||||
|
Serial.print(buf);
|
||||||
|
Serial.println(" ]");
|
||||||
|
va_end(arg);
|
||||||
|
}
|
||||||
|
|
||||||
// I/O:
|
// I/O:
|
||||||
void DebugPinDetail::write(int high) {
|
void DebugPinDetail::write(int high) {
|
||||||
if (high != _isHigh) {
|
if (high != _isHigh) {
|
||||||
_isHigh = high;
|
_isHigh = high;
|
||||||
if (shouldEvent()) {
|
if (shouldEvent()) {
|
||||||
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Writing pin %s = %d", toString().c_str(), high);
|
WriteSerial( "Write %s < %d", toString().c_str(), high);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
_implementation->write(high);
|
_implementation->write(high);
|
||||||
@@ -18,7 +34,7 @@ namespace Pins {
|
|||||||
int DebugPinDetail::read() {
|
int DebugPinDetail::read() {
|
||||||
auto result = _implementation->read();
|
auto result = _implementation->read();
|
||||||
if (shouldEvent()) {
|
if (shouldEvent()) {
|
||||||
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Reading pin %s = %d", toString().c_str(), result);
|
WriteSerial("Read %s > %d", toString().c_str(), result);
|
||||||
}
|
}
|
||||||
return result;
|
return result;
|
||||||
}
|
}
|
||||||
@@ -49,7 +65,7 @@ namespace Pins {
|
|||||||
buf[n++] = 0;
|
buf[n++] = 0;
|
||||||
|
|
||||||
if (shouldEvent()) {
|
if (shouldEvent()) {
|
||||||
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Setting pin attr %s = %s", toString().c_str(), buf);
|
WriteSerial("Set pin attr %s = %s", toString().c_str(), buf);
|
||||||
}
|
}
|
||||||
_implementation->setAttr(value);
|
_implementation->setAttr(value);
|
||||||
}
|
}
|
||||||
@@ -57,7 +73,7 @@ namespace Pins {
|
|||||||
void DebugPinDetail::CallbackHandler::handle(void* arg) {
|
void DebugPinDetail::CallbackHandler::handle(void* arg) {
|
||||||
auto handler = static_cast<CallbackHandler*>(arg);
|
auto handler = static_cast<CallbackHandler*>(arg);
|
||||||
if (handler->_myPin->shouldEvent()) {
|
if (handler->_myPin->shouldEvent()) {
|
||||||
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Received ISR on pin %s", handler->_myPin->toString().c_str());
|
WriteSerial("Received ISR on pin %s", handler->_myPin->toString().c_str());
|
||||||
}
|
}
|
||||||
handler->callback(handler->argument);
|
handler->callback(handler->argument);
|
||||||
}
|
}
|
||||||
@@ -69,7 +85,7 @@ namespace Pins {
|
|||||||
_isrHandler.callback = callback;
|
_isrHandler.callback = callback;
|
||||||
|
|
||||||
if (shouldEvent()) {
|
if (shouldEvent()) {
|
||||||
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Attaching interrupt to pin %s, mode %d", toString().c_str(), mode);
|
WriteSerial("Attaching interrupt to pin %s, mode %d", toString().c_str(), mode);
|
||||||
}
|
}
|
||||||
_implementation->attachInterrupt(_isrHandler.handle, &_isrHandler, mode);
|
_implementation->attachInterrupt(_isrHandler.handle, &_isrHandler, mode);
|
||||||
}
|
}
|
||||||
@@ -90,7 +106,7 @@ namespace Pins {
|
|||||||
} else if (_eventCount == 10) {
|
} else if (_eventCount == 10) {
|
||||||
_lastEvent = time;
|
_lastEvent = time;
|
||||||
++_eventCount;
|
++_eventCount;
|
||||||
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Suppressing events...");
|
WriteSerial("Suppressing events...");
|
||||||
return false;
|
return false;
|
||||||
} else {
|
} else {
|
||||||
_lastEvent = time;
|
_lastEvent = time;
|
||||||
|
@@ -143,12 +143,6 @@ namespace Pins {
|
|||||||
pinModeValue |= OUTPUT;
|
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:
|
// PU/PD should be specified by the user. Code has nothing to do with them:
|
||||||
if (_attributes.has(PinAttributes::PullUp)) {
|
if (_attributes.has(PinAttributes::PullUp)) {
|
||||||
pinModeValue |= PULLUP;
|
pinModeValue |= PULLUP;
|
||||||
|
Reference in New Issue
Block a user