mirror of
https://github.com/bdring/Grbl_Esp32.git
synced 2025-09-08 21:30:54 +02:00
Handled some more motor settings
Handled SPI
This commit is contained in:
@@ -475,7 +475,7 @@ Error gc_execute_line(char* line, uint8_t client) {
|
|||||||
gc_block.modal.spindle = SpindleState::Cw;
|
gc_block.modal.spindle = SpindleState::Cw;
|
||||||
break;
|
break;
|
||||||
case 4: // Supported if SPINDLE_DIR_PIN is defined or laser mode is on.
|
case 4: // Supported if SPINDLE_DIR_PIN is defined or laser mode is on.
|
||||||
if (spindle->is_reversable || laser_mode->get()) {
|
if (spindle->is_reversable || MachineConfig::instance()->_laserMode) {
|
||||||
gc_block.modal.spindle = SpindleState::Ccw;
|
gc_block.modal.spindle = SpindleState::Ccw;
|
||||||
} else {
|
} else {
|
||||||
FAIL(Error::GcodeUnsupportedCommand);
|
FAIL(Error::GcodeUnsupportedCommand);
|
||||||
@@ -1292,7 +1292,7 @@ Error gc_execute_line(char* line, uint8_t client) {
|
|||||||
return status;
|
return status;
|
||||||
}
|
}
|
||||||
// If in laser mode, setup laser power based on current and past parser conditions.
|
// If in laser mode, setup laser power based on current and past parser conditions.
|
||||||
if (laser_mode->get()) {
|
if (MachineConfig::instance()->_laserMode) {
|
||||||
if (!((gc_block.modal.motion == Motion::Linear) || (gc_block.modal.motion == Motion::CwArc) ||
|
if (!((gc_block.modal.motion == Motion::Linear) || (gc_block.modal.motion == Motion::CwArc) ||
|
||||||
(gc_block.modal.motion == Motion::CcwArc))) {
|
(gc_block.modal.motion == Motion::CcwArc))) {
|
||||||
gc_parser_flags |= GCParserLaserDisable;
|
gc_parser_flags |= GCParserLaserDisable;
|
||||||
|
@@ -296,7 +296,7 @@ Axes::~Axes() {
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void I2SO::validate() const {
|
void I2SOBus::validate() const {
|
||||||
if (!_bck.undefined() || !_data.undefined() || !_ws.undefined()) {
|
if (!_bck.undefined() || !_data.undefined() || !_ws.undefined()) {
|
||||||
Assert(!_bck.undefined(), "I2SO BCK pin should be configured once.");
|
Assert(!_bck.undefined(), "I2SO BCK pin should be configured once.");
|
||||||
Assert(!_data.undefined(), "I2SO Data pin should be configured once.");
|
Assert(!_data.undefined(), "I2SO Data pin should be configured once.");
|
||||||
@@ -304,19 +304,37 @@ void I2SO::validate() const {
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void I2SO::handle(Configuration::HandlerBase& handler) {
|
void I2SOBus::handle(Configuration::HandlerBase& handler) {
|
||||||
handler.handle("bck", _bck);
|
handler.handle("bck", _bck);
|
||||||
handler.handle("data", _data);
|
handler.handle("data", _data);
|
||||||
handler.handle("ws", _ws);
|
handler.handle("ws", _ws);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void SPIBus::validate() const {
|
||||||
|
if (!_ss.undefined() || !_miso.undefined() || !_mosi.undefined() || !_sck.undefined()) {
|
||||||
|
Assert(!_ss.undefined(), "SPI SS pin should be configured once.");
|
||||||
|
Assert(!_miso.undefined(), "SPI MISO pin should be configured once.");
|
||||||
|
Assert(!_mosi.undefined(), "SPI MOSI pin should be configured once.");
|
||||||
|
Assert(!_sck.undefined(), "SPI SCK pin should be configured once.");
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void SPIBus::handle(Configuration::HandlerBase& handler) {
|
||||||
|
handler.handle("ss", _ss);
|
||||||
|
handler.handle("miso", _miso);
|
||||||
|
handler.handle("mosi", _mosi);
|
||||||
|
handler.handle("mosi", _sck);
|
||||||
|
}
|
||||||
|
|
||||||
void MachineConfig::validate() const {}
|
void MachineConfig::validate() const {}
|
||||||
|
|
||||||
void MachineConfig::handle(Configuration::HandlerBase& handler) {
|
void MachineConfig::handle(Configuration::HandlerBase& handler) {
|
||||||
handler.handle("axes", _axes);
|
handler.handle("axes", _axes);
|
||||||
handler.handle("i2so", _i2so);
|
handler.handle("i2so", _i2so);
|
||||||
|
handler.handle("spi", _spi);
|
||||||
handler.handle("coolant", _coolant);
|
handler.handle("coolant", _coolant);
|
||||||
handler.handle("probe", _probe);
|
handler.handle("probe", _probe);
|
||||||
|
handler.handle("laser_mode", _laserMode);
|
||||||
}
|
}
|
||||||
|
|
||||||
bool MachineConfig::load(const char* filename) {
|
bool MachineConfig::load(const char* filename) {
|
||||||
|
@@ -123,9 +123,9 @@ public:
|
|||||||
~Axes();
|
~Axes();
|
||||||
};
|
};
|
||||||
|
|
||||||
class I2SO : public Configuration::Configurable {
|
class I2SOBus : public Configuration::Configurable {
|
||||||
public:
|
public:
|
||||||
I2SO() = default;
|
I2SOBus() = default;
|
||||||
|
|
||||||
Pin _bck;
|
Pin _bck;
|
||||||
Pin _data;
|
Pin _data;
|
||||||
@@ -134,16 +134,33 @@ public:
|
|||||||
void validate() const override;
|
void validate() const override;
|
||||||
void handle(Configuration::HandlerBase& handler) override;
|
void handle(Configuration::HandlerBase& handler) override;
|
||||||
|
|
||||||
~I2SO() {}
|
~I2SOBus() = default;
|
||||||
|
};
|
||||||
|
|
||||||
|
class SPIBus : public Configuration::Configurable {
|
||||||
|
public:
|
||||||
|
SPIBus() = default;
|
||||||
|
|
||||||
|
Pin _ss;
|
||||||
|
Pin _miso;
|
||||||
|
Pin _mosi;
|
||||||
|
Pin _sck;
|
||||||
|
|
||||||
|
void validate() const override;
|
||||||
|
void handle(Configuration::HandlerBase& handler) override;
|
||||||
|
|
||||||
|
~SPIBus() = default;
|
||||||
};
|
};
|
||||||
|
|
||||||
class MachineConfig : public Configuration::Configurable {
|
class MachineConfig : public Configuration::Configurable {
|
||||||
public:
|
public:
|
||||||
MachineConfig() = default;
|
MachineConfig() = default;
|
||||||
Axes* _axes = nullptr;
|
Axes* _axes = nullptr;
|
||||||
I2SO* _i2so = nullptr;
|
SPIBus* _spi = nullptr;
|
||||||
|
I2SOBus* _i2so = nullptr;
|
||||||
CoolantControl* _coolant = nullptr;
|
CoolantControl* _coolant = nullptr;
|
||||||
Probe* _probe = nullptr;
|
Probe* _probe = nullptr;
|
||||||
|
bool _laserMode = false;
|
||||||
|
|
||||||
static MachineConfig*& instance() {
|
static MachineConfig*& instance() {
|
||||||
static MachineConfig* instance = nullptr;
|
static MachineConfig* instance = nullptr;
|
||||||
|
@@ -197,8 +197,10 @@ namespace Motors {
|
|||||||
if (_has_errors) {
|
if (_has_errors) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
auto axis = MachineConfig::instance()->_axes->_axis[_axis_index];
|
||||||
sys_position[_axis_index] =
|
sys_position[_axis_index] =
|
||||||
axis_settings[_axis_index]->home_mpos->get() * axis_settings[_axis_index]->steps_per_mm->get(); // convert to steps
|
axis->_homing->_mpos * axis->_stepsPerMm; // convert to steps
|
||||||
|
|
||||||
set_disable(false);
|
set_disable(false);
|
||||||
set_location(); // force the PWM to update now
|
set_location(); // force the PWM to update now
|
||||||
@@ -229,8 +231,10 @@ namespace Motors {
|
|||||||
|
|
||||||
read_settings();
|
read_settings();
|
||||||
|
|
||||||
int32_t pos_min_steps = lround(limitsMinPosition(_axis_index) * axis_settings[_axis_index]->steps_per_mm->get());
|
auto axis = MachineConfig::instance()->_axes->_axis[_axis_index];
|
||||||
int32_t pos_max_steps = lround(limitsMaxPosition(_axis_index) * axis_settings[_axis_index]->steps_per_mm->get());
|
|
||||||
|
int32_t pos_min_steps = lround(limitsMinPosition(_axis_index) * axis->_stepsPerMm);
|
||||||
|
int32_t pos_max_steps = lround(limitsMaxPosition(_axis_index) * axis->_stepsPerMm);
|
||||||
|
|
||||||
int32_t temp = map(dxl_position, DXL_COUNT_MIN, DXL_COUNT_MAX, pos_min_steps, pos_max_steps);
|
int32_t temp = map(dxl_position, DXL_COUNT_MIN, DXL_COUNT_MAX, pos_min_steps, pos_max_steps);
|
||||||
|
|
||||||
|
@@ -29,6 +29,7 @@
|
|||||||
*/
|
*/
|
||||||
|
|
||||||
#include "RcServo.h"
|
#include "RcServo.h"
|
||||||
|
#include "../MachineConfig.h"
|
||||||
|
|
||||||
namespace Motors {
|
namespace Motors {
|
||||||
// RcServo::RcServo(Pin pwm_pin) : Servo(), _pwm_pin(pwm_pin) {}
|
// RcServo::RcServo(Pin pwm_pin) : Servo(), _pwm_pin(pwm_pin) {}
|
||||||
@@ -36,15 +37,6 @@ namespace Motors {
|
|||||||
void RcServo::init() {
|
void RcServo::init() {
|
||||||
_axis_index = axis_index();
|
_axis_index = axis_index();
|
||||||
|
|
||||||
// TODO FIXME: This is leaking if init() is called multiple times.
|
|
||||||
char* setting_cal_min = (char*)malloc(20);
|
|
||||||
snprintf(setting_cal_min, 20, "%c/RcServo/Cal/Min", report_get_axis_letter(_axis_index));
|
|
||||||
rc_servo_cal_min = new FloatSetting(EXTENDED, WG, NULL, setting_cal_min, 1.0, 0.5, 2.0);
|
|
||||||
|
|
||||||
char* setting_cal_max = (char*)malloc(20);
|
|
||||||
snprintf(setting_cal_max, 20, "%c/RcServo/Cal/Max", report_get_axis_letter(_axis_index));
|
|
||||||
rc_servo_cal_max = new FloatSetting(EXTENDED, WG, NULL, setting_cal_max, 1.0, 0.5, 2.0);
|
|
||||||
|
|
||||||
auto pwmNative = _pwm_pin.getNative(Pin::Capabilities::PWM);
|
auto pwmNative = _pwm_pin.getNative(Pin::Capabilities::PWM);
|
||||||
|
|
||||||
read_settings();
|
read_settings();
|
||||||
@@ -92,8 +84,8 @@ namespace Motors {
|
|||||||
|
|
||||||
// Homing justs sets the new system position and the servo will move there
|
// Homing justs sets the new system position and the servo will move there
|
||||||
bool RcServo::set_homing_mode(bool isHoming) {
|
bool RcServo::set_homing_mode(bool isHoming) {
|
||||||
sys_position[_axis_index] =
|
auto axis = MachineConfig::instance()->_axes->_axis[_axis_index];
|
||||||
axis_settings[_axis_index]->home_mpos->get() * axis_settings[_axis_index]->steps_per_mm->get(); // convert to steps
|
sys_position[_axis_index] = axis->_homing->_mpos * axis->_stepsPerMm; // convert to steps
|
||||||
|
|
||||||
set_location(); // force the PWM to update now
|
set_location(); // force the PWM to update now
|
||||||
vTaskDelay(750); // give time to move
|
vTaskDelay(750); // give time to move
|
||||||
@@ -130,8 +122,8 @@ namespace Motors {
|
|||||||
}
|
}
|
||||||
|
|
||||||
void RcServo::read_settings() {
|
void RcServo::read_settings() {
|
||||||
_pwm_pulse_min = SERVO_MIN_PULSE * rc_servo_cal_min->get();
|
_pwm_pulse_min = SERVO_MIN_PULSE * _cal_min;
|
||||||
_pwm_pulse_max = SERVO_MAX_PULSE * rc_servo_cal_max->get();
|
_pwm_pulse_max = SERVO_MAX_PULSE * _cal_max;
|
||||||
|
|
||||||
if (bitnum_istrue(dir_invert_mask->get(), _axis_index)) { // normal direction
|
if (bitnum_istrue(dir_invert_mask->get(), _axis_index)) { // normal direction
|
||||||
swap(_pwm_pulse_min, _pwm_pulse_max);
|
swap(_pwm_pulse_min, _pwm_pulse_max);
|
||||||
@@ -139,8 +131,7 @@ namespace Motors {
|
|||||||
}
|
}
|
||||||
|
|
||||||
// Configuration registration
|
// Configuration registration
|
||||||
namespace
|
namespace {
|
||||||
{
|
|
||||||
MotorFactory::InstanceBuilder<RcServo> registration("rc_servo");
|
MotorFactory::InstanceBuilder<RcServo> registration("rc_servo");
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@@ -42,8 +42,8 @@ namespace Motors {
|
|||||||
|
|
||||||
bool _disabled;
|
bool _disabled;
|
||||||
|
|
||||||
FloatSetting* rc_servo_cal_min;
|
float _cal_min;
|
||||||
FloatSetting* rc_servo_cal_max;
|
float _cal_max;
|
||||||
|
|
||||||
int _axis_index = -1;
|
int _axis_index = -1;
|
||||||
|
|
||||||
@@ -66,6 +66,8 @@ namespace Motors {
|
|||||||
|
|
||||||
void handle(Configuration::HandlerBase& handler) override {
|
void handle(Configuration::HandlerBase& handler) override {
|
||||||
handler.handle("pwm", _pwm_pin);
|
handler.handle("pwm", _pwm_pin);
|
||||||
|
handler.handle("cal_min", _cal_min);
|
||||||
|
handler.handle("cal_max", _cal_max);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Name of the configurable. Must match the name registered in the cpp file.
|
// Name of the configurable. Must match the name registered in the cpp file.
|
||||||
|
@@ -90,10 +90,12 @@ namespace Motors {
|
|||||||
|
|
||||||
config_message();
|
config_message();
|
||||||
|
|
||||||
auto ssPin = SPISSPin->get().getNative(Pin::Capabilities::Output | Pin::Capabilities::Native);
|
auto spiConfig = MachineConfig::instance()->_spi;
|
||||||
auto mosiPin = SPIMOSIPin->get().getNative(Pin::Capabilities::Output | Pin::Capabilities::Native);
|
|
||||||
auto sckPin = SPISCKPin->get().getNative(Pin::Capabilities::Output | Pin::Capabilities::Native);
|
auto ssPin = spiConfig->_ss.getNative(Pin::Capabilities::Output | Pin::Capabilities::Native);
|
||||||
auto misoPin = SPIMISOPin->get().getNative(Pin::Capabilities::Input | Pin::Capabilities::Native);
|
auto mosiPin = spiConfig->_mosi.getNative(Pin::Capabilities::Output | Pin::Capabilities::Native);
|
||||||
|
auto sckPin = spiConfig->_sck.getNative(Pin::Capabilities::Output | Pin::Capabilities::Native);
|
||||||
|
auto misoPin = spiConfig->_miso.getNative(Pin::Capabilities::Input | Pin::Capabilities::Native);
|
||||||
|
|
||||||
SPI.begin(sckPin, misoPin, mosiPin, ssPin); // this will get called for each motor, but does not seem to hurt anything
|
SPI.begin(sckPin, misoPin, mosiPin, ssPin); // this will get called for each motor, but does not seem to hurt anything
|
||||||
|
|
||||||
@@ -197,18 +199,18 @@ namespace Motors {
|
|||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
uint16_t run_i_ma = (uint16_t)(axis_settings[axis_index()]->run_current->get() * 1000.0);
|
uint16_t run_i_ma = (uint16_t)(_run_current * 1000.0);
|
||||||
float hold_i_percent;
|
float hold_i_percent;
|
||||||
|
|
||||||
if (axis_settings[axis_index()]->run_current->get() == 0) {
|
if (_run_current == 0) {
|
||||||
hold_i_percent = 0;
|
hold_i_percent = 0;
|
||||||
} else {
|
} else {
|
||||||
hold_i_percent = axis_settings[axis_index()]->hold_current->get() / axis_settings[axis_index()]->run_current->get();
|
hold_i_percent = _hold_current / _run_current;
|
||||||
if (hold_i_percent > 1.0)
|
if (hold_i_percent > 1.0)
|
||||||
hold_i_percent = 1.0;
|
hold_i_percent = 1.0;
|
||||||
}
|
}
|
||||||
|
|
||||||
tmcstepper->microsteps(axis_settings[axis_index()]->microsteps->get());
|
tmcstepper->microsteps(_microsteps);
|
||||||
tmcstepper->rms_current(run_i_ma, hold_i_percent);
|
tmcstepper->rms_current(run_i_ma, hold_i_percent);
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -250,14 +252,18 @@ namespace Motors {
|
|||||||
break;
|
break;
|
||||||
case TrinamicMode ::StallGuard:
|
case TrinamicMode ::StallGuard:
|
||||||
//grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Stallguard");
|
//grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Stallguard");
|
||||||
|
{
|
||||||
|
auto feedrate = MachineConfig::instance()->_axes->_axis[axis_index()]->_homing->_feedRate;
|
||||||
|
|
||||||
tmcstepper->en_pwm_mode(false);
|
tmcstepper->en_pwm_mode(false);
|
||||||
tmcstepper->pwm_autoscale(false);
|
tmcstepper->pwm_autoscale(false);
|
||||||
tmcstepper->TCOOLTHRS(calc_tstep(homing_feed_rate->get(), 150.0));
|
tmcstepper->TCOOLTHRS(calc_tstep(feedrate, 150.0));
|
||||||
tmcstepper->THIGH(calc_tstep(homing_feed_rate->get(), 60.0));
|
tmcstepper->THIGH(calc_tstep(feedrate, 60.0));
|
||||||
tmcstepper->sfilt(1);
|
tmcstepper->sfilt(1);
|
||||||
tmcstepper->diag1_stall(true); // stallguard i/o is on diag1
|
tmcstepper->diag1_stall(true); // stallguard i/o is on diag1
|
||||||
tmcstepper->sgt(axis_settings[axis_index()]->stallguard->get());
|
tmcstepper->sgt(_stallguard);
|
||||||
break;
|
break;
|
||||||
|
}
|
||||||
default:
|
default:
|
||||||
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "TRINAMIC_MODE_UNDEFINED");
|
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "TRINAMIC_MODE_UNDEFINED");
|
||||||
}
|
}
|
||||||
@@ -284,7 +290,7 @@ namespace Motors {
|
|||||||
tmcstepper->stallguard(),
|
tmcstepper->stallguard(),
|
||||||
tmcstepper->sg_result(),
|
tmcstepper->sg_result(),
|
||||||
feedrate,
|
feedrate,
|
||||||
axis_settings[axis_index()]->stallguard->get());
|
_stallguard);
|
||||||
|
|
||||||
TMC2130_n ::DRV_STATUS_t status { 0 }; // a useful struct to access the bits.
|
TMC2130_n ::DRV_STATUS_t status { 0 }; // a useful struct to access the bits.
|
||||||
status.sr = tmcstepper->DRV_STATUS();
|
status.sr = tmcstepper->DRV_STATUS();
|
||||||
@@ -308,8 +314,7 @@ namespace Motors {
|
|||||||
// This is used to set the stallguard window from the homing speed.
|
// This is used to set the stallguard window from the homing speed.
|
||||||
// The percent is the offset on the window
|
// The percent is the offset on the window
|
||||||
uint32_t TrinamicDriver::calc_tstep(float speed, float percent) {
|
uint32_t TrinamicDriver::calc_tstep(float speed, float percent) {
|
||||||
double tstep =
|
double tstep = speed / 60.0 * MachineConfig::instance()->_axes->_axis[axis_index()]->_stepsPerMm * (256.0 / _microsteps);
|
||||||
speed / 60.0 * axis_settings[axis_index()]->steps_per_mm->get() * (256.0 / axis_settings[axis_index()]->microsteps->get());
|
|
||||||
tstep = TRINAMIC_FCLK / tstep * percent / 100.0;
|
tstep = TRINAMIC_FCLK / tstep * percent / 100.0;
|
||||||
|
|
||||||
return static_cast<uint32_t>(tstep);
|
return static_cast<uint32_t>(tstep);
|
||||||
@@ -431,8 +436,7 @@ namespace Motors {
|
|||||||
}
|
}
|
||||||
|
|
||||||
// Configuration registration
|
// Configuration registration
|
||||||
namespace
|
namespace {
|
||||||
{
|
|
||||||
MotorFactory::InstanceBuilder<TMC2130> registration_2130("tmc_2130");
|
MotorFactory::InstanceBuilder<TMC2130> registration_2130("tmc_2130");
|
||||||
MotorFactory::InstanceBuilder<TMC5160> registration_5160("tmc_5160");
|
MotorFactory::InstanceBuilder<TMC5160> registration_5160("tmc_5160");
|
||||||
}
|
}
|
||||||
|
@@ -82,6 +82,11 @@ namespace Motors {
|
|||||||
bool _has_errors;
|
bool _has_errors;
|
||||||
bool _disabled;
|
bool _disabled;
|
||||||
|
|
||||||
|
float _run_current = 0.25;
|
||||||
|
float _hold_current = 0.25;
|
||||||
|
int _microsteps = 256;
|
||||||
|
int _stallguard = 0;
|
||||||
|
|
||||||
TrinamicMode _mode = TrinamicMode::None;
|
TrinamicMode _mode = TrinamicMode::None;
|
||||||
bool test();
|
bool test();
|
||||||
void set_mode(bool isHoming);
|
void set_mode(bool isHoming);
|
||||||
@@ -128,6 +133,10 @@ namespace Motors {
|
|||||||
void handle(Configuration::HandlerBase& handler) override {
|
void handle(Configuration::HandlerBase& handler) override {
|
||||||
handler.handle("cs", _cs_pin);
|
handler.handle("cs", _cs_pin);
|
||||||
handler.handle("r_sense", _r_sense);
|
handler.handle("r_sense", _r_sense);
|
||||||
|
handler.handle("run_current", _run_current);
|
||||||
|
handler.handle("hold_current", _hold_current);
|
||||||
|
handler.handle("microsteps", _microsteps);
|
||||||
|
handler.handle("stallguard", _stallguard);
|
||||||
|
|
||||||
StandardStepper::handle(handler);
|
StandardStepper::handle(handler);
|
||||||
}
|
}
|
||||||
|
@@ -98,7 +98,7 @@ bool can_park() {
|
|||||||
#ifdef ENABLE_PARKING_OVERRIDE_CONTROL
|
#ifdef ENABLE_PARKING_OVERRIDE_CONTROL
|
||||||
sys.override_ctrl == Override::ParkingMotion &&
|
sys.override_ctrl == Override::ParkingMotion &&
|
||||||
#endif
|
#endif
|
||||||
homing_enable->get() && !laser_mode->get();
|
homing_enable->get() && !MachineConfig::instance()->_laserMode;
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
@@ -560,7 +560,7 @@ static void protocol_exec_rt_suspend() {
|
|||||||
restore_spindle_speed = block->spindle_speed;
|
restore_spindle_speed = block->spindle_speed;
|
||||||
}
|
}
|
||||||
#ifdef DISABLE_LASER_DURING_HOLD
|
#ifdef DISABLE_LASER_DURING_HOLD
|
||||||
if (laser_mode->get()) {
|
if (MachineConfig::instance()->_laserMode) {
|
||||||
sys_rt_exec_accessory_override.bit.spindleOvrStop = true;
|
sys_rt_exec_accessory_override.bit.spindleOvrStop = true;
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
@@ -663,7 +663,7 @@ static void protocol_exec_rt_suspend() {
|
|||||||
if (gc_state.modal.spindle != SpindleState::Disable) {
|
if (gc_state.modal.spindle != SpindleState::Disable) {
|
||||||
// Block if safety door re-opened during prior restore actions.
|
// Block if safety door re-opened during prior restore actions.
|
||||||
if (!sys.suspend.bit.restartRetract) {
|
if (!sys.suspend.bit.restartRetract) {
|
||||||
if (laser_mode->get()) {
|
if (MachineConfig::instance()->_laserMode) {
|
||||||
// When in laser mode, ignore spindle spin-up delay. Set to turn on laser when cycle starts.
|
// When in laser mode, ignore spindle spin-up delay. Set to turn on laser when cycle starts.
|
||||||
sys.step_control.updateSpindleRpm = true;
|
sys.step_control.updateSpindleRpm = true;
|
||||||
} else {
|
} else {
|
||||||
@@ -719,7 +719,7 @@ static void protocol_exec_rt_suspend() {
|
|||||||
} else if (sys.spindle_stop_ovr.bit.restore || sys.spindle_stop_ovr.bit.restoreCycle) {
|
} else if (sys.spindle_stop_ovr.bit.restore || sys.spindle_stop_ovr.bit.restoreCycle) {
|
||||||
if (gc_state.modal.spindle != SpindleState::Disable) {
|
if (gc_state.modal.spindle != SpindleState::Disable) {
|
||||||
report_feedback_message(Message::SpindleRestore);
|
report_feedback_message(Message::SpindleRestore);
|
||||||
if (laser_mode->get()) {
|
if (MachineConfig::instance()->_laserMode) {
|
||||||
// When in laser mode, ignore spindle spin-up delay. Set to turn on laser when cycle starts.
|
// When in laser mode, ignore spindle spin-up delay. Set to turn on laser when cycle starts.
|
||||||
sys.step_control.updateSpindleRpm = true;
|
sys.step_control.updateSpindleRpm = true;
|
||||||
} else {
|
} else {
|
||||||
|
@@ -19,6 +19,7 @@
|
|||||||
*/
|
*/
|
||||||
|
|
||||||
#include "SDCard.h"
|
#include "SDCard.h"
|
||||||
|
#include "MachineConfig.h"
|
||||||
|
|
||||||
File myFile;
|
File myFile;
|
||||||
bool SD_ready_next = false; // Grbl has processed a line and is waiting for another
|
bool SD_ready_next = false; // Grbl has processed a line and is waiting for another
|
||||||
@@ -130,11 +131,14 @@ uint8_t sd_state = SDCARD_IDLE;
|
|||||||
uint8_t get_sd_state(bool refresh) {
|
uint8_t get_sd_state(bool refresh) {
|
||||||
// Before we use the SD library, we *must* make sure SPI is properly initialized. Re-initialization
|
// Before we use the SD library, we *must* make sure SPI is properly initialized. Re-initialization
|
||||||
// fortunately doesn't change any of the settings.
|
// fortunately doesn't change any of the settings.
|
||||||
auto ssPin = SPISSPin->get().getNative(Pin::Capabilities::Output | Pin::Capabilities::Native);
|
auto spiConfig = MachineConfig::instance()->_spi;
|
||||||
auto mosiPin = SPIMOSIPin->get().getNative(Pin::Capabilities::Output | Pin::Capabilities::Native);
|
|
||||||
auto sckPin = SPISCKPin->get().getNative(Pin::Capabilities::Output | Pin::Capabilities::Native);
|
auto ssPin = spiConfig->_ss.getNative(Pin::Capabilities::Output | Pin::Capabilities::Native);
|
||||||
auto misoPin = SPIMISOPin->get().getNative(Pin::Capabilities::Input | Pin::Capabilities::Native);
|
auto mosiPin = spiConfig->_mosi.getNative(Pin::Capabilities::Output | Pin::Capabilities::Native);
|
||||||
SPI.begin(sckPin, misoPin, mosiPin, ssPin);
|
auto sckPin = spiConfig->_sck.getNative(Pin::Capabilities::Output | Pin::Capabilities::Native);
|
||||||
|
auto misoPin = spiConfig->_miso.getNative(Pin::Capabilities::Input | Pin::Capabilities::Native);
|
||||||
|
|
||||||
|
SPI.begin(sckPin, misoPin, mosiPin, ssPin); // this will get called for each motor, but does not seem to hurt anything
|
||||||
|
|
||||||
//no need to go further if SD detect is not correct
|
//no need to go further if SD detect is not correct
|
||||||
if (SDCardDetPin->get() != Pin::UNDEFINED) {
|
if (SDCardDetPin->get() != Pin::UNDEFINED) {
|
||||||
|
@@ -33,6 +33,7 @@
|
|||||||
|
|
||||||
*/
|
*/
|
||||||
#include "VFDSpindle.h"
|
#include "VFDSpindle.h"
|
||||||
|
#include "../MachineConfig.h"
|
||||||
|
|
||||||
const uart_port_t VFD_RS485_UART_PORT = UART_NUM_2; // hard coded for this port right now
|
const uart_port_t VFD_RS485_UART_PORT = UART_NUM_2; // hard coded for this port right now
|
||||||
const int VFD_RS485_BUF_SIZE = 127;
|
const int VFD_RS485_BUF_SIZE = 127;
|
||||||
@@ -318,7 +319,7 @@ namespace Spindles {
|
|||||||
pins_settings_ok = false;
|
pins_settings_ok = false;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (laser_mode->get()) {
|
if (MachineConfig::instance()->_laserMode) {
|
||||||
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "VFD spindle disabled in laser mode. Set $GCode/LaserMode=Off and restart");
|
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "VFD spindle disabled in laser mode. Set $GCode/LaserMode=Off and restart");
|
||||||
pins_settings_ok = false;
|
pins_settings_ok = false;
|
||||||
}
|
}
|
||||||
|
@@ -554,7 +554,7 @@ void st_prep_buffer() {
|
|||||||
prep.current_speed = sqrt(pl_block->entry_speed_sqr);
|
prep.current_speed = sqrt(pl_block->entry_speed_sqr);
|
||||||
}
|
}
|
||||||
|
|
||||||
if (spindle->isRateAdjusted()) { // laser_mode->get() {
|
if (spindle->isRateAdjusted()) { // MachineConfig::instance()->_laserMode {
|
||||||
if (pl_block->spindle == SpindleState::Ccw) {
|
if (pl_block->spindle == SpindleState::Ccw) {
|
||||||
// Pre-compute inverse programmed rate to speed up PWM updating per step segment.
|
// Pre-compute inverse programmed rate to speed up PWM updating per step segment.
|
||||||
prep.inv_rate = 1.0 / pl_block->programmed_rate;
|
prep.inv_rate = 1.0 / pl_block->programmed_rate;
|
||||||
|
Reference in New Issue
Block a user