diff --git a/FluidNC/ld/esp32/README.md b/FluidNC/ld/esp32/README.md index 38b7ea99e..b23cca0a8 100644 --- a/FluidNC/ld/esp32/README.md +++ b/FluidNC/ld/esp32/README.md @@ -57,13 +57,6 @@ vtables from several code modules to be placed in RAM. We use the INCLUDE technique to isolate the changes into one new file, for easier maintenance. -For the wifi and noradio builds, the vtables are placed in IRAM because -there is enough free space there, freeing up some DRAM to use as heap. -For the bt build, bluetooth functions use so much IRAM that there is -not enough room for the vtables, so they are placed into DRAM. The -bt version does not need as much heap as the wifi version (wifi needs -quite a few large buffers for wifi packets). - ### Making PlatformIO Use the Modified File To make PlatformIO use the modified sections.ld instead diff --git a/FluidNC/ld/esp32/bt/sections.ld b/FluidNC/ld/esp32/bt/sections.ld index 50f150df4..b75ea73df 100644 --- a/FluidNC/ld/esp32/bt/sections.ld +++ b/FluidNC/ld/esp32/bt/sections.ld @@ -558,8 +558,6 @@ SECTIONS *libspi_flash.a:spi_flash_chip_winbond.*(.rodata .rodata.*) *libspi_flash.a:spi_flash_rom_patch.*(.rodata .rodata.*) - /* For the bluetooth build we must use DRAM for the ISR vtables */ - /* because there is not enough space left in IRAM */ INCLUDE ../vtable_in_dram.ld _data_end = ABSOLUTE(.); diff --git a/FluidNC/ld/esp32/noradio/sections.ld b/FluidNC/ld/esp32/noradio/sections.ld index 6b5f7e18d..b75ea73df 100644 --- a/FluidNC/ld/esp32/noradio/sections.ld +++ b/FluidNC/ld/esp32/noradio/sections.ld @@ -558,6 +558,8 @@ SECTIONS *libspi_flash.a:spi_flash_chip_winbond.*(.rodata .rodata.*) *libspi_flash.a:spi_flash_rom_patch.*(.rodata .rodata.*) + INCLUDE ../vtable_in_dram.ld + _data_end = ABSOLUTE(.); . = ALIGN(4); } > dram0_0_seg @@ -775,11 +777,6 @@ SECTIONS *(.iram2.coredump .iram2.coredump.*) _coredump_iram_end = ABSOLUTE(.); - /* For the wifi build we can use IRAM for the ISR vtables */ - /* because there is enough space left there, conserving */ - /* DRAM which is needed for extra heap space */ - INCLUDE ../vtable_in_dram.ld - _iram_data_end = ABSOLUTE(.); } > iram0_0_seg diff --git a/FluidNC/ld/esp32/vtable_in_dram.ld b/FluidNC/ld/esp32/vtable_in_dram.ld index ff51ecba0..0a662d6c2 100644 --- a/FluidNC/ld/esp32/vtable_in_dram.ld +++ b/FluidNC/ld/esp32/vtable_in_dram.ld @@ -1,28 +1,8 @@ /* List of files and sections to place in RAM instead of FLASH */ /* See README.md in this directory for a complete explanation */ - *Laser.cpp.o(.rodata .rodata.* .xt.prop .xt.prop.*) - /* All files whose name ends with Spindle.cpp */ - **Spindle.cpp.o(.rodata .rodata.* .xt.prop .xt.prop.*) - - /* Motors */ - *Motor.cpp.o(.rodata .rodata.* .xt.prop .xt.prop.*) - *Dynamixel2.cpp.o(.rodata .rodata.* .xt.prop .xt.prop.*) - *MotorDriver.cpp.o(.rodata .rodata.* .xt.prop .xt.prop.*) - *NullMotor.cpp.o(.rodata .rodata.* .xt.prop .xt.prop.*) - *RcServo.cpp.o(.rodata .rodata.* .xt.prop .xt.prop.*) - *Servo.cpp.o(.rodata .rodata.* .xt.prop .xt.prop.*) - *Solenoid.cpp.o(.rodata .rodata.* .xt.prop .xt.prop.*) - *StandardStepper.cpp.o(.rodata .rodata.* .xt.prop .xt.prop.*) - *StepStick.cpp.o(.rodata .rodata.* .xt.prop .xt.prop.*) - *TMC*Driver.cpp.o(.rodata .rodata.* .xt.prop .xt.prop.*) - *TrinamicBase.cpp.o(.rodata .rodata.* .xt.prop .xt.prop.*) - *TrinamicSpiDriver.cpp.o(.rodata .rodata.* .xt.prop .xt.prop.*) - *TrinamicUartDriver.cpp.o(.rodata .rodata.* .xt.prop .xt.prop.*) - *UnipolarMotor.cpp.o(.rodata .rodata.* .xt.prop .xt.prop.*) - /* Pin Details */ - **Detail.cpp.o(.rodata .rodata.* .xt.prop .xt.prop.*) - *PwmPin.cpp.o(.rodata .rodata.* .xt.prop .xt.prop.*) - *Pin.cpp.o(.rodata .rodata.* .xt.prop .xt.prop.*) + /* An earlier version included .xt.prop and .xt.prop.* but */ + /* it turns out that those bits can stay in FLASH */ + **Spindle.cpp.o(.rodata .rodata.*) diff --git a/FluidNC/ld/esp32/wifi/sections.ld b/FluidNC/ld/esp32/wifi/sections.ld index 6b5f7e18d..b75ea73df 100644 --- a/FluidNC/ld/esp32/wifi/sections.ld +++ b/FluidNC/ld/esp32/wifi/sections.ld @@ -558,6 +558,8 @@ SECTIONS *libspi_flash.a:spi_flash_chip_winbond.*(.rodata .rodata.*) *libspi_flash.a:spi_flash_rom_patch.*(.rodata .rodata.*) + INCLUDE ../vtable_in_dram.ld + _data_end = ABSOLUTE(.); . = ALIGN(4); } > dram0_0_seg @@ -775,11 +777,6 @@ SECTIONS *(.iram2.coredump .iram2.coredump.*) _coredump_iram_end = ABSOLUTE(.); - /* For the wifi build we can use IRAM for the ISR vtables */ - /* because there is enough space left there, conserving */ - /* DRAM which is needed for extra heap space */ - INCLUDE ../vtable_in_dram.ld - _iram_data_end = ABSOLUTE(.); } > iram0_0_seg diff --git a/FluidNC/src/Kinematics/Cartesian.cpp b/FluidNC/src/Kinematics/Cartesian.cpp index b318f5dc5..f45b614db 100644 --- a/FluidNC/src/Kinematics/Cartesian.cpp +++ b/FluidNC/src/Kinematics/Cartesian.cpp @@ -294,12 +294,11 @@ namespace Kinematics { auto n_axis = axes->_numberAxis; for (int axis = 0; axis < n_axis; axis++) { if (bitnum_is_true(axisMask, axis)) { - auto paxis = axes->_axis[axis]; if (bitnum_is_true(motors, Machine::Axes::motor_bit(axis, 0))) { - paxis->_motors[0]->unlimit(); + Stepping::unlimit(axis, 0); } if (bitnum_is_true(motors, Machine::Axes::motor_bit(axis, 1))) { - paxis->_motors[1]->unlimit(); + Stepping::unlimit(axis, 1); } } } diff --git a/FluidNC/src/Kinematics/CoreXY.cpp b/FluidNC/src/Kinematics/CoreXY.cpp index 7a531b9f3..c3e9b80d9 100644 --- a/FluidNC/src/Kinematics/CoreXY.cpp +++ b/FluidNC/src/Kinematics/CoreXY.cpp @@ -75,7 +75,7 @@ namespace Kinematics { auto n_axis = axes->_numberAxis; for (size_t axis = X_AXIS; axis < n_axis; axis++) { if (bitnum_is_true(axisMask, axis)) { - axes->_axis[axis]->_motors[0]->unlimit(); + Stepping::unlimit(axis, 0); } } } diff --git a/FluidNC/src/Machine/Axes.cpp b/FluidNC/src/Machine/Axes.cpp index 0fff03c1d..dd47ddf2e 100644 --- a/FluidNC/src/Machine/Axes.cpp +++ b/FluidNC/src/Machine/Axes.cpp @@ -93,9 +93,9 @@ namespace Machine { auto a = _axis[axis]; if (a != nullptr) { for (size_t motor = 0; motor < Axis::MAX_MOTORS_PER_AXIS; motor++) { + Stepping::unblock(axis, motor); auto m = _axis[axis]->_motors[motor]; if (m) { - m->unblock(); if (m->_driver->set_homing_mode(isHoming)) { set_bitnum(motorsCanHome, motor_bit(axis, motor)); } @@ -108,62 +108,6 @@ namespace Machine { return motorsCanHome; } - void IRAM_ATTR Axes::step(uint8_t step_mask, uint8_t dir_mask) { - auto n_axis = _numberAxis; - //log_info("motors_set_direction_pins:0x%02X", onMask); - - // Set the direction pins, but optimize for the common - // situation where the direction bits haven't changed. - static uint8_t previous_dir = 255; // should never be this value - if (dir_mask != previous_dir) { - previous_dir = dir_mask; - - for (int axis = X_AXIS; axis < n_axis; axis++) { - bool thisDir = bitnum_is_true(dir_mask, axis); - - for (size_t motor = 0; motor < Axis::MAX_MOTORS_PER_AXIS; motor++) { - auto m = _axis[axis]->_motors[motor]; - if (m) { - m->_driver->set_direction(thisDir); - } - } - } - config->_stepping->waitDirection(); - } - - // Turn on step pulses for motors that are supposed to step now - for (size_t axis = X_AXIS; axis < n_axis; axis++) { - if (bitnum_is_true(step_mask, axis)) { - bool dir = bitnum_is_true(dir_mask, axis); - - auto a = _axis[axis]; - for (size_t motor = 0; motor < Axis::MAX_MOTORS_PER_AXIS; motor++) { - auto m = a->_motors[motor]; - if (m) { - m->step(dir); - } - } - } - } - config->_stepping->startPulseTimer(); - } - - // Turn all stepper pins off - void IRAM_ATTR Axes::unstep() { - config->_stepping->waitPulse(); - auto n_axis = _numberAxis; - for (size_t axis = X_AXIS; axis < n_axis; axis++) { - for (size_t motor = 0; motor < Axis::MAX_MOTORS_PER_AXIS; motor++) { - auto m = _axis[axis]->_motors[motor]; - if (m) { - m->_driver->unstep(); - } - } - } - - config->_stepping->finishPulse(); - } - void Axes::config_motors() { for (int axis = 0; axis < _numberAxis; ++axis) { _axis[axis]->config_motors(); diff --git a/FluidNC/src/Machine/Homing.cpp b/FluidNC/src/Machine/Homing.cpp index 470c200fe..577c6fe2e 100644 --- a/FluidNC/src/Machine/Homing.cpp +++ b/FluidNC/src/Machine/Homing.cpp @@ -199,11 +199,11 @@ namespace Machine { travel = axisConfig->extraPulloff(); if (travel < 0) { // Motor0's pulloff is greater than motor1's, so we block motor1 - axisConfig->_motors[1]->block(); + Stepping::block(axis, 1); travel = -travel; } else if (travel > 0) { // Motor1's pulloff is greater than motor0's, so we block motor0 - axisConfig->_motors[0]->block(); + Stepping::block(axis, 0); } // All motors will be unblocked later by set_homing_mode() break; @@ -357,7 +357,7 @@ namespace Machine { gc_sync_position(); plan_sync_position(); - config->_stepping->endLowLatency(); + Stepping::endLowLatency(); if (!sys.abort) { set_state(unhomed_axes() ? State::Alarm : State::Idle); @@ -521,7 +521,7 @@ namespace Machine { set_state(State::Alarm); return; } - config->_stepping->beginLowLatency(); + Stepping::beginLowLatency(); set_state(State::Homing); nextCycle(); diff --git a/FluidNC/src/Machine/LimitPin.cpp b/FluidNC/src/Machine/LimitPin.cpp index f2b4b96e7..ccc3adeec 100644 --- a/FluidNC/src/Machine/LimitPin.cpp +++ b/FluidNC/src/Machine/LimitPin.cpp @@ -6,9 +6,9 @@ #include "src/Protocol.h" // protocol_send_event_from_ISR() namespace Machine { - LimitPin::LimitPin(Pin& pin, int axis, int motor, int direction, bool& pHardLimits, bool& pLimited) : - EventPin(&limitEvent, "Limit"), _axis(axis), _motorNum(motor), _value(false), _pHardLimits(pHardLimits), _pLimited(pLimited), - _pin(&pin) { + LimitPin::LimitPin(Pin& pin, int axis, int motor, int direction, bool& pHardLimits) : + EventPin(&limitEvent, "Limit"), _axis(axis), _motorNum(motor), _value(false), _pHardLimits(pHardLimits), _pin(&pin) { + _pLimited = Stepping::limit_var(axis, motor); const char* sDir; // Select one or two bitmask variables to receive the switch data switch (direction) { @@ -56,7 +56,7 @@ namespace Machine { void LimitPin::update(bool value) { if (value) { if (Homing::approach() || (!state_is(State::Homing) && _pHardLimits)) { - _pLimited = value; + *_pLimited = value; if (_pExtraLimited != nullptr) { *_pExtraLimited = value; @@ -70,7 +70,7 @@ namespace Machine { set_bits(*_negLimits, _bitmask); } } else { - _pLimited = value; + *_pLimited = value; if (_pExtraLimited != nullptr) { *_pExtraLimited = value; @@ -92,6 +92,6 @@ namespace Machine { } void LimitPin::setExtraMotorLimit(int axis, int motorNum) { - _pExtraLimited = &config->_axes->_axis[axis]->_motors[motorNum]->_limited; + _pExtraLimited = Stepping::limit_var(axis, motorNum); } } diff --git a/FluidNC/src/Machine/LimitPin.h b/FluidNC/src/Machine/LimitPin.h index 75d02e4fd..13eb5578f 100644 --- a/FluidNC/src/Machine/LimitPin.h +++ b/FluidNC/src/Machine/LimitPin.h @@ -19,7 +19,7 @@ namespace Machine { // touch, increasing the accuracy of homing // _pExtraLimited lets the limit control two motors, as with // CoreXY - volatile bool& _pLimited; + volatile bool* _pLimited; volatile bool* _pExtraLimited = nullptr; volatile uint32_t* _posLimits = nullptr; @@ -28,7 +28,7 @@ namespace Machine { Pin* _pin; public: - LimitPin(Pin& pin, int axis, int motorNum, int direction, bool& phardLimits, bool& pLimited); + LimitPin(Pin& pin, int axis, int motorNum, int direction, bool& phardLimits); void update(bool value) override; diff --git a/FluidNC/src/Machine/Motor.cpp b/FluidNC/src/Machine/Motor.cpp index a6e0eb566..770240aea 100644 --- a/FluidNC/src/Machine/Motor.cpp +++ b/FluidNC/src/Machine/Motor.cpp @@ -31,15 +31,13 @@ namespace Machine { } _driver->init(); - _negLimitPin = new LimitPin(_negPin, _axis, _motorNum, -1, _hardLimits, _limited); - _posLimitPin = new LimitPin(_posPin, _axis, _motorNum, 1, _hardLimits, _limited); - _allLimitPin = new LimitPin(_allPin, _axis, _motorNum, 0, _hardLimits, _limited); + _negLimitPin = new LimitPin(_negPin, _axis, _motorNum, -1, _hardLimits); + _posLimitPin = new LimitPin(_posPin, _axis, _motorNum, 1, _hardLimits); + _allLimitPin = new LimitPin(_allPin, _axis, _motorNum, 0, _hardLimits); _negLimitPin->init(); _posLimitPin->init(); _allLimitPin->init(); - - unblock(); } void Motor::config_motor() { @@ -71,21 +69,6 @@ namespace Machine { return _driver->isReal(); } - void IRAM_ATTR Motor::step(bool reverse) { - // Skip steps based on limit pins - // _blocked is for asymmetric pulloff - // _limited is for limit pins - if (_blocked || _limited) { - return; - } - _driver->step(); - _steps += reverse ? -1 : 1; - } - - void IRAM_ATTR Motor::unstep() { - _driver->unstep(); - } - Motor::~Motor() { delete _driver; } diff --git a/FluidNC/src/Machine/Motor.h b/FluidNC/src/Machine/Motor.h index fb14faca7..72e25f147 100644 --- a/FluidNC/src/Machine/Motor.h +++ b/FluidNC/src/Machine/Motor.h @@ -35,10 +35,6 @@ namespace Machine { Pin _allPin; bool _hardLimits = false; - int32_t _steps = 0; - bool _limited = false; // _limited is set by the LimitPin ISR - bool _blocked = false; // _blocked is used during asymmetric homing pulloff - // Configuration system helpers: void group(Configuration::HandlerBase& handler) override; void afterParse() override; @@ -48,11 +44,6 @@ namespace Machine { void limitOtherAxis(int axis); void init(); void config_motor(); - void step(bool reverse); - void unstep(); - void block() { _blocked = true; } - void unblock() { _blocked = false; } - void unlimit() { _limited = false; } ~Motor(); }; } diff --git a/FluidNC/src/Motors/MotorDriver.cpp b/FluidNC/src/Motors/MotorDriver.cpp index 3c7988f2d..ab2edee6c 100644 --- a/FluidNC/src/Motors/MotorDriver.cpp +++ b/FluidNC/src/Motors/MotorDriver.cpp @@ -38,14 +38,11 @@ namespace MotorDrivers { size_t MotorDriver::axis_index() const { Assert(config != nullptr && config->_axes != nullptr, "Expected machine to be configured before this is called."); - return size_t(config->_axes->findAxisIndex(this)); + return size_t(Axes::findAxisIndex(this)); } size_t MotorDriver::dual_axis_index() const { Assert(config != nullptr && config->_axes != nullptr, "Expected machine to be configured before this is called."); - return size_t(config->_axes->findAxisMotor(this)); + return size_t(Axes::findAxisMotor(this)); } void IRAM_ATTR MotorDriver::set_disable(bool disable) {} - void IRAM_ATTR MotorDriver::set_direction(bool) {} - void IRAM_ATTR MotorDriver::step() {} - void IRAM_ATTR MotorDriver::unstep() {} } diff --git a/FluidNC/src/Motors/MotorDriver.h b/FluidNC/src/Motors/MotorDriver.h index db8f57e48..c62e03c24 100644 --- a/FluidNC/src/Motors/MotorDriver.h +++ b/FluidNC/src/Motors/MotorDriver.h @@ -64,22 +64,6 @@ namespace MotorDrivers { // make a motor transition between idle and non-idle states. virtual void set_disable(bool disable); - // set_direction() sets the motor movement direction. It is - // invoked for every motion segment. - virtual void set_direction(bool); - - // step() initiates a step operation on a motor. It is called - // from motors_step() for ever motor than needs to step now. - // For ordinary step/direction motors, it sets the step pin - // to the active state. - virtual void step(); - - // unstep() turns off the step pin, if applicable, for a motor. - // It is called from motors_unstep() for all motors, since - // motors_unstep() is used in many contexts where the previous - // states of the step pins are unknown. - virtual void unstep(); - // this is used to configure and test motors. This would be used for Trinamic virtual void config_motor() {} diff --git a/FluidNC/src/Motors/StandardStepper.cpp b/FluidNC/src/Motors/StandardStepper.cpp index 20b3aec2b..e66c9c961 100644 --- a/FluidNC/src/Motors/StandardStepper.cpp +++ b/FluidNC/src/Motors/StandardStepper.cpp @@ -9,7 +9,7 @@ #include "../Machine/MachineConfig.h" #include "../Stepper.h" // ST_I2S_* -#include "../Stepping.h" // config->_stepping->_engine +#include "../Stepping.h" // Stepping::_engine #include // gpio #include // CONFIG_IDF_TARGET_* @@ -18,108 +18,41 @@ using namespace Machine; namespace MotorDrivers { - static void init_rmt_channel(rmt_channel_t& rmt_chan_num, Pin& step_pin, bool invert_step, uint32_t dir_delay_ms, uint32_t pulse_us) { - static rmt_channel_t next_RMT_chan_num = RMT_CHANNEL_0; - if (rmt_chan_num == RMT_CHANNEL_MAX) { - if (next_RMT_chan_num == RMT_CHANNEL_MAX) { - log_error("Out of RMT channels"); - return; - } - rmt_chan_num = next_RMT_chan_num; - next_RMT_chan_num = static_cast(static_cast(next_RMT_chan_num) + 1); - } - - auto step_pin_gpio = step_pin.getNative(Pin::Capabilities::Output); - - rmt_config_t rmtConfig = { .rmt_mode = RMT_MODE_TX, - .channel = rmt_chan_num, - .gpio_num = gpio_num_t(step_pin_gpio), - .clk_div = 20, - .mem_block_num = 2, - .flags = 0, - .tx_config = { - .carrier_freq_hz = 0, - .carrier_level = RMT_CARRIER_LEVEL_LOW, - .idle_level = invert_step ? RMT_IDLE_LEVEL_HIGH : RMT_IDLE_LEVEL_LOW, - .carrier_duty_percent = 50, -#if SOC_RMT_SUPPORT_TX_LOOP_COUNT - .loop_count = 1, -#endif - .carrier_en = false, - .loop_en = false, - .idle_output_en = true, - } }; - - rmt_item32_t rmtItem[2]; - rmtItem[0].duration0 = dir_delay_ms ? dir_delay_ms * 4 : 1; - rmtItem[0].duration1 = 4 * pulse_us; - rmtItem[1].duration0 = 0; - rmtItem[1].duration1 = 0; - - rmtItem[0].level0 = rmtConfig.tx_config.idle_level; - rmtItem[0].level1 = !rmtConfig.tx_config.idle_level; - rmt_config(&rmtConfig); - rmt_fill_tx_items(rmtConfig.channel, &rmtItem[0], rmtConfig.mem_block_num, 0); - } - void StandardStepper::init() { read_settings(); config_message(); } - void StandardStepper::read_settings() { init_step_dir_pins(); } + void StandardStepper::read_settings() { + init_step_dir_pins(); + } void StandardStepper::init_step_dir_pins() { - auto axisIndex = axis_index(); - - _invert_step = _step_pin.getAttr().has(Pin::Attr::ActiveLow); - _invert_disable = _disable_pin.getAttr().has(Pin::Attr::ActiveLow); + auto axisIndex = axis_index(); + auto dualAxisIndex = dual_axis_index(); + _step_pin.setAttr(Pin::Attr::Output); _dir_pin.setAttr(Pin::Attr::Output); - auto stepping = config->_stepping; - if (stepping->_engine == Stepping::RMT) { - init_rmt_channel(_rmt_chan_num, _step_pin, _invert_step, stepping->_directionDelayUsecs, stepping->_pulseUsecs); - } else { - _step_pin.setAttr(Pin::Attr::Output); - } - if (_disable_pin.defined()) { _disable_pin.setAttr(Pin::Attr::Output); } + + if (_step_pin.canStep()) { + Stepping::assignMotor(axisIndex, dualAxisIndex, _step_pin.index(), _step_pin.inverted(), _dir_pin.index(), _dir_pin.inverted()); + } + + auto dir_gpio = _step_pin.getNative(Pin::Capabilities::Output); } void StandardStepper::config_message() { log_info(" " << name() << " Step:" << _step_pin.name() << " Dir:" << _dir_pin.name() << " Disable:" << _disable_pin.name()); } - void IRAM_ATTR StandardStepper::step() { - if (config->_stepping->_engine == Stepping::RMT && _rmt_chan_num != RMT_CHANNEL_MAX) { -#ifdef CONFIG_IDF_TARGET_ESP32 - RMT.conf_ch[_rmt_chan_num].conf1.mem_rd_rst = 1; - RMT.conf_ch[_rmt_chan_num].conf1.mem_rd_rst = 0; - RMT.conf_ch[_rmt_chan_num].conf1.tx_start = 1; -#endif -#ifdef CONFIG_IDF_TARGET_ESP32S3 - RMT.chnconf0[_rmt_chan_num].mem_rd_rst_n = 1; - RMT.chnconf0[_rmt_chan_num].mem_rd_rst_n = 0; - RMT.chnconf0[_rmt_chan_num].tx_start_n = 1; -#endif - } else { - _step_pin.on(); - } - } - - void IRAM_ATTR StandardStepper::unstep() { - if (config->_stepping->_engine != Stepping::RMT) { - _step_pin.off(); - } + void IRAM_ATTR StandardStepper::set_disable(bool disable) { + _disable_pin.synchronousWrite(disable); } - void IRAM_ATTR StandardStepper::set_direction(bool dir) { _dir_pin.write(dir); } - - void IRAM_ATTR StandardStepper::set_disable(bool disable) { _disable_pin.synchronousWrite(disable); } - // Configuration registration namespace { MotorFactory::InstanceBuilder registration("standard_stepper"); @@ -127,7 +60,7 @@ namespace MotorDrivers { void StandardStepper::validate() { Assert(_step_pin.defined(), "Step pin must be configured."); - bool isI2SO = config->_stepping->_engine == Stepping::I2S_STREAM || config->_stepping->_engine == Stepping::I2S_STATIC; + bool isI2SO = Stepping::_engine == Stepping::I2S_STREAM || Stepping::_engine == Stepping::I2S_STATIC; if (isI2SO) { Assert(_step_pin.name().rfind("I2SO", 0) == 0, "Step pin must be an I2SO pin"); if (_dir_pin.defined()) { diff --git a/FluidNC/src/Motors/StandardStepper.h b/FluidNC/src/Motors/StandardStepper.h index e74759415..fb060f7ef 100644 --- a/FluidNC/src/Motors/StandardStepper.h +++ b/FluidNC/src/Motors/StandardStepper.h @@ -2,8 +2,6 @@ #include "MotorDriver.h" -#include - namespace MotorDrivers { class StandardStepper : public MotorDriver { public: @@ -17,9 +15,6 @@ namespace MotorDrivers { // No special action, but return true to say homing is possible bool set_homing_mode(bool isHoming) override { return true; } void set_disable(bool) override; - void set_direction(bool) override; - void step() override; - void unstep() override; void read_settings() override; void init_step_dir_pins(); @@ -39,12 +34,5 @@ namespace MotorDrivers { handler.item("direction_pin", _dir_pin); handler.item("disable_pin", _disable_pin); } - - private: - // Initialized after configuration for RMT steps: - bool _invert_step; - bool _invert_disable; - - rmt_channel_t _rmt_chan_num = RMT_CHANNEL_MAX; }; } diff --git a/FluidNC/src/Motors/UnipolarMotor.cpp b/FluidNC/src/Motors/UnipolarMotor.cpp deleted file mode 100644 index f1b14dde9..000000000 --- a/FluidNC/src/Motors/UnipolarMotor.cpp +++ /dev/null @@ -1,128 +0,0 @@ -// Copyright (c) 2020 - Bart Dring -// Use of this source code is governed by a GPLv3 license that can be found in the LICENSE file. - -#include "UnipolarMotor.h" -#include "../Machine/MachineConfig.h" - -namespace MotorDrivers { - void UnipolarMotor::init() { - _pin_phase0.setAttr(Pin::Attr::Output); - _pin_phase1.setAttr(Pin::Attr::Output); - _pin_phase2.setAttr(Pin::Attr::Output); - _pin_phase3.setAttr(Pin::Attr::Output); - _current_phase = 0; - config_message(); - } - - void UnipolarMotor::config_message() { - log_info(" " << name() << " Ph0:" << _pin_phase0.name() << " Ph1:" << _pin_phase1.name() << " Ph2:" << _pin_phase2.name() - << " Ph3:" << _pin_phase3.name()); - } - - void IRAM_ATTR UnipolarMotor::set_disable(bool disable) { - if (disable) { - _pin_phase0.off(); - _pin_phase1.off(); - _pin_phase2.off(); - _pin_phase3.off(); - } - _enabled = !disable; - } - - void IRAM_ATTR UnipolarMotor::set_direction(bool dir) { - _dir = dir; - } - - void IRAM_ATTR UnipolarMotor::step() { - uint8_t _phase[8] = { 0, 0, 0, 0, 0, 0, 0, 0 }; // temporary phase values...all start as off - uint8_t phase_max; - - if (!_enabled) { - return; // don't do anything, phase is not changed or lost - } - - phase_max = _half_step ? 7 : 3; - - if (_dir) { // count up - _current_phase = _current_phase == phase_max ? 0 : _current_phase + 1; - } else { // count down - _current_phase = _current_phase == 0 ? phase_max : _current_phase - 1; - } - /* - 8 Step : A – AB – B – BC – C – CD – D – DA - 4 Step : AB – BC – CD – DA - - Step IN4 IN3 IN2 IN1 - A 0 0 0 1 - AB 0 0 1 1 - B 0 0 1 0 - BC 0 1 1 0 - C 0 1 0 0 - CD 1 1 0 0 - D 1 0 0 0 - DA 1 0 0 1 - */ - if (_half_step) { - switch (_current_phase) { - case 0: - _phase[0] = 1; - break; - case 1: - _phase[0] = 1; - _phase[1] = 1; - break; - case 2: - _phase[1] = 1; - break; - case 3: - _phase[1] = 1; - _phase[2] = 1; - break; - case 4: - _phase[2] = 1; - break; - case 5: - _phase[2] = 1; - _phase[3] = 1; - break; - case 6: - _phase[3] = 1; - break; - case 7: - _phase[3] = 1; - _phase[0] = 1; - break; - } - } else { - switch (_current_phase) { - case 0: - _phase[0] = 1; - _phase[1] = 1; - break; - case 1: - _phase[1] = 1; - _phase[2] = 1; - break; - case 2: - _phase[2] = 1; - _phase[3] = 1; - break; - case 3: - _phase[3] = 1; - _phase[0] = 1; - break; - } - } - - _pin_phase0.write(_phase[0]); - _pin_phase1.write(_phase[1]); - _pin_phase2.write(_phase[2]); - _pin_phase3.write(_phase[3]); - Stepping::startPulseTimer(); - } - - // Configuration registration - namespace { - MotorFactory::InstanceBuilder registration("unipolar"); - } -} diff --git a/FluidNC/src/Motors/UnipolarMotor.h b/FluidNC/src/Motors/UnipolarMotor.h deleted file mode 100644 index 872f8054c..000000000 --- a/FluidNC/src/Motors/UnipolarMotor.h +++ /dev/null @@ -1,49 +0,0 @@ -// Copyright (c) 2020 - Bart Dring -// Use of this source code is governed by a GPLv3 license that can be found in the LICENSE file. - -#pragma once - -#include "MotorDriver.h" - -namespace MotorDrivers { - class UnipolarMotor : public MotorDriver { - public: - UnipolarMotor(const char* name) : MotorDriver(name) {} - - // Overrides for inherited methods - void init() override; - bool set_homing_mode(bool isHoming) override { return true; } - void set_disable(bool disable) override; - void set_direction(bool) override; - void step() override; - - // Configuration handlers: - void validate() override { - Assert(!_pin_phase0.undefined(), "Phase 0 pin should be configured."); - Assert(!_pin_phase1.undefined(), "Phase 1 pin should be configured."); - Assert(!_pin_phase2.undefined(), "Phase 2 pin should be configured."); - Assert(!_pin_phase3.undefined(), "Phase 3 pin should be configured."); - } - - void group(Configuration::HandlerBase& handler) override { - handler.item("phase0_pin", _pin_phase0); - handler.item("phase1_pin", _pin_phase1); - handler.item("phase2_pin", _pin_phase2); - handler.item("phase3_pin", _pin_phase3); - handler.item("half_step", _half_step); - } - - private: - Pin _pin_phase0; - Pin _pin_phase1; - Pin _pin_phase2; - Pin _pin_phase3; - uint8_t _current_phase = 0; - bool _half_step = true; - bool _enabled = false; - bool _dir = true; - - protected: - void config_message() override; - }; -} diff --git a/FluidNC/src/Pin.h b/FluidNC/src/Pin.h index 9d6cf1d2d..f7d8a7e05 100644 --- a/FluidNC/src/Pin.h +++ b/FluidNC/src/Pin.h @@ -113,6 +113,9 @@ class Pin { Assert(_detail->capabilities().has(expectedBehavior), "Requested pin %s does not have the expected behavior.", name().c_str()); return _detail->_index; } + inline bool canStep() { return _detail->canStep(); } + inline int index() { return _detail->_index; } + inline bool inverted() { return _detail->_inverted; } void write(bool value) const; void synchronousWrite(bool value) const; diff --git a/FluidNC/src/Pins/GPIOPinDetail.cpp b/FluidNC/src/Pins/GPIOPinDetail.cpp index 5a1b201d2..1e40b16b9 100644 --- a/FluidNC/src/Pins/GPIOPinDetail.cpp +++ b/FluidNC/src/Pins/GPIOPinDetail.cpp @@ -83,7 +83,7 @@ namespace Pins { } GPIOPinDetail::GPIOPinDetail(pinnum_t index, PinOptionsParser options) : - PinDetail(index), _capabilities(GetDefaultCapabilities(index)), _attributes(Pins::PinAttributes::Undefined), _readWriteMask(0) { + PinDetail(index), _capabilities(GetDefaultCapabilities(index)), _attributes(Pins::PinAttributes::Undefined) { // NOTE: // // RAII is very important here! If we throw an exception in the constructor, the resources @@ -121,7 +121,7 @@ namespace Pins { _claimed[index] = true; // readWriteMask is xor'ed with the value to invert it if active low - _readWriteMask = int(_attributes.has(PinAttributes::ActiveLow)); + _inverted = _attributes.has(PinAttributes::ActiveLow); } PinAttributes GPIOPinDetail::getAttr() const { @@ -139,13 +139,13 @@ namespace Pins { log_error(toString()); } Assert(_attributes.has(PinAttributes::Output), "Pin %s cannot be written", toString().c_str()); - int value = _readWriteMask ^ high; + int value = _inverted ^ (bool)high; gpio_write(_index, value); } } int IRAM_ATTR GPIOPinDetail::read() { auto raw = gpio_read(_index); - return raw ^ _readWriteMask; + return (bool)raw ^ _inverted; } void GPIOPinDetail::setAttr(PinAttributes value) { @@ -165,7 +165,7 @@ namespace Pins { // If the pin is ActiveLow, we should take that into account here: if (value.has(PinAttributes::Output)) { - gpio_write(_index, int(value.has(PinAttributes::InitialOn)) ^ _readWriteMask); + gpio_write(_index, int(value.has(PinAttributes::InitialOn)) ^ _inverted); } gpio_mode(_index, diff --git a/FluidNC/src/Pins/GPIOPinDetail.h b/FluidNC/src/Pins/GPIOPinDetail.h index 68dbdee0b..d6940b395 100644 --- a/FluidNC/src/Pins/GPIOPinDetail.h +++ b/FluidNC/src/Pins/GPIOPinDetail.h @@ -9,7 +9,6 @@ namespace Pins { class GPIOPinDetail : public PinDetail { PinCapabilities _capabilities; PinAttributes _attributes; - int _readWriteMask; static PinCapabilities GetDefaultCapabilities(pinnum_t index); @@ -32,6 +31,8 @@ namespace Pins { void setAttr(PinAttributes value) override; PinAttributes getAttr() const override; + bool canStep() override { return true; } + void registerEvent(EventPin* obj) override; std::string toString() override; diff --git a/FluidNC/src/Pins/I2SOPinDetail.cpp b/FluidNC/src/Pins/I2SOPinDetail.cpp index f54938131..b6a5f1db5 100644 --- a/FluidNC/src/Pins/I2SOPinDetail.cpp +++ b/FluidNC/src/Pins/I2SOPinDetail.cpp @@ -11,8 +11,7 @@ namespace Pins { std::vector I2SOPinDetail::_claimed(nI2SOPins, false); I2SOPinDetail::I2SOPinDetail(pinnum_t index, const PinOptionsParser& options) : - PinDetail(index), _capabilities(PinCapabilities::Output | PinCapabilities::I2S), _attributes(Pins::PinAttributes::Undefined), - _readWriteMask(0) { + PinDetail(index), _capabilities(PinCapabilities::Output | PinCapabilities::I2S), _attributes(Pins::PinAttributes::Undefined) { Assert(index < nI2SOPins, "Pin number is greater than max %d", nI2SOPins - 1); Assert(!_claimed[index], "Pin is already used."); // User defined pin capabilities @@ -28,7 +27,7 @@ namespace Pins { _claimed[index] = true; // readWriteMask is xor'ed with the value to invert it if active low - _readWriteMask = int(_attributes.has(PinAttributes::ActiveLow)); + _inverted = _attributes.has(PinAttributes::ActiveLow); } PinCapabilities I2SOPinDetail::capabilities() const { @@ -40,7 +39,7 @@ namespace Pins { void IRAM_ATTR I2SOPinDetail::write(int high) { if (high != _lastWrittenValue) { _lastWrittenValue = high; - i2s_out_write(_index, _readWriteMask ^ high); + i2s_out_write(_index, _inverted ^ (bool)high); } } @@ -50,7 +49,7 @@ namespace Pins { if (high != _lastWrittenValue) { _lastWrittenValue = high; - i2s_out_write(_index, _readWriteMask ^ high); + i2s_out_write(_index, _inverted ^ (bool)high); i2s_out_push(); i2s_out_delay(); } @@ -58,7 +57,7 @@ namespace Pins { int I2SOPinDetail::read() { auto raw = i2s_out_read(_index); - return raw ^ _readWriteMask; + return (bool)raw ^ _inverted; } void I2SOPinDetail::setAttr(PinAttributes value) { @@ -77,7 +76,7 @@ namespace Pins { // just check for conflicts above... // If the pin is ActiveLow, we should take that into account here: - i2s_out_write(_index, value.has(PinAttributes::InitialOn) ^ _readWriteMask); + i2s_out_write(_index, value.has(PinAttributes::InitialOn) ^ _inverted); } PinAttributes I2SOPinDetail::getAttr() const { diff --git a/FluidNC/src/Pins/I2SOPinDetail.h b/FluidNC/src/Pins/I2SOPinDetail.h index e47e3d4fe..1f9e1fadd 100644 --- a/FluidNC/src/Pins/I2SOPinDetail.h +++ b/FluidNC/src/Pins/I2SOPinDetail.h @@ -10,7 +10,7 @@ namespace Pins { class I2SOPinDetail : public PinDetail { PinCapabilities _capabilities; PinAttributes _attributes; - int _readWriteMask; + int _inverted; static const int nI2SOPins = 32; static std::vector _claimed; @@ -29,6 +29,8 @@ namespace Pins { void setAttr(PinAttributes value) override; PinAttributes getAttr() const override; + bool canStep() override { return true; } + std::string toString() override; ~I2SOPinDetail() override { _claimed[_index] = false; } diff --git a/FluidNC/src/Pins/PinDetail.h b/FluidNC/src/Pins/PinDetail.h index ecfc77bc7..bec7c89bf 100644 --- a/FluidNC/src/Pins/PinDetail.h +++ b/FluidNC/src/Pins/PinDetail.h @@ -21,13 +21,14 @@ namespace Pins { class PinDetail { protected: public: - int _index; + int _index = -1; + bool _inverted = false; PinDetail(int number) : _index(number) {} - PinDetail(const PinDetail& o) = delete; - PinDetail(PinDetail&& o) = delete; + PinDetail(const PinDetail& o) = delete; + PinDetail(PinDetail&& o) = delete; PinDetail& operator=(const PinDetail& o) = delete; - PinDetail& operator=(PinDetail&& o) = delete; + PinDetail& operator=(PinDetail&& o) = delete; virtual PinCapabilities capabilities() const = 0; @@ -38,6 +39,8 @@ namespace Pins { virtual void setAttr(PinAttributes value) = 0; virtual PinAttributes getAttr() const = 0; + virtual bool canStep() { return false; } + virtual void registerEvent(EventPin* obj); virtual std::string toString() = 0; diff --git a/FluidNC/src/Spindles/Laser.cpp b/FluidNC/src/Spindles/LaserSpindle.cpp similarity index 98% rename from FluidNC/src/Spindles/Laser.cpp rename to FluidNC/src/Spindles/LaserSpindle.cpp index f43246079..a04d34d88 100644 --- a/FluidNC/src/Spindles/Laser.cpp +++ b/FluidNC/src/Spindles/LaserSpindle.cpp @@ -6,7 +6,7 @@ M4 speed vs. power compensation. */ -#include "Laser.h" +#include "LaserSpindle.h" #include "Driver/PwmPin.h" // pwmInit(), etc. #include "../Machine/MachineConfig.h" diff --git a/FluidNC/src/Spindles/Laser.h b/FluidNC/src/Spindles/LaserSpindle.h similarity index 100% rename from FluidNC/src/Spindles/Laser.h rename to FluidNC/src/Spindles/LaserSpindle.h diff --git a/FluidNC/src/Stepper.cpp b/FluidNC/src/Stepper.cpp index 6c44bd6e0..563844052 100644 --- a/FluidNC/src/Stepper.cpp +++ b/FluidNC/src/Stepper.cpp @@ -177,7 +177,7 @@ static st_prep_t prep; // Stepper shutdown void IRAM_ATTR Stepper::stop_stepping() { - config->_axes->unstep(); + Stepping::unstep(); st.step_outbits = 0; } @@ -203,7 +203,7 @@ bool IRAM_ATTR Stepper::pulse_func() { } auto n_axis = Axes::_numberAxis; - config->_axes->step(st.step_outbits, st.dir_outbits); + Stepping::step(st.step_outbits, st.dir_outbits); // If there is no step segment, attempt to pop one from the stepper buffer if (st.exec_segment == NULL) { @@ -266,7 +266,7 @@ bool IRAM_ATTR Stepper::pulse_func() { segment_buffer_tail = segment_buffer_tail >= (Stepping::_segments - 1) ? 0 : segment_buffer_tail + 1; } - config->_axes->unstep(); + Stepping::unstep(); return true; } @@ -294,7 +294,7 @@ void Stepper::go_idle() { // Reset and clear stepper subsystem variables void Stepper::reset() { // Initialize Stepping driver idle state. - config->_stepping->reset(); + Stepping::reset(); go_idle(); diff --git a/FluidNC/src/Stepping.cpp b/FluidNC/src/Stepping.cpp index 0df329e0a..ebf7a5956 100644 --- a/FluidNC/src/Stepping.cpp +++ b/FluidNC/src/Stepping.cpp @@ -4,11 +4,20 @@ #include "Stepper.h" #include "Machine/MachineConfig.h" // config +#include +#include + #include namespace Machine { - int Stepping::_engine = RMT; + // fStepperTimer should be an integer divisor of the bus speed, i.e. of fTimers + const int ticksPerMicrosecond = Stepping::fStepperTimer / 1000000; + + int Stepping::_engine = RMT_ENGINE; + + int Stepping::_n_active_axes = 0; + bool Stepping::_switchedStepper = false; int32_t Stepping::_stepPulseEndTime; size_t Stepping::_segments = 12; @@ -19,10 +28,10 @@ namespace Machine { uint32_t Stepping::_disableDelayUsecs = 0; const EnumItem stepTypes[] = { { Stepping::TIMED, "Timed" }, - { Stepping::RMT, "RMT" }, + { Stepping::RMT_ENGINE, "RMT" }, { Stepping::I2S_STATIC, "I2S_static" }, { Stepping::I2S_STREAM, "I2S_stream" }, - EnumItem(Stepping::RMT) }; + EnumItem(Stepping::RMT_ENGINE) }; void Stepping::init() { log_info("Stepping:" << stepTypes[_engine].name << " Pulse:" << _pulseUsecs << "us Dsbl Delay:" << _disableDelayUsecs @@ -41,6 +50,196 @@ namespace Machine { Stepper::init(); } + rmt_channel_t _rmt_chan_num = RMT_CHANNEL_MAX; + + static int init_rmt_channel(rmt_channel_t& rmt_chan_num, int step_gpio, bool invert_step, uint32_t dir_delay_ms, uint32_t pulse_us) { + static rmt_channel_t next_RMT_chan_num = RMT_CHANNEL_0; + if (rmt_chan_num == RMT_CHANNEL_MAX) { + if (next_RMT_chan_num == RMT_CHANNEL_MAX) { + log_error("Out of RMT channels"); + return -1; + } + rmt_chan_num = next_RMT_chan_num; + next_RMT_chan_num = static_cast(static_cast(next_RMT_chan_num) + 1); + } + + rmt_config_t rmtConfig = { .rmt_mode = RMT_MODE_TX, + .channel = rmt_chan_num, + .gpio_num = gpio_num_t(step_gpio), + .clk_div = 20, + .mem_block_num = 2, + .flags = 0, + .tx_config = { + .carrier_freq_hz = 0, + .carrier_level = RMT_CARRIER_LEVEL_LOW, + .idle_level = invert_step ? RMT_IDLE_LEVEL_HIGH : RMT_IDLE_LEVEL_LOW, + .carrier_duty_percent = 50, +#if SOC_RMT_SUPPORT_TX_LOOP_COUNT + .loop_count = 1, +#endif + .carrier_en = false, + .loop_en = false, + .idle_output_en = true, + } }; + + rmt_item32_t rmtItem[2]; + rmtItem[0].duration0 = dir_delay_ms ? dir_delay_ms * 4 : 1; + rmtItem[0].duration1 = 4 * pulse_us; + rmtItem[1].duration0 = 0; + rmtItem[1].duration1 = 0; + + rmtItem[0].level0 = rmtConfig.tx_config.idle_level; + rmtItem[0].level1 = !rmtConfig.tx_config.idle_level; + rmt_config(&rmtConfig); + rmt_fill_tx_items(rmtConfig.channel, &rmtItem[0], rmtConfig.mem_block_num, 0); + return rmt_chan_num; + } + + Stepping::motor_t* Stepping::axis_motors[MAX_N_AXIS][MAX_MOTORS_PER_AXIS] = { nullptr }; + + void Stepping::assignMotor(int axis, int motor, int step_pin, bool step_invert, int dir_pin, bool dir_invert) { + if (axis >= _n_active_axes) { + _n_active_axes = axis + 1; + } + if (_engine == RMT_ENGINE) { + step_pin = init_rmt_channel(_rmt_chan_num, step_pin, step_invert, _directionDelayUsecs, _pulseUsecs); + } + + motor_t* m = new motor_t; + axis_motors[axis][motor] = m; + m->step_pin = step_pin; + m->step_invert = step_invert; + m->dir_pin = dir_pin; + m->dir_invert = dir_invert; + m->blocked = false; + m->limited = false; + } + + int Stepping::axis_steps[MAX_N_AXIS] = { 0 }; + + bool* Stepping::limit_var(int axis, int motor) { + auto m = axis_motors[axis][motor]; + return m ? &(m->limited) : nullptr; + } + + void Stepping::block(int axis, int motor) { + auto m = axis_motors[axis][motor]; + if (m) { + m->blocked = true; + } + } + + void Stepping::unblock(int axis, int motor) { + auto m = axis_motors[axis][motor]; + if (m) { + m->blocked = false; + } + } + + void Stepping::limit(int axis, int motor) { + auto m = axis_motors[axis][motor]; + if (m) { + m->limited = true; + } + } + void Stepping::unlimit(int axis, int motor) { + auto m = axis_motors[axis][motor]; + if (m) { + m->limited = false; + } + } + + void IRAM_ATTR Stepping::step(uint8_t step_mask, uint8_t dir_mask) { + // Set the direction pins, but optimize for the common + // situation where the direction bits haven't changed. + static uint8_t previous_dir_mask = 255; // should never be this value + if (dir_mask != previous_dir_mask) { + for (size_t axis = 0; axis < _n_active_axes; axis++) { + bool dir = bitnum_is_true(dir_mask, axis); + bool old_dir = bitnum_is_true(previous_dir_mask, axis); + if (dir != old_dir) { + for (size_t motor = 0; motor < MAX_MOTORS_PER_AXIS; motor++) { + auto m = axis_motors[axis][motor]; + if (m) { + int pin = m->dir_pin; + bool inverted = m->dir_invert; + bool direction = dir ^ inverted; + if (_engine == RMT_ENGINE || _engine == TIMED) { + gpio_write(pin, direction); + } else if (_engine == I2S_STATIC || _engine == I2S_STREAM) { + i2s_out_write(pin, direction); + } + } + } + } + waitDirection(); + previous_dir_mask = dir_mask; + } + } + + // Turn on step pulses for motors that are supposed to step now + for (size_t axis = 0; axis < _n_active_axes; axis++) { + if (bitnum_is_true(step_mask, axis)) { + auto increment = bitnum_is_true(dir_mask, axis) ? 1 : -1; + axis_steps[axis] += increment; + for (size_t motor = 0; motor < MAX_MOTORS_PER_AXIS; motor++) { + auto m = axis_motors[axis][motor]; + if (m && !m->blocked && !m->limited) { + int pin = m->step_pin; + bool inverted = m->step_invert; + if (_engine == RMT_ENGINE) { + // Restart the RMT which has already been configured + // for the desired pulse length and polarity +#ifdef CONFIG_IDF_TARGET_ESP32 + RMT.conf_ch[pin].conf1.mem_rd_rst = 1; + RMT.conf_ch[pin].conf1.mem_rd_rst = 0; + RMT.conf_ch[pin].conf1.tx_start = 1; +#endif +#ifdef CONFIG_IDF_TARGET_ESP32S3 + RMT.chnconf0[pin].mem_rd_rst_n = 1; + RMT.chnconf0[pin].mem_rd_rst_n = 0; + RMT.chnconf0[pin].tx_start_n = 1; +#endif + } else if (_engine == I2S_STATIC || _engine == I2S_STREAM) { + i2s_out_write(pin, !inverted); + } else if (_engine == TIMED) { + gpio_write(pin, !inverted); + } + } + } + } + } + startPulseTimer(); + } + + // Turn all stepper pins off + void IRAM_ATTR Stepping::unstep() { + // With RMT, the end of the step is automatic + if (_engine == RMT_ENGINE) { + return; + } + if (_engine == I2S_STATIC || _engine == TIMED) { // Wait pulse + spinUntil(_stepPulseEndTime); + } + for (size_t axis = 0; axis < _n_active_axes; axis++) { + for (size_t motor = 0; motor < MAX_MOTORS_PER_AXIS; motor++) { + auto m = axis_motors[axis][motor]; + if (m) { + int pin = m->step_pin; + bool inverted = m->step_invert; + if (_engine == I2S_STATIC || _engine == I2S_STREAM) { + i2s_out_write(pin, inverted); + } else if (_engine == TIMED) { + gpio_write(pin, inverted); + } + } + } + } + if (_engine == stepper_id_t::I2S_STATIC) { + i2s_out_push(); + } + } + void Stepping::reset() { if (_engine == I2S_STREAM) { i2s_out_reset(); @@ -65,14 +264,8 @@ namespace Machine { _engine = I2S_STREAM; } } - // Called only from Axes::unstep() - void IRAM_ATTR Stepping::waitPulse() { - if (_engine == I2S_STATIC || _engine == TIMED) { - spinUntil(_stepPulseEndTime); - } - } - // Called only from Axes::step() + // Called only from step() void IRAM_ATTR Stepping::waitDirection() { if (_directionDelayUsecs) { // Stepper drivers need some time between changing direction and doing a pulse. @@ -91,7 +284,7 @@ namespace Machine { } } - // Called from Axes::step() and, probably incorrectly, from UnipolarMotor::step() + // Called from step() void IRAM_ATTR Stepping::startPulseTimer() { // Do not use switch() in IRAM if (_engine == stepper_id_t::I2S_STREAM) { @@ -105,13 +298,6 @@ namespace Machine { } } - // Called only from Axes::unstep() - void IRAM_ATTR Stepping::finishPulse() { - if (_engine == stepper_id_t::I2S_STATIC) { - i2s_out_push(); - } - } - // Called only from Stepper::pulse_func when a new segment is loaded // The argument is in units of ticks of the timer that generates ISRs void IRAM_ATTR Stepping::setTimerPeriod(uint16_t timerTicks) { @@ -169,7 +355,7 @@ namespace Machine { case stepper_id_t::I2S_STREAM: case stepper_id_t::I2S_STATIC: return i2s_out_max_steps_per_sec; - case stepper_id_t::RMT: + case stepper_id_t::RMT_ENGINE: return 1000000 / (2 * _pulseUsecs + _directionDelayUsecs); case stepper_id_t::TIMED: default: diff --git a/FluidNC/src/Stepping.h b/FluidNC/src/Stepping.h index 0dfb25f6f..466a4c549 100644 --- a/FluidNC/src/Stepping.h +++ b/FluidNC/src/Stepping.h @@ -6,24 +6,35 @@ #include "Configuration/Configurable.h" #include "Driver/StepTimer.h" - namespace Machine { class Stepping : public Configuration::Configurable { public: // fStepperTimer should be an integer divisor of the bus speed, i.e. of fTimers static const uint32_t fStepperTimer = 20000000; // frequency of step pulse timer - private: - static const int ticksPerMicrosecond = fStepperTimer / 1000000; - static bool _switchedStepper; static int32_t _stepPulseEndTime; + static const int MAX_MOTORS_PER_AXIS = 2; + struct motor_t { + int step_pin; + int dir_pin; + bool step_invert; + bool dir_invert; + bool blocked; + bool limited; + }; + static motor_t* axis_motors[MAX_N_AXIS][MAX_MOTORS_PER_AXIS]; + static int _n_active_axes; + + static void startPulseTimer(); + static void waitDirection(); // Wait for direction delay + static int32_t axis_steps[MAX_N_AXIS]; public: enum stepper_id_t { TIMED = 0, - RMT, + RMT_ENGINE, I2S_STATIC, I2S_STREAM, }; @@ -49,20 +60,26 @@ namespace Machine { // Interfaces to stepping engine static void init(); - static void assignMotor(int axis, int motor, int step_pin, bool step_invert, int dir_pin, bool dir_invert); + static uint32_t getSteps(int axis) { return axis_steps[axis]; } + static void setSteps(int axis, uint32_t steps) { axis_steps[axis] = steps; } - static void setStepPin(int axis, int motor, int pin, bool invert); - static void setDirPin(int axis, int motor, int pin, bool invert); + static void assignMotor(int axis, int motor, int step_pin, bool step_invert, int dir_pin, bool dir_invert); static void reset(); // Clean up old state and start fresh static void beginLowLatency(); static void endLowLatency(); - static void startPulseTimer(); - static void waitPulse(); // Wait for pulse length - static void waitDirection(); // Wait for direction delay - static void waitMotion(); // Wait for motion to complete - static void finishPulse(); // Cleanup after unstep + static void step(uint8_t step_mask, uint8_t dir_mask); + static void unstep(); + + // Used to stop a motor quickly when a limit switch is hit + static bool* limit_var(int axis, int motor); + static void limit(int axis, int motor); + static void unlimit(int axis, int motor); + + // Used to stop a motor during ganged homint + static void block(int axis, int motor); + static void unblock(int axis, int motor); static uint32_t maxPulsesPerSec(); diff --git a/FluidNC/src/System.cpp b/FluidNC/src/System.cpp index 907f48e93..dd07eb4c0 100644 --- a/FluidNC/src/System.cpp +++ b/FluidNC/src/System.cpp @@ -10,6 +10,7 @@ #include "Report.h" // report_ovr_counter #include "Config.h" // MAX_N_AXIS #include "Machine/MachineConfig.h" // config +#include "src/Stepping.h" // config #include // memset #include // roundf @@ -51,17 +52,11 @@ void motor_steps_to_mpos(float* position, int32_t* steps) { } void set_motor_steps(size_t axis, int32_t steps) { - auto a = config->_axes->_axis[axis]; - for (size_t motor = 0; motor < Machine::Axis::MAX_MOTORS_PER_AXIS; motor++) { - auto m = a->_motors[motor]; - if (m) { - m->_steps = steps; - } - } + Stepping::setSteps(axis, steps); } void set_motor_steps_from_mpos(float* mpos) { - auto n_axis = config->_axes->_numberAxis; + auto n_axis = Axes::_numberAxis; float motor_steps[n_axis]; config->_kinematics->transform_cartesian_to_motors(motor_steps, mpos); for (size_t axis = 0; axis < n_axis; axis++) { @@ -70,16 +65,14 @@ void set_motor_steps_from_mpos(float* mpos) { } int32_t get_axis_motor_steps(size_t axis) { - auto m = config->_axes->_axis[axis]->_motors[0]; - return m ? m->_steps : 0; + return Stepping::getSteps(axis); } void get_motor_steps(int32_t* motor_steps) { auto axes = config->_axes; auto n_axis = axes->_numberAxis; for (size_t axis = 0; axis < n_axis; axis++) { - auto m = axes->_axis[axis]->_motors[0]; - motor_steps[axis] = m ? m->_steps : 0; + motor_steps[axis] = Stepping::getSteps(axis); } } int32_t* get_motor_steps() {