1
0
mirror of https://github.com/bdring/Grbl_Esp32.git synced 2025-08-29 09:10:03 +02:00

Endstops - ISR limit mask handler works

This commit is contained in:
Mitch Bradley
2021-07-19 15:12:07 -10:00
parent 4486849df2
commit 03ef840927
16 changed files with 157 additions and 183 deletions

View File

@@ -121,7 +121,7 @@ void grbl_init() {
// NOTE: The startup script will run after successful completion of the homing cycle, but
// not after disabling the alarm locks. Prevents motion startup blocks from crashing into
// things uncontrollably. Very bad.
if (config->_homingInitLock && homingAxes) {
if (config->_homingInitLock && Machine::Axes::homingMask) {
// If there is an axis with homing configured, enter Alarm state on startup
sys.state = State::Alarm;
}

View File

@@ -37,6 +37,7 @@
#include "Protocol.h" // protocol_execute_realtime
#include "I2SOut.h" // I2S_OUT_DELAY_MS
#include "Platform.h"
#include "Machine/Axes.h"
#include <freertos/task.h>
#include <freertos/queue.h>
@@ -45,35 +46,8 @@
#include <algorithm> // min, max
#include <atomic> // fence
AxisMask limitAxes = 0; // Axes that have limit switches
AxisMask homingAxes = 0; // Axes that have homing configured
xQueueHandle limit_sw_queue; // used by limit switch debouncing
void IRAM_ATTR isr_limit_switches(void* /*unused */) {
// Ignore limit switches if already in an alarm state or in-process of executing an alarm.
// When in the alarm state, Grbl should have been reset or will force a reset, so any pending
// moves in the planner and serial buffers are all cleared and newly sent blocks will be
// locked out until a homing cycle or a kill lock command. Allows the user to disable the hard
// limit setting if their limits are constantly triggering after a reset and move their axes.
if (sys.state != State::Alarm && sys.state != State::ConfigAlarm && sys.state != State::Homing) {
if (sys_rt_exec_alarm == ExecAlarm::None) {
if (config->_softwareDebounceMs) {
// we will start a task that will recheck the switches after a small delay
int evt;
xQueueSendFromISR(limit_sw_queue, &evt, NULL);
} else {
// Check limit pin state.
if (limits_check(limitAxes)) {
log_debug("Hard limits");
mc_reset(); // Initiate system kill.
sys_rt_exec_alarm = ExecAlarm::HardLimit; // Indicate hard limit critical event
}
}
}
}
}
// Returns true if an error occurred
static ExecAlarm limits_handle_errors(bool approach, uint8_t cycle_mask) {
// This checks some of the events that would normally be handled
@@ -119,7 +93,7 @@ static void limits_go_home(uint8_t cycle_mask, uint32_t n_locate_cycles) {
auto axes = config->_axes;
auto n_axis = axes->_numberAxis;
cycle_mask &= homingAxes;
cycle_mask &= Machine::Axes::homingMask;
// Initialize plan data struct for homing motion. Spindle and coolant are disabled.
@@ -373,8 +347,6 @@ static void limits_run_one_homing_cycle(AxisMask homing_mask) {
}
void limits_run_homing_cycles(AxisMask axis_mask) {
limits_homing_mode(); // Disable hard limits pin change register for cycle duration
// -------------------------------------------------------------------------------------
// Perform homing routine. NOTE: Special motion case. Only system reset works.
if (axis_mask != HOMING_CYCLE_ALL) {
@@ -405,39 +377,10 @@ void limits_run_homing_cycles(AxisMask axis_mask) {
sys.state = State::Alarm;
}
}
limits_run_mode(); // Disable hard limits pin change register for cycle duration
}
void limits_init() {
auto axes = config->_axes;
auto n_axis = axes->_numberAxis;
for (int axis = 0; axis < n_axis; axis++) {
if (axes->_axis[axis]->_homing) {
bitnum_true(homingAxes, axis);
}
for (int gang_index = 0; gang_index < 2; gang_index++) {
auto gangConfig = axes->_axis[axis]->_gangs[gang_index];
if (gangConfig->_endstops != nullptr && gangConfig->_endstops->_dual.defined()) {
if (!limitAxes) {
log_info("Initializing endstops...");
}
bitnum_true(limitAxes, axis);
Pin& pin = gangConfig->_endstops->_dual;
log_info(reportAxisNameMsg(axis, gang_index) << " limit on " << pin.name());
pin.setAttr(Pin::Attr::Input | Pin::Attr::ISR);
if (gangConfig->_endstops->_hardLimits) {
pin.attachInterrupt(isr_limit_switches, CHANGE, nullptr);
} else {
pin.detachInterrupt();
}
}
}
}
if (limitAxes) {
if (Machine::Axes::limitMask) {
if (limit_sw_queue == NULL && config->_softwareDebounceMs != 0) {
// setup task used for debouncing
if (limit_sw_queue == NULL) {
@@ -453,67 +396,19 @@ void limits_init() {
}
}
void limits_homing_mode() {
auto n_axis = config->_axes->_numberAxis;
for (int axis = 0; axis < n_axis; axis++) {
for (int gang_index = 0; gang_index < 2; gang_index++) {
auto gangConfig = config->_axes->_axis[axis]->_gangs[gang_index];
if (gangConfig->_endstops != nullptr && gangConfig->_endstops->_dual.defined()) {
Pin& pin = gangConfig->_endstops->_dual;
pin.detachInterrupt();
}
}
}
}
void limits_run_mode() {
auto n_axis = config->_axes->_numberAxis;
for (int axis = 0; axis < n_axis; axis++) {
for (int gang_index = 0; gang_index < 2; gang_index++) {
auto gangConfig = config->_axes->_axis[axis]->_gangs[gang_index];
if (gangConfig->_endstops != nullptr && gangConfig->_endstops->_dual.defined()) {
if (gangConfig->_endstops->_hardLimits) {
Pin& pin = gangConfig->_endstops->_dual;
pin.attachInterrupt(isr_limit_switches, CHANGE, nullptr);
}
}
}
}
}
static bool limits_check_axis(int axis) {
for (int gang_index = 0; gang_index < 2; gang_index++) {
auto gangConfig = config->_axes->_axis[axis]->_gangs[gang_index];
if (gangConfig->_endstops != nullptr && gangConfig->_endstops->_dual.defined()) {
Pin& pin = gangConfig->_endstops->_dual;
if (pin.read()) {
return true;
}
}
}
return false;
}
// Check the limit switches for the axes listed in check_mask.
// Return a mask of the switches that are engaged.
AxisMask limits_check(AxisMask check_mask) {
AxisMask pinMask = 0;
auto n_axis = config->_axes->_numberAxis;
for (int axis = 0; axis < n_axis; axis++) {
if (bitnum_istrue(check_mask, axis)) {
if (limits_check_axis(axis)) {
bitnum_true(pinMask, axis);
}
}
}
return pinMask;
// Expand the bitmask to include both gangs
bit_true(check_mask, check_mask << MAX_N_AXIS);
return bit_istrue(Machine::Axes::posLimitMask, check_mask) || bit_istrue(Machine::Axes::negLimitMask, check_mask);
}
// 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).
AxisMask limits_get_state() {
return limits_check(limitAxes);
return limits_check(Machine::Axes::limitMask);
}
// Performs a soft limit check. Called from mcline() only. Assumes the machine has been homed,
@@ -596,16 +491,6 @@ bool WEAK_LINK limitsCheckTravel(float* target) {
return false;
}
bool limitsSwitchDefined(uint8_t axis, uint8_t gang_index) {
auto gangConfig = config->_axes->_axis[axis]->_gangs[gang_index];
if (gangConfig->_endstops != nullptr) {
return gangConfig->_endstops->_dual.defined();
} else {
return false;
}
}
bool WEAK_LINK user_defined_homing(AxisMask cycle_mask) {
return false;
}

View File

@@ -48,25 +48,13 @@ void limits_soft_check(float* target);
float limitsMaxPosition(uint8_t axis);
float limitsMinPosition(uint8_t axis);
// check if a switch has been defined
bool limitsSwitchDefined(uint8_t axis, uint8_t gang_index);
extern AxisMask homingAxes;
extern AxisMask limitAxes;
// Private
// Returns limit state under mask
AxisMask limits_check(AxisMask check_mask);
void isr_limit_switches(void* /*unused*/);
// A task that runs after a limit switch interrupt.
void limitCheckTask(void* pvParameters);
// Internal factor used by limits_soft_check
bool limitsCheckTravel(float* target);
void limits_homing_mode();
void limits_run_mode();

View File

@@ -8,8 +8,13 @@
#include "MachineConfig.h" // config->
namespace Machine {
uint32_t Axes::posLimitMask = 0;
uint32_t Axes::negLimitMask = 0;
uint32_t Axes::homingMask = 0;
uint32_t Axes::limitMask = 0;
Axes::Axes() : _axis() {
for (int i = 0; i < MAX_NUMBER_AXIS; ++i) {
for (int i = 0; i < MAX_N_AXIS; ++i) {
_axis[i] = nullptr;
}
}
@@ -24,18 +29,9 @@ namespace Machine {
// certain motors need features to be turned on. Check them here
for (uint8_t axis = X_AXIS; axis < _numberAxis; axis++) {
for (uint8_t gang_index = 0; gang_index < Axis::MAX_NUMBER_GANGED; gang_index++) {
auto a = _axis[axis];
if (a) {
auto g = a->_gangs[gang_index];
if (g) {
auto m = g->_motor;
if (m == nullptr) {
m = new Motors::Nullmotor();
}
m->init();
}
}
auto a = _axis[axis];
if (a) {
a->init();
}
}
}
@@ -199,10 +195,12 @@ namespace Machine {
handler.item("number_axis", _numberAxis);
handler.item("shared_stepper_disable", _sharedStepperDisable);
// Handle axis names xyzabc. handler.section is inferred
// from a template.
char tmp[3];
tmp[2] = '\0';
for (size_t i = 0; i < MAX_NUMBER_AXIS; ++i) {
for (size_t i = 0; i < MAX_N_AXIS; ++i) {
tmp[0] = tolower(_names[i]);
tmp[1] = '\0';
@@ -211,7 +209,7 @@ namespace Machine {
}
void Axes::afterParse() {
for (size_t i = 0; i < MAX_NUMBER_AXIS; ++i) {
for (size_t i = 0; i < MAX_N_AXIS; ++i) {
if (_axis[i] == nullptr) {
_axis[i] = new Axis(i);
}
@@ -219,7 +217,7 @@ namespace Machine {
}
Axes::~Axes() {
for (int i = 0; i < MAX_NUMBER_AXIS; ++i) {
for (int i = 0; i < MAX_N_AXIS; ++i) {
delete _axis[i];
}
}

View File

@@ -27,20 +27,25 @@ namespace Motors {
namespace Machine {
class Axes : public Configuration::Configurable {
static const int MAX_NUMBER_AXIS = 6;
static constexpr const char* _names = "XYZABC";
static constexpr const char* _names = "XYZABC";
bool _switchedStepper = false;
public:
Axes();
inline char axisName(int index) { return index < MAX_NUMBER_AXIS ? _names[index] : '?'; }
// Bitmasks to collect information about axes that have limits and homing
static uint32_t posLimitMask;
static uint32_t negLimitMask;
static uint32_t homingMask;
static uint32_t limitMask;
inline char axisName(int index) { return index < MAX_N_AXIS ? _names[index] : '?'; }
Pin _sharedStepperDisable;
int _numberAxis = 3;
Axis* _axis[MAX_NUMBER_AXIS];
Axis* _axis[MAX_N_AXIS];
// Some small helpers to find the axis index and axis ganged index for a given motor. This
// is helpful for some motors that need this info, as well as debug information.
@@ -57,9 +62,15 @@ namespace Machine {
}
inline bool hasHardLimits() const {
for (int i = 0; i < _numberAxis; ++i) {
for (int j = 0; j < Axis::MAX_NUMBER_GANGED; ++j) {
if (_axis[i]->_gangs[j]->_endstops != nullptr && _axis[i]->_gangs[j]->_endstops->_hardLimits) {
for (int axis = 0; axis < _numberAxis; ++axis) {
auto a = _axis[axis];
auto ae = a->_endstops;
if (ae && ae->_hardLimits) {
return true;
}
for (int gang = 0; gang < Axis::MAX_NUMBER_GANGED; ++gang) {
auto ge = a->_gangs[gang]->_endstops;
if (ge && ge->_hardLimits) {
return true;
}
}

View File

@@ -1,3 +1,4 @@
#include "Axes.h"
#include "Axis.h"
#include <cstring>
@@ -10,6 +11,7 @@ namespace Machine {
handler.item("max_travel", _maxTravel);
handler.item("soft_limits", _softLimits);
handler.section("endstops", _endstops, _axis, -1);
handler.section("homing", _homing);
char tmp[6];
@@ -20,18 +22,31 @@ namespace Machine {
tmp[4] = char(g + '0');
tmp[5] = '\0';
handler.section(tmp, _gangs[g], g);
handler.section(tmp, _gangs[g], _axis, g);
}
}
void Axis::afterParse() {
for (size_t i = 0; i < MAX_NUMBER_GANGED; ++i) {
if (_gangs[i] == nullptr) {
_gangs[i] = new Gang(i);
_gangs[i] = new Gang(_axis, i);
}
}
}
void Axis::init() {
for (uint8_t gang_index = 0; gang_index < Axis::MAX_NUMBER_GANGED; gang_index++) {
_gangs[gang_index]->init();
}
if (_homing) {
_homing->init();
bitnum_true(Axes::homingMask, _axis);
}
if (_endstops) {
_endstops->init();
}
}
// Checks if a motor matches this axis:
bool Axis::hasMotor(const Motors::Motor* const motor) const {
for (uint8_t gang_index = 0; gang_index < MAX_NUMBER_GANGED; gang_index++) {

View File

@@ -19,8 +19,10 @@
*/
#include "../Configuration/Configurable.h"
// #include "Axes.h"
#include "Gang.h"
#include "Homing.h"
#include "Endstops.h"
namespace Motors {
class Motor;
@@ -28,8 +30,10 @@ namespace Motors {
namespace Machine {
class Axis : public Configuration::Configurable {
int _axis;
public:
Axis(int currentAxis): _index(currentAxis) {
Axis(int currentAxis) : _axis(currentAxis) {
for (int i = 0; i < MAX_NUMBER_GANGED; ++i) {
_gangs[i] = nullptr;
}
@@ -37,8 +41,9 @@ namespace Machine {
static const int MAX_NUMBER_GANGED = 2;
Gang* _gangs[MAX_NUMBER_GANGED];
Homing* _homing = nullptr;
Gang* _gangs[MAX_NUMBER_GANGED];
Homing* _homing = nullptr;
Endstops* _endstops = nullptr;
float _stepsPerMm = 320.0f;
float _maxRate = 1000.0f;
@@ -46,8 +51,6 @@ namespace Machine {
float _maxTravel = 200.0f;
bool _softLimits = false;
int _index;
// Configuration system helpers:
void group(Configuration::HandlerBase& handler) override;
void afterParse() override;
@@ -55,6 +58,8 @@ namespace Machine {
// Checks if a motor matches this axis:
bool hasMotor(const Motors::Motor* const motor) const;
void init();
~Axis();
};
}

View File

@@ -19,6 +19,17 @@
*/
namespace Machine {
Endstops::Endstops(int axis, int gang) : _axis(axis), _gang(gang) {
_negLimitPin = new LimitPin(_negPin, _axis, _gang, -1, _hardLimits);
_posLimitPin = new LimitPin(_posPin, _axis, _gang, 1, _hardLimits);
_allLimitPin = new LimitPin(_allPin, _axis, _gang, 0, _hardLimits);
}
void Endstops::init() {
_negLimitPin->init();
_posLimitPin->init();
_allLimitPin->init();
}
void Endstops::validate() const {
// if (_dual.defined()) {
@@ -31,9 +42,9 @@ namespace Machine {
}
void Endstops::group(Configuration::HandlerBase& handler) {
// handler.item("positive", _positive);
// handler.item("negative", _negative);
handler.item("dual", _dual);
handler.item("limit_neg", _negPin);
handler.item("limit_pos", _posPin);
handler.item("limit_all", _allPin);
handler.item("hard_limits", _hardLimits);
}
}

View File

@@ -19,16 +19,25 @@
*/
#include "../Configuration/Configurable.h"
#include "../System.h" // AxisMask
#include "LimitPin.h"
namespace Machine {
class Endstops : public Configuration::Configurable {
LimitPin* _negLimitPin;
LimitPin* _posLimitPin;
LimitPin* _allLimitPin;
int _axis;
int _gang; // 0:gang0, 1:gang1, or -1:axis
public:
Endstops() = default;
Endstops(int axis, int gang);
// Pin _positive;
// Pin _negative;
Pin _dual;
bool _hardLimits = false;
Pin _negPin;
Pin _posPin;
Pin _allPin;
bool _hardLimits = true;
void init();
// Configuration system helpers:
void validate() const override;

View File

@@ -20,18 +20,27 @@
#include "../Motors/Motor.h"
#include "../Motors/NullMotor.h"
#include "Endstops.h"
namespace Machine {
void Gang::group(Configuration::HandlerBase& handler) {
handler.section("endstops", _endstops);
handler.section("endstops", _endstops, _axis, _gang);
Motors::MotorFactory::factory(handler, _motor);
}
void Gang::afterParse() {
if (_motor == nullptr) {
_motor = new Motors::Nullmotor();
}
}
void Gang::init() {
_motor->init();
if (_endstops) {
_endstops->init();
}
}
Gang::~Gang() {
delete _motor;
delete _endstops;

View File

@@ -20,18 +20,22 @@
#include "../Configuration/Configurable.h"
#include "Endstops.h"
namespace Motors {
class Motor;
}
namespace Machine {
class Gang : public Configuration::Configurable {
public:
Gang(int index) : _index(index) {}
class Endstops;
}
namespace Machine {
class Gang : public Configuration::Configurable {
int _axis;
int _gang;
public:
Gang(int axis, int gang) : _axis(axis), _gang(gang) {}
int _index;
Motors::Motor* _motor = nullptr;
Endstops* _endstops = nullptr;
@@ -39,6 +43,7 @@ namespace Machine {
void group(Configuration::HandlerBase& handler) override;
void afterParse() override;
void init();
~Gang();
};
}

View File

@@ -53,5 +53,7 @@ namespace Machine {
handler.item("seek_scaler", _seek_scaler);
handler.item("feed_scaler", _feed_scaler);
}
void init() {}
};
}

View File

@@ -45,6 +45,14 @@ namespace Motors {
public:
Motor() = default;
static constexpr int max_n_axis = MAX_N_AXIS;
static constexpr uint32_t axis_mask = (1 << max_n_axis) - 1;
static inline int axisGangToMotor(int gang, int axis) { return (gang << max_n_axis) + axis; }
static inline void motorToAxisGang(int& gang, int& axis, int motor) {
gang = motor >> max_n_axis;
axis = motor & ~axis_mask;
}
// init() establishes configured motor parameters. It is called after
// all motor objects have been constructed.
virtual void init() {}

View File

@@ -15,6 +15,7 @@
#include "Limits.h" // homingAxes
#include "SettingsDefinitions.h" // build_info
#include "Protocol.h" // LINE_BUFFER_SIZE
#include "Uart.h" // Uart0.write()
#include <cstring>
#include <map>
@@ -263,7 +264,7 @@ Error home(int cycle) {
return Error::ConfigurationInvalid;
}
if (!homingAxes) {
if (!Machine::Axes::homingMask) {
return Error::SettingDisabled;
}
if (config->_control->system_check_safety_door_ajar()) {
@@ -307,6 +308,31 @@ Error home_b(const char* value, WebUI::AuthenticationLevel auth_level, WebUI::ES
Error home_c(const char* value, WebUI::AuthenticationLevel auth_level, WebUI::ESPResponseStream* out) {
return home(bit(C_AXIS));
}
void write_limit_set(uint32_t mask) {
const char* axisName = "xyzabcXYZABC";
for (int i = 0; i < MAX_N_AXIS * 2; i++) {
Uart0.write(bitnum_istrue(mask, i) ? uint8_t(axisName[i]) : ' ');
}
}
Error show_limits(const char* value, WebUI::AuthenticationLevel auth_level, WebUI::ESPResponseStream* out) {
Uart0.write("Homing Axes: ");
write_limit_set(Machine::Axes::homingMask);
Uart0.write('\n');
Uart0.write("Limit Axes: ");
write_limit_set(Machine::Axes::limitMask);
Uart0.write('\n');
Uart0.write("PosLimitPins NegLimitPins\n");
do {
write_limit_set(Machine::Axes::posLimitMask);
Uart0.write(' ');
write_limit_set(Machine::Axes::negLimitMask);
Uart0.write('\r');
vTaskDelay(400);
} while (!rtFeedHold);
rtFeedHold = false;
Uart0.write('\n');
return Error::Ok;
}
Error sleep_grbl(const char* value, WebUI::AuthenticationLevel auth_level, WebUI::ESPResponseStream* out) {
rtSleep = true;
return Error::Ok;
@@ -489,6 +515,7 @@ void make_grbl_commands() {
new GrblCommand("$", "GrblSettings/List", report_normal_settings, notCycleOrHold);
new GrblCommand("+", "ExtendedSettings/List", report_extended_settings, notCycleOrHold);
new GrblCommand("L", "GrblNames/List", list_grbl_names, notCycleOrHold);
new GrblCommand("Limits", "Limits/Show", show_limits, notCycleOrHold);
new GrblCommand("S", "Settings/List", list_settings, notCycleOrHold);
new GrblCommand("SC", "Settings/ListChanged", list_changed_settings, notCycleOrHold);
new GrblCommand("P", "Pins/List", list_pins, notCycleOrHold);

View File

@@ -100,9 +100,9 @@ Error execute_line(char* line, uint8_t client, WebUI::AuthenticationLevel auth_l
bool can_park() {
if (config->_enableParkingOverrideControl) {
return sys.override_ctrl == Override::ParkingMotion && homingAxes && !config->_laserMode;
return sys.override_ctrl == Override::ParkingMotion && Machine::Axes::homingMask && !config->_laserMode;
} else {
return homingAxes && !config->_laserMode;
return Machine::Axes::homingMask && !config->_laserMode;
}
}

View File

@@ -119,6 +119,7 @@ public:
if (esp_err_t err = nvs_get_stats(NULL, &stats)) {
return Error::NvsGetStatsFailed;
}
log_info("NVS Used:" << stats.used_entries << " Free:" << stats.free_entries << " Total:" << stats.total_entries);
#if 0 // The SDK we use does not have this yet
nvs_iterator_t it = nvs_entry_find(NULL, NULL, NVS_TYPE_ANY);