mirror of
https://github.com/bdring/Grbl_Esp32.git
synced 2025-09-02 10:53:01 +02:00
Removed invert masks from settings and defines throughout the code base. This is handled in Pin class now.
This commit is contained in:
@@ -48,12 +48,6 @@ Some features should not be changed. See notes below.
|
||||
|
||||
// Note: HOMING_CYCLES are now settings
|
||||
|
||||
// Inverts pin logic of the control command pins based on a mask. This essentially means you can use
|
||||
// normally-closed switches on the specified pins, rather than the default normally-open switches.
|
||||
// The mask order is Cycle Start | Feed Hold | Reset | Safety Door
|
||||
// For example B1101 will invert the function of the Reset pin.
|
||||
#define INVERT_CONTROL_PIN_MASK B1111
|
||||
|
||||
#define ENABLE_CONTROL_SW_DEBOUNCE // Default disabled. Uncomment to enable.
|
||||
#define CONTROL_SW_DEBOUNCE_PERIOD 32 // in milliseconds default 32 microseconds
|
||||
|
||||
@@ -263,19 +257,6 @@ static const uint8_t NHomingLocateCycle = 1; // Integer (1-128)
|
||||
const double SAFETY_DOOR_SPINDLE_DELAY = 4.0; // Float (seconds)
|
||||
const double SAFETY_DOOR_COOLANT_DELAY = 1.0; // Float (seconds)
|
||||
|
||||
// Inverts select limit pin states based on the following mask. This effects all limit pin functions,
|
||||
// such as hard limits and homing. However, this is different from overall invert limits setting.
|
||||
// This build option will invert only the limit pins defined here, and then the invert limits setting
|
||||
// will be applied to all of them. This is useful when a user has a mixed set of limit pins with both
|
||||
// normally-open(NO) and normally-closed(NC) switches installed on their machine.
|
||||
// NOTE: PLEASE DO NOT USE THIS, unless you have a situation that needs it.
|
||||
// #define INVERT_LIMIT_PIN_MASK (bit(X_AXIS)|bit(Y_AXIS)) // Default disabled. Uncomment to enable.
|
||||
|
||||
// Inverts the selected coolant pin from low-disabled/high-enabled to low-enabled/high-disabled. Useful
|
||||
// for some pre-built electronic boards.
|
||||
// #define INVERT_COOLANT_FLOOD_PIN // Default disabled. Uncomment to enable.
|
||||
// #define INVERT_COOLANT_MIST_PIN // Default disabled. Note: Enable M7 mist coolant in config.h
|
||||
|
||||
// When Grbl powers-cycles or is hard reset with the Arduino reset button, Grbl boots up with no ALARM
|
||||
// by default. This is to make it as simple as possible for new users to start using Grbl. When homing
|
||||
// is enabled and a user has installed limit switches, Grbl will boot up in an ALARM state to indicate
|
||||
|
@@ -44,23 +44,13 @@ CoolantState coolant_get_state() {
|
||||
bool pinState;
|
||||
|
||||
if (CoolantFloodPin->get() != Pin::UNDEFINED) {
|
||||
auto pinState = CoolantFloodPin->get().read();
|
||||
#ifdef INVERT_COOLANT_FLOOD_PIN
|
||||
pinState = !pinState;
|
||||
#endif
|
||||
|
||||
if (pinState) {
|
||||
if (CoolantFloodPin->get().read()) {
|
||||
cl_state.Flood = 1;
|
||||
}
|
||||
}
|
||||
|
||||
if (CoolantMistPin->get() != Pin::UNDEFINED) {
|
||||
auto pinState = CoolantMistPin->get().read();
|
||||
#ifdef INVERT_COOLANT_MIST_PIN
|
||||
pinState = !pinState;
|
||||
#endif
|
||||
|
||||
if (pinState) {
|
||||
if (CoolantMistPin->get().read()) {
|
||||
cl_state.Mist = 1;
|
||||
}
|
||||
}
|
||||
@@ -71,17 +61,11 @@ CoolantState coolant_get_state() {
|
||||
static inline void coolant_write(CoolantState state) {
|
||||
if (CoolantFloodPin->get() != Pin::UNDEFINED) {
|
||||
bool pinState = state.Flood;
|
||||
#ifdef INVERT_COOLANT_FLOOD_PIN
|
||||
pinState = !pinState;
|
||||
#endif
|
||||
CoolantFloodPin->get().write(pinState);
|
||||
}
|
||||
|
||||
if (CoolantMistPin->get() != Pin::UNDEFINED) {
|
||||
bool pinState = state.Mist;
|
||||
#ifdef INVERT_COOLANT_MIST_PIN
|
||||
pinState = !pinState;
|
||||
#endif
|
||||
CoolantMistPin->get().write(pinState);
|
||||
}
|
||||
}
|
||||
|
@@ -46,26 +46,10 @@
|
||||
# define DEFAULT_STEPPER_IDLE_LOCK_TIME 250 // $1 msec (0-254, 255 keeps steppers enabled)
|
||||
#endif
|
||||
|
||||
#ifndef DEFAULT_STEPPING_INVERT_MASK
|
||||
# define DEFAULT_STEPPING_INVERT_MASK 0 // $2 uint8_t
|
||||
#endif
|
||||
|
||||
#ifndef DEFAULT_DIRECTION_INVERT_MASK
|
||||
# define DEFAULT_DIRECTION_INVERT_MASK 0 // $3 uint8_
|
||||
#endif
|
||||
|
||||
#ifndef DEFAULT_INVERT_ST_ENABLE
|
||||
# define DEFAULT_INVERT_ST_ENABLE 0 // $4 boolean
|
||||
#endif
|
||||
|
||||
#ifndef DEFAULT_INVERT_LIMIT_PINS
|
||||
# define DEFAULT_INVERT_LIMIT_PINS 1 // $5 boolean
|
||||
#endif
|
||||
|
||||
#ifndef DEFAULT_INVERT_PROBE_PIN
|
||||
# define DEFAULT_INVERT_PROBE_PIN 0 // $6 boolean
|
||||
#endif
|
||||
|
||||
#ifndef DEFAULT_STATUS_REPORT_MASK
|
||||
# define DEFAULT_STATUS_REPORT_MASK 1 // $10
|
||||
#endif
|
||||
@@ -187,14 +171,6 @@
|
||||
# define DEFAULT_SPINDLE_DELAY_SPINDOWN 0
|
||||
#endif
|
||||
|
||||
#ifndef DEFAULT_INVERT_SPINDLE_OUTPUT_PIN
|
||||
# define DEFAULT_INVERT_SPINDLE_OUTPUT_PIN 0
|
||||
#endif
|
||||
|
||||
#ifndef DEFAULT_INVERT_SPINDLE_ENABLE_PIN
|
||||
# define DEFAULT_INVERT_SPINDLE_ENABLE_PIN 0
|
||||
#endif
|
||||
|
||||
#ifndef DEFAULT_SPINDLE_ENABLE_OFF_WITH_ZERO_SPEED
|
||||
# define DEFAULT_SPINDLE_ENABLE_OFF_WITH_ZERO_SPEED 0
|
||||
#endif
|
||||
|
@@ -263,10 +263,8 @@ void limits_init() {
|
||||
for (int gang_index = 0; gang_index < 2; gang_index++) {
|
||||
Pin pin;
|
||||
if ((pin = LimitPins[axis][gang_index]->get()) != Pin::UNDEFINED) {
|
||||
|
||||
#ifndef DISABLE_LIMIT_PIN_PULL_UP
|
||||
if (pin.capabilities().has(Pins::PinCapabilities::PullUp))
|
||||
{
|
||||
if (pin.capabilities().has(Pins::PinCapabilities::PullUp)) {
|
||||
mode = mode | Pin::Attr::PullUp;
|
||||
}
|
||||
#endif
|
||||
@@ -313,8 +311,8 @@ void limits_disable() {
|
||||
}
|
||||
|
||||
// Returns limit state as a bit-wise uint8 variable. Each bit indicates an axis limit, where
|
||||
// triggered is 1 and not triggered is 0. Invert mask is applied. Axes are defined by their
|
||||
// number in bit position, i.e. Z_AXIS is bit(2), and Y_AXIS is bit(1).
|
||||
// triggered is 1 and not triggered is 0. Invert mask is handled through active low/high in pins.
|
||||
// Axes are defined by their number in bit position, i.e. Z_AXIS is bit(2), and Y_AXIS is bit(1).
|
||||
AxisMask limits_get_state() {
|
||||
AxisMask pinMask = 0;
|
||||
auto n_axis = number_axis->get();
|
||||
@@ -322,18 +320,11 @@ AxisMask limits_get_state() {
|
||||
for (int gang_index = 0; gang_index < 2; gang_index++) {
|
||||
Pin pin = LimitPins[axis][gang_index]->get();
|
||||
if (pin != Pin::UNDEFINED) {
|
||||
if (limit_invert->get()) {
|
||||
pinMask |= (!pin.read() << axis);
|
||||
} else {
|
||||
pinMask |= (pin.read() << axis);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
#ifdef INVERT_LIMIT_PIN_MASK // not normally used..unless you have both normal and inverted switches
|
||||
pinMask ^= INVERT_LIMIT_PIN_MASK;
|
||||
#endif
|
||||
return pinMask;
|
||||
}
|
||||
|
||||
|
@@ -115,7 +115,6 @@ Socket #5
|
||||
// #define CONTROL_FEED_HOLD_PIN "gpio.4"
|
||||
// #define CONTROL_RESET_PIN "gpio.16"
|
||||
// #define CONTROL_SAFETY_DOOR_PIN "gpio.27"
|
||||
// //#define INVERT_CONTROL_PIN_MASK B0000
|
||||
|
||||
// ================= Setting Defaults ==========================
|
||||
#define DEFAULT_X_STEPS_PER_MM 800
|
||||
|
@@ -63,14 +63,9 @@
|
||||
#define ENABLE_CONTROL_SW_DEBOUNCE
|
||||
#endif
|
||||
|
||||
#ifdef INVERT_CONTROL_PIN_MASK
|
||||
#undef INVERT_CONTROL_PIN_MASK
|
||||
#endif
|
||||
#define INVERT_CONTROL_PIN_MASK B01110000
|
||||
|
||||
#define MACRO_BUTTON_0_PIN "gpio.34" // Pen Switch
|
||||
#define MACRO_BUTTON_1_PIN "gpio.35" // Color Switch
|
||||
#define MACRO_BUTTON_2_PIN "gpio.36" // Paper Switch
|
||||
#define MACRO_BUTTON_0_PIN "gpio.34:low" // Pen Switch
|
||||
#define MACRO_BUTTON_1_PIN "gpio.35:low" // Color Switch
|
||||
#define MACRO_BUTTON_2_PIN "gpio.36:low" // Paper Switch
|
||||
|
||||
#ifdef DEFAULTS_GENERIC
|
||||
#undef DEFAULTS_GENERIC // undefine generic then define each default below
|
||||
@@ -78,11 +73,7 @@
|
||||
#define DEFAULT_STEP_PULSE_MICROSECONDS 3
|
||||
#define DEFAULT_STEPPER_IDLE_LOCK_TIME 200 // 200ms
|
||||
|
||||
#define DEFAULT_STEPPING_INVERT_MASK 0 // uint8_t
|
||||
#define DEFAULT_DIRECTION_INVERT_MASK 0 // uint8_t
|
||||
#define DEFAULT_INVERT_ST_ENABLE 0 // boolean
|
||||
#define DEFAULT_INVERT_LIMIT_PINS 1 // boolean
|
||||
#define DEFAULT_INVERT_PROBE_PIN 0 // boolean
|
||||
|
||||
#define DEFAULT_STATUS_REPORT_MASK 1
|
||||
|
||||
|
@@ -74,13 +74,6 @@
|
||||
|
||||
#define PROBE_PIN "gpio.35"
|
||||
|
||||
// The default value in config.h is wrong for this controller
|
||||
#ifdef INVERT_CONTROL_PIN_MASK
|
||||
#undef INVERT_CONTROL_PIN_MASK
|
||||
#endif
|
||||
|
||||
#define INVERT_CONTROL_PIN_MASK B1110
|
||||
|
||||
#define CONTROL_RESET_PIN "gpio.34" // needs external pullup
|
||||
#define CONTROL_FEED_HOLD_PIN "gpio.36" // needs external pullup
|
||||
#define CONTROL_CYCLE_START_PIN "gpio.39" // needs external pullup
|
||||
#define CONTROL_RESET_PIN "gpio.34:low" // needs external pullup
|
||||
#define CONTROL_FEED_HOLD_PIN "gpio.36:low" // needs external pullup
|
||||
#define CONTROL_CYCLE_START_PIN "gpio.39:low" // needs external pullup
|
||||
|
@@ -45,8 +45,8 @@
|
||||
|
||||
#define STEPPERS_DISABLE_PIN "gpio.13"
|
||||
|
||||
#define X_LIMIT_PIN "gpio.2"
|
||||
#define Y_LIMIT_PIN "gpio.4"
|
||||
#define X_LIMIT_PIN "gpio.2:low"
|
||||
#define Y_LIMIT_PIN "gpio.4:low"
|
||||
|
||||
#define Z_SERVO_PIN "gpio.27"
|
||||
|
||||
@@ -64,11 +64,7 @@
|
||||
#define DEFAULT_STEP_PULSE_MICROSECONDS 3
|
||||
#define DEFAULT_STEPPER_IDLE_LOCK_TIME 255 // stay on
|
||||
|
||||
#define DEFAULT_STEPPING_INVERT_MASK 0 // uint8_t
|
||||
#define DEFAULT_DIRECTION_INVERT_MASK 2 // uint8_t
|
||||
#define DEFAULT_INVERT_ST_ENABLE 0 // boolean
|
||||
#define DEFAULT_INVERT_LIMIT_PINS 1 // boolean
|
||||
#define DEFAULT_INVERT_PROBE_PIN 0 // boolean
|
||||
|
||||
#define DEFAULT_STATUS_REPORT_MASK 1
|
||||
|
||||
|
@@ -58,9 +58,9 @@
|
||||
|
||||
#define COOLANT_MIST_PIN "gpio.2"
|
||||
|
||||
#define X_LIMIT_PIN "gpio.17"
|
||||
#define Y_LIMIT_PIN "gpio.4"
|
||||
#define Z_LIMIT_PIN "gpio.15"
|
||||
#define X_LIMIT_PIN "gpio.17:low"
|
||||
#define Y_LIMIT_PIN "gpio.4:low"
|
||||
#define Z_LIMIT_PIN "gpio.15:low"
|
||||
|
||||
#ifndef ENABLE_SOFTWARE_DEBOUNCE // V1P2 does not have R/C filters
|
||||
#define ENABLE_SOFTWARE_DEBOUNCE
|
||||
@@ -68,25 +68,14 @@
|
||||
|
||||
#define PROBE_PIN "gpio.35"
|
||||
|
||||
// The default value in config.h is wrong for this controller
|
||||
#ifdef INVERT_CONTROL_PIN_MASK
|
||||
#undef INVERT_CONTROL_PIN_MASK
|
||||
#endif
|
||||
|
||||
#define INVERT_CONTROL_PIN_MASK B1110
|
||||
|
||||
#define CONTROL_RESET_PIN "gpio.34" // needs external pullup
|
||||
#define CONTROL_FEED_HOLD_PIN "gpio.36" // needs external pullup
|
||||
#define CONTROL_CYCLE_START_PIN "gpio.39" // needs external pullup
|
||||
#define CONTROL_RESET_PIN "gpio.34:low" // needs external pullup
|
||||
#define CONTROL_FEED_HOLD_PIN "gpio.36:low" // needs external pullup
|
||||
#define CONTROL_CYCLE_START_PIN "gpio.39:low" // needs external pullup
|
||||
|
||||
#define DEFAULT_STEP_PULSE_MICROSECONDS 3
|
||||
#define DEFAULT_STEPPER_IDLE_LOCK_TIME 255 // 255 = Keep steppers on
|
||||
|
||||
#define DEFAULT_STEPPING_INVERT_MASK 0 // uint8_t
|
||||
#define DEFAULT_DIRECTION_INVERT_MASK 0 // uint8_t
|
||||
#define DEFAULT_INVERT_ST_ENABLE 0 // boolean
|
||||
#define DEFAULT_INVERT_LIMIT_PINS 1 // boolean
|
||||
#define DEFAULT_INVERT_PROBE_PIN 0 // boolean
|
||||
|
||||
#define DEFAULT_STATUS_REPORT_MASK 1
|
||||
|
||||
|
@@ -67,31 +67,20 @@
|
||||
//#define COOLANT_MIST_PIN "gpio.2"
|
||||
|
||||
|
||||
#define X_LIMIT_PIN "gpio.2"
|
||||
#define Y_LIMIT_PIN "gpio.4"
|
||||
#define Z_LIMIT_PIN "gpio.15"
|
||||
#define X_LIMIT_PIN "gpio.2:low"
|
||||
#define Y_LIMIT_PIN "gpio.4:low"
|
||||
#define Z_LIMIT_PIN "gpio.15:low"
|
||||
|
||||
#define PROBE_PIN "gpio.35"
|
||||
|
||||
// The default value in config.h is wrong for this controller
|
||||
#ifdef INVERT_CONTROL_PIN_MASK
|
||||
#undef INVERT_CONTROL_PIN_MASK
|
||||
#endif
|
||||
|
||||
#define INVERT_CONTROL_PIN_MASK B1110
|
||||
|
||||
#define CONTROL_RESET_PIN "gpio.34" // needs external pullup
|
||||
#define CONTROL_FEED_HOLD_PIN "gpio.36" // needs external pullup
|
||||
#define CONTROL_CYCLE_START_PIN "gpio.39" // needs external pullup
|
||||
#define CONTROL_RESET_PIN "gpio.34:low" // needs external pullup
|
||||
#define CONTROL_FEED_HOLD_PIN "gpio.36:low" // needs external pullup
|
||||
#define CONTROL_CYCLE_START_PIN "gpio.39:low" // needs external pullup
|
||||
|
||||
#define DEFAULT_STEP_PULSE_MICROSECONDS 3
|
||||
#define DEFAULT_STEPPER_IDLE_LOCK_TIME 255 // 255 = Keep steppers on
|
||||
|
||||
#define DEFAULT_STEPPING_INVERT_MASK 0 // uint8_t
|
||||
#define DEFAULT_DIRECTION_INVERT_MASK 0 // uint8_t
|
||||
#define DEFAULT_INVERT_ST_ENABLE 0 // boolean
|
||||
#define DEFAULT_INVERT_LIMIT_PINS 1 // boolean
|
||||
#define DEFAULT_INVERT_PROBE_PIN 0 // boolean
|
||||
|
||||
#define DEFAULT_STATUS_REPORT_MASK 1
|
||||
|
||||
|
@@ -67,9 +67,9 @@
|
||||
//#define COOLANT_MIST_PIN "gpio.2"
|
||||
|
||||
|
||||
#define X_LIMIT_PIN "gpio.17"
|
||||
#define Y_LIMIT_PIN "gpio.4"
|
||||
#define Z_LIMIT_PIN "gpio.15"
|
||||
#define X_LIMIT_PIN "gpio.17:low"
|
||||
#define Y_LIMIT_PIN "gpio.4:low"
|
||||
#define Z_LIMIT_PIN "gpio.15:low"
|
||||
|
||||
#ifndef ENABLE_SOFTWARE_DEBOUNCE // V1P2 does not have R/C filters
|
||||
#define ENABLE_SOFTWARE_DEBOUNCE
|
||||
@@ -77,25 +77,14 @@
|
||||
|
||||
#define PROBE_PIN "gpio.35"
|
||||
|
||||
// The default value in config.h is wrong for this controller
|
||||
#ifdef INVERT_CONTROL_PIN_MASK
|
||||
#undef INVERT_CONTROL_PIN_MASK
|
||||
#endif
|
||||
|
||||
#define INVERT_CONTROL_PIN_MASK B1110
|
||||
|
||||
#define CONTROL_RESET_PIN "gpio.34" // needs external pullup
|
||||
#define CONTROL_FEED_HOLD_PIN "gpio.36" // needs external pullup
|
||||
#define CONTROL_CYCLE_START_PIN "gpio.39" // needs external pullup
|
||||
#define CONTROL_RESET_PIN "gpio.34:low" // needs external pullup
|
||||
#define CONTROL_FEED_HOLD_PIN "gpio.36:low" // needs external pullup
|
||||
#define CONTROL_CYCLE_START_PIN "gpio.39:low" // needs external pullup
|
||||
|
||||
#define DEFAULT_STEP_PULSE_MICROSECONDS 3
|
||||
#define DEFAULT_STEPPER_IDLE_LOCK_TIME 255 // 255 = Keep steppers on
|
||||
|
||||
#define DEFAULT_STEPPING_INVERT_MASK 0 // uint8_t
|
||||
#define DEFAULT_DIRECTION_INVERT_MASK 0 // uint8_t
|
||||
#define DEFAULT_INVERT_ST_ENABLE 0 // boolean
|
||||
#define DEFAULT_INVERT_LIMIT_PINS 1 // boolean
|
||||
#define DEFAULT_INVERT_PROBE_PIN 0 // boolean
|
||||
|
||||
#define DEFAULT_STATUS_REPORT_MASK 1
|
||||
|
||||
|
@@ -44,12 +44,12 @@
|
||||
#define STEPPERS_DISABLE_PIN "gpio.13"
|
||||
|
||||
#ifdef PEN_LASER_V1
|
||||
#define X_LIMIT_PIN "gpio.2"
|
||||
#define X_LIMIT_PIN "gpio.2:low"
|
||||
#endif
|
||||
#ifdef PEN_LASER_V2
|
||||
#define X_LIMIT_PIN "gpio.15"
|
||||
#define X_LIMIT_PIN "gpio.15:low"
|
||||
#endif
|
||||
#define Y_LIMIT_PIN "gpio.4"
|
||||
#define Y_LIMIT_PIN "gpio.4:low"
|
||||
|
||||
#define USING_SERVO // uncomment to use this feature
|
||||
|
||||
@@ -63,11 +63,7 @@
|
||||
#define DEFAULT_STEP_PULSE_MICROSECONDS 3
|
||||
#define DEFAULT_STEPPER_IDLE_LOCK_TIME 250 // stay on
|
||||
|
||||
#define DEFAULT_STEPPING_INVERT_MASK 0 // uint8_t
|
||||
#define DEFAULT_DIRECTION_INVERT_MASK 0 // uint8_t
|
||||
#define DEFAULT_INVERT_ST_ENABLE 0 // boolean
|
||||
#define DEFAULT_INVERT_LIMIT_PINS 1 // boolean
|
||||
#define DEFAULT_INVERT_PROBE_PIN 0 // boolean
|
||||
|
||||
#define DEFAULT_STATUS_REPORT_MASK 1
|
||||
|
||||
|
@@ -50,7 +50,7 @@
|
||||
|
||||
#define Z_SERVO_PIN "gpio.16"
|
||||
|
||||
#define X_LIMIT_PIN "gpio.4"
|
||||
#define X_LIMIT_PIN "gpio.4:low"
|
||||
|
||||
#define SPINDLE_TYPE SpindleType::NONE
|
||||
|
||||
@@ -63,14 +63,9 @@
|
||||
#endif
|
||||
#define CONTROL_SW_DEBOUNCE_PERIOD 100 // really long debounce
|
||||
|
||||
#ifdef INVERT_CONTROL_PIN_MASK
|
||||
#undef INVERT_CONTROL_PIN_MASK
|
||||
#endif
|
||||
#define INVERT_CONTROL_PIN_MASK B11111111
|
||||
|
||||
#define MACRO_BUTTON_0_PIN "gpio.13"
|
||||
#define MACRO_BUTTON_1_PIN "gpio.12"
|
||||
#define MACRO_BUTTON_2_PIN "gpio.14"
|
||||
#define MACRO_BUTTON_0_PIN "gpio.13:low"
|
||||
#define MACRO_BUTTON_1_PIN "gpio.12:low"
|
||||
#define MACRO_BUTTON_2_PIN "gpio.14:low"
|
||||
|
||||
|
||||
// this 'bot only homes the X axis
|
||||
@@ -82,11 +77,7 @@
|
||||
#define DEFAULT_STEP_PULSE_MICROSECONDS 3
|
||||
#define DEFAULT_STEPPER_IDLE_LOCK_TIME 255 // stay on
|
||||
|
||||
#define DEFAULT_STEPPING_INVERT_MASK 0 // uint8_t
|
||||
#define DEFAULT_DIRECTION_INVERT_MASK 2 // uint8_t
|
||||
#define DEFAULT_INVERT_ST_ENABLE 0 // boolean
|
||||
#define DEFAULT_INVERT_LIMIT_PINS 1 // boolean
|
||||
#define DEFAULT_INVERT_PROBE_PIN 0 // boolean
|
||||
|
||||
#define DEFAULT_STATUS_REPORT_MASK 2 // MPos enabled
|
||||
|
||||
|
@@ -89,9 +89,7 @@
|
||||
|
||||
#define DEFAULT_STATUS_REPORT_MASK 1
|
||||
|
||||
#define DEFAULT_STEPPING_INVERT_MASK 0 // uint8_t
|
||||
#define DEFAULT_DIRECTION_INVERT_MASK 0 // uint8_t
|
||||
#define DEFAULT_INVERT_ST_ENABLE 0 // boolean
|
||||
|
||||
#define DEFAULT_SOFT_LIMIT_ENABLE 0 // false
|
||||
#define DEFAULT_HARD_LIMIT_ENABLE 0 // false
|
||||
|
@@ -115,7 +115,7 @@
|
||||
// #define X_LIMIT_PIN "gpio.2"
|
||||
// #define Y_LIMIT_PIN "gpio.25"
|
||||
// #define Z_LIMIT_PIN "gpio.39"
|
||||
// #define PROBE_PIN "gpio.36"
|
||||
// #define PROBE_PIN "gpio.36:low"
|
||||
|
||||
//Example Quad MOSFET module on socket #3
|
||||
// https://github.com/bdring/6-Pack_CNC_Controller/wiki/Quad-MOSFET-Module
|
||||
@@ -174,7 +174,6 @@
|
||||
#define DEFAULT_HOMING_SEEK_RATE 100
|
||||
#define DEFAULT_HOMING_DIR_MASK (bit(X_AXIS) | bit(Y_AXIS) | bit(Z_AXIS)) // all axes home negative
|
||||
#define DEFAULT_HOMING_ENABLE 1
|
||||
#define DEFAULT_INVERT_LIMIT_PINS 0
|
||||
#define DEFAULT_HOMING_CYCLE_0 (bit(X_AXIS) | bit(Y_AXIS) | bit(Z_AXIS))
|
||||
#define DEFAULT_HOMING_CYCLE_1 0 // override this one in defaults.h
|
||||
|
||||
@@ -192,6 +191,4 @@
|
||||
|
||||
#define DEFAULT_HOMING_PULLOFF -DEFAULT_X_HOMING_MPOS
|
||||
|
||||
#define DEFAULT_INVERT_PROBE_PIN 1
|
||||
|
||||
#define SPINDLE_TYPE SpindleType::NONE
|
||||
|
@@ -87,9 +87,9 @@
|
||||
// #define Z_STEP_PIN "gpio.27"
|
||||
// #define Z_DIRECTION_PIN "gpio.33"
|
||||
|
||||
// #define X_LIMIT_PIN "gpio.17"
|
||||
// #define Y_LIMIT_PIN "gpio.4"
|
||||
// #define Z_LIMIT_PIN "gpio.16"
|
||||
// #define X_LIMIT_PIN "gpio.17:low"
|
||||
// #define Y_LIMIT_PIN "gpio.4:low"
|
||||
// #define Z_LIMIT_PIN "gpio.16:low"
|
||||
|
||||
// Common enable for all steppers. If it is okay to leave
|
||||
// your drivers enabled at all times, you can leave
|
||||
@@ -147,18 +147,10 @@
|
||||
// The default values are established in defaults.h, but you
|
||||
// can override any one of them by definining it here, for example:
|
||||
|
||||
//#define DEFAULT_INVERT_LIMIT_PINS 1
|
||||
//#define DEFAULT_REPORT_INCHES 1
|
||||
|
||||
// === Control Pins
|
||||
|
||||
// If some of the control pin switches are normally closed
|
||||
// (the default is normally open), you can invert some of them
|
||||
// with INVERT_CONTROL_PIN_MASK. The bits in the mask are
|
||||
// Cycle Start, Feed Hold, Reset, Safety Door. To use a
|
||||
// normally open switch on Reset, you would say
|
||||
// #define INVERT_CONTROL_PIN_MASK B1101
|
||||
|
||||
// If your control pins do not have adequate hardware signal
|
||||
// conditioning, you can define these to use software to
|
||||
// reduce false triggering.
|
||||
|
@@ -439,9 +439,6 @@ void motors_set_disable(bool disable) {
|
||||
}
|
||||
|
||||
// invert only inverts the global stepper disable pin.
|
||||
if (step_enable_invert->get()) {
|
||||
disable = !disable; // Apply pin invert.
|
||||
}
|
||||
SteppersDisablePin->get().write(disable);
|
||||
}
|
||||
|
||||
|
@@ -48,8 +48,6 @@ namespace Motors {
|
||||
}
|
||||
|
||||
void StandardStepper::init_step_dir_pins() {
|
||||
_invert_step_pin = bitnum_istrue(step_invert_mask->get(), _axis_index);
|
||||
_invert_dir_pin = bitnum_istrue(dir_invert_mask->get(), _axis_index);
|
||||
_dir_pin.setAttr(Pin::Attr::Output);
|
||||
|
||||
#ifdef USE_RMT_STEPS
|
||||
@@ -78,10 +76,13 @@ namespace Motors {
|
||||
return;
|
||||
}
|
||||
|
||||
// Check if the stepper pin is inverted
|
||||
bool invertStepPin = _step_pin.attributes().has(Pins::PinAttributes::ActiveLow);
|
||||
|
||||
auto step_pin_gpio = _step_pin.getNative(Pin::Capabilities::Output);
|
||||
rmt_set_source_clk(_rmt_chan_num, RMT_BASECLK_APB);
|
||||
rmtConfig.channel = _rmt_chan_num;
|
||||
rmtConfig.tx_config.idle_level = _invert_step_pin ? RMT_IDLE_LEVEL_HIGH : RMT_IDLE_LEVEL_LOW;
|
||||
rmtConfig.tx_config.idle_level = invertStepPin ? RMT_IDLE_LEVEL_HIGH : RMT_IDLE_LEVEL_LOW;
|
||||
rmtConfig.gpio_num = gpio_num_t(step_pin_gpio);
|
||||
rmtItem[0].level0 = rmtConfig.tx_config.idle_level;
|
||||
rmtItem[0].level1 = !rmtConfig.tx_config.idle_level;
|
||||
@@ -112,17 +113,17 @@ namespace Motors {
|
||||
RMT.conf_ch[_rmt_chan_num].conf1.mem_rd_rst = 1;
|
||||
RMT.conf_ch[_rmt_chan_num].conf1.tx_start = 1;
|
||||
#else
|
||||
_step_pin.write(!_invert_step_pin);
|
||||
_step_pin.on();
|
||||
#endif // USE_RMT_STEPS
|
||||
}
|
||||
|
||||
void StandardStepper::unstep() {
|
||||
#ifndef USE_RMT_STEPS
|
||||
_step_pin.write(_invert_step_pin);
|
||||
_step_pin.off();
|
||||
#endif // USE_RMT_STEPS
|
||||
}
|
||||
|
||||
void StandardStepper::set_direction(bool dir) { _dir_pin.write(dir ^ _invert_dir_pin); }
|
||||
void StandardStepper::set_direction(bool dir) { _dir_pin.write(dir); }
|
||||
|
||||
void StandardStepper::set_disable(bool disable) { _disable_pin.write(disable); }
|
||||
}
|
||||
|
@@ -25,8 +25,6 @@ namespace Motors {
|
||||
#ifdef USE_RMT_STEPS
|
||||
rmt_channel_t _rmt_chan_num;
|
||||
#endif
|
||||
bool _invert_step_pin;
|
||||
bool _invert_dir_pin;
|
||||
Pin _step_pin;
|
||||
Pin _dir_pin;
|
||||
Pin _disable_pin;
|
||||
|
@@ -113,6 +113,11 @@ public:
|
||||
return detail->capabilities();
|
||||
}
|
||||
|
||||
Attr attributes() const {
|
||||
auto detail = Pins::PinLookup::_instance.GetPin(_index);
|
||||
return detail->attributes();
|
||||
}
|
||||
|
||||
inline String name() const {
|
||||
auto detail = Pins::PinLookup::_instance.GetPin(_index);
|
||||
return detail->toString();
|
||||
|
@@ -28,6 +28,7 @@ namespace Pins {
|
||||
{}
|
||||
|
||||
PinCapabilities capabilities() const override { return _implementation->capabilities(); }
|
||||
PinAttributes attributes() const override { return _implementation->attributes(); }
|
||||
|
||||
// I/O:
|
||||
void write(int high) override;
|
||||
|
@@ -5,6 +5,7 @@ namespace Pins {
|
||||
ErrorPinDetail::ErrorPinDetail(const PinOptionsParser& options) : PinDetail(0) {}
|
||||
|
||||
PinCapabilities ErrorPinDetail::capabilities() const { return PinCapabilities::Error; }
|
||||
PinAttributes ErrorPinDetail::attributes() const { return PinAttributes::None; }
|
||||
|
||||
void ErrorPinDetail::write(int high) { Assert(false, "Cannot write to an error pin."); }
|
||||
int ErrorPinDetail::read() { Assert(false, "Cannot read from an error pin."); }
|
||||
|
@@ -9,6 +9,7 @@ namespace Pins {
|
||||
ErrorPinDetail(const PinOptionsParser& options);
|
||||
|
||||
PinCapabilities capabilities() const override;
|
||||
PinAttributes attributes() const override;
|
||||
|
||||
// I/O will all give an error:
|
||||
void write(int high) override;
|
||||
|
@@ -110,6 +110,7 @@ namespace Pins {
|
||||
}
|
||||
|
||||
PinCapabilities GPIOPinDetail::capabilities() const { return _capabilities; }
|
||||
PinAttributes GPIOPinDetail::attributes() const { return _attributes; }
|
||||
|
||||
void GPIOPinDetail::write(int high) {
|
||||
Assert(_attributes.has(PinAttributes::Output), "Pin has no output attribute defined. Cannot write to it.");
|
||||
|
@@ -14,6 +14,7 @@ namespace Pins {
|
||||
GPIOPinDetail(uint8_t index, PinOptionsParser options);
|
||||
|
||||
PinCapabilities capabilities() const override;
|
||||
PinAttributes attributes() const override;
|
||||
|
||||
// I/O:
|
||||
void write(int high) override;
|
||||
|
@@ -30,6 +30,7 @@ namespace Pins {
|
||||
}
|
||||
|
||||
PinCapabilities I2SOPinDetail::capabilities() const { return PinCapabilities::Output | PinCapabilities::I2S; }
|
||||
PinAttributes I2SOPinDetail::attributes() const { return _attributes; }
|
||||
|
||||
void I2SOPinDetail::write(int high) {
|
||||
Assert(_attributes.has(PinAttributes::Output), "Pin has no output attribute defined. Cannot write to it.");
|
||||
|
@@ -13,6 +13,7 @@ namespace Pins {
|
||||
I2SOPinDetail(uint8_t index, const PinOptionsParser& options);
|
||||
|
||||
PinCapabilities capabilities() const override;
|
||||
PinAttributes attributes() const override;
|
||||
|
||||
// I/O:
|
||||
void write(int high) override;
|
||||
|
@@ -23,6 +23,7 @@ namespace Pins {
|
||||
PinDetail& operator=(PinDetail&& o) = delete;
|
||||
|
||||
virtual PinCapabilities capabilities() const = 0;
|
||||
virtual PinAttributes attributes() const = 0;
|
||||
|
||||
// I/O:
|
||||
virtual void write(int high) = 0;
|
||||
|
@@ -8,6 +8,7 @@ namespace Pins {
|
||||
// Void pins support basic functionality. It just won't do you any good.
|
||||
return PinCapabilities::Output | PinCapabilities::Input | PinCapabilities::ISR | PinCapabilities::Void;
|
||||
}
|
||||
PinAttributes VoidPinDetail::attributes() const { return PinAttributes::None; }
|
||||
|
||||
void VoidPinDetail::write(int high) {}
|
||||
int VoidPinDetail::read() { return 0; }
|
||||
|
@@ -10,6 +10,7 @@ namespace Pins {
|
||||
VoidPinDetail(const PinOptionsParser& options);
|
||||
|
||||
PinCapabilities capabilities() const override;
|
||||
PinAttributes attributes() const override;
|
||||
|
||||
// I/O:
|
||||
void write(int high) override;
|
||||
|
@@ -59,7 +59,7 @@ void set_probe_direction(bool is_away) {
|
||||
|
||||
// Returns the probe pin state. Triggered = true. Called by gcode parser and probe state monitor.
|
||||
bool probe_get_state() {
|
||||
return ProbePin->get().read() ^ probe_invert->get();
|
||||
return ProbePin->get().read();
|
||||
}
|
||||
|
||||
// Monitors probe pin state and records the system position when detected. Called by the
|
||||
|
@@ -13,16 +13,11 @@ StringSetting* build_info;
|
||||
IntSetting* pulse_microseconds;
|
||||
IntSetting* stepper_idle_lock_time;
|
||||
|
||||
AxisMaskSetting* step_invert_mask;
|
||||
AxisMaskSetting* dir_invert_mask;
|
||||
// TODO Settings - need to call st_generate_step_invert_masks;
|
||||
AxisMaskSetting* homing_dir_mask;
|
||||
AxisMaskSetting* homing_squared_axes;
|
||||
AxisMaskSetting* stallguard_debug_mask;
|
||||
|
||||
FlagSetting* step_enable_invert;
|
||||
FlagSetting* limit_invert;
|
||||
FlagSetting* probe_invert;
|
||||
FlagSetting* report_inches;
|
||||
FlagSetting* soft_limits;
|
||||
// TODO Settings - need to check for HOMING_ENABLE
|
||||
@@ -48,8 +43,6 @@ FloatSetting* rpm_min;
|
||||
FloatSetting* spindle_delay_spinup;
|
||||
FloatSetting* spindle_delay_spindown;
|
||||
FlagSetting* spindle_enbl_off_with_zero_speed;
|
||||
FlagSetting* spindle_enable_invert;
|
||||
FlagSetting* spindle_output_invert;
|
||||
|
||||
FloatSetting* spindle_pwm_off_value;
|
||||
FloatSetting* spindle_pwm_min_value;
|
||||
@@ -331,7 +324,6 @@ void make_settings() {
|
||||
new FloatSetting(EXTENDED, WG, "34", "Spindle/PWM/Off", DEFAULT_SPINDLE_OFF_VALUE, 0.0, 100.0); // these are percentages
|
||||
// IntSetting spindle_pwm_bit_precision(EXTENDED, WG, "Spindle/PWM/Precision", DEFAULT_SPINDLE_BIT_PRECISION, 1, 16);
|
||||
spindle_pwm_freq = new FloatSetting(EXTENDED, WG, "33", "Spindle/PWM/Frequency", DEFAULT_SPINDLE_FREQ, 0, 100000);
|
||||
spindle_output_invert = new FlagSetting(GRBL, WG, NULL, "Spindle/PWM/Invert", DEFAULT_INVERT_SPINDLE_OUTPUT_PIN);
|
||||
|
||||
spindle_delay_spinup = new FloatSetting(EXTENDED, WG, NULL, "Spindle/Delay/SpinUp", DEFAULT_SPINDLE_DELAY_SPINUP, 0, 30);
|
||||
spindle_delay_spindown = new FloatSetting(EXTENDED, WG, NULL, "Spindle/Delay/SpinDown", DEFAULT_SPINDLE_DELAY_SPINUP, 0, 30);
|
||||
@@ -339,8 +331,6 @@ void make_settings() {
|
||||
spindle_enbl_off_with_zero_speed =
|
||||
new FlagSetting(GRBL, WG, NULL, "Spindle/Enable/OffWithSpeed", DEFAULT_SPINDLE_ENABLE_OFF_WITH_ZERO_SPEED);
|
||||
|
||||
spindle_enable_invert = new FlagSetting(GRBL, WG, NULL, "Spindle/Enable/Invert", DEFAULT_INVERT_SPINDLE_ENABLE_PIN);
|
||||
|
||||
// GRBL Non-numbered settings
|
||||
startup_line_0 = new StringSetting(GRBL, WG, "N0", "GCode/Line0", "", checkStartupLine);
|
||||
startup_line_1 = new StringSetting(GRBL, WG, "N1", "GCode/Line1", "", checkStartupLine);
|
||||
@@ -373,11 +363,7 @@ void make_settings() {
|
||||
junction_deviation = new FloatSetting(GRBL, WG, "11", "GCode/JunctionDeviation", DEFAULT_JUNCTION_DEVIATION, 0, 10);
|
||||
status_mask = new IntSetting(GRBL, WG, "10", "Report/Status", DEFAULT_STATUS_REPORT_MASK, 0, 3);
|
||||
|
||||
probe_invert = new FlagSetting(GRBL, WG, "6", "Probe/Invert", DEFAULT_INVERT_PROBE_PIN);
|
||||
limit_invert = new FlagSetting(GRBL, WG, "5", "Limits/Invert", DEFAULT_INVERT_LIMIT_PINS);
|
||||
step_enable_invert = new FlagSetting(GRBL, WG, "4", "Stepper/EnableInvert", DEFAULT_INVERT_ST_ENABLE);
|
||||
dir_invert_mask = new AxisMaskSetting(GRBL, WG, "3", "Stepper/DirInvert", DEFAULT_DIRECTION_INVERT_MASK);
|
||||
step_invert_mask = new AxisMaskSetting(GRBL, WG, "2", "Stepper/StepInvert", DEFAULT_STEPPING_INVERT_MASK);
|
||||
stepper_idle_lock_time = new IntSetting(GRBL, WG, "1", "Stepper/IdleTime", DEFAULT_STEPPER_IDLE_LOCK_TIME, 0, 255);
|
||||
pulse_microseconds = new IntSetting(GRBL, WG, "0", "Stepper/Pulse", DEFAULT_STEP_PULSE_MICROSECONDS, 3, 1000);
|
||||
spindle_type = new EnumSetting(NULL, EXTENDED, WG, NULL, "Spindle/Type", static_cast<int8_t>(SPINDLE_TYPE), &spindleTypes);
|
||||
|
@@ -21,15 +21,11 @@ extern StringSetting* build_info;
|
||||
extern IntSetting* pulse_microseconds;
|
||||
extern IntSetting* stepper_idle_lock_time;
|
||||
|
||||
extern AxisMaskSetting* step_invert_mask;
|
||||
extern AxisMaskSetting* dir_invert_mask;
|
||||
extern AxisMaskSetting* homing_dir_mask;
|
||||
extern AxisMaskSetting* homing_squared_axes;
|
||||
extern AxisMaskSetting* homing_cycle[MAX_N_AXIS];
|
||||
|
||||
extern FlagSetting* step_enable_invert;
|
||||
extern FlagSetting* limit_invert;
|
||||
extern FlagSetting* probe_invert;
|
||||
extern FlagSetting* report_inches;
|
||||
extern FlagSetting* soft_limits;
|
||||
extern FlagSetting* hard_limits;
|
||||
@@ -50,8 +46,6 @@ extern FloatSetting* rpm_min;
|
||||
extern FloatSetting* spindle_delay_spinup;
|
||||
extern FloatSetting* spindle_delay_spindown;
|
||||
extern FlagSetting* spindle_enbl_off_with_zero_speed;
|
||||
extern FlagSetting* spindle_enable_invert;
|
||||
extern FlagSetting* spindle_output_invert;
|
||||
|
||||
extern FloatSetting* spindle_pwm_off_value;
|
||||
extern FloatSetting* spindle_pwm_min_value;
|
||||
|
@@ -131,7 +131,6 @@ namespace Spindles {
|
||||
}
|
||||
|
||||
void _10v::stop() {
|
||||
// inverts are delt with in methods
|
||||
set_enable_pin(false);
|
||||
set_output(_pwm_off_value);
|
||||
}
|
||||
@@ -142,10 +141,6 @@ namespace Spindles {
|
||||
enable = false;
|
||||
}
|
||||
|
||||
if (spindle_enable_invert->get()) {
|
||||
enable = !enable;
|
||||
}
|
||||
|
||||
_enable_pin.write(enable);
|
||||
|
||||
// turn off anything that acts like an enable
|
||||
|
@@ -61,9 +61,6 @@ namespace Spindles {
|
||||
// setup all the pins
|
||||
|
||||
_output_pin = SpindleOutputPin->get();
|
||||
|
||||
_invert_pwm = spindle_output_invert->get();
|
||||
|
||||
_enable_pin = SpindleEnablePin->get();
|
||||
|
||||
_off_with_zero_speed = spindle_enbl_off_with_zero_speed->get();
|
||||
@@ -182,7 +179,6 @@ namespace Spindles {
|
||||
}
|
||||
|
||||
void PWM::stop() {
|
||||
// inverts are delt with in methods
|
||||
set_enable_pin(false);
|
||||
set_output(_pwm_off_value);
|
||||
}
|
||||
@@ -211,10 +207,6 @@ namespace Spindles {
|
||||
|
||||
_current_pwm_duty = duty;
|
||||
|
||||
if (_invert_pwm) {
|
||||
duty = (1 << _pwm_precision) - duty;
|
||||
}
|
||||
|
||||
//grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "set_output(%d)", duty);
|
||||
|
||||
ledcWrite(_pwm_chan_num, duty);
|
||||
@@ -229,10 +221,6 @@ namespace Spindles {
|
||||
enable = false;
|
||||
}
|
||||
|
||||
if (spindle_enable_invert->get()) {
|
||||
enable = !enable;
|
||||
}
|
||||
|
||||
_enable_pin.write(enable);
|
||||
}
|
||||
|
||||
|
@@ -59,7 +59,6 @@ namespace Spindles {
|
||||
uint8_t _pwm_precision;
|
||||
bool _piecewide_linear;
|
||||
bool _off_with_zero_speed;
|
||||
bool _invert_pwm;
|
||||
//uint32_t _pwm_gradient; // Precalulated value to speed up rpm to PWM conversions.
|
||||
|
||||
virtual void set_dir_pin(bool Clockwise);
|
||||
|
@@ -66,9 +66,6 @@ namespace Spindles {
|
||||
}
|
||||
|
||||
void Relay::set_output(uint32_t duty) {
|
||||
#ifdef INVERT_SPINDLE_PWM
|
||||
duty = (duty == 0); // flip duty
|
||||
#endif
|
||||
_output_pin.write(duty > 0); // anything greater
|
||||
}
|
||||
}
|
||||
|
@@ -960,10 +960,6 @@ void IRAM_ATTR Stepper_Timer_Stop() {
|
||||
bool get_stepper_disable() { // returns true if steppers are disabled
|
||||
if (SteppersDisablePin->get() != Pin::UNDEFINED) {
|
||||
bool disabled = SteppersDisablePin->get().read();
|
||||
|
||||
if (step_enable_invert->get()) {
|
||||
disabled = !disabled; // Apply pin invert.
|
||||
}
|
||||
return disabled;
|
||||
} else {
|
||||
return false; // thery are never disabled if there is no pin defined
|
||||
|
@@ -273,9 +273,6 @@ ControlPins system_control_get_state() {
|
||||
pin_states.bit.macro3 = true;
|
||||
}
|
||||
|
||||
#ifdef INVERT_CONTROL_PIN_MASK
|
||||
pin_states.value ^= (INVERT_CONTROL_PIN_MASK & defined_pins.value);
|
||||
#endif
|
||||
return pin_states;
|
||||
}
|
||||
|
||||
|
Reference in New Issue
Block a user