Skip to content

Commit

Permalink
Merge pull request #44 from bdring/Devt
Browse files Browse the repository at this point in the history
Devt
  • Loading branch information
bdring authored Oct 7, 2021
2 parents ca68365 + 57e540a commit 936305d
Show file tree
Hide file tree
Showing 52 changed files with 1,385 additions and 1,037 deletions.
1 change: 1 addition & 0 deletions .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -23,3 +23,4 @@ packages/
pio_machine.h
project.checksum
version.cpp
esptool*.zip
16 changes: 8 additions & 8 deletions FluidNC/src/Control.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,14 +22,14 @@ void Control::init() {
}

void Control::group(Configuration::HandlerBase& handler) {
handler.item("safety_door", _safetyDoor._pin);
handler.item("reset", _reset._pin);
handler.item("feed_hold", _feedHold._pin);
handler.item("cycle_start", _cycleStart._pin);
handler.item("macro0", _macro0._pin);
handler.item("macro1", _macro1._pin);
handler.item("macro2", _macro2._pin);
handler.item("macro3", _macro3._pin);
handler.item("safety_door_pin", _safetyDoor._pin);
handler.item("reset_pin", _reset._pin);
handler.item("feed_hold_pin", _feedHold._pin);
handler.item("cycle_start_pin", _cycleStart._pin);
handler.item("macro0_pin", _macro0._pin);
handler.item("macro1_pin", _macro1._pin);
handler.item("macro2_pin", _macro2._pin);
handler.item("macro3_pin", _macro3._pin);
}

String Control::report() {
Expand Down
4 changes: 2 additions & 2 deletions FluidNC/src/CoolantControl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -80,7 +80,7 @@ void CoolantControl::off() {
}

void CoolantControl::group(Configuration::HandlerBase& handler) {
handler.item("flood", _flood);
handler.item("mist", _mist);
handler.item("flood_pin", _flood);
handler.item("mist_pin", _mist);
handler.item("delay_ms", _delay_ms);
}
8 changes: 2 additions & 6 deletions FluidNC/src/GCode.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,11 +45,7 @@ void gc_init() {

// Load default G54 coordinate system.
gc_state.modal.coord_select = CoordIndex::G54;
if (config->_deactivateParkingUponInit) {
gc_state.modal.override = Override::Disabled;
} else {
gc_state.modal.override = Override::ParkingMotion;
}
gc_state.modal.override = config->_start->_deactivateParking ? Override::Disabled : Override::ParkingMotion;
coords[gc_state.modal.coord_select]->get(gc_state.coord_system);
}

Expand Down Expand Up @@ -1624,7 +1620,7 @@ Error gc_execute_line(char* line, Print& client) {
gc_state.modal.spindle = SpindleState::Disable;
gc_state.modal.coolant = {};
if (config->_enableParkingOverrideControl) {
if (config->_deactivateParkingUponInit) {
if (config->_start->_deactivateParking) {
gc_state.modal.override = Override::Disabled;
} else {
gc_state.modal.override = Override::ParkingMotion;
Expand Down
8 changes: 6 additions & 2 deletions FluidNC/src/Limits.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@
xQueueHandle limit_sw_queue; // used by limit switch debouncing

void limits_init() {
#ifdef LATER // We need to rethink debouncing
if (Machine::Axes::limitMask) {
if (limit_sw_queue == NULL && config->_softwareDebounceMs != 0) {
// setup task used for debouncing
Expand All @@ -31,6 +32,7 @@ void limits_init() {
}
}
}
#endif
}

// Returns limit state as a bit-wise uint32 variable. Each bit indicates an axis limit, where
Expand Down Expand Up @@ -73,6 +75,7 @@ void limits_soft_check(float* target) {
}
}

#ifdef LATER // We need to rethink debouncing
void limitCheckTask(void* pvParameters) {
while (true) {
std::atomic_thread_fence(std::memory_order::memory_order_seq_cst); // read fence for settings
Expand All @@ -87,11 +90,12 @@ void limitCheckTask(void* pvParameters) {
rtAlarm = ExecAlarm::HardLimit; // Indicate hard limit critical event
}
static UBaseType_t uxHighWaterMark = 0;
#ifdef DEBUG_TASK_STACK
# ifdef DEBUG_TASK_STACK
reportTaskStackSize(uxHighWaterMark);
#endif
# endif
}
}
#endif

float limitsMaxPosition(size_t axis) {
auto axisConfig = config->_axes->_axis[axis];
Expand Down
10 changes: 9 additions & 1 deletion FluidNC/src/Machine/Axes.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,6 +39,8 @@ namespace Machine {
a->init();
}
}

config_motors();
}

void IRAM_ATTR Axes::set_disable(int axis, bool disable) {
Expand Down Expand Up @@ -146,6 +148,12 @@ namespace Machine {
config->_stepping->finishPulse();
}

void Axes::config_motors() {
for (int axis = 0; axis < _numberAxis; ++axis) {
_axis[axis]->config_motors();
}
}

// Some small helpers to find the axis index and axis motor index for a given motor. This
// is helpful for some motors that need this info, as well as debug information.
size_t Axes::findAxisIndex(const MotorDrivers::MotorDriver* const driver) const {
Expand Down Expand Up @@ -180,7 +188,7 @@ namespace Machine {
// Configuration helpers:

void Axes::group(Configuration::HandlerBase& handler) {
handler.item("shared_stepper_disable", _sharedStepperDisable);
handler.item("shared_stepper_disable_pin", _sharedStepperDisable);

// Handle axis names xyzabc. handler.section is inferred
// from a template.
Expand Down
1 change: 1 addition & 0 deletions FluidNC/src/Machine/Axes.h
Original file line number Diff line number Diff line change
Expand Up @@ -80,6 +80,7 @@ namespace Machine {
void set_disable(bool disable);
void step(uint8_t step_mask, uint8_t dir_mask);
void unstep();
void config_motors();

// Configuration helpers:
void group(Configuration::HandlerBase& handler) override;
Expand Down
16 changes: 12 additions & 4 deletions FluidNC/src/Machine/Axis.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -7,9 +7,9 @@
namespace Machine {
void Axis::group(Configuration::HandlerBase& handler) {
handler.item("steps_per_mm", _stepsPerMm);
handler.item("max_rate", _maxRate);
handler.item("acceleration", _acceleration);
handler.item("max_travel", _maxTravel);
handler.item("max_rate_mm_per_min", _maxRate);
handler.item("acceleration_mm_per_sec2", _acceleration);
handler.item("max_travel_mm", _maxTravel);
handler.item("soft_limits", _softLimits);
handler.section("homing", _homing);

Expand Down Expand Up @@ -51,6 +51,14 @@ namespace Machine {
}
}

void Axis::config_motors() {
for (int motor = 0; motor < Axis::MAX_MOTORS_PER_AXIS; ++motor) {
auto mot = _motors[motor];
if (mot)
mot->config_motor();
}
}

// Checks if a motor matches this axis:
bool Axis::hasMotor(const MotorDrivers::MotorDriver* const driver) const {
for (size_t i = 0; i < MAX_MOTORS_PER_AXIS; i++) {
Expand Down Expand Up @@ -79,7 +87,7 @@ namespace Machine {

// returns the offset between the pulloffs
// value is positive when motor1 has a larger pulloff
float Axis::pulloffOffset() { return hasDualMotor()? _motors[1]->_pulloff - _motors[0]->_pulloff : 0.0f; }
float Axis::pulloffOffset() { return hasDualMotor() ? _motors[1]->_pulloff - _motors[0]->_pulloff : 0.0f; }

Axis::~Axis() {
for (size_t i = 0; i < MAX_MOTORS_PER_AXIS; i++) {
Expand Down
1 change: 1 addition & 0 deletions FluidNC/src/Machine/Axis.h
Original file line number Diff line number Diff line change
Expand Up @@ -46,6 +46,7 @@ namespace Machine {
float pulloffOffset();

void init();
void config_motors();

~Axis();
};
Expand Down
6 changes: 3 additions & 3 deletions FluidNC/src/Machine/Homing.h
Original file line number Diff line number Diff line change
Expand Up @@ -42,9 +42,9 @@ namespace Machine {
void group(Configuration::HandlerBase& handler) override {
handler.item("cycle", _cycle);
handler.item("positive_direction", _positiveDirection);
handler.item("mpos", _mpos);
handler.item("feed_rate", _feedRate);
handler.item("seek_rate", _seekRate);
handler.item("mpos_mm", _mpos);
handler.item("feed_mm_per_min", _feedRate);
handler.item("seek_mm_per_min", _seekRate);
handler.item("debounce_ms", _debounce_ms);
handler.item("seek_scaler", _seek_scaler);
handler.item("feed_scaler", _feed_scaler);
Expand Down
6 changes: 3 additions & 3 deletions FluidNC/src/Machine/I2SOBus.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,9 +15,9 @@ namespace Machine {
}

void I2SOBus::group(Configuration::HandlerBase& handler) {
handler.item("bck", _bck);
handler.item("data", _data);
handler.item("ws", _ws);
handler.item("bck_pin", _bck);
handler.item("data_pin", _data);
handler.item("ws_pin", _ws);
}

void I2SOBus::init() {
Expand Down
14 changes: 7 additions & 7 deletions FluidNC/src/Machine/MachineConfig.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,19 +41,15 @@ namespace Machine {
handler.section("coolant", _coolant);
handler.section("probe", _probe);
handler.section("macros", _macros);
handler.section("start", _start);

handler.section("user_outputs", _userOutputs);
handler.item("software_debounce_ms", _softwareDebounceMs);
// TODO: Consider putting these under a gcode: hierarchy level? Or motion control?
handler.item("arc_tolerance", _arcTolerance);
handler.item("junction_deviation", _junctionDeviation);
handler.item("arc_tolerance_mm", _arcTolerance);
handler.item("junction_deviation_mm", _junctionDeviation);
handler.item("verbose_errors", _verboseErrors);
handler.item("report_inches", _reportInches);
handler.item("homing_init_lock", _homingInitLock);
handler.item("enable_parking_override_control", _enableParkingOverrideControl);
handler.item("deactivate_parking_upon_init", _deactivateParkingUponInit);
handler.item("check_limits_at_init", _checkLimitsAtInit);
handler.item("disable_laser_during_hold", _disableLaserDuringHold);
handler.item("use_line_numbers", _useLineNumbers);

Spindles::SpindleFactory::factory(handler, _spindles);
Expand Down Expand Up @@ -99,6 +95,10 @@ namespace Machine {
_control = new Control();
}

if (_start == nullptr) {
_start = new Start();
}

if (_spindles.size() == 0) {
log_info("Spindle: using defaults (no spindle)");
_spindles.push_back(new Spindles::Null());
Expand Down
46 changes: 28 additions & 18 deletions FluidNC/src/Machine/MachineConfig.h
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,29 @@
#include "Macros.h"

namespace Machine {
class Start : public Configuration::Configurable {
public:
bool _mustHome = true;
bool _deactivateParking = false;

// At power-up or a reset, the limit switches will be checked
// to ensure they are not already active. If so, and hard
// limits are enabled, Alarm state will be entered instead of
// Idle and the user will be told to check the limits.
bool _checkLimits = false;

public:
Start() {}

void group(Configuration::HandlerBase& handler) {
handler.item("must_home", _mustHome);
handler.item("deactivate_parking", _deactivateParking);
handler.item("check_limits", _checkLimits);
}

~Start() = default;
};

class MachineConfig : public Configuration::Configurable {
public:
MachineConfig() = default;
Expand All @@ -39,33 +62,20 @@ namespace Machine {
UserOutputs* _userOutputs = nullptr;
SDCard* _sdCard = nullptr;
Macros* _macros = nullptr;
Start* _start = nullptr;

Spindles::SpindleList _spindles;

float _arcTolerance = 0.002f;
float _junctionDeviation = 0.01f;
bool _verboseErrors = false;
bool _reportInches = false;
bool _homingInitLock = true;
int _softwareDebounceMs = 0;
float _arcTolerance = 0.002f;
float _junctionDeviation = 0.01f;
bool _verboseErrors = false;
bool _reportInches = false;

// Enables a special set of M-code commands that enables and disables the parking motion.
// These are controlled by `M56`, `M56 P1`, or `M56 Px` to enable and `M56 P0` to disable.
// The command is modal and will be set after a planner sync. Since it is GCode, it is
// executed in sync with GCode commands. It is not a real-time command.
bool _enableParkingOverrideControl = false;
bool _deactivateParkingUponInit = false;

// At power-up or a reset, the limit switches will be checked to ensure they are not active
// before initialization. If a problem is detected and hard limits are enabled, Alarm state
// will be entered instead of Idle, messaging the user to check the limits, rather than idle.
bool _checkLimitsAtInit = true;

// This option will automatically disable the laser during a feed hold by invoking a spindle stop
// override immediately after coming to a stop. However, this also means that the laser still may
// be reenabled by disabling the spindle stop override, if needed. This is purely a safety feature
// to ensure the laser doesn't inadvertently remain powered while at a stop and cause a fire.
bool _disableLaserDuringHold = true;

// Tracks and reports gcode line numbers. Disabled by default.
bool _useLineNumbers = false;
Expand Down
4 changes: 2 additions & 2 deletions FluidNC/src/Machine/Macros.h
Original file line number Diff line number Diff line change
Expand Up @@ -56,8 +56,8 @@ namespace Machine {
// TODO: We could validate the startup lines

void group(Configuration::HandlerBase& handler) override {
handler.item("n0", _startup_line[0]);
handler.item("n1", _startup_line[1]);
handler.item("startup_line0", _startup_line[0]);
handler.item("startup_line1", _startup_line[1]);
handler.item("macro0", _macro[0]);
handler.item("macro1", _macro[1]);
handler.item("macro2", _macro[2]);
Expand Down
14 changes: 10 additions & 4 deletions FluidNC/src/Machine/Motor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,11 +14,11 @@ namespace Machine {
_negLimitPin = new LimitPin(_negPin, _axis, _motorNum, -1, _hardLimits);
_posLimitPin = new LimitPin(_posPin, _axis, _motorNum, 1, _hardLimits);
_allLimitPin = new LimitPin(_allPin, _axis, _motorNum, 0, _hardLimits);
handler.item("limit_neg", _negPin);
handler.item("limit_pos", _posPin);
handler.item("limit_all", _allPin);
handler.item("limit_neg_pin", _negPin);
handler.item("limit_pos_pin", _posPin);
handler.item("limit_all_pin", _allPin);
handler.item("hard_limits", _hardLimits);
handler.item("pulloff", _pulloff);
handler.item("pulloff_mm", _pulloff);
MotorDrivers::MotorFactory::factory(handler, _driver);
}

Expand All @@ -39,6 +39,12 @@ namespace Machine {
_allLimitPin->init();
}

void Motor::config_motor() {
if (_driver != nullptr) {
_driver->config_motor();
}
}

// tru if there is at least one switch for this motor
bool Motor::hasSwitches() { return (_negPin.defined() || _posPin.defined() || _allPin.defined()); }

Expand Down
1 change: 1 addition & 0 deletions FluidNC/src/Machine/Motor.h
Original file line number Diff line number Diff line change
Expand Up @@ -41,6 +41,7 @@ namespace Machine {
bool hasSwitches();
void makeDualSwitches();
void init();
void config_motor();
~Motor();
};
}
6 changes: 3 additions & 3 deletions FluidNC/src/Machine/SPIBus.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,9 +36,9 @@ namespace Machine {
}

void SPIBus::group(Configuration::HandlerBase& handler) {
handler.item("miso", _miso);
handler.item("mosi", _mosi);
handler.item("sck", _sck);
handler.item("miso_pin", _miso);
handler.item("mosi_pin", _mosi);
handler.item("sck_pin", _sck);
}

// XXX it would be nice to have some way to turn off SPI entirely
Expand Down
Loading

0 comments on commit 936305d

Please sign in to comment.